From 1caa507896faf758eb52e12d47fa0c192777f114 Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Thu, 11 May 2023 17:09:11 +0100 Subject: [PATCH] Camera: add camera zoom plugin - fix gimbal test world - add example world for gimbal and camera - add gimbal_small_3d - update command topic names in gimbal test world - update quote style in gimbal_small_3d - rename zoom plugin and attach to sensor - resolve parent model and subscribe to zoom command - implement zoom for standard camera - remove whitespace for linter - provide alternative to gz::sim::Sensor - handle RenderTeardown event to exit cleanly - find package gz-common5 - use degrees for pose in gimbal world - format plugin attributes. Signed-off-by: Rhys Mainwaring --- CMakeLists.txt | 26 + include/CameraZoomPlugin.hh | 67 ++ models/gimbal_small_3d/meshes/base_plate.dae | 676 ++++++++++++++++++ .../meshes/camera_enclosure.dae | 448 ++++++++++++ models/gimbal_small_3d/meshes/roll_arm.dae | 526 ++++++++++++++ models/gimbal_small_3d/meshes/yaw_arm.dae | 552 ++++++++++++++ models/gimbal_small_3d/model.config | 21 + models/gimbal_small_3d/model.sdf | 231 ++++++ src/CameraZoomPlugin.cc | 412 +++++++++++ tests/worlds/test_gimbal.sdf | 63 +- worlds/gimbal.sdf | 288 ++++++++ 11 files changed, 3279 insertions(+), 31 deletions(-) create mode 100644 include/CameraZoomPlugin.hh create mode 100644 models/gimbal_small_3d/meshes/base_plate.dae create mode 100644 models/gimbal_small_3d/meshes/camera_enclosure.dae create mode 100644 models/gimbal_small_3d/meshes/roll_arm.dae create mode 100644 models/gimbal_small_3d/meshes/yaw_arm.dae create mode 100644 models/gimbal_small_3d/model.config create mode 100644 models/gimbal_small_3d/model.sdf create mode 100644 src/CameraZoomPlugin.cc create mode 100755 worlds/gimbal.sdf diff --git a/CMakeLists.txt b/CMakeLists.txt index 11f6181..6dd9a22 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -22,6 +22,12 @@ if("$ENV{GZ_VERSION}" STREQUAL "harmonic") find_package(gz-cmake3 REQUIRED) set(GZ_CMAKE_VER ${gz-cmake3_VERSION_MAJOR}) + gz_find_package(gz-common5 REQUIRED) + set(GZ_COMMON_VER ${gz-common5_VERSION_MAJOR}) + + gz_find_package(gz-rendering8 REQUIRED) + set(GZ_RENDERING_VER ${gz-rendering8_VERSION_MAJOR}) + gz_find_package(gz-sim8 REQUIRED) set(GZ_SIM_VER ${gz-sim8_VERSION_MAJOR}) @@ -31,6 +37,12 @@ elseif("$ENV{GZ_VERSION}" STREQUAL "garden" OR NOT DEFINED "ENV{GZ_VERSION}") find_package(gz-cmake3 REQUIRED) set(GZ_CMAKE_VER ${gz-cmake3_VERSION_MAJOR}) + gz_find_package(gz-common5 REQUIRED) + set(GZ_COMMON_VER ${gz-common5_VERSION_MAJOR}) + + gz_find_package(gz-rendering7 REQUIRED) + set(GZ_RENDERING_VER ${gz-rendering7_VERSION_MAJOR}) + gz_find_package(gz-sim7 REQUIRED) set(GZ_SIM_VER ${gz-sim7_VERSION_MAJOR}) @@ -70,6 +82,19 @@ target_link_libraries(ParachutePlugin PRIVATE gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER} ) +add_library(CameraZoomPlugin + SHARED + src/CameraZoomPlugin.cc +) +target_include_directories(CameraZoomPlugin PRIVATE + include +) +target_link_libraries(CameraZoomPlugin PRIVATE + gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER} + gz-rendering${GZ_RENDERING_VER}::gz-rendering${GZ_RENDERING_VER} + gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER} +) + # --------------------------------------------------------------------------- # # Install. @@ -77,6 +102,7 @@ install( TARGETS ArduPilotPlugin ParachutePlugin + CameraZoomPlugin DESTINATION lib/${PROJECT_NAME} ) diff --git a/include/CameraZoomPlugin.hh b/include/CameraZoomPlugin.hh new file mode 100644 index 0000000..2250f34 --- /dev/null +++ b/include/CameraZoomPlugin.hh @@ -0,0 +1,67 @@ +/* + Copyright (C) 2023 ArduPilot.org + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +#ifndef CAMERAZOOMPLUGIN_HH_ +#define CAMERAZOOMPLUGIN_HH_ + +#include + +#include + +namespace gz { +namespace sim { +inline namespace GZ_SIM_VERSION_NAMESPACE { +namespace systems { + +/// \brief Camera zoom plugin. +class CameraZoomPlugin : + public System, + public ISystemConfigure, + public ISystemPreUpdate, + public ISystemPostUpdate +{ + /// \brief Destructor + public: virtual ~CameraZoomPlugin(); + + /// \brief Constructor + public: CameraZoomPlugin(); + + // Documentation inherited + public: void PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) final; + + // Documentation inherited + public: void PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) final; + + // Documentation inherited + public: void Configure(const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &) final; + + /// \internal + /// \brief Private implementation + private: class Impl; + private: std::unique_ptr impl; +}; + +} // namespace systems +} +} // namespace sim +} // namespace gz + +#endif // CAMERAZOOMPLUGIN_HH_ diff --git a/models/gimbal_small_3d/meshes/base_plate.dae b/models/gimbal_small_3d/meshes/base_plate.dae new file mode 100644 index 0000000..76fabc2 --- /dev/null +++ b/models/gimbal_small_3d/meshes/base_plate.dae @@ -0,0 +1,676 @@ + + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-05-11T22:41:59 + 2023-05-11T22:41:59 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1000 + 29.99998 + 75 + 0.15 + 0 + 1 + 2 + 0.04999995 + 30.002 + 1 + 3 + 2880 + 3 + 1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.03642219 0.078 0.002173483 0.03643339 0.07300001 0.002335011 0.0361244 0.07300001 9.72651e-4 0.0360412 0.078 7.89206e-4 0.03548288 0.07300001 -1.55921e-4 0.035461 0.078 -1.84007e-4 0.03646618 0.078 0.004209935 0.03649151 0.07300001 0.004655659 0.03679442 0.078 0.006994962 0.03684693 0.07300001 0.007196903 0.03751868 0.07300001 0.009641706 0.03760224 0.078 0.009889721 0.059771 0.078 -0.07424998 0.06065654 0.078 -0.07319581 0.05868417 0.078 -0.07491338 0.06598216 0.078 -0.07975697 0.06566977 0.078 -0.08147388 0.06117123 0.078 -0.07191747 0.06492459 0.078 -0.08332067 0.05776864 0.078 -0.07518643 0.06349325 0.078 -0.08528661 0.06176894 0.078 -0.08665776 0.05997663 0.078 -0.08752566 0.05650204 0.078 -0.07524847 0.05793792 0.078 -0.08797776 0.06124955 0.078 -0.07075768 0.06106591 0.078 -0.06971132 0.04645019 0.078 -0.08302479 0.04573857 0.078 -0.08360236 0.04674935 0.078 -0.08220499 0.04492616 0.078 -0.08376628 0.05498701 0.078 -0.07476681 0.04670912 0.078 -0.08159589 0.04640346 0.078 -0.08091878 0.05397254 0.078 -0.07399761 0.05321484 0.078 -0.07297837 0.04578995 0.078 -0.08042877 0.04524827 0.078 -0.08026134 0.05283397 0.078 -0.07187277 0.04459351 0.078 -0.08028304 0.05273848 0.078 -0.07082027 0.05292385 0.078 -0.06977415 0.04392528 0.078 -0.08060449 0.06598877 0.078 -0.02533489 0.06046617 0.078 -0.06850802 0.05959784 0.078 -0.06762325 0.05997121 0.078 -0.02904629 0.06058007 0.078 -0.0283122 0.05904352 0.078 -0.02975267 0.05855882 0.078 -0.06702792 0.06115353 0.078 -0.0270223 0.05753159 0.078 -0.03024208 0.06122452 0.078 -0.02532869 0.06580775 0.078 -0.02394783 0.06509763 0.078 -0.02186244 0.06079 0.078 -0.02405697 0.04610723 0.078 -0.03836625 0.05707246 0.078 -0.06672304 0.04655623 0.078 -0.0378313 0.05543804 0.078 -0.06702023 0.04540824 0.078 -0.03872394 0.0467512 0.078 -0.03716123 0.05618703 0.078 -0.03018212 0.06005889 0.078 -0.02301639 0.0639975 0.078 -0.02019053 0.05420243 0.078 -0.06778031 0.05527681 0.078 -0.02989202 0.04440629 0.078 -0.03867357 0.04669159 0.078 -0.03650939 0.05335897 0.078 -0.06877505 0.05433952 0.078 -0.02933603 0.06277436 0.078 -0.01893025 0.04626101 0.078 -0.03574967 0.05354189 0.078 -0.02848619 0.05299031 0.078 -0.02745938 0.04546409 0.078 -0.03529769 0.05900943 0.078 -0.02224326 0.06110829 0.078 -0.01783901 0.05272257 0.078 -0.02596586 0.04476755 0.078 -0.0352568 0.05812382 0.078 -0.02189457 0.05966746 0.078 -0.01725858 0.05795878 0.078 -0.01689082 0.0569663 0.078 -0.02172917 0.05486112 0.078 -0.01681941 0.05581831 0.078 -0.02191084 0.05483895 0.078 -0.02232271 0.05224341 0.078 -0.01642078 0.05402874 0.078 -0.02295362 0.04996484 0.078 -0.0157985 0.05341988 0.078 -0.02368772 0.05296272 0.078 -0.02464354 0.04690021 0.078 -0.0144695 0.04410552 0.078 -0.03547906 -0.0240308 0.078 -0.08347439 0.04405093 0.078 -0.08349597 -0.02353912 0.078 -0.08297914 0.04350662 0.078 -0.08292883 -0.02330571 0.078 -0.08246248 0.04323029 0.078 -0.08214712 -0.02324426 0.078 -0.08189845 -0.02340036 0.078 -0.08126276 0.04444718 0.078 -0.01287055 0.04263776 0.078 -0.01135218 0.04350721 0.078 -0.03605288 0.01284402 0.078 -0.03860217 0.04342037 0.078 -0.0812062 0.04327905 0.078 -0.03736203 0.0435965 0.078 -0.03808116 0.04325896 0.078 -0.03675162 -0.03795874 0.078 -0.08798021 -0.02472364 0.078 -0.08373951 -0.02652454 0.078 -0.08288019 -0.02606409 0.078 -0.08340477 -0.02542096 0.078 -0.08371025 0.00784403 0.078 -0.03860217 -0.02378195 0.078 -0.08073145 0.03900229 0.078 -0.00680083 0.03747421 0.078 -0.005681633 0.0359916 0.078 -0.005161821 0.04070299 0.078 -0.009223282 0.01284402 0.078 -0.02860212 -0.03422892 0.078 -0.07424998 -0.02629852 0.078 -0.080814 -0.02660638 0.078 -0.08129006 -0.03334337 0.078 -0.07319581 -0.02573859 0.078 -0.0803976 -0.03550767 0.078 -0.07500177 -0.02677482 0.078 -0.08205872 -0.03282874 0.078 -0.07191747 -0.02505767 0.078 -0.08024227 -0.03707247 0.078 -0.07527691 -0.03278255 0.078 -0.07025635 -0.02436858 0.078 -0.08035242 -0.04010176 0.078 -0.0874809 -0.04187476 0.078 -0.08659076 -0.04326021 0.078 -0.08549398 -0.03852742 0.078 -0.07498234 -0.04466664 0.078 -0.08378303 -0.04565191 0.078 -0.08156466 -0.04598015 0.078 -0.07973867 -0.04068177 0.078 -0.07316458 -0.0397194 0.078 -0.07429325 -0.04120808 0.078 -0.07174199 -0.04120409 0.078 -0.07025867 0.0180574 0.078 -0.01098573 0.01750123 0.078 -0.01147615 0.01832711 0.078 -0.01043814 0.03508454 0.078 -0.004409372 0.01687681 0.078 -0.01167434 0.01840329 0.078 -0.00978744 0.01622337 0.078 -0.01164674 0.03453481 0.078 -0.003367066 0.01812529 0.078 -0.008960187 0.0155577 0.078 -0.01131922 0.00784403 0.078 -0.02860212 0.05997931 0.078 0.03594535 0.06442958 0.078 0.03304743 0.06343883 0.078 0.03183197 0.06169986 0.078 0.03042674 0.06086862 0.078 0.03717482 0.06519961 0.078 0.03439658 0.05875837 0.078 0.03510302 0.0657761 0.078 0.03608447 0.05983006 0.078 0.02958655 0.06599032 0.078 0.03759735 0.06127375 0.078 0.03882086 0.05724638 0.078 0.03473615 0.05604422 0.078 0.02851688 0.06598877 0.078 0.03951704 0.06572216 0.078 0.04133296 0.05597966 0.078 0.03486353 0.06103765 0.078 0.04039216 0.05486655 0.078 0.0353046 0.06487298 0.078 0.04337847 0.06044048 0.078 0.04151278 0.05213236 0.078 0.02681523 0.06399744 0.078 0.0446614 0.01341277 0.078 -0.005198538 0.01531267 0.078 -0.008776605 0.01602548 0.078 -0.008273601 0.01258838 0.078 -0.00592041 0.05395114 0.078 0.03602606 0.01401114 0.078 -0.00429964 0.01689386 0.078 -0.008186638 0.01171082 0.078 -0.006376504 0.01498997 0.078 -0.009345531 0.05979388 0.078 0.04221111 0.01439177 0.078 -0.003201544 0.0627743 0.078 0.04592162 0.01488363 0.078 -0.009947478 0.0106424 0.078 -0.006600737 0.05332636 0.078 0.03684222 0.01798152 0.078 0.001324832 0.01755005 0.078 -0.008425652 0.03442597 0.078 -0.002193391 0.01722031 0.078 8.15102e-4 0.01832592 0.078 0.001981675 0.0143612 0.078 -0.001645624 0.03477531 0.078 -0.001066863 0.04906803 0.078 0.02496737 0.05900943 0.078 0.04275673 0.01840209 0.078 0.002632319 0.01626271 0.078 7.51834e-4 0.01822006 0.078 0.003260552 0.06085848 0.078 0.04714828 0.01372098 0.078 -1.90234e-4 0.00574398 0.078 -0.008982479 0.01505839 0.078 -0.01071333 0.009554445 0.078 -0.006537914 0.005140841 0.078 -0.009416282 0.01786345 0.078 0.00375694 0.006153285 0.078 -0.008114516 -0.02402669 0.078 -0.03848034 -0.02337539 0.078 -0.0377171 -0.03341048 0.078 -0.06868171 0.004551768 0.078 -0.00957638 0.008257627 0.078 -0.006044924 -0.02476751 0.078 -0.03874319 -0.03418427 0.078 -0.06780934 -0.02325034 0.078 -0.0367217 0.00609523 0.078 -0.00733143 0.0154196 0.078 0.001210749 -0.03496181 0.078 -0.06725704 0.003816008 0.078 -0.009483873 -0.02546411 0.078 -0.03870224 0.01720637 0.078 0.00416094 0.03868746 0.078 0.01262307 0.01503062 0.078 0.001791596 0.05781316 0.078 0.0431928 -0.03608298 0.078 -0.06683444 0.005776703 0.078 -0.006709873 0.007285416 0.078 -0.005194962 -0.0235781 0.078 -0.03596043 0.003186404 0.078 -0.009091734 -0.02604955 0.078 -0.0384081 0.01256728 0.078 9.03818e-4 -0.03721225 0.078 -0.06674623 0.05918806 0.078 0.04772597 -0.02644515 0.078 -0.03800207 0.005120158 0.078 -0.00620383 -0.03815305 0.078 -0.0669015 0.006651341 0.078 -0.004189729 0.01489108 0.078 0.002340972 0.01495653 0.078 0.002991974 0.004392266 0.078 -0.006062507 0.0110799 0.078 0.001465797 0.05763769 0.078 0.04798489 0.006311655 0.078 -0.002640604 0.01528543 0.078 0.00360763 0.05643689 0.078 0.04322791 0.003707706 0.078 -0.00620079 0.05550044 0.078 0.04793983 0.05511659 0.078 0.04283326 0.05318754 0.078 0.04764485 0.05391913 0.078 0.04195791 0.05034452 0.078 0.04687678 0.05319434 0.078 0.04091519 0.0472207 0.078 0.04548591 0.005716502 0.078 0.003401458 0.008048176 0.078 7.39753e-4 0.004979193 0.078 0.002933502 0.006991028 0.078 -3.85218e-4 0.006152093 0.078 0.004305183 0.009490907 0.078 0.001408159 0.05286782 0.078 0.04002118 0.004418075 0.078 0.002844393 0.006533563 0.078 -0.00136578 0.006035566 0.078 0.005301713 0.003857314 0.078 0.002924561 0.04403185 0.078 0.04327869 0.05273228 0.078 0.03889352 0.05293154 0.078 0.03774499 0.03696203 0.078 0.03633505 0.04670351 0.078 0.02317368 0.003320515 0.078 0.003217101 0.01575386 0.078 0.004000425 0.003042697 0.078 -0.006695687 0.0344991 0.078 0.0345366 0.04452782 0.078 0.02115517 0.005524694 0.078 0.005954682 0.002935171 0.078 0.003632843 0.0163806 0.078 0.004232048 0.03212833 0.078 0.03320276 0.04256206 0.078 0.01893156 0.02904474 0.078 0.03199148 0.04044526 0.078 0.01595175 0.02631962 0.078 0.03134071 -0.03385102 0.078 -0.02887684 -0.02621287 0.078 -0.03571379 -0.02668029 0.078 -0.0364505 -0.03477776 0.078 -0.02963668 -0.0331943 0.078 -0.02791517 -0.02553254 0.078 -0.03532105 -0.03587657 0.078 -0.03011465 -0.02673846 0.078 -0.03732097 -0.03281289 0.078 -0.02681273 -0.02492594 0.078 -0.03524523 -0.03742635 0.078 -0.03026115 0.02371829 0.078 0.03102242 -0.03275042 0.078 -0.02575773 -0.03872317 0.078 -0.02989202 0.004993379 0.078 0.006255865 -0.03916102 0.078 -0.06732273 -0.03966045 0.078 -0.02933603 -0.01421624 0.078 -0.004395604 0.002713561 0.078 -0.008358359 -0.01487267 0.078 -0.004985034 -0.0155946 0.078 -0.005358636 -0.01367241 0.078 -0.003349661 0.002682864 0.078 -0.007442295 -0.01357066 0.078 -0.002176582 -0.01667028 0.078 -0.005571305 -0.02202922 0.078 -0.01074868 -0.02390277 0.078 -0.01244825 -0.02420455 0.078 -0.03541696 -0.02044475 0.078 -0.008872091 -0.01770079 0.078 -0.005952715 -0.02630722 0.078 -0.01413762 0.002693533 0.078 0.004193782 -0.01869112 0.078 -0.006609976 -0.01938688 0.078 -0.007343053 -0.0138089 0.078 -0.001325666 -0.03293406 0.078 -0.02471131 -0.01421344 0.078 -6.29124e-4 0.002669334 0.078 0.004934847 -0.02993106 0.078 -0.01580345 -0.03338378 0.078 -0.02375489 -0.01506203 0.078 1.67407e-4 -0.0339725 0.078 -0.02300238 -0.03333753 0.078 -0.01663488 -0.03489601 0.078 -0.02228975 -0.01582217 0.078 0.001180827 -0.01638466 0.078 0.002687394 -0.03571861 0.078 -0.01685243 -0.03587615 0.078 -0.02189457 -0.03703361 0.078 -0.02172917 -0.04597061 0.078 -0.02490264 -0.04014891 0.078 -0.0681231 -0.04080563 0.078 -0.06908476 -0.04124712 0.078 -0.02631831 -0.04100966 0.078 -0.02745944 -0.04045808 0.078 -0.02848619 -0.0383653 0.078 -0.01692777 -0.04115355 0.078 -0.02497762 -0.01656073 0.078 0.005395174 -0.03818166 0.078 -0.02191084 -0.04560279 0.078 -0.02319383 -0.04059517 0.078 -0.0175963 -0.03916102 0.078 -0.02232271 -0.04502242 0.078 -0.02175313 -0.04058009 0.078 -0.02368772 -0.04250192 0.078 -0.01869958 -0.04406684 0.078 -0.020267 -0.03997117 0.078 -0.02295362 -0.01716184 0.078 0.008559823 0.003041505 0.078 0.005723953 -0.0185799 0.078 0.01238405 -0.002692162 0.078 0.03102672 0.003706514 0.078 0.00621891 0.004391074 0.078 0.006357192 -0.005127191 0.078 0.03130733 -0.01991826 0.078 0.01503282 -0.007779836 0.078 0.03191119 -0.02151173 0.078 0.01753652 -0.01087808 0.078 0.03308451 -0.02334463 0.078 0.01987046 -0.01333397 0.078 0.03443223 -0.0253992 0.078 0.02201211 -0.01585561 0.078 0.03623861 -0.02765518 0.078 0.0239402 -0.03009068 0.078 0.02563613 -0.03402876 0.078 0.03595364 -0.03329509 0.078 0.027395 -0.03341984 0.078 0.03668779 -0.0347777 0.078 0.03536337 -0.03284639 0.078 0.03797763 -0.03564465 0.078 0.03496617 -0.02268815 0.078 0.04296135 -0.03680449 0.078 0.02875691 -0.03675353 0.078 0.03473615 -0.0327593 0.078 0.03945738 -0.02537381 0.078 0.04498642 -0.03969126 0.078 0.02954649 -0.03802031 0.078 0.03486353 -0.03316098 0.078 0.04088664 -0.04102474 0.078 0.03007447 -0.02876478 0.078 0.04667317 -0.03913342 0.078 0.0353046 -0.04253411 0.078 0.03102493 -0.044128 0.078 0.03259271 -0.04027503 0.078 0.03625184 -0.0339725 0.078 0.04199755 -0.03158783 0.078 0.04751199 -0.04534775 0.078 0.03471791 -0.03471595 0.078 0.04259169 -0.04100966 0.078 0.03754055 -0.03443938 0.078 0.0479561 -0.03557282 0.078 0.04301422 -0.04595983 0.078 0.03702282 -0.03650063 0.078 0.04322701 -0.04124712 0.078 0.03868162 -0.03793799 0.078 0.04795861 -0.03756308 0.078 0.04322791 -0.04594737 0.078 0.04020708 -0.04115355 0.078 0.04002231 -0.03956156 0.078 0.04762542 -0.03858309 0.078 0.0429511 -0.04540729 0.078 0.04223334 -0.0411939 0.078 0.04697763 -0.04058009 0.078 0.04131221 -0.04464817 0.078 0.0437594 -0.03966557 0.078 0.04234254 -0.04322987 0.078 0.04553395 0.03922545 0.07300001 -0.007098555 0.03851455 0.07300001 -0.006371557 0.03745204 0.07300001 -0.005681037 0.03632646 0.07300001 -0.005302667 0.05482178 0.07300001 -0.0168237 0.05207788 0.07300001 -0.01638448 0.04973816 0.07300001 -0.01571941 0.04666191 0.07300001 -0.01433825 0.04350972 0.07300001 -0.01215302 0.0411576 0.07300001 -0.009781181 0.06593364 0.07300001 -0.08037489 0.0623759 0.07300001 -0.07624334 0.06112629 0.07300001 -0.07728481 0.06320297 0.07300001 -0.07522904 0.06392568 0.07300001 -0.07391965 0.0651834 0.07300001 -0.08280646 0.05927413 0.07300001 -0.07817512 0.06414389 0.07300001 -0.08450525 0.06277441 0.07300001 -0.08594071 0.06435859 0.07300001 -0.07248765 0.06110829 0.07300001 -0.08703202 0.05718761 0.07300001 -0.07851862 0.05966752 0.07300001 -0.08761239 0.06451016 0.07300001 -0.0711342 0.05795878 0.07300001 -0.08798021 0.06438785 0.07300001 -0.06964331 0.05545961 0.07300001 -0.07835173 0.04743564 0.07300001 -0.0837844 0.04649275 0.07300001 -0.08463054 0.04793649 0.07300001 -0.08270233 0.04528278 0.07300001 -0.08500611 0.05385649 0.07300001 -0.07782965 0.04797947 0.07300001 -0.08151078 0.05258053 0.07300001 -0.07706695 0.04755777 0.07300001 -0.08039557 0.05158585 0.07300001 -0.07620656 0.04673731 0.07300001 -0.07953053 0.0505554 0.07300001 -0.07487213 0.04593306 0.07300001 -0.079144 0.04986304 0.07300001 -0.07334196 0.04501187 0.07300001 -0.07898253 0.04949706 0.07300001 -0.07156223 0.04957103 0.07300001 -0.06992751 0.04317414 0.07300001 -0.08439397 0.02820062 0.07300001 -0.08407509 0.04259836 0.07300001 -0.08381015 0.02721828 0.07300001 -0.08475768 0.044097 0.07300001 -0.08488118 0.04210877 0.07300001 -0.08288842 0.02886378 0.07300001 -0.08296215 0.0263738 0.07300001 -0.08498305 0.02900439 0.07300001 -0.08200138 0.04199838 0.07300001 -0.08200049 0.02429395 0.07300001 -0.08450233 0.02229416 0.07300001 -0.08395594 0.02343994 0.07300001 -0.08359223 0.0214228 0.07300001 -0.08466315 0.02285444 0.07300001 -0.08298444 0.02309125 0.07300001 -0.08276385 0.02547621 0.07300001 -0.08497041 0.0205 0.07300001 -0.08496546 0.023 0.07300001 -0.08200001 0.01960158 0.07300001 -0.08498835 0.06307721 0.07300001 -0.06655907 0.06271976 0.07300001 -0.03086876 0.06164342 0.07300001 -0.0650869 0.06149458 0.07300001 -0.03202694 0.06357109 0.07300001 -0.02963882 0.06038242 0.07300001 -0.06429934 0.06004089 0.07300001 -0.03286832 0.05916327 0.07300001 -0.06380683 0.05843448 0.07300001 -0.03338021 0.0659905 0.07300001 -0.02532446 0.06397253 0.07300001 -0.06820625 0.06422185 0.07300001 -0.02809041 0.05756163 0.07300001 -0.06350505 0.06452667 0.07300001 -0.02605819 0.06578028 0.07300001 -0.02382552 0.06425237 0.07300001 -0.02401781 0.06521445 0.07300001 -0.02215182 0.06353908 0.07300001 -0.02228969 0.04703307 0.07300001 -0.03922611 0.05606645 0.07300001 -0.06355077 0.05695313 0.07300001 -0.03350579 0.04774689 0.07300001 -0.03826618 0.04594188 0.07300001 -0.03988051 0.05455213 0.07300001 -0.06389129 0.05551075 0.07300001 -0.03336691 0.06407725 0.07300001 -0.02025115 0.05308419 0.07300001 -0.06459224 0.04802793 0.07300001 -0.0368734 0.05412763 0.07300001 -0.0329346 0.04500043 0.07300001 -0.04000103 0.05046856 0.07300001 -0.06729036 0.05160945 0.07300001 -0.06574225 0.05281138 0.07300001 -0.03224349 0.06229704 0.07300001 -0.02065247 0.04769349 0.07300001 -0.03564578 0.05140024 0.07300001 -0.03101688 0.0470159 0.07300001 -0.03475207 0.0624957 0.07300001 -0.01871758 0.0608015 0.07300001 -0.01952159 0.0504983 0.07300001 -0.02975362 0.04618889 0.07300001 -0.03423762 0.06119692 0.07300001 -0.01789212 0.04979056 0.07300001 -0.02816295 0.04517751 0.07300001 -0.03398066 0.05961102 0.07300001 -0.0189628 0.05955505 0.07300001 -0.01720952 0.05835652 0.07300001 -0.01861208 0.043931 0.07300001 -0.03417646 0.04951632 0.07300001 -0.02656084 0.05772912 0.07300001 -0.01688134 0.05662506 0.07300001 -0.01848834 0.05478459 0.07300001 -0.0188179 0.05340963 0.07300001 -0.01940667 0.05216872 0.07300001 -0.02024245 0.04198169 0.07300001 -0.03697621 0.0290175 0.07300001 -0.03698796 0.05077832 0.07300001 -0.02175819 0.04224252 0.07300001 -0.03577047 0.02870792 0.07300001 -0.03563928 0.04292744 0.07300001 -0.03480458 0.02789825 0.07300001 -0.03465783 0.04992359 0.07300001 -0.02348083 0.01767528 0.07300001 -0.08391958 -0.02317416 0.07300001 -0.08439397 -0.0225054 0.07300001 -0.08369296 0.01853477 0.07300001 -0.08464014 0.01710253 0.07300001 -0.08286827 -0.02409702 0.07300001 -0.08488124 -0.02207773 0.07300001 -0.08274132 0.01699894 0.07300001 -0.08200043 -0.0219984 0.07300001 -0.08200025 0.023 0.07300001 -0.03699994 0.02299588 0.07300001 -0.03658896 0.04953312 0.07300001 -0.02512097 0.02261352 0.07300001 -0.03549104 0.02355372 0.07300001 -0.03521096 0.02199065 0.07300001 -0.03474444 0.02457714 0.07300001 -0.0343368 0.02135193 0.07300001 -0.03431367 -0.03815042 0.07300001 -0.08796226 -0.02543342 0.07300001 -0.08499932 -0.02661615 0.07300001 -0.08454495 -0.02743566 0.07300001 -0.0837844 -0.02793651 0.07300001 -0.08270233 0.01699811 0.07300001 -0.03699958 0.01284402 0.07300001 -0.037 0.01707977 0.07300001 -0.03625637 0.01757431 0.07300001 -0.03519308 0.03522473 0.07300001 -0.01266521 0.03438818 0.07300001 -0.01350992 0.03567034 0.07300001 -0.01156306 0.02748692 0.07299304 -0.01902532 0.02711963 0.07300001 -0.03420883 0.02899289 0.07299435 -0.01730579 0.03565591 0.07300001 -0.01037442 0.02236622 0.07299363 -0.02304619 0.02624893 0.07300001 -0.03399544 0.03329038 0.07300001 -0.0139662 0.03039479 0.07299602 -0.01540577 0.03232425 0.07300001 -0.01398795 0.03142189 0.07300204 -0.01373392 0.02542543 0.07300001 -0.03405088 0.03527033 0.07300001 -0.009434044 0.02030152 0.07300001 -0.03398644 -0.02755779 0.07300001 -0.08039557 -0.03175193 0.07300001 -0.07638031 -0.02673727 0.07300001 -0.07953053 -0.03051072 0.07300001 -0.07481366 -0.03323948 0.07300001 -0.07751333 -0.02797943 0.07300001 -0.08151084 0.01669847 0.07299369 -0.02542769 -0.02593308 0.07300001 -0.079144 -0.02501183 0.07300001 -0.07898253 -0.03496432 0.07300001 -0.07823503 -0.0297839 0.07300001 -0.07308548 0.0346089 0.07300001 -0.008662819 0.01920717 0.07300001 -0.03409898 -0.02948838 0.07300001 -0.07137483 -0.0368123 0.07300001 -0.07851862 0.01842945 0.07300001 -0.03442978 -0.04018533 0.07300001 -0.0874412 -0.02967494 0.07300001 -0.06926834 -0.03854036 0.07300001 -0.07835173 0.03395485 0.07299703 -0.005990564 0.03554677 0.07300001 -0.004867136 -0.04176896 0.07300001 -0.08665776 -0.04316943 0.07300001 -0.0855804 0.03483194 0.07300001 -0.004037499 -0.04014343 0.07300001 -0.07782965 -0.04420137 0.07300001 -0.08441925 -0.04502242 0.07300001 -0.08311796 0.03452348 0.07300281 -0.003274917 0.03441107 0.07299971 -0.002425789 -0.04566979 0.07300001 -0.08147394 -0.04141944 0.07300001 -0.07706695 -0.04598218 0.07300001 -0.07975685 -0.04254943 0.07300001 -0.07607239 0.00784403 0.07300001 -0.037 -0.04362946 0.07300001 -0.07454615 0.002739191 0.0729922 -0.0249257 -0.04435086 0.07300001 -0.07261812 -0.04450291 0.07300001 -0.07043766 -7.87598e-5 0.07299327 -0.02376228 -0.032507 0.07300001 -0.0649805 -0.02500045 0.07300001 -0.04000103 -0.03140336 0.07300001 -0.06599009 -0.03042429 0.07300001 -0.06735491 -0.0219984 0.07300001 -0.0369997 -0.03361755 0.07300001 -0.06429934 -0.02209132 0.07300001 -0.03619062 -0.02589207 0.07300001 -0.03989207 -0.03483664 0.07300001 -0.06380689 -0.02262628 0.07300001 -0.03513431 -0.03643828 0.07300001 -0.06350505 -0.02699685 0.07300001 -0.03926271 -0.03793352 0.07300001 -0.06355077 -0.02352625 0.07300001 -0.03436499 -0.01099014 0.0730043 -0.01391017 -0.0121234 0.07300001 -0.01400625 -0.01319295 0.07300001 -0.01367658 -0.02741396 0.07300001 -0.03520071 -0.03192752 0.07300001 -0.03154945 -0.02653646 0.07300001 -0.03438776 -0.02786523 0.07300001 -0.0360623 -0.03071504 0.07300001 -0.03012621 -0.03361797 0.07300001 -0.03272432 -0.02801352 0.07300001 -0.03730148 -0.02995985 0.07300001 -0.02861869 -0.02525126 0.07300001 -0.03399109 -0.03556543 0.07300001 -0.03338021 -0.02951651 0.07300001 -0.0268073 -0.02436 0.07300001 -0.03406441 -0.02764523 0.07300001 -0.03844046 -0.03704679 0.07300001 -0.03350579 -0.02958625 0.07300001 -0.02474987 -0.03848922 0.07300001 -0.03336691 -0.03944784 0.07300001 -0.06389123 -0.01349109 0.07300001 -0.008505284 -0.01272237 0.07299715 -0.008144915 -0.03987228 0.07300001 -0.0329346 -0.04091578 0.07300001 -0.06459218 -0.04118859 0.07300001 -0.03224349 -0.04239046 0.07300001 -0.06574225 -0.01409614 0.07300001 -0.004235386 -0.0149486 0.07300001 -0.005052685 -0.0137028 0.07300746 -0.003404498 -0.01576614 0.07300001 -0.005401432 -0.01441568 0.07300001 -0.009479522 -0.01355981 0.07299965 -0.002637922 -0.04259967 0.07300001 -0.03101688 -0.01702225 0.07300001 -0.005652129 -0.01470798 0.07300001 -0.01180577 -0.02220362 0.07300001 -0.01092743 -0.01412689 0.07300001 -0.01293313 -0.02445894 0.07300001 -0.01289266 -0.02055114 0.07300001 -0.00901252 -0.01479512 0.07300001 -0.01068997 -0.01827073 0.07300001 -0.006294131 -0.01921248 0.07300001 -0.007110893 -0.02698189 0.07300001 -0.01449972 -0.02999579 0.07300001 -0.02330154 -0.04353141 0.07300001 -0.0672903 -0.03065395 0.07300001 -0.02196836 -0.04359841 0.07300001 -0.02959334 -0.03019922 0.07300001 -0.01589357 -0.03159421 0.07300001 -0.02079254 -0.03257232 0.07300001 -0.01993227 -0.03358441 0.07300001 -0.01667207 -0.03386229 0.07300001 -0.01917535 -0.03510242 0.07300001 -0.01873785 -0.03741818 0.07300001 -0.01687657 -0.03638571 0.07300001 -0.01851373 -0.04596817 0.07300001 -0.0249235 -0.04417586 0.07300001 -0.0282135 -0.04449987 0.07300001 -0.02656209 -0.04413694 0.07300001 -0.06865793 -0.04444175 0.07300001 -0.02502024 -0.03774744 0.07300001 -0.01852983 -0.03903591 0.07300001 -0.0170812 -0.0441246 0.07300001 -0.0236063 -0.03921538 0.07300001 -0.0188179 -0.0455777 0.07300001 -0.0230937 -0.04049795 0.07300001 -0.01756149 -0.04322159 0.07300001 -0.02175819 -0.04466664 0.07300001 -0.02108794 -0.04059028 0.07300001 -0.01940667 -0.04206717 0.07300001 -0.01839762 -0.04183119 0.07300001 -0.02024245 -0.04340791 0.07300001 -0.0195319 0.04986304 0.07300001 -0.06865799 -0.01641476 0.07300001 0.002977609 -0.01609987 0.07300001 0.001758754 -0.01528471 0.07300001 3.91344e-4 -0.01370859 0.07300001 -0.001549363 -0.01424396 0.07300001 -5.91596e-4 0.03472238 0.07300001 -0.00114566 0.03385967 0.07299685 0.001435875 0.03333032 0.07299518 0.003755629 0.06451064 0.07300001 0.03314119 0.06271982 0.07300001 0.03413128 0.06289619 0.07300001 0.03129768 0.06178885 0.07300001 0.03322017 0.06070953 0.07300001 0.03246849 0.06542086 0.07300001 0.03492516 0.06357109 0.07300001 0.03536111 0.06102478 0.07300001 0.03007447 0.05934184 0.07300001 0.03186297 0.06595182 0.07300001 0.03697806 0.06422185 0.07300001 0.03690952 0.05969709 0.07300001 0.02954852 0.03259325 0.07299518 0.006003916 0.05774825 0.07300001 0.03152137 0.06452667 0.07300001 0.03894174 0.0570544 0.07300001 0.02883613 0.0659905 0.07300001 0.03952741 0.05606579 0.07300001 0.03154486 0.06568551 0.07300001 0.04146546 0.03138095 0.07299453 0.008647978 0.06429195 0.07300001 0.04080212 0.05346125 0.07300001 0.02747845 0.05455756 0.07300001 0.03189677 0.06379038 0.07300001 0.04221117 0.06481122 0.07300001 0.04348742 0.05319845 0.07300001 0.0325216 0.03857988 0.07300001 0.01238399 0.06291306 0.07300001 0.04364341 0.06392723 0.07300001 0.04474693 0.05160701 0.07300001 0.0337398 0.05009061 0.07300001 0.02563613 0.06267154 0.07300001 0.04600596 0.06186062 0.07300001 0.04471957 0.04702162 0.07300001 0.02345651 0.0608015 0.07300001 0.04547834 0.04025214 0.07300001 0.01563429 0.05024391 0.07300001 0.03568184 0.06085598 0.07300001 0.04714304 0.05944246 0.07300001 0.04610317 0.05918884 0.07300001 0.04772913 0.05816507 0.07300001 0.04641497 0.02527207 0.07298767 0.01577979 0.05761206 0.07300001 0.04798293 0.05686575 0.07300001 0.04651015 0.05500966 0.07300001 0.04791325 0.05555862 0.07300001 0.04636627 0.05425506 0.07300001 0.04599404 0.052504 0.07300001 0.04749059 0.0529257 0.07300001 0.04530817 0.05011308 0.07300001 0.04679393 0.05152213 0.07300001 0.04416209 0.04697841 0.07300001 0.04534864 0.0504983 0.07300001 0.04275363 0.04992359 0.07300001 0.0415191 0.04400652 0.07300001 0.04324698 0.04953318 0.07300001 0.03987896 0.04956603 0.07300001 0.03782075 0.03693354 0.07300001 0.03629934 0.03334605 0.07300001 0.03381621 0.04434549 0.07300001 0.02096676 0.04239922 0.07300001 0.01872611 0.02929538 0.07300001 0.03205424 0.02612739 0.07300001 0.03130733 0.02295017 0.07299411 0.01762837 0.02369242 0.07300001 0.03102672 0.02088224 0.07299423 0.01877957 0.01817095 0.07299309 0.01990175 -0.0131815 0.07299691 1.12405e-4 -0.01655429 0.07300001 0.005395948 -0.01198422 0.07299405 0.005228638 -0.01724737 0.07300001 0.008863568 -0.01003581 0.07299488 0.009525895 -0.008729398 0.07299435 0.01148986 -0.01868748 0.07300001 0.01262313 -0.002718091 0.07300001 0.03102236 0.00824511 0.07299315 0.02109175 0.005905985 0.07299357 0.0207656 -8.16707e-4 0.07299667 0.0184707 -0.02004891 0.07300001 0.0152601 -0.005904257 0.07300001 0.03144139 -0.02212685 0.07300001 0.01839888 -0.008528351 0.07300001 0.03215926 -0.01112806 0.07300001 0.03320276 -0.02452778 0.07300001 0.02115517 -0.01349884 0.07300001 0.0345366 -0.01603949 0.07300001 0.03639709 -0.02670347 0.07300001 0.02317363 -0.02906799 0.07300001 0.02496731 -0.0312801 0.07300001 0.03413128 -0.03235822 0.07300001 0.03309446 -0.03213238 0.07300001 0.02681523 -0.03033548 0.07300001 0.03551995 -0.03345149 0.07300001 0.03238576 -0.03465807 0.07300001 0.03186297 -0.0362178 0.07300001 0.02858352 -0.02968287 0.07300001 0.03727209 -0.02267456 0.07300001 0.04294234 -0.03625166 0.07300001 0.03152137 -0.02947974 0.07300001 0.03931701 -0.03774744 0.07300001 0.03152984 -0.04003322 0.07300001 0.02964901 -0.02484953 0.07300001 0.04463583 -0.03939622 0.07300001 0.0318678 -0.02976202 0.07300001 0.04098784 -0.0302841 0.07300001 0.04237979 -0.04188585 0.07300001 0.03055524 -0.02752524 0.07300001 0.04613637 -0.04118859 0.07300001 0.03275644 -0.04375314 0.07300001 0.03214204 -0.03121191 0.07300001 0.04378736 -0.04276829 0.07300001 0.03415977 -0.03063094 0.07300001 0.04728966 -0.03227525 0.07300001 0.04483932 -0.04511016 0.07300001 0.03418755 -0.04385083 0.07300001 0.03590875 -0.03336924 0.07300001 0.04556941 -0.03422409 0.07300001 0.04794019 -0.03455752 0.07300001 0.04610317 -0.04577606 0.07300001 0.03608441 -0.04436445 0.07300001 0.03751134 -0.03583484 0.07300001 0.04641497 -0.04598706 0.07300001 0.03756111 -0.03756266 0.07300001 0.04650896 -0.04451441 0.07300001 0.03943336 -0.0379588 0.07300001 0.04796105 -0.04598218 0.07300001 0.0397377 -0.04563015 0.07300001 0.04160845 -0.0441246 0.07300001 0.04139369 -0.04031431 0.07300001 0.04739153 -0.03962427 0.07300001 0.04604548 -0.04474043 0.07300001 0.04362988 -0.04350167 0.07300001 0.04275357 -0.04107427 0.07300001 0.04530817 -0.04224097 0.07300001 0.04632323 -0.04247784 0.07300001 0.04416209 -0.04352623 0.07300001 0.04520392 -0.02961975 0.07499998 -0.06956547 -0.03013163 0.07499998 -0.06795907 -0.03077197 0.07499998 -0.06681054 -0.03171014 0.07499998 -0.06565731 -0.03334921 0.07499998 -0.06441771 -0.03527218 0.07499998 -0.06368285 -0.0368129 0.07499998 -0.06349486 -0.03830498 0.07499998 -0.06359815 -0.03986865 0.07499998 -0.06405794 -0.04118746 0.07499998 -0.06476408 -0.0426048 0.07499998 -0.06597602 -0.04356938 0.07499998 -0.06736922 -0.04424858 0.07499998 -0.0689606 -0.04451018 0.07499998 -0.07086575 -0.04441493 0.07499998 -0.07216519 -0.04404544 0.07499998 -0.07362431 -0.0433802 0.07499998 -0.07495373 -0.04247289 0.07499998 -0.07615488 -0.04118746 0.07499998 -0.07723581 -0.03951954 0.07499998 -0.07809269 -0.03769505 0.07499998 -0.07847917 -0.03600937 0.07499998 -0.07845282 -0.03402268 0.07499998 -0.07791304 -0.03242248 0.07499998 -0.07695543 -0.03120464 0.07499998 -0.07578951 -0.03038573 0.07499998 -0.07454848 -0.02979922 0.07499998 -0.07316225 -0.02949333 0.07499998 -0.07137459 -0.03375869 0.07499998 -0.0737589 -0.03445303 0.07499998 -0.07441526 -0.03312093 0.07499998 -0.07278722 -0.03534561 0.07499998 -0.07492458 -0.0365746 0.07499998 -0.07525175 -0.0327956 0.07499998 -0.07166403 -0.03274923 0.07499998 -0.0707134 -0.03798121 0.07499998 -0.07515084 -0.0329315 0.07499998 -0.06974506 -0.03916108 0.07499998 -0.07467722 -0.03341388 0.07499998 -0.06868392 -0.03999334 0.07499998 -0.07402604 -0.03418278 0.07499998 -0.06780767 -0.04059606 0.07499998 -0.07328456 -0.03496313 0.07499998 -0.06725955 -0.04103726 0.07499998 -0.0723564 -0.03594839 0.07499998 -0.06686991 -0.04124993 0.07499998 -0.0713185 -0.0368939 0.07499998 -0.06674587 -0.04117399 0.07499998 -0.07012259 -0.03791695 0.07499998 -0.06683444 -0.04059737 0.07499998 -0.06867659 -0.03932201 0.07499998 -0.06740474 0.06450659 0.07499998 -0.07062536 0.06424486 0.07499998 -0.06901687 0.06354743 0.07499998 -0.06728708 0.06241416 0.07499998 -0.06579345 0.06127512 0.07499998 -0.06482386 0.05979907 0.07499998 -0.06402206 0.05774974 0.07499998 -0.06350737 0.05569493 0.07499998 -0.06359815 0.05413126 0.07499998 -0.06405794 0.05281251 0.07499998 -0.06476408 0.05139511 0.07499998 -0.06597608 0.05043059 0.07499998 -0.06736922 0.04989677 0.07499998 -0.0685575 0.04951637 0.07499998 -0.0702511 0.04955369 0.07499998 -0.07198667 0.04984146 0.07499998 -0.0732572 0.05034017 0.07499998 -0.07447385 0.05139511 0.07499998 -0.07602393 0.05281251 0.07499998 -0.07723587 0.05448043 0.07499998 -0.07809263 0.05630493 0.07499998 -0.07847917 0.05799055 0.07499998 -0.07845282 0.05997723 0.07499998 -0.07791304 0.06157749 0.07499998 -0.07695543 0.06263047 0.07499998 -0.07596898 0.06370073 0.07499998 -0.07443529 0.06438022 0.07499998 -0.07243454 0.05964022 0.07499998 -0.07436543 0.06049978 0.07499998 -0.07342255 0.06099659 0.07499998 -0.07248979 0.05842709 0.07499998 -0.07501423 0.05749934 0.07499998 -0.07522702 0.06124597 0.07499998 -0.07135021 0.05643695 0.07499998 -0.07522791 0.06117123 0.07499998 -0.07008248 0.05521571 0.07499998 -0.0748741 0.06073915 0.07499998 -0.06896382 0.05426222 0.07499998 -0.07426255 0.06012535 0.07499998 -0.06809997 0.05341047 0.07499998 -0.07331824 0.05933445 0.07499998 -0.0674408 0.05835902 0.07499998 -0.06695514 0.05280059 0.07499998 -0.07181406 0.05731797 0.07499998 -0.06675648 0.05279988 0.07499998 -0.07022529 0.05618667 0.07499998 -0.06680715 0.05330288 0.07499998 -0.06886547 0.05489605 0.07499998 -0.06728971 0.05402725 0.07499998 -0.06795203 0.02299624 0.07199996 -0.03714948 0.02300071 0.07200086 -0.03714901 0.02295207 0.07199996 -0.03757381 0.02281814 0.07599997 -0.03804975 0.0226897 0.07199996 -0.03835272 0.02238869 0.07599997 -0.03883922 0.02201956 0.07199996 -0.03925168 0.02149116 0.07599997 -0.03963154 0.02091294 0.07199996 -0.03987807 0.02035123 0.07599997 -0.03999423 0.01972329 0.07199996 -0.04000669 0.01945555 0.07599997 -0.03995764 0.0187146 0.07199996 -0.03972256 0.01853477 0.07599997 -0.03964012 0.017744 0.07199996 -0.03902357 0.01772725 0.07599997 -0.03897464 0.01724612 0.07599997 -0.03821694 0.01721096 0.07199996 -0.03811746 0.01700264 0.07199996 -0.03732377 0.01696997 0.07599997 -0.03703641 0.01705962 0.07199996 -0.03635269 0.01745057 0.07199996 -0.03538209 0.01810735 0.07199996 -0.03466284 0.01876264 0.07199996 -0.03425782 0.01957422 0.07199996 -0.03401947 0.02039629 0.07199996 -0.03401887 0.02140152 0.07199996 -0.03431957 0.0223084 0.07199996 -0.03506302 0.02285444 0.07199996 -0.03601551 0.02299636 0.07199996 -0.03685039 0.01284402 0.07599997 -0.037 0.0230025 0.0719996 -0.03685015 0.023292 0.07199996 -0.03563928 0.02410173 0.07199996 -0.03465783 0.02488029 0.07199996 -0.03420883 0.02575099 0.07199996 -0.03399544 0.02694016 0.07199996 -0.03412508 0.02791738 0.07199996 -0.03467875 0.02851635 0.07199996 -0.03534698 0.02893823 0.07199996 -0.03630459 0.02899456 0.07199996 -0.03727698 0.02900624 0.07599997 -0.03700172 0.02885055 0.07599997 -0.03801155 0.02881103 0.07199996 -0.0380783 0.02835488 0.07199996 -0.03887796 0.02827274 0.07599997 -0.03897464 0.0277549 0.07199996 -0.03944098 0.02769291 0.07599997 -0.03948318 0.02705156 0.07199996 -0.03982114 0.02700775 0.07599997 -0.03983706 0.02629911 0.07199996 -0.03999042 0.02599996 0.07599997 -0.04001784 0.02547669 0.07199996 -0.03996759 0.02489805 0.07599997 -0.03980773 0.02444618 0.07199996 -0.03958892 0.02412551 0.07599997 -0.03935045 0.02361124 0.07199996 -0.03883922 0.02343177 0.07599997 -0.03859788 0.02310001 0.07199996 -0.03784096 0.02299553 0.07599997 -0.03733754 0.04199802 0.07599997 -0.03700011 0.0230025 0.0719996 -0.08185017 0.02300071 0.07200086 -0.08214902 0.02299928 0.07599997 -0.08174759 0.02326434 0.07199996 -0.08070957 0.02318179 0.07599997 -0.0809502 0.02369862 0.07599997 -0.08003711 0.0241506 0.07199996 -0.07959902 0.02451586 0.07599997 -0.07938432 0.02530598 0.07199996 -0.07906615 0.0252797 0.07599997 -0.07907664 0.02624893 0.07599997 -0.07899546 0.02627652 0.07199996 -0.07900196 0.02707767 0.07199996 -0.07919239 0.02733176 0.07599997 -0.07929009 0.02792233 0.07199996 -0.07967156 0.0281158 0.07599997 -0.07986283 0.02863615 0.07199996 -0.08053725 0.02865892 0.07599997 -0.08057904 0.02896624 0.07199996 -0.08147698 0.02893388 0.07599997 -0.08135211 0.02900624 0.07599997 -0.08199822 0.02897745 0.07199996 -0.0824728 0.02866852 0.07199996 -0.08339411 0.02792912 0.07199996 -0.08433729 0.02686518 0.07199996 -0.08488374 0.02574968 0.07199996 -0.08501434 0.02453482 0.07199996 -0.08464014 0.02367526 0.07199996 -0.08391958 0.02311134 0.07199996 -0.08289104 0.0419777 0.07599997 -0.08199006 0.02299666 0.0719999 -0.08214962 0.02284097 0.07199996 -0.08300876 0.02218657 0.07199996 -0.08409839 0.02125734 0.07199996 -0.08473187 0.02039837 0.07199996 -0.08498835 0.01949995 0.07199996 -0.08496546 0.01857715 0.07199996 -0.08466315 0.01770579 0.07199996 -0.08395594 0.0171169 0.07199996 -0.08291476 0.01700228 0.07199996 -0.08162432 0.01699697 0.07599997 -0.08199977 0.01705318 0.07599997 -0.08140426 0.01735103 0.07599997 -0.0805574 0.01729124 0.07199996 -0.08069562 0.01772719 0.07199996 -0.08002537 0.01802301 0.07599997 -0.07972389 0.01861917 0.07199996 -0.07930672 0.01869654 0.07599997 -0.07929366 0.01954972 0.07599997 -0.07901263 0.01964837 0.07199996 -0.07901328 0.0205233 0.07199996 -0.07903236 0.02089267 0.07599997 -0.07910597 0.02164202 0.07199996 -0.07945752 0.02203595 0.07599997 -0.0797702 0.0223965 0.07199996 -0.08018481 0.02275377 0.07599997 -0.08075743 0.022794 0.07199996 -0.08087837 0.02299779 0.07199972 -0.08185005 -0.02199798 0.07599997 -0.08199965 -0.02675026 0.07199996 -0.08185517 -0.02653056 0.07199996 -0.08109956 -0.02586984 0.07199996 -0.08046489 -0.02507376 0.07199996 -0.08023369 -0.02413797 0.07199996 -0.08044743 -0.02351284 0.07199996 -0.08105623 -0.02326303 0.07199996 -0.08170795 -0.02328598 0.07199996 -0.08240556 -0.02365213 0.07199996 -0.08314973 -0.0244494 0.07199996 -0.0836839 -0.0252763 0.07199996 -0.08373951 -0.02581191 0.07199996 -0.08355504 -0.02627062 0.07199996 -0.0832197 -0.02668029 0.07199996 -0.08254939 -0.0267384 0.07199996 -0.03667896 -0.02642184 0.07199996 -0.03596043 -0.02586984 0.07199996 -0.03546488 -0.02516138 0.07199996 -0.03524601 -0.02455341 0.07199996 -0.03530144 -0.02403414 0.07199996 -0.03553026 -0.02356171 0.07199996 -0.03598326 -0.02330571 0.07199996 -0.0365374 -0.02324426 0.07199996 -0.0371015 -0.02345103 0.07199996 -0.03785991 -0.02398467 0.07199996 -0.03843593 -0.02457904 0.07199996 -0.03871029 -0.02523243 0.07199996 -0.03874319 -0.02585464 0.07199996 -0.03854006 -0.02641499 0.07199996 -0.03805392 -0.02670758 0.07199996 -0.03742045 0.04332357 0.07199996 -0.03646844 0.04365754 0.07199996 -0.03585499 0.04440629 0.07199996 -0.03532636 0.04540824 0.07199996 -0.03527599 0.04610723 0.07199996 -0.03563368 0.04662454 0.07199996 -0.03628283 0.04675227 0.07199996 -0.03723394 0.04649329 0.07199996 -0.03792881 0.04608559 0.07199996 -0.03838354 0.04546409 0.07199996 -0.03870224 0.04476749 0.07199996 -0.03874319 0.04414528 0.07199996 -0.03854006 0.04358494 0.07199996 -0.03805398 0.04324603 0.07199996 -0.03724974 0.04329365 0.07199996 -0.08155083 0.04365754 0.07199996 -0.08085501 0.04421001 0.07199996 -0.08042877 0.04492616 0.07199996 -0.08023369 0.04586195 0.07199996 -0.08044743 0.0464608 0.07199996 -0.08102077 0.04669421 0.07199996 -0.08153742 0.04675227 0.07199996 -0.08223396 0.04637926 0.07199996 -0.08311843 0.04555052 0.07199996 -0.0836839 0.04472362 0.07199996 -0.08373951 0.04418802 0.07199996 -0.08355504 0.0437293 0.07199996 -0.0832197 0.04328668 0.07199996 -0.08246695 -0.0245282 0.07199996 -0.03401249 -0.02334934 0.07199996 -0.0344718 -0.02250027 0.07199996 -0.03530651 -0.02203989 0.07199996 -0.03640466 -0.02202993 0.07199996 -0.03751802 -0.02199798 0.07599997 -0.03700029 -0.02209132 0.07599997 -0.03780937 -0.02241933 0.07199996 -0.03856736 -0.02262628 0.07599997 -0.03886562 -0.02322602 0.07199996 -0.03944319 -0.02352625 0.07599997 -0.03963494 -0.0240274 0.07199996 -0.03984272 -0.02436 0.07599997 -0.03993552 -0.02477675 0.07199996 -0.04000359 -0.02499914 0.07599997 -0.04000616 -0.02561789 0.07199996 -0.03994315 -0.02650892 0.07199996 -0.03961348 -0.02730727 0.07199996 -0.03893607 -0.02781498 0.07199996 -0.03807926 -0.0280255 0.07199996 -0.0368244 -0.0276401 0.07199996 -0.03553479 -0.02697461 0.07199996 -0.03472721 -0.0259419 0.07199996 -0.03411948 -0.0249983 0.07599997 -0.07899385 -0.02209132 0.07599997 -0.08119064 -0.02436 0.07599997 -0.07906442 -0.02352631 0.07599997 -0.07936495 -0.02262628 0.07599997 -0.08013427 0.04224252 0.07599997 -0.08077049 0.04292738 0.07599997 -0.07980465 0.04393094 0.07599997 -0.07917648 0.00784403 0.07599997 -0.03860217 0.00784403 0.07599997 -0.037 0.01284402 0.07599997 -0.03860217 0.04253715 0.07599997 -0.03874629 0.04339814 0.07599997 -0.03955906 0.04207664 0.07599997 -0.03773611 0.04421621 0.07599997 -0.03990042 0.04499387 0.07599997 -0.07898736 0.04499691 0.07599997 -0.04001283 -0.02433151 0.07199996 -0.07905393 -0.02322596 0.07199996 -0.07955676 -0.02241933 0.07199996 -0.08043265 -0.02202993 0.07199996 -0.08148193 -0.02203077 0.07199996 -0.08252263 -0.02229195 0.07199996 -0.08330172 -0.02273708 0.07199996 -0.08399212 -0.0234276 0.07199996 -0.08456361 -0.02417832 0.07199996 -0.0848965 -0.02529257 0.07199996 -0.08501052 -0.02636456 0.07199996 -0.08468383 -0.02720504 0.07199996 -0.08406269 -0.02783244 0.07199996 -0.08304601 -0.02801644 0.07199996 -0.08186572 -0.02772825 0.07199996 -0.08070635 -0.02701306 0.07199996 -0.07974958 -0.02625316 0.07199996 -0.07926923 -0.0254718 0.07199996 -0.0790224 0.0456472 0.07199996 -0.03405958 0.04661786 0.07199996 -0.03445053 0.04743385 0.07199996 -0.03522086 0.04796552 0.07199996 -0.03637546 0.04794436 0.07199996 -0.0376476 0.04747003 0.07199996 -0.03874576 0.04659223 0.07199996 -0.03956001 0.04554802 0.07199996 -0.03996926 0.04425734 0.07199996 -0.0399338 0.04310697 0.07199996 -0.03935217 0.04234474 0.07199996 -0.03843736 0.04202187 0.07199996 -0.03744339 0.04203987 0.07199996 -0.03640466 0.04250025 0.07199996 -0.03530657 0.04334938 0.07199996 -0.0344718 0.04452818 0.07199996 -0.03401249 0.04547178 0.07199996 -0.0790224 0.04659527 0.07199996 -0.07943022 0.04750543 0.07199996 -0.08031493 0.04796284 0.07199996 -0.08141839 0.04795652 0.07199996 -0.08261293 0.04759818 0.07199996 -0.08351451 0.04698914 0.07199996 -0.0842716 0.04588228 0.07199996 -0.08489316 0.04476755 0.07199996 -0.08500182 0.04396581 0.07199996 -0.08482396 0.04311376 0.07199996 -0.08435785 0.04238772 0.07199996 -0.08350509 0.04204863 0.07199996 -0.08259558 0.04199904 0.07199996 -0.08185076 0.04216092 0.07199996 -0.08097219 0.04277908 0.07199996 -0.0799545 0.04374253 0.07199996 -0.07925498 0.04462838 0.07199996 -0.07901769 0.01284402 0.07600373 -0.02860212 0.00784403 0.07600373 -0.02860212 0.00784403 0.07600027 -0.01760214 0.01284402 0.07600015 -0.01760214 -0.01173269 0.06675887 -0.008013963 -0.01105993 0.06681448 -0.0080899 -0.01015955 0.06685757 -0.008484303 -0.009501636 0.06689423 -0.009062469 -0.0091331 0.06676077 -0.009642958 -0.008995175 0.07183241 -0.009914159 -0.008796751 0.0719285 -0.0107212 -0.008800506 0.06686526 -0.01084685 -0.008816599 0.07214367 -0.01140838 -0.008952856 0.06672233 -0.01193982 -0.009070336 0.07250481 -0.01229411 -0.009226977 0.06689774 -0.01256495 -0.009566247 0.07280206 -0.01302158 -0.009647965 0.06685554 -0.01309853 -0.01011657 0.07295644 -0.0135017 -0.01010185 0.06669491 -0.01346266 -0.01079148 0.06698644 -0.01384729 -0.01151561 0.06677037 -0.01398479 -0.01219546 0.0668165 -0.01398158 -0.01282751 0.0667752 -0.01381552 -0.01353985 0.06673824 -0.01344186 -0.01406711 0.06685322 -0.01296347 -0.01445227 0.06677192 -0.01238751 -0.01470935 0.06672632 -0.01170676 -0.01479256 0.06686252 -0.01116394 -0.0145756 0.06672179 -0.009899675 -0.01431614 0.06669354 -0.009399592 -0.01395076 0.06685167 -0.008917033 -0.01349163 0.06669199 -0.008547365 -0.01299679 0.06685721 -0.008256435 -0.01204186 0.07292723 -0.008009314 -0.01178139 0.06550705 -0.009293973 -0.01238435 0.06604403 -0.008396565 -0.01179677 0.06597596 -0.008384704 -0.0120691 0.06569153 -0.008762836 -0.01246559 0.06553888 -0.009236693 -0.0131607 0.06550896 -0.009969353 -0.01347601 0.06564128 -0.009643435 -0.01333808 0.0654996 -0.01118034 -0.01375377 0.06555497 -0.01079797 -0.01356846 0.06553971 -0.01167428 -0.01315408 0.06563723 -0.01267772 -0.0125429 0.06550794 -0.01257812 -0.0125333 0.06560665 -0.01294362 -0.01081883 0.06655657 -0.0137822 -0.01109784 0.06551337 -0.01267647 -0.01189178 0.06568127 -0.01324361 -0.0106247 0.06550353 -0.01221531 -0.0101068 0.06563317 -0.0123226 -0.009905517 0.06552928 -0.01117563 -0.0104289 0.06549948 -0.01016998 -0.009700119 0.06562334 -0.0114175 -0.01050692 0.06552386 -0.009716093 -0.009908199 0.06565827 -0.009884357 -0.01040345 0.06564825 -0.009336292 -0.0111432 0.06563925 -0.008939921 -0.01121395 0.06596553 -0.008469581 -0.01240998 0.06678867 -0.008069455 -0.01202225 0.06648486 -0.008093535 -0.01303344 0.06637042 -0.008404314 -0.01333695 0.06597167 -0.008895933 -0.01282441 0.06593561 -0.008651316 -0.01380252 0.06640642 -0.008921742 -0.01296252 0.06569176 -0.009076893 -0.01406979 0.06617516 -0.009431898 -0.01386165 0.06596803 -0.009400427 -0.01434975 0.06616121 -0.009966909 -0.01472842 0.06666761 -0.01041513 -0.01403361 0.06575971 -0.01022833 -0.01464718 0.06633061 -0.01100635 -0.0144447 0.0660634 -0.01055085 -0.0143963 0.06622338 -0.01204228 -0.0144726 0.06611382 -0.01150709 -0.01422446 0.06642347 -0.01258265 -0.01428425 0.06585425 -0.0110144 -0.01380252 0.06640642 -0.01308739 -0.01392495 0.06609725 -0.01268357 -0.01404982 0.06577295 -0.01180744 -0.01367717 0.06577819 -0.01248925 -0.01316076 0.06638485 -0.01354092 -0.01333701 0.06597161 -0.0131132 -0.01270377 0.06626075 -0.01367098 -0.01255106 0.06596422 -0.01350498 -0.01256418 0.06578588 -0.01327663 -0.01207995 0.06634432 -0.01385354 -0.0116381 0.06623309 -0.0138126 -0.01043272 0.06638485 -0.01354092 -0.0108391 0.06612515 -0.01355928 -0.0113852 0.06591707 -0.01352345 -0.01022469 0.06596416 -0.01308304 -0.01096123 0.06576299 -0.01322865 -0.009791016 0.06640636 -0.01308739 -0.009668648 0.06609725 -0.01268357 -0.01039707 0.06569623 -0.01277154 -0.009369015 0.06642347 -0.0125826 -0.009704291 0.0658226 -0.0122826 -0.009318351 0.06610924 -0.01212942 -0.008847296 0.06671553 -0.01150256 -0.008998334 0.06622153 -0.01100456 -0.009149789 0.06611526 -0.01166117 -0.008884429 0.06672996 -0.0102964 -0.009151697 0.06620562 -0.01011151 -0.009324371 0.06638067 -0.009527683 -0.009515285 0.06572836 -0.01062858 -0.009676277 0.06638097 -0.009055495 -0.009747922 0.06594383 -0.009424626 -0.009342253 0.06591135 -0.01028186 -0.01027083 0.06637084 -0.008563697 -0.01009595 0.06614381 -0.008848488 -0.01070833 0.06636673 -0.008345842 -0.01055061 0.06591874 -0.008766531 -0.01135182 0.06634151 -0.008184313 -0.009375572 0.06581825 -0.01132589 0.03270268 0.06668549 -0.008021473 0.03266406 0.06550717 -0.009294867 0.03149574 0.0668596 -0.008259057 0.03099292 0.06669718 -0.008554279 0.03270316 0.06597596 -0.008384704 0.03217536 0.06588011 -0.008544147 0.0304746 0.06671178 -0.009007394 0.03243017 0.06560522 -0.008938312 0.03008383 0.06685709 -0.009543776 0.02986139 0.06672734 -0.01006489 0.03153866 0.0655061 -0.009750604 0.03133857 0.06563919 -0.009332835 0.0297178 0.06680405 -0.01133143 0.03092205 0.06553786 -0.01036763 0.029926 0.06674593 -0.01213401 0.03016126 0.06660628 -0.01251935 0.03041392 0.06689697 -0.01295393 0.0304771 0.06568276 -0.01069009 0.03131306 0.0655027 -0.01194483 0.0310589 0.06666988 -0.01349645 0.03168743 0.06693661 -0.01384085 0.03091591 0.06553179 -0.01146 0.03088003 0.06564539 -0.01217597 0.03134948 0.06563925 -0.01268512 0.03215646 0.06552821 -0.01275473 0.03406304 0.06683319 -0.0136826 0.03306812 0.06550848 -0.01270782 0.03465837 0.06670957 -0.01326614 0.03256732 0.06563276 -0.01313364 0.03498792 0.06668949 -0.0129314 0.03536385 0.0667575 -0.01237064 0.03561091 0.06672048 -0.01172238 0.03403526 0.06563317 -0.01268404 0.0338695 0.06550353 -0.01222383 0.03338897 0.06565618 -0.01307672 0.03569793 0.06686836 -0.01122272 0.03565055 0.06673043 -0.01047635 0.03452473 0.06554675 -0.01166743 0.03547626 0.06679934 -0.009869992 0.03524512 0.06668478 -0.009441912 0.03419524 0.06550401 -0.01016765 0.03489118 0.06669133 -0.008972883 0.03499317 0.06570607 -0.01084715 0.03446525 0.066715 -0.008588731 0.03405123 0.06669783 -0.008335292 0.03331452 0.0667876 -0.008069276 0.03469508 0.06562668 -0.01023954 0.0340662 0.06564217 -0.009328901 0.03329509 0.06553614 -0.009227335 0.03208953 0.0667926 -0.00806874 0.0320599 0.06628376 -0.00824207 0.03144335 0.06636321 -0.008426249 0.03102093 0.06611555 -0.008854687 0.0317192 0.06582766 -0.008745729 0.03054708 0.06614381 -0.009303748 0.03023082 0.06638067 -0.009527683 0.03112268 0.06585335 -0.009090542 0.03053551 0.06587356 -0.009742796 0.03077548 0.06569176 -0.009838879 0.02992612 0.06625652 -0.01053351 0.02973455 0.06677287 -0.01062238 0.02989792 0.06623476 -0.01103621 0.02991288 0.06633126 -0.01158154 0.03021985 0.06586343 -0.01131689 0.03016799 0.06618422 -0.01213294 0.03071194 0.06637084 -0.01308363 0.03054708 0.06614381 -0.01270538 0.03053486 0.06587821 -0.0122745 0.03056281 0.06569975 -0.0117439 0.03112322 0.06594383 -0.01305335 0.03145402 0.06611657 -0.01343327 0.03179311 0.06625217 -0.01366543 0.03216326 0.06658387 -0.0139048 0.03256696 0.06686031 -0.01400518 0.03195655 0.0657562 -0.01324635 0.03270316 0.06632894 -0.01385438 0.03327363 0.06673026 -0.01394397 0.03240793 0.06606811 -0.01367986 0.03402757 0.06639182 -0.01356703 0.03332668 0.06610971 -0.01366323 0.03288656 0.06578856 -0.01340186 0.03391057 0.06588602 -0.01322674 0.03440397 0.06614381 -0.01316064 0.03485304 0.06611555 -0.01268678 0.03517556 0.06638067 -0.01248145 0.03453099 0.0657621 -0.01251572 0.03536897 0.0662598 -0.01191198 0.03500372 0.06588256 -0.01202946 0.03548026 0.06618005 -0.01111638 0.0351538 0.06587463 -0.01153606 0.03530782 0.06631791 -0.009844183 0.03517431 0.06600415 -0.01006525 0.03488159 0.06616342 -0.009311199 0.03457754 0.06577509 -0.009518861 0.03440397 0.06614381 -0.008848488 0.03417116 0.0658648 -0.008994698 0.03379023 0.06625121 -0.008404672 0.03318023 0.06626051 -0.008227348 0.0334984 0.06591981 -0.008565723 0.03338545 0.06569808 -0.008843719 0.03012853 0.06604194 -0.01026797 0.0353477 0.0660603 -0.01053643 0.03252941 0.07286071 -0.007990658 0.03358405 0.07300227 -0.008123278 0.03081381 0.07291704 -0.01333886 0.02980363 0.0723412 -0.01184409 0.02982938 0.07186752 -0.0100969 0.03024595 0.07195287 -0.009266018 0.03073203 0.07216501 -0.008734285 0.03145128 0.07249331 -0.00826174 0.01284402 0.07100313 -0.02235013 0.01452052 0.07159006 -0.02261304 0.01469969 0.07101005 -0.0220443 0.01284408 0.07176572 -0.02306979 0.01439183 0.07195544 -0.0230655 0.01284545 0.07229393 -0.02380299 0.01284444 0.07278263 -0.02490514 0.01672023 0.07100224 -0.02149075 0.01498454 0.07271039 -0.02436089 0.01538264 0.07228523 -0.02334809 0.01284408 0.07298141 -0.02588927 0.01666617 0.0716421 -0.02211201 0.01578062 0.07290977 -0.02491956 0.01753818 0.07211714 -0.02244663 0.01663082 0.07264405 -0.02376502 0.01857471 0.07132697 -0.02106761 0.01844483 0.07179594 -0.02164375 0.01798182 0.07256388 -0.02310788 0.01993525 0.07099992 -0.02013802 0.01841306 0.07289969 -0.02406793 0.02026677 0.07139027 -0.02029442 0.01994347 0.07253217 -0.02221071 0.0196467 0.0721417 -0.02159881 0.0203951 0.07174038 -0.0206319 0.02135264 0.07211178 -0.02063095 0.02113407 0.07287627 -0.02271825 0.02196234 0.07156348 -0.01943248 0.02243757 0.07099997 -0.01850789 0.02198106 0.07251822 -0.02105367 0.02280116 0.07137978 -0.01862275 0.02271068 0.07282221 -0.02157169 0.0233196 0.07211697 -0.01929324 0.02351349 0.07271045 -0.02059489 0.02443379 0.07100033 -0.01680338 0.02383655 0.07177817 -0.01831358 0.02371084 0.07251632 -0.01985257 0.02422255 0.07135629 -0.01739346 0.02498722 0.07226747 -0.01817554 0.02545487 0.07298403 -0.02061837 0.02540129 0.07193827 -0.01711362 0.02614092 0.07261842 -0.01805722 0.02588063 0.07169878 -0.01617819 0.02551609 0.07282423 -0.01944494 0.02588278 0.07100111 -0.01519387 0.02643263 0.07226377 -0.01669216 0.02687025 0.07136976 -0.0144242 0.02722793 0.07100009 -0.01336777 0.02740073 0.07196205 -0.01477962 0.02760022 0.07289248 -0.01772707 0.02788215 0.0725342 -0.01571989 0.02848917 0.07169538 -0.01249444 0.02866256 0.07212609 -0.01331114 0.0291987 0.07287114 -0.01552951 0.02861106 0.07132828 -0.01148802 0.02845019 0.07100003 -0.01121097 0.02928727 0.07248574 -0.01341968 0.02945065 0.07168698 -0.01047396 0.02969777 0.07202512 -0.01094526 0.0292499 0.07100248 -0.009263455 0.03029578 0.07273578 -0.0128172 0.02997171 0.07163476 -0.008912324 0.03025919 0.07158243 -0.007709443 0.02990084 0.07100009 -0.00708872 0.03050988 0.07155388 -0.006469726 0.03026151 0.07100087 -0.005088686 0.0312615 0.07211911 -0.006250441 0.0307163 0.0715295 -0.005153357 0.03195726 0.07253038 -0.006370663 0.03281354 0.07278656 -0.005463063 0.03161901 0.07218837 -0.004158616 0.03042179 0.07100021 -0.00315696 0.03083938 0.07149446 -0.003107845 0.03229868 0.07253396 -0.003648459 0.03357326 0.07292562 -0.003878653 0.0313971 0.07198882 -0.002619862 0.03068417 0.07136982 -0.001069903 0.03029567 0.07099997 4.56513e-5 0.0313977 0.07202571 -0.001007318 0.03301024 0.07279914 -0.001986205 0.03417199 0.07299715 -0.001224815 0.03231275 0.07257556 -4.81783e-4 0.03048169 0.07141548 9.35857e-4 0.03106331 0.07202416 0.001594126 0.03172641 0.07239049 0.001141786 0.03305268 0.0728926 0.001538991 0.03019076 0.07159292 0.002993702 0.02932989 0.07100087 0.004094183 0.03217983 0.07278275 0.003414273 0.03115576 0.07233178 0.003180742 0.02943801 0.07146203 0.004869639 0.02982497 0.0720039 0.005584001 0.03118711 0.07252615 0.004377543 0.02866822 0.07150852 0.006702482 0.0281797 0.07100081 0.006699323 0.02987891 0.07231664 0.006622493 0.03090494 0.0726723 0.006117582 0.0314359 0.07289576 0.006804704 0.02784478 0.07144194 0.008045315 0.02655184 0.07100087 0.009355306 0.02874922 0.07215082 0.008166849 0.02961671 0.07262825 0.008468806 0.0271371 0.07158976 0.009399473 0.02985829 0.0728324 0.009273886 0.02764362 0.07210087 0.009761273 0.02442383 0.07100009 0.01180326 0.02792114 0.07254087 0.0106827 0.02594989 0.07165509 0.01101034 0.02936863 0.07298642 0.01150453 0.02502304 0.07136929 0.01161158 0.02638751 0.0721544 0.01147145 0.02758425 0.07284098 0.01245969 0.02444392 0.07169502 0.01261866 0.02597552 0.07239824 0.0125066 0.02574032 0.07259303 0.01331394 0.02316367 0.07161843 0.01359409 0.0219838 0.07100015 0.01382797 0.02381575 0.07221454 0.01407408 0.02723795 0.07298129 0.01394408 0.02201288 0.07150864 0.01433098 0.02418184 0.07263815 0.01483631 0.02426415 0.07284337 0.0155937 0.02149796 0.07206708 0.0154432 0.02027118 0.07100099 0.01489806 0.02028006 0.07151895 0.0154066 0.02195423 0.07254254 0.0161156 0.01779466 0.07100015 0.01610666 0.02049821 0.07252579 0.01690697 0.01964414 0.07199615 0.01635283 0.02101898 0.07291716 0.01806443 0.0183897 0.0713827 0.01618748 0.02078932 0.07282185 0.01766753 0.01892751 0.07239454 0.01735496 0.01749116 0.07165914 0.0168296 0.0177735 0.07215559 0.01739925 0.01556009 0.07158821 0.01734834 0.01473307 0.07100015 0.01703339 0.01777869 0.07272756 0.01862025 0.01637995 0.07244426 0.01838231 0.01575368 0.07211828 0.01797771 0.01724165 0.0729019 0.0194565 0.01250529 0.07099997 0.01739293 0.01356464 0.07152259 0.01769858 0.01490175 0.07288956 0.02000141 0.01366722 0.07206416 0.01832747 0.01434767 0.07278585 0.01971101 0.01376515 0.07253253 0.01911419 0.01152843 0.07141149 0.01780605 0.01529788 0.07299309 0.020684 0.01103609 0.07193547 0.0184074 0.0097934 0.07100051 0.01749265 0.01104503 0.07232105 0.01898044 0.009611308 0.07141298 0.01782011 0.0116195 0.07260549 0.0195145 0.01294684 0.07299041 0.02099359 0.01054167 0.07282441 0.02019882 0.01055353 0.07298463 0.02103203 0.008412361 0.07206547 0.01848316 0.007534086 0.07100087 0.01728224 0.008904218 0.0725314 0.01932096 0.007460296 0.07157999 0.01778542 0.006357312 0.07197296 0.01805955 0.006008803 0.07143265 0.01736152 0.004955589 0.07100802 0.0167213 0.007203936 0.07268238 0.01948994 0.006278336 0.07234412 0.01860803 0.006002187 0.07290834 0.02013248 0.00393331 0.07177823 0.01719063 0.003080725 0.07099997 0.01611143 0.004257559 0.07215684 0.01779431 0.004378914 0.07280939 0.01931041 0.004676103 0.07256168 0.01867479 0.002634465 0.07133972 0.01621621 0.003096103 0.07299327 0.02004969 0.002284646 0.07275009 0.01836568 0.002183854 0.07226711 0.01722854 0.001526474 0.07176786 0.0161913 4.81384e-4 0.07100057 0.01486366 0.001060426 0.07298356 0.01907998 1.21145e-4 0.07158696 0.01520973 4.3979e-4 0.07253003 0.01696175 3.68282e-4 0.07210797 0.01609677 -0.002051174 0.07099997 0.0131452 -9.69792e-4 0.07144302 0.01438099 -8.32177e-4 0.07282561 0.01719611 -0.001531004 0.07227665 0.01524484 -0.002057671 0.07153654 0.01369273 -0.002408564 0.07261914 0.01547741 -0.002629399 0.07298737 0.01711326 -0.003131151 0.07213479 0.01375716 -0.003439009 0.07157289 0.01259326 -0.003669917 0.0728324 0.01531302 -0.003761887 0.07100117 0.01158314 -0.004927754 0.07298547 0.01534718 -0.004660904 0.07236075 0.01288974 -0.004781365 0.07144278 0.01104372 -0.004546284 0.07205975 0.01232671 -0.004978418 0.07264244 0.01341503 -0.005258202 0.07100081 0.009893715 -0.006518065 0.07282441 0.01260507 -0.0060063 0.07207059 0.01071608 -0.006550967 0.07100075 0.008086204 -0.006580173 0.07173687 0.009257495 -0.006593286 0.07253032 0.01122891 -0.007165968 0.07298541 0.0131334 -0.007110536 0.07136976 0.00772655 -0.007507026 0.07230633 0.009257912 -0.008496284 0.0727126 0.009333252 -0.008049488 0.07185721 0.007086157 -0.0094226 0.0729078 0.00922805 -0.008042156 0.07136976 0.005929768 -0.008235514 0.07099997 0.004763603 -0.008578419 0.07230389 0.007425069 -0.009889781 0.07277119 0.007118344 -0.009002983 0.07193571 0.005230009 -0.00883466 0.07142269 0.004062831 -0.009532451 0.07231861 0.005425572 -0.01107466 0.0729928 0.007412731 -0.01051908 0.07262307 0.00459659 -0.009463727 0.07157605 0.002493023 -0.009049534 0.07100105 0.002031505 -0.009863257 0.07207846 0.003308713 -0.01134198 0.072865 0.004391789 -0.01047646 0.0723707 0.002857804 -0.009533762 0.07100021 -9.38395e-4 -0.01020979 0.07198923 0.00126779 -0.00988084 0.07147771 -4.14327e-4 -0.0124579 0.07298564 0.002887248 -0.01173162 0.07277917 0.001445889 -0.01123118 0.0725159 3.29861e-4 -0.01056826 0.07204979 -8.35607e-4 -0.00987339 0.07136958 -0.002920806 -0.01229107 0.07283985 -0.001304149 -0.0105499 0.07199394 -0.002923369 -0.01152116 0.07257384 -0.001865983 -0.009432673 0.07099997 -0.005097925 -0.01298016 0.07296735 -0.001938104 -0.009677886 0.0713672 -0.005408346 -0.01006543 0.07170587 -0.004970133 -0.01126891 0.07248008 -0.004537761 -0.01061844 0.07214516 -0.005063474 -0.01185506 0.07273042 -0.004570305 -0.01231831 0.07287698 -0.004944026 -0.01004213 0.07200831 -0.007267951 -0.009205698 0.07149988 -0.008146166 -0.008669137 0.07099997 -0.008501887 -0.01069772 0.07241517 -0.007230579 -0.009435474 0.07195055 -0.009124398 -0.0114026 0.07277828 -0.008022487 -0.01039505 0.07240808 -0.008324861 -0.007546424 0.07100021 -0.01131612 -0.008494913 0.07148212 -0.01015889 -0.007842361 0.07144761 -0.01152145 -0.006561338 0.07100468 -0.01304239 -0.007106006 0.07176357 -0.01352429 -0.007739007 0.0722959 -0.01387572 -0.005670368 0.07139164 -0.01491731 -0.004712998 0.07099986 -0.01562261 -0.008373737 0.07268047 -0.01437246 -0.006140232 0.07199621 -0.0153858 -0.008261084 0.07287585 -0.01566499 -0.006590366 0.07259273 -0.01648652 -0.004480779 0.07157385 -0.01656675 -0.005571365 0.0722146 -0.01655924 -0.00678116 0.07299542 -0.01899844 -0.006669998 0.07290202 -0.01790022 -0.002947688 0.07139927 -0.01782226 -0.001943886 0.07100009 -0.01824063 -0.005302548 0.0726971 -0.01828914 -0.003611385 0.07197773 -0.01808178 -0.0040856 0.07235872 -0.01844871 -0.001842141 0.07155007 -0.01888591 -0.004555165 0.07287627 -0.0197848 -6.41734e-4 0.07148301 -0.0196551 -1.14035e-4 0.07099992 -0.01950997 -0.001778662 0.07204973 -0.01967418 -0.003244221 0.07263481 -0.01989525 -0.001696348 0.07238996 -0.02039968 -0.00310254 0.07296359 -0.02159535 6.2318e-5 0.0720703 -0.0208801 0.001281201 0.07151705 -0.02078551 0.002575457 0.07099992 -0.02093386 -0.002087771 0.07276964 -0.02118796 6.00287e-4 0.07253038 -0.02204972 0.003160357 0.07153898 -0.02163302 0.001928329 0.07211458 -0.02188599 5.45542e-5 0.07287204 -0.02286905 0.00298357 0.07222408 -0.02247655 0.005243659 0.07144397 -0.02221769 0.005652844 0.07100135 -0.02192723 0.003014445 0.0726251 -0.02333676 0.003076076 0.07281315 -0.02392983 0.004845976 0.07188785 -0.02260166 0.004466652 0.07230305 -0.02310967 0.007842123 0.07099986 -0.02235329 0.00482428 0.07297968 -0.02534931 0.007842838 0.07139068 -0.02267074 0.006448984 0.07196879 -0.02307343 0.005995452 0.07247918 -0.02383244 0.00606966 0.07279098 -0.02463281 0.00784403 0.07188636 -0.02319467 0.00784403 0.07241153 -0.02397638 0.00784403 0.07277977 -0.02487695 0.00784403 0.07297748 -0.02582597 0.01284474 0.07200515 -0.01959764 0.01498782 0.07100003 -0.0202071 0.01284402 0.07099997 -0.02059638 0.01491945 0.07200044 -0.01916742 0.01701337 0.07199698 -0.01846927 0.01839596 0.07100003 -0.01895701 0.01938509 0.07200026 -0.01726567 0.02148979 0.07099997 -0.01705801 0.02183103 0.07200038 -0.01548594 0.02414745 0.07099997 -0.01458495 0.02385044 0.07200342 -0.0133599 0.02626395 0.07099997 -0.01163542 0.02528297 0.07200062 -0.01130419 0.02628201 0.07199841 -0.009323894 0.02775573 0.07099997 -0.008325815 0.02703601 0.07200038 -0.007222115 0.02856403 0.07099997 -0.004786491 0.02748119 0.07200026 -0.005141794 0.02770489 0.0720005 -0.00253278 0.02865684 0.07099997 -0.001157283 0.02743601 0.07200044 4.5763e-4 0.02803057 0.07099997 0.002418577 0.02693331 0.07200032 0.002525866 0.02603322 0.07200479 0.004896819 0.02670991 0.07099997 0.005800306 0.02430897 0.07200074 0.007779359 0.02474695 0.07099997 0.008854269 0.02254962 0.07199841 0.009776473 0.02221894 0.07099997 0.01146012 0.02092564 0.07200354 0.01119506 0.01922589 0.07099997 0.01351487 0.01918363 0.07200044 0.012362 0.01722049 0.0719971 0.01336836 0.01588577 0.07099997 0.01493757 0.01513785 0.07200038 0.01409298 0.01266229 0.07200485 0.01461994 0.01233041 0.07100003 0.01567202 0.01008307 0.07199841 0.01474648 0.009153962 0.07099997 0.01571357 0.007938027 0.07200354 0.01457309 0.006014168 0.07099997 0.01523011 0.005883574 0.07200038 0.01413869 0.003793716 0.0719971 0.01343458 0.002595663 0.07099997 0.01400774 0.001494348 0.07200354 0.01226162 -5.13864e-4 0.07099997 0.01213383 -2.30993e-4 0.07200038 0.0110616 -0.001827478 0.0720005 0.009651422 -0.00319159 0.07099997 0.009682357 -0.003758668 0.07200056 0.007351517 -0.005332052 0.07099997 0.006749987 -0.005432009 0.07200056 0.004342138 -0.006850659 0.07099997 0.00345242 -0.0063712 0.07200044 0.00146836 -0.007687628 0.07099997 -8.02106e-5 -0.006818294 0.0720005 -0.001500725 -0.007809877 0.07099997 -0.003708541 -0.006675302 0.0720005 -0.004941046 -0.007212638 0.07099997 -0.007289469 -0.005828619 0.07199579 -0.008366286 -0.005919456 0.07099997 -0.01068168 -0.00433892 0.07200473 -0.01146453 -0.003981292 0.07099997 -0.01375138 -0.002325952 0.07200038 -0.01415979 -0.001474857 0.07099997 -0.01637744 2.38342e-4 0.07200038 -0.01645779 0.001501262 0.07100003 -0.01845639 0.003207385 0.07200032 -0.01820164 0.004829466 0.07100003 -0.01990616 0.005673527 0.0720002 -0.01909375 0.007843255 0.07199865 -0.01957941 0.007843852 0.07100003 -0.02058625 0.00784403 0.07599997 -0.01956218 0.005734622 0.07599997 -0.01912879 0.002636671 0.07599997 -0.01792621 7.03179e-5 0.07599997 -0.0163179 -0.001874864 0.07599997 -0.01461726 -0.003795504 0.07599997 -0.01231211 -0.005278348 0.07599997 -0.009671151 -0.006293356 0.07599997 -0.006847679 -0.006822168 0.07599997 -0.003443479 -0.006708085 0.07599997 -4.16876e-4 -0.006068229 0.07599997 0.002639293 -0.00471121 0.07599997 0.005805909 -0.003333449 0.07599997 0.007901489 -0.001958787 0.07599997 0.00951749 -2.54457e-5 0.07599997 0.01123166 0.001863479 0.07599997 0.01247435 0.003794014 0.07599997 0.01342773 0.006543457 0.07599997 0.01432675 0.009222567 0.07599997 0.01470774 0.01180648 0.07599997 0.01470994 0.01428264 0.07599997 0.01431202 0.01642268 0.07599997 0.01368647 0.01876926 0.07599997 0.01260483 0.02128261 0.07599997 0.01094013 0.02344024 0.07599997 0.0088346 0.025164 0.07599997 0.006511807 0.02650129 0.07599997 0.003794372 0.02726179 0.07599997 0.001324832 0.02768343 0.07599997 -0.001645743 0.02759283 0.07599997 -0.00427401 0.02725493 0.07599997 -0.006368637 0.02649009 0.07599997 -0.008836686 0.02516287 0.07599997 -0.01152759 0.02335107 0.07599997 -0.01395457 0.02141696 0.07599997 -0.01582652 0.01893579 0.07599997 -0.01753848 0.0162912 0.07599997 -0.01874476 0.01284509 0.07599997 -0.01963579 0.01443481 0.07599997 -0.002307236 0.01436913 0.07599997 -0.003228664 0.01399868 0.07599997 -0.004367589 0.0131902 0.07600182 -0.005414664 0.01244795 0.07600224 -0.00598663 0.01134467 0.0760017 -0.006411075 0.01040488 0.076002 -0.006515204 0.009570002 0.07600176 -0.006420552 0.008815109 0.07600164 -0.006174385 0.008123636 0.07600164 -0.005784213 0.007248282 0.07600158 -0.004976093 0.006540894 0.07600164 -0.003554105 0.006438434 0.0760017 -0.001969277 0.006823062 0.07600253 -7.17639e-4 0.007224202 0.07600164 -9.8207e-5 0.008145928 0.07599997 8.0929e-4 0.009610772 0.07599997 0.001434981 0.0112037 0.07599997 0.001443624 0.01267522 0.07599997 8.3379e-4 0.01379507 0.07599997 -2.99078e-4 0.01427769 0.07599997 -0.001396417 0.007247149 0.07600373 -0.005149126 0.008203268 0.07600373 -0.006011366 0.006716847 0.07600373 -0.004311263 0.009305298 0.07600373 -0.006471157 0.006385982 0.07600373 -0.003270924 0.01038265 0.07600373 -0.006621479 0.006372749 0.07600373 -0.001981377 0.01165264 0.07600373 -0.006397068 -0.037 0.07499998 0.03473806 -0.03808206 0.07499998 0.03487926 -0.03906548 0.07499998 0.03527373 -0.0399211 0.07499998 0.03589862 -0.04053366 0.07499998 0.03662711 -0.04100644 0.07499998 0.03754174 -0.04125815 0.07499998 0.0387544 -0.04115498 0.07499998 0.03994834 -0.04077655 0.07499998 0.04097193 -0.04003381 0.07499998 0.04200613 -0.03872811 0.07499998 0.0429129 -0.03749936 0.07499998 0.04322701 -0.03643685 0.07499998 0.04322791 -0.0350182 0.07499998 0.04279077 -0.0337755 0.07499998 0.04180067 -0.03305697 0.07499998 0.04062634 -0.03278666 0.07499998 0.03960454 -0.0327593 0.07499998 0.03854256 -0.03307121 0.07499998 0.0373438 -0.03366792 0.07499998 0.03634274 -0.03442835 0.07499998 0.03560495 -0.03560531 0.07499998 0.03495615 -0.0368939 0.07499998 -0.03025627 -0.03808641 0.07499998 -0.03013044 -0.03931313 0.07499998 -0.02958154 -0.04034072 0.07499998 -0.02866417 -0.04105913 0.07499998 -0.02732831 -0.04127037 0.07499998 -0.02575266 -0.04095411 0.07499998 -0.02441376 -0.04025471 0.07499998 -0.02322429 -0.03910392 0.07499998 -0.02228975 -0.03812384 0.07499998 -0.02189457 -0.03696632 0.07499998 -0.02172917 -0.03581827 0.07499998 -0.02191084 -0.03483897 0.07499998 -0.02232271 -0.03377556 0.07499998 -0.02319926 -0.03305697 0.07499998 -0.02437359 -0.03278666 0.07499998 -0.02539545 -0.0327593 0.07499998 -0.02645736 -0.03316098 0.07499998 -0.02788662 -0.03417104 0.07499998 -0.0292055 -0.03560531 0.07499998 -0.03004378 0.05689358 0.07499998 -0.03026568 0.05561029 0.07499998 -0.03003251 0.05460083 0.07499998 -0.02951896 0.0536592 0.07499998 -0.02866417 0.05299353 0.07499998 -0.02745819 0.05272829 0.07499998 -0.02610647 0.0529623 0.07499998 -0.02460783 0.05355948 0.07499998 -0.02348721 0.05428582 0.07499998 -0.02271598 0.05546903 0.07499998 -0.02200579 0.05703365 0.07499998 -0.02172917 0.05818164 0.07499998 -0.02191084 0.05906546 0.07499998 -0.02227371 0.06015872 0.07499998 -0.02311557 0.060943 0.07499998 -0.02437359 0.06127375 0.07499998 -0.02582091 0.06109982 0.07499998 -0.02715355 0.06060588 0.07499998 -0.02828878 0.05973953 0.07499998 -0.02926468 0.0584647 0.07499998 -0.03002417 0.05699998 0.07499998 0.03473806 0.05591785 0.07499998 0.03487926 0.0549345 0.07499998 0.03527373 0.05384117 0.07499998 0.03611558 0.05302608 0.07499998 0.03744029 0.05272829 0.07499998 0.03889346 0.0529623 0.07499998 0.04039216 0.05355948 0.07499998 0.04151272 0.05420607 0.07499998 0.04221111 0.05499053 0.07499998 0.04275673 0.05618679 0.07499998 0.0431928 0.05756306 0.07499998 0.04322791 0.05888336 0.07499998 0.04283326 0.05992108 0.07499998 0.04210126 0.06059604 0.07499998 0.04128456 0.06100994 0.07499998 0.04042744 0.06127375 0.07499998 0.03917908 0.06109982 0.07499998 0.03784638 0.06060588 0.07499998 0.03671115 0.05968499 0.07499998 0.03568589 0.05839467 0.07499998 0.03495615 0.05135148 0.07499998 0.03401511 0.05307835 0.07499998 0.03258234 0.05014455 0.07499998 0.03590673 0.05465811 0.07499998 0.03186297 0.04954868 0.07499998 0.03793573 0.05630743 0.07499998 0.03151357 0.04954713 0.07499998 0.03999066 0.05779385 0.07499998 0.0315361 0.05926972 0.07499998 0.03183239 0.04989993 0.07499998 0.04143494 0.05049091 0.07499998 0.04275792 0.0608015 0.07499998 0.0325216 0.06186062 0.07499998 0.03328037 0.05149221 0.07499998 0.04411041 0.06303489 0.07499998 0.03450173 0.05281138 0.07499998 0.0452435 0.06394201 0.07499998 0.03613126 0.05465805 0.07499998 0.04615324 0.06445127 0.07499998 0.03793573 0.05681246 0.07499998 0.0465216 0.06448131 0.07499998 0.03960776 0.05861961 0.07499998 0.04633468 0.06426578 0.07499998 0.04090487 0.06038194 0.07499998 0.04572427 0.0637443 0.07499998 0.04230672 0.06306689 0.07499998 0.04341948 0.06207233 0.07499998 0.04454946 0.05135154 0.07499998 -0.03098481 0.05307835 0.07499998 -0.03241759 0.05014455 0.07499998 -0.0290932 0.05465799 0.07499998 -0.0331369 0.04954868 0.07499998 -0.0270642 0.05630737 0.07499998 -0.03348636 0.04954713 0.07499998 -0.02500927 0.05798673 0.07499998 -0.03344625 0.05925732 0.07499998 -0.03315848 0.05008691 0.07499998 -0.02302277 0.06064504 0.07499998 -0.03257566 0.05093312 0.07499998 -0.02158039 0.06229704 0.07499998 -0.03134745 0.05206328 0.07499998 -0.02031815 0.06333047 0.07499998 -0.03003287 0.05362045 0.07499998 -0.01929175 0.06394201 0.07499998 -0.02886867 0.05483227 0.07499998 -0.01881384 0.06445127 0.07499998 -0.0270642 0.05625164 0.07499998 -0.01852136 0.06448131 0.07499998 -0.02539223 0.05770069 0.07499998 -0.01852679 0.06422185 0.07499998 -0.0239095 0.05916225 0.07499998 -0.01879924 0.06357109 0.07499998 -0.02236109 0.06070959 0.07499998 -0.01946854 0.06271976 0.07499998 -0.02113121 0.06178885 0.07499998 -0.02022016 -0.04264843 0.07499998 0.03401511 -0.04092156 0.07499998 0.03258234 -0.04385536 0.07499998 0.03590673 -0.03934186 0.07499998 0.03186297 -0.04445129 0.07499998 0.03793573 -0.03769248 0.07499998 0.03151357 -0.04445278 0.07499998 0.03999066 -0.03620606 0.07499998 0.0315361 -0.03473019 0.07499998 0.03183239 -0.04391306 0.07499998 0.04197722 -0.03336924 0.07499998 0.03243052 -0.04287624 0.07499998 0.04368609 -0.03227525 0.07499998 0.03316062 -0.03121191 0.07499998 0.03421252 -0.04139566 0.07499998 0.04511386 -0.03028416 0.07499998 0.03562015 -0.03974348 0.07499998 0.0459904 -0.02976202 0.07499998 0.0370121 -0.0379936 0.07499998 0.04646098 -0.02947974 0.07499998 0.03868299 -0.03611868 0.07499998 0.04645949 -0.02961635 0.07499998 0.04034954 -0.03465801 0.07499998 0.04613691 -0.02995985 0.07499998 0.0416187 -0.03345149 0.07499998 0.04561418 -0.03061836 0.07499998 0.04296177 -0.03235822 0.07499998 0.04490548 -0.03140312 0.07499998 0.04400146 -0.04264843 0.07499998 -0.03098481 -0.04092156 0.07499998 -0.03241759 -0.04385536 0.07499998 -0.02909326 -0.03934198 0.07499998 -0.0331369 -0.04445129 0.07499998 -0.0270642 -0.03769254 0.07499998 -0.03348636 -0.04445278 0.07499998 -0.02500927 -0.03601324 0.07499998 -0.03344625 -0.04410004 0.07499998 -0.02356505 -0.03474265 0.07499998 -0.03315848 -0.04339206 0.07499998 -0.02202564 -0.03335493 0.07499998 -0.03257566 -0.03213936 0.07499998 -0.03171962 -0.04184246 0.07499998 -0.02022898 -0.03121197 0.07499998 -0.0307874 -0.03028416 0.07499998 -0.02937984 -0.04025745 0.07499998 -0.01923602 -0.03867429 0.07499998 -0.01866465 -0.02970796 0.07499998 -0.02780199 -0.02948272 0.07499998 -0.02613109 -0.03686577 0.07499998 -0.01848977 -0.02961635 0.07499998 -0.02465039 -0.03555864 0.07499998 -0.01863366 -0.03002208 0.07499998 -0.02320092 -0.03413152 0.07499998 -0.0190503 -0.03082382 0.07499998 -0.02172487 -0.03265845 0.07499998 -0.0198704 -0.0316596 0.07499998 -0.02072548 0.00360769 0.07599997 0.006185412 0.002985179 0.07599997 0.005636453 0.00270158 0.07599997 0.005046844 0.002656042 0.07599997 0.004437267 0.002882122 0.07599997 0.003685057 0.003512084 0.07599997 0.003080308 0.004129111 0.07599997 0.002861738 0.004783153 0.07599997 0.002878367 0.005308449 0.07599997 0.003094911 0.005745112 0.07599997 0.003455698 0.006128907 0.07599997 0.004190325 0.006115198 0.07599997 0.005019605 0.005863606 0.07599997 0.005576729 0.005444467 0.07599997 0.006020486 0.004640102 0.07599997 0.006358802 0.003655612 0.07599997 -0.006230652 0.003189563 0.07599997 -0.006554365 0.002847552 0.07599997 -0.007006466 0.002630412 0.07599997 -0.007806539 0.002852618 0.07599997 -0.008651077 0.003430545 0.07599997 -0.009304881 0.00426048 0.07599997 -0.00957638 0.004826247 0.07599997 -0.009524285 0.005349934 0.07599997 -0.009308218 0.005825877 0.07599997 -0.008858859 0.00609523 0.07599997 -0.008310735 0.006153285 0.07599997 -0.007527649 0.005818605 0.07599997 -0.006768763 0.005262434 0.07599997 -0.006278336 0.004420578 0.07599997 -0.006049454 0.01577341 0.07599997 -0.008395314 0.01519763 0.07599997 -0.00892961 0.01490986 0.07599997 -0.009613037 0.01492083 0.07599997 -0.01026803 0.01515513 0.07599997 -0.01087874 0.01567757 0.07599997 -0.01140534 0.01632529 0.07599997 -0.01166552 0.01719671 0.07599997 -0.01162135 0.01789414 0.07599997 -0.01117122 0.01833748 0.07599997 -0.01047074 0.01837921 0.07599997 -0.009641766 0.01811361 0.07599997 -0.008949458 0.01738846 0.07599997 -0.008320808 0.01652735 0.07599997 -0.008176028 0.01609611 0.07599997 0.004160284 0.0154196 0.07599997 0.003761768 0.01497572 0.07599997 0.003061652 0.014889 0.07599997 0.002368569 0.01502007 0.07599997 0.00181663 0.01539909 0.07599997 0.001230716 0.01611006 0.07599997 8.04488e-4 0.01684874 0.07599997 7.36912e-4 0.01739299 0.07599997 9.0007e-4 0.01786345 0.07599997 0.001215577 0.01822006 0.07599997 0.001711964 0.01840209 0.07599997 0.002340197 0.01832592 0.07599997 0.002990841 0.01798152 0.07599997 0.003647685 0.0173003 0.07599997 0.004120647 0.01670104 0.07599997 0.004241585 0.006469964 0.05899995 -0.04317343 0.006468176 0.06099998 -0.04313421 0.006820857 0.06099998 -0.04427951 0.006765484 0.05899995 -0.04412871 0.007270812 0.05899995 -0.04498547 0.007576584 0.06099998 -0.04533201 0.008141696 0.05899995 -0.04580616 0.008710801 0.06099998 -0.046148 0.009404063 0.05899995 -0.0464003 0.01025998 0.06099998 -0.04652929 0.01109695 0.05899995 -0.04648411 0.0116415 0.06099998 -0.04633367 0.01258283 0.05899995 -0.0459007 0.01271551 0.06099998 -0.04580616 0.01361364 0.05899995 -0.04495924 0.0135864 0.06099998 -0.04498553 0.01413512 0.06099998 -0.04403674 0.01422393 0.05899995 -0.04381477 0.01445806 0.06099998 -0.04267549 0.01442128 0.05899995 -0.04283446 0.01438724 0.05899995 -0.04184043 0.01422393 0.06099998 -0.04119908 0.01388669 0.05899995 -0.04043173 0.01377844 0.06099998 -0.04030978 0.01313626 0.06099998 -0.03954321 0.01264387 0.05899995 -0.03913682 0.01223117 0.06099998 -0.03892511 0.01125442 0.05899995 -0.03857845 0.01119363 0.06099998 -0.03856611 0.00976032 0.05899995 -0.03852969 0.009696364 0.06099998 -0.03854101 0.00853753 0.05899995 -0.03897529 0.00848788 0.06099998 -0.03900235 0.007721006 0.05899995 -0.03954321 0.007675468 0.06099998 -0.03958541 0.006809234 0.05899995 -0.04072791 0.006883382 0.06099998 -0.04061233 0.006449162 0.06099998 -0.04193913 0.006441831 0.05899995 -0.04207777 0.04862034 0.07099997 -0.03341376 0.04621791 0.07099997 -0.03342145 0.04596912 0.07300001 -0.03338545 0.04862034 0.07300001 -0.03341376 0.04707109 0.07099997 -0.03371232 0.04798603 0.07099997 -0.03447324 0.04856145 0.07099997 -0.03560209 0.04862952 0.07300001 -0.0361675 -0.0267837 0.07300001 -0.03156203 -0.02834963 0.07300001 -0.03340125 -0.02812278 0.07300001 -0.03216993 -0.02915674 0.07300001 -0.03309714 -0.02980148 0.07300001 -0.03403878 -0.02837961 0.07300001 -0.04036867 -0.03036415 0.07300001 -0.04036867 0.04655313 0.07300001 -0.03142249 0.04212188 0.07300001 -0.03336542 0.04791826 0.07300001 -0.03191179 0.04894185 0.07300001 -0.0325945 0.04982346 0.07300001 -0.03361505 0.05035322 0.07300001 -0.03468072 0.05061954 0.07300001 -0.03583598 0.05063581 0.07295 -0.04586869 0.04863584 0.07293331 -0.04586869 -0.03032124 0.07300001 -0.03551667 -0.02574717 0.07300001 -0.03137725 -0.02753347 0.07099997 -0.03426933 -0.02834212 0.07099997 -0.03339374 -0.02676159 0.07099997 -0.033706 -0.02810639 0.07099997 -0.03512668 -0.02589118 0.07099997 -0.03339833 -0.028337 0.07099997 -0.03593033 -0.02563369 0.07099997 -0.03590238 -0.02722966 0.07099997 -0.03427159 -0.02610969 0.07099997 -0.03639566 -0.02803063 0.07099997 -0.03522378 -0.02614504 0.07099997 -0.033679 -0.02626472 0.07099997 -0.03704184 -0.02499997 0.07099997 -0.03573888 -0.02528363 0.07099997 -0.03350681 -0.02833318 0.07099997 -0.03810524 -0.02445501 0.07099997 -0.03352969 -0.02429938 0.07099997 -0.03593456 -0.02343964 0.07099997 -0.03385305 -0.02608633 0.07099997 -0.0376389 -0.02774447 0.07099997 -0.03920137 -0.02244091 0.07099997 -0.03457838 -0.02567648 0.07099997 -0.0380662 -0.02672773 0.07099997 -0.04007017 -0.02382284 0.07099997 -0.036538 -0.0217083 0.07099997 -0.03574812 -0.02523916 0.07099997 -0.03823 -0.02540677 0.07099997 -0.04049825 -0.02149236 0.07099997 -0.03687995 -0.02478086 0.07099997 -0.03824269 -0.02374672 0.07099997 -0.03709393 -0.02435958 0.07099997 -0.04044634 -0.02163052 0.07099997 -0.03802698 -0.02386707 0.07099997 -0.0375455 -0.02336865 0.07099997 -0.04012203 -0.02421212 0.07099997 -0.03798794 -0.02228903 0.07099997 -0.03924918 0.04212188 0.07099997 -0.03336769 -0.02837443 0.07099997 -0.04036867 0.02126103 0.06099998 -0.08200001 0.02117049 0.07099997 -0.08154064 0.02106541 0.06099998 -0.08129936 0.02081602 0.07099997 -0.08102756 0.020518 0.06099998 -0.08085191 0.02014714 0.07099997 -0.08074313 0.01990532 0.06099998 -0.08073711 0.01938098 0.07099997 -0.08088517 0.01926177 0.06099998 -0.08097332 0.01883953 0.07099997 -0.08148777 0.01882302 0.06099998 -0.08152699 0.01874667 0.07099997 -0.08212536 0.01876515 0.06099998 -0.0823037 0.01889204 0.07099997 -0.08259201 0.01911944 0.06099998 -0.08290272 0.01921361 0.07099997 -0.08298587 0.01957911 0.06099998 -0.08318561 0.01963025 0.07099997 -0.08319824 0.0201258 0.07099997 -0.08325731 0.02006268 0.06099998 -0.08325582 0.02050751 0.06099998 -0.08314901 0.02063655 0.07099997 -0.08308291 0.02089357 0.06099998 -0.08288562 0.02104479 0.07099997 -0.08271235 0.02115362 0.06099998 -0.082497 0.02126008 0.07099997 -0.08209443 0.02726107 0.06099998 -0.08200001 0.02722078 0.07099997 -0.08171135 0.02711051 0.06099998 -0.08139526 0.02704066 0.07099997 -0.08129042 0.02660709 0.06099998 -0.08088511 0.02649569 0.07099997 -0.08082383 0.02583152 0.06099998 -0.08073955 0.02564555 0.07099997 -0.08077871 0.0252062 0.06099998 -0.08102101 0.02507668 0.07099997 -0.08114326 0.02482014 0.06099998 -0.08153694 0.02475565 0.07099997 -0.08173775 0.02475041 0.06099998 -0.08214646 0.0248605 0.07099997 -0.08257234 0.02491927 0.06099998 -0.08264845 0.02541059 0.06099998 -0.08312678 0.02544921 0.07099997 -0.08314377 0.02624237 0.06099998 -0.08325183 0.02613592 0.07099997 -0.08325541 0.02669227 0.07099997 -0.08305311 0.02687269 0.06099998 -0.08290922 0.02706223 0.07099997 -0.08267408 0.02715361 0.06099998 -0.082497 0.02724766 0.07099997 -0.08217781 0.0272656 0.07099997 -0.03708446 0.02720725 0.06099998 -0.0366382 0.02707958 0.07099997 -0.03632801 0.0269438 0.06099998 -0.03616702 0.02657455 0.07099997 -0.03587913 0.02637547 0.06099998 -0.03578263 0.02612501 0.07099997 -0.03575122 0.02557593 0.06099998 -0.03580451 0.02561801 0.07099997 -0.0357964 0.02504211 0.07099997 -0.03616845 0.02508586 0.06099998 -0.03613835 0.0247938 0.06099998 -0.03661715 0.02478981 0.07099997 -0.03666955 0.02474665 0.07099997 -0.03712534 0.02475726 0.06099998 -0.03718727 0.02496927 0.07099997 -0.03774106 0.02500963 0.06099998 -0.03780317 0.02557593 0.07099997 -0.03819543 0.02559882 0.06099998 -0.03819394 0.026084 0.06099998 -0.0382533 0.02626019 0.07099997 -0.0382356 0.02657526 0.06099998 -0.03812217 0.02671468 0.07099997 -0.03803098 0.0269618 0.06099998 -0.03780704 0.02704691 0.07099997 -0.03770154 0.02723425 0.06099998 -0.03729236 0.02125632 0.07099997 -0.03718936 0.02126538 0.06099998 -0.03701025 0.02116525 0.07099997 -0.03651982 0.02113229 0.06099998 -0.03645473 0.02083444 0.07099997 -0.03605449 0.02078843 0.06099998 -0.03601133 0.02025109 0.07099997 -0.03575772 0.02028912 0.06099998 -0.03577756 0.01979106 0.06099998 -0.03575712 0.01953727 0.07099997 -0.03582108 0.01924568 0.06099998 -0.03598725 0.01907241 0.07099997 -0.03615289 0.01888501 0.06099998 -0.03641712 0.01877993 0.07099997 -0.03665667 0.01873457 0.06099998 -0.03698968 0.01877272 0.07099997 -0.03728008 0.01896369 0.06099998 -0.03774505 0.01896262 0.07099997 -0.03770732 0.0193668 0.07099997 -0.03809672 0.01957768 0.06099998 -0.03819 0.02007353 0.07099997 -0.03826624 0.02022987 0.06099998 -0.03824436 0.02069222 0.07099997 -0.03805309 0.02073293 0.06099998 -0.03801941 0.02108836 0.06099998 -0.03764021 0.02102416 0.07099997 -0.03772443 0.02300184 0.06098687 -0.08212459 0.02298825 0.07099997 -0.08199995 0.02299946 0.06100004 -0.08212292 0.0230652 0.07099997 -0.08266901 0.0232523 0.06111466 -0.08324295 0.02346259 0.07099997 -0.08363932 0.02376425 0.0614832 -0.08401149 0.02424997 0.07099997 -0.08445572 0.02449297 0.06199675 -0.0846163 0.02542459 0.07099997 -0.08497428 0.02541828 0.06247001 -0.08495038 0.02625584 0.06255972 -0.0850014 0.02680867 0.07099997 -0.08491498 0.02706086 0.06225728 -0.08481377 0.02779507 0.06179749 -0.0844174 0.02782672 0.07099997 -0.08439362 0.02843129 0.06134039 -0.08377552 0.02845251 0.07099997 -0.08374631 0.02885818 0.06104588 -0.0829522 0.02892971 0.07099997 -0.08274632 0.02899974 0.06099855 -0.08219057 0.0289812 0.07099997 -0.08155137 0.02895146 0.06099998 -0.08140569 0.02858293 0.07099997 -0.08042609 0.02867931 0.06099998 -0.08063411 0.02811688 0.06099998 -0.07984703 0.02770674 0.07099997 -0.07950919 0.02712041 0.06099998 -0.07919621 0.02660828 0.07099997 -0.07904243 0.02594989 0.06099998 -0.0789811 0.0254147 0.07099997 -0.07903784 0.024787 0.06099998 -0.07923501 0.02431267 0.07099997 -0.07949602 0.02381289 0.06099998 -0.0799185 0.02347415 0.07099997 -0.08034557 0.02317845 0.06099998 -0.08092534 0.02311295 0.07099997 -0.08116781 0.02300328 0.06099998 -0.08185154 0.0229963 0.06099998 -0.08185166 0.02295053 0.07099997 -0.08138114 0.02289915 0.06099998 -0.08121144 0.02255439 0.06099998 -0.08039033 0.0226655 0.07099997 -0.08061343 0.02214896 0.07099997 -0.07987898 0.02173388 0.06099998 -0.07952821 0.02115923 0.07099997 -0.07921195 0.02064406 0.06099998 -0.07905018 0.02006334 0.07099997 -0.07898586 0.01945412 0.06099998 -0.07903039 0.01888656 0.07099997 -0.07918769 0.01834899 0.06099998 -0.079472 0.01789087 0.07099997 -0.07984572 0.01750028 0.06099998 -0.08030641 0.01721173 0.07099997 -0.08082753 0.01706022 0.06099998 -0.08133178 0.01698529 0.07099997 -0.08199673 0.01702463 0.06099486 -0.08251106 0.01718181 0.07099997 -0.0830844 0.01730823 0.06115585 -0.08333885 0.01764988 0.07099997 -0.08387309 0.01779967 0.06150847 -0.08406114 0.01824998 0.07099997 -0.08445572 0.01861864 0.06207287 -0.0846759 0.01942461 0.07099997 -0.08497428 0.01965379 0.06255346 -0.08499866 0.02080863 0.07099997 -0.08491498 0.02065122 0.06244862 -0.08493828 0.02158904 0.06193995 -0.08456546 0.02182674 0.07099997 -0.08439362 0.02243101 0.06134122 -0.08378851 0.02245247 0.07099997 -0.08374631 0.02292823 0.07099997 -0.08275085 0.02283531 0.06106084 -0.08299547 -0.02152884 0.0609979 -0.08253264 0.04154157 0.06100207 -0.08258008 -0.02173477 0.06113481 -0.08327108 0.04175764 0.0611515 -0.08333885 -0.02207905 0.06143426 -0.08394515 0.04215037 0.06150281 -0.0840438 -0.02281218 0.06214433 -0.08475214 0.04282188 0.06215465 -0.08475744 -0.02362138 0.06304138 -0.08522278 0.0436173 0.0630328 -0.08522212 -0.02402746 0.06374919 -0.08536261 0.04402989 0.06376254 -0.0853632 0.02300357 0.06099998 -0.03714787 0.022991 0.07099997 -0.03699994 0.02304929 0.07099997 -0.0376181 0.02300053 0.06100004 -0.03687304 0.023 0.06099998 -0.03726309 0.02323412 0.06099998 -0.03821063 0.02333384 0.07099997 -0.03838533 0.02384936 0.07099997 -0.03911924 0.02391511 0.06099998 -0.03918379 0.02483755 0.07099997 -0.03978663 0.02491867 0.06099998 -0.03981894 0.02600705 0.07099997 -0.04001939 0.02608966 0.06099998 -0.0400179 0.02731704 0.07099997 -0.03972929 0.02717655 0.06099998 -0.03977555 0.02793258 0.06099998 -0.03930413 0.02830809 0.07099997 -0.03893947 0.0285722 0.06099998 -0.03858101 0.02886021 0.07099997 -0.03796744 0.02898293 0.06099998 -0.03746658 0.02901053 0.07099997 -0.03670102 0.02893012 0.06099534 -0.03628754 0.0286467 0.07099997 -0.0355544 0.0286405 0.06110525 -0.0355668 0.02823859 0.06132811 -0.03499054 0.0281403 0.07099997 -0.0348913 0.02739596 0.0617997 -0.03431493 0.02738213 0.07099997 -0.03431087 0.02607613 0.07099997 -0.0339756 0.02626872 0.0621562 -0.03400135 0.02550667 0.06211286 -0.0340355 0.02496719 0.07099997 -0.03417187 0.024773 0.06187087 -0.03425079 0.02405446 0.07099997 -0.03469121 0.02414619 0.06154817 -0.03463572 0.02355498 0.06120908 -0.03523403 0.02323383 0.07099997 -0.03576213 0.02314329 0.06100893 -0.03605902 0.023 0.06099998 -0.03676366 0.04148083 0.06099998 -0.03715664 0.0416305 0.06101101 -0.03602182 0.04181593 0.06099998 -0.03850692 0.04264765 0.06099998 -0.03962212 0.02299642 0.06099998 -0.03714787 0.02276581 0.06099998 -0.03821063 0.02208489 0.06099998 -0.03918379 0.02108126 0.06099998 -0.03981894 0.0170921 0.06099998 -0.03775608 0.01698416 0.06099981 -0.03689718 0.01742774 0.06099998 -0.03858101 0.01806735 0.06099998 -0.03930413 0.01882338 0.06099998 -0.03977555 0.01991033 0.06099998 -0.0400179 0.0458545 0.06100469 -0.07860243 0.04486656 0.06099998 -0.07848036 0.04510819 0.06099915 -0.04051381 0.0438463 0.06099998 -0.04032832 0.04352819 0.06099998 -0.07880008 0.0424146 0.06099998 -0.07960808 0.04169547 0.06099998 -0.08078116 0.04150092 0.06099998 -0.08179241 -0.02150475 0.06099969 -0.03671211 -0.02156889 0.06099998 -0.03779584 -0.0221365 0.06099998 -0.03905099 -0.02314227 0.06099998 -0.03999245 -0.02240324 0.06099998 -0.07964068 -0.02327835 0.06099998 -0.0789268 -0.02194905 0.06099998 -0.08027392 -0.02156102 0.06099998 -0.08123755 -0.02451711 0.06099998 -0.04049497 -0.02465718 0.06099915 -0.07849019 -0.02565616 0.06100875 -0.04044336 0.02281564 0.06102091 -0.03592401 0.02299731 0.06099998 -0.0368728 0.02294707 0.07099997 -0.03640258 0.02264666 0.07099997 -0.0355544 0.02230638 0.06128907 -0.03506129 0.02214032 0.07099997 -0.0348913 0.02161353 0.06168055 -0.03445893 0.02138215 0.07099997 -0.03431087 0.0207985 0.0620374 -0.03409677 0.02007609 0.07099997 -0.0339756 0.01976412 0.06216925 -0.03399085 0.01896715 0.07099997 -0.03417187 0.01861101 0.06179904 -0.03431749 0.01805448 0.07099997 -0.03469121 0.01778578 0.06134307 -0.03496134 0.01723337 0.07099997 -0.03576302 0.01722329 0.06103527 -0.03581625 0.01698523 0.07099997 -0.03700941 0.01719135 0.07099997 -0.03810828 0.01774376 0.07099997 -0.03899359 0.01855432 0.07099997 -0.03965079 0.01969337 0.07099997 -0.04000377 0.0208801 0.07099997 -0.03988826 0.02192968 0.07099997 -0.03932225 0.02267825 0.07099997 -0.03839403 0.02297055 0.07099997 -0.03746855 0.04622662 0.06104362 -0.04029417 0.04650068 0.06111901 -0.07882905 0.04701989 0.06133282 -0.03986436 0.04710566 0.0613811 -0.0792005 0.04754287 0.06167668 -0.03941315 0.04771244 0.06181704 -0.07976466 0.04806542 0.06222474 -0.0387144 0.0481916 0.06242257 -0.08055013 0.0483908 0.06280463 -0.03789108 0.04845601 0.06296634 -0.08138102 0.04848825 0.06305664 -0.08241176 0.04851096 0.06313991 -0.03701663 0.04861879 0.0637086 -0.0360372 0.04864448 0.07099997 -0.07636868 0.04865652 0.07289999 -0.07636868 0.04866456 0.07292854 -0.06636869 0.05063581 0.07293331 -0.07636868 0.05063581 0.07295 -0.06636869 0.04864734 0.07099997 -0.05586868 0.04866343 0.07291996 -0.05586868 0.04864275 0.07099997 -0.06636869 0.04862368 0.07099997 -0.0827049 0.05063581 0.07296663 -0.05586868 0.05061954 0.07300001 -0.08290141 0.04542154 0.06099998 -0.08081227 0.04571825 0.07099997 -0.08096444 0.04584705 0.06099998 -0.08107244 0.0460605 0.07099997 -0.08132678 0.04618835 0.06099998 -0.08155649 0.04626107 0.07099997 -0.08187377 0.04624187 0.06099998 -0.082219 0.04617285 0.07099997 -0.08244973 0.04603892 0.06099998 -0.08270829 0.04590272 0.07099997 -0.08288055 0.04571574 0.06099998 -0.08303225 0.04534327 0.07099997 -0.08322 0.04524987 0.06099998 -0.08323603 0.04469883 0.07099997 -0.08322376 0.04458618 0.06099998 -0.08319902 0.04422342 0.07099997 -0.08298987 0.04407095 0.06099998 -0.08284837 0.04391705 0.07099997 -0.08263659 0.04377174 0.06099998 -0.08231276 0.04374456 0.07099997 -0.08213591 0.04379034 0.06099998 -0.08163756 0.04379332 0.07099997 -0.0816605 0.04402911 0.07099997 -0.08118528 0.04413855 0.06099998 -0.08107167 0.04450291 0.07099997 -0.0808463 0.04477989 0.06099998 -0.08075183 0.04509484 0.07099997 -0.08073407 -0.02452909 0.07099997 -0.0808283 -0.02452117 0.06099998 -0.08083862 -0.02398991 0.06099998 -0.08122169 -0.02407091 0.07099997 -0.08115166 -0.02382707 0.07099997 -0.08155024 -0.02373158 0.06099998 -0.08198964 -0.02374082 0.07099997 -0.08203136 -0.02384024 0.07099997 -0.08247834 -0.02391719 0.06099998 -0.0826497 -0.0240972 0.07099997 -0.08288055 -0.02428418 0.06099998 -0.08303225 -0.02465671 0.07099997 -0.08322 -0.02475011 0.06099998 -0.08323603 -0.02530115 0.07099997 -0.08322376 -0.02538281 0.06099998 -0.08320617 -0.02590298 0.07099997 -0.08289533 -0.02590924 0.06099998 -0.08287268 -0.02624201 0.06099998 -0.08227282 -0.02625262 0.07099997 -0.08219927 -0.02615475 0.06099998 -0.0814675 -0.02620661 0.07099997 -0.0816605 -0.02597087 0.07099997 -0.08118528 -0.02567642 0.06099998 -0.08093369 -0.02528399 0.07099997 -0.08075565 -0.02506303 0.06099998 -0.08073699 -0.02478158 0.06099998 -0.03576165 -0.02435344 0.06099998 -0.03592294 -0.02396243 0.06099998 -0.03628015 -0.02374869 0.06099998 -0.03684312 -0.02384185 0.06099998 -0.03752249 -0.02424114 0.06099998 -0.03800183 -0.02475935 0.06099998 -0.03824234 -0.02534049 0.06099998 -0.03821045 -0.0257588 0.06099998 -0.03800183 -0.02613073 0.06099998 -0.03756809 -0.02626061 0.06099998 -0.0369268 -0.02602636 0.06099998 -0.03624922 -0.02539408 0.06099998 -0.03579431 0.04518842 0.06099998 -0.03574955 0.04561424 0.07099997 -0.03589361 0.04569935 0.06099998 -0.0359565 0.04605311 0.06099998 -0.03630769 0.04603892 0.07099997 -0.03629159 0.04625654 0.07099997 -0.03684252 0.04623532 0.06099998 -0.03677213 0.0462262 0.06099998 -0.03730159 0.04614919 0.07099997 -0.03752982 0.04584449 0.06099998 -0.03795695 0.045852 0.07099997 -0.03791821 0.04544246 0.07099997 -0.03818553 0.04517781 0.06099998 -0.03824764 0.0448535 0.07099997 -0.03824955 0.04465949 0.06099998 -0.03821045 0.04432344 0.07099997 -0.0380662 0.04406434 0.06099998 -0.03786808 0.04386168 0.07099997 -0.03755962 0.04375708 0.06099998 -0.03720885 0.04374307 0.07099997 -0.03685283 0.04377752 0.06099998 -0.03671079 0.04394423 0.07099997 -0.03631812 0.04396104 0.06099998 -0.03629159 0.04436624 0.07099997 -0.03590238 0.04444772 0.06099998 -0.03585326 0.04499995 0.07099997 -0.03573888 0.04572117 0.05900442 -0.03593236 0.04645651 0.05907541 -0.0358982 0.04713493 0.059233 -0.03602117 0.04796242 0.05957752 -0.03590768 0.04868334 0.06004244 -0.03588712 0.04928177 0.06057751 -0.03602784 0.04973751 0.06112986 -0.03625631 0.05017423 0.06190228 -0.03609341 0.05039745 0.06250649 -0.03589856 0.05061024 0.06339186 -0.03609377 0.04850393 0.07099997 -0.03716337 0.04835754 0.07099997 -0.03801953 0.04795658 0.07099997 -0.03889656 0.0473802 0.07099997 -0.03957366 0.04660236 0.07099997 -0.04013055 0.04569357 0.07099997 -0.04043638 0.04480785 0.07099997 -0.04050731 0.043953 0.07099997 -0.04034537 0.04300373 0.07099997 -0.03990244 0.04203426 0.07099997 -0.03890109 0.04159748 0.07099997 -0.03785645 0.04149132 0.07099997 -0.03699171 0.0416457 0.07099997 -0.03594154 0.04208338 0.0612933 -0.03502637 0.04215198 0.07099997 -0.03494513 0.04300892 0.07099997 -0.03409421 0.04281556 0.06186038 -0.03425759 0.04338014 0.06230074 -0.03389245 0.04423266 0.07099997 -0.03356647 0.04415196 0.06284916 -0.03359246 0.04507505 0.07099997 -0.03349792 0.04586321 0.07099997 -0.03359413 0.04508787 0.06315094 -0.03349047 0.0459876 0.06279349 -0.03363388 0.04671424 0.06258833 -0.03393864 0.04683059 0.07099997 -0.03400284 0.04732215 0.06250983 -0.03437554 0.04781699 0.07099997 -0.03487151 0.0478248 0.06252568 -0.03491616 0.04825037 0.06267982 -0.03568661 0.04841792 0.07099997 -0.03616672 0.04841893 0.06287753 -0.0362311 0.04397118 0.07099997 -0.08535432 0.04279577 0.07099997 -0.08475846 0.04182332 0.07099997 -0.08353549 0.04147768 0.07099997 -0.08210551 0.04171818 0.07099997 -0.08072078 0.04246348 0.07099997 -0.07955598 0.04359978 0.07099997 -0.07876783 0.04469245 0.07099997 -0.07850497 0.04573082 0.07099997 -0.07856035 0.04700565 0.07099997 -0.07909542 0.04806786 0.07099997 -0.08025836 0.04844069 0.07099997 -0.08132642 0.04850232 0.07099997 -0.08242058 0.04825139 0.06285935 -0.08333694 0.04804855 0.07099997 -0.08375579 0.04768073 0.06285941 -0.08427035 0.04720014 0.07099997 -0.08475095 0.04711967 0.06301724 -0.08478969 0.04659992 0.0632534 -0.08511888 0.04620611 0.07099997 -0.08529168 0.0461083 0.063712 -0.08532124 0.04601025 0.0636149 -0.08735138 0.04669725 0.06351304 -0.08724606 0.04605102 0.06276196 -0.08721446 0.04730206 0.06339162 -0.087062 0.04789036 0.06374663 -0.08683449 0.04868167 0.06366699 -0.08633387 0.0480656 0.06300681 -0.08663839 0.04684168 0.06218779 -0.08688473 0.04605352 0.06191748 -0.08690953 0.04764097 0.0623793 -0.08666884 0.0494042 0.06372863 -0.08566039 0.04882574 0.06304043 -0.08611422 0.04621142 0.0612083 -0.08650183 0.04726964 0.0616185 -0.08646208 0.04958426 0.06298464 -0.08529663 0.04841411 0.06205934 -0.08605939 0.04918849 0.06248944 -0.08557248 0.04995411 0.06380492 -0.08489316 0.04780083 0.06142669 -0.08608812 0.04607939 0.06064802 -0.08607053 0.05001348 0.0631057 -0.08464151 0.05028516 0.06362652 -0.08420205 0.04866653 0.06154131 -0.08552783 0.04688584 0.06059962 -0.08584088 0.04591923 0.06008112 -0.08547341 0.04939097 0.06172448 -0.08478951 0.0477221 0.06062448 -0.08543747 0.04988211 0.06230908 -0.08442276 0.05055034 0.06362861 -0.08331626 0.04898864 0.06113415 -0.08475744 0.05027949 0.06281501 -0.08381581 0.04600399 0.05963599 -0.08480501 0.04823875 0.06048494 -0.0848276 0.04677563 0.06000101 -0.08516907 0.04967927 0.061562 -0.08404892 0.05009329 0.06201064 -0.08351463 0.05043661 0.06263017 -0.08285218 0.04756212 0.05990368 -0.08452701 0.04587042 0.0593093 -0.08411133 0.05062276 0.06351751 -0.0824927 0.04681432 0.05957508 -0.08440274 0.04896742 0.06055516 -0.08387136 0.04977953 0.06122314 -0.08294957 0.04829281 0.05995279 -0.0836842 0.05011624 0.06179159 -0.08280152 0.04672569 0.05930477 -0.08377313 0.04936397 0.06067728 -0.08280718 0.04766994 0.05957508 -0.08354723 0.04880481 0.06013929 -0.08279687 0.04600161 0.05907464 -0.08321994 0.04808712 0.05964386 -0.08273541 0.0473476 0.05930107 -0.08274275 0.04585272 0.05900245 -0.08256793 0.04661172 0.05909484 -0.08259755 0.05050081 0.06360864 -0.0352022 0.04971837 0.06122058 -0.03548258 0.05024683 0.06236273 -0.03526031 0.0497539 0.06163179 -0.03476804 0.05021929 0.06340885 -0.03440183 0.04997885 0.06244981 -0.03439956 0.04923307 0.06083691 -0.03485733 0.04826384 0.05994802 -0.03503751 0.04827427 0.060144 -0.03453397 0.0470941 0.05934655 -0.03518569 0.04980516 0.06338524 -0.03363955 0.04927712 0.06179434 -0.03371578 0.04959267 0.06241112 -0.03374552 0.04878348 0.06090527 -0.03399568 0.04738491 0.0596888 -0.03450071 0.04920309 0.06366479 -0.03285646 0.04593062 0.05922114 -0.03488469 0.04788541 0.06033313 -0.03379327 0.04906207 0.0626021 -0.03297728 0.04849845 0.06160038 -0.03300952 0.04658067 0.05953133 -0.03430294 0.04796409 0.06099385 -0.03309834 0.04884874 0.06303972 -0.03264552 0.04716545 0.0602017 -0.03347301 0.04602706 0.05958324 -0.03403121 0.04617762 0.06006312 -0.03330159 0.04831933 0.06352651 -0.03215503 0.04803931 0.06246697 -0.03224688 0.04732346 0.06098139 -0.03273886 0.04741424 0.06152862 -0.03237825 0.04623633 0.06067365 -0.03265947 0.04767578 0.06347042 -0.03181946 0.04732286 0.06251704 -0.03188979 0.0466094 0.06172472 -0.03200072 0.04581135 0.06122046 -0.03220099 0.04702359 0.06343352 -0.03157866 0.04613649 0.06282657 -0.03151392 0.04618281 0.06360596 -0.03139585 0.04583406 0.06215685 -0.03171712 0.04852813 0.06320881 -0.03614294 0.04843389 0.06321883 -0.03556364 0.04843866 0.06377464 -0.03529995 0.0482465 0.06305193 -0.03519207 0.04808944 0.06373012 -0.03463399 0.04780894 0.06296873 -0.03454595 0.04758679 0.06357121 -0.03410637 0.04713374 0.06287723 -0.03401297 0.04721236 0.06363016 -0.03382527 0.0465517 0.06311345 -0.03364098 0.04660785 0.06367486 -0.03353357 0.04589968 0.06325829 -0.03346383 0.04592448 0.06367719 -0.03338539 0.04641222 0.0637961 -0.08526855 0.0469383 0.06374996 -0.08507001 0.04761707 0.06381911 -0.08463299 0.04728466 0.06340378 -0.0848152 0.04776298 0.06341201 -0.08441597 0.04823315 0.0636987 -0.08387672 0.04822081 0.06315857 -0.08366149 0.04848951 0.0636093 -0.08327424 0.04862809 0.06392967 -0.08266454 0.04857707 0.06339079 -0.08258503 0.04843312 0.07099997 -0.08348172 0.04784858 0.07099997 -0.08443027 0.04676687 0.07099997 -0.08517163 0.0503031 0.07300001 -0.08421009 0.04963928 0.07300001 -0.08538389 0.04850053 0.07300001 -0.08650493 0.04705536 0.07300001 -0.0871753 0.04601895 0.07300001 -0.08736014 0.04867035 0.07300001 -0.07636868 0.04864031 0.07300001 -0.08538377 0.04864031 0.07099997 -0.08537626 -0.02554422 0.06378853 -0.03337579 -0.02167546 0.06103026 -0.03587543 -0.02201855 0.06125015 -0.0351569 -0.02250546 0.06161797 -0.03453046 -0.02337527 0.06229895 -0.03387904 -0.02441167 0.0629881 -0.03354209 -0.02516925 0.06312322 -0.03349828 -0.02556669 0.05900144 -0.03616619 -0.02561736 0.05909752 -0.03538519 -0.02557206 0.05978858 -0.0336644 -0.006364107 0.07300001 -0.08541375 -0.006364107 0.07300001 -0.08736866 -0.02837961 0.07300001 -0.0523687 -0.03036415 0.07300001 -0.06836867 -0.03036415 0.07300001 -0.0523687 -0.02837961 0.07300001 -0.06836867 -0.02837961 0.07300001 -0.07736867 -0.03032934 0.07300001 -0.08313912 -0.03036415 0.07300001 -0.07736867 -0.02837961 0.07300001 -0.08541375 -0.02992767 0.07300001 -0.08442974 -0.02938842 0.07300001 -0.08535337 -0.02866101 0.07300001 -0.08613753 -0.02765405 0.07300001 -0.08683305 -0.02613449 0.07300001 -0.08733397 -0.02236413 0.07300001 -0.08541375 -0.02236413 0.07300001 -0.08736866 -0.006364107 0.07099997 -0.08539873 -0.006364107 0.06599998 -0.08736866 -0.006364107 0.06599998 -0.08536869 -0.02236413 0.07099997 -0.08539873 -0.02837961 0.07099997 -0.08541375 -0.02837443 0.07099997 -0.07736867 -0.02236413 0.06599998 -0.08736866 -0.03036415 0.06799995 -0.07736867 -0.02836412 0.06799995 -0.07736867 -0.02837187 0.07099997 -0.0523687 -0.02836412 0.06400001 -0.0523687 -0.03036415 0.06400001 -0.0523687 -0.03036415 0.06799995 -0.06836867 -0.03034752 0.06361585 -0.08273535 -0.03034698 0.06352609 -0.03608322 -0.03023016 0.06381374 -0.03519886 -0.02965331 0.06365323 -0.03380221 -0.02907997 0.06378209 -0.03301101 -0.02810966 0.06365078 -0.03218251 -0.02717173 0.06375402 -0.03170442 -0.02632641 0.06356668 -0.03146755 -0.02564382 0.06352114 -0.03138625 -0.02779853 0.06380742 -0.08412659 -0.02734965 0.06376475 -0.08460807 -0.02699995 0.06379771 -0.08488142 -0.02714896 0.07099997 -0.08478659 -0.02774024 0.07099997 -0.0842083 -0.02739948 0.07099997 -0.08456546 -0.02236413 0.06599998 -0.08536869 -0.02744501 0.07099997 -0.07946509 -0.02811688 0.07099997 -0.08038687 -0.02651315 0.07099997 -0.07883363 -0.02836316 0.07099997 -0.08102476 -0.02567303 0.07099997 -0.07855659 -0.02444154 0.07099997 -0.0785157 -0.02306461 0.07099997 -0.07905656 -0.02236431 0.07099997 -0.07969349 -0.02376741 0.07099997 -0.08529698 -0.02241975 0.07099997 -0.08441042 -0.02236062 0.06599998 -0.0843085 -0.02170753 0.06599998 -0.08326804 -0.02148687 0.06599998 -0.08201867 -0.02170908 0.06599998 -0.08072698 -0.02235728 0.06599998 -0.07969665 -0.02631175 0.06362855 -0.08728319 -0.02732264 0.06361776 -0.08696943 -0.02823787 0.0634759 -0.08645105 -0.02907997 0.06378215 -0.08572632 -0.02962827 0.06347972 -0.08496344 -0.02999711 0.06366163 -0.08425146 -0.03026169 0.06339091 -0.08330881 -0.02836412 0.06799995 -0.06836867 -0.02837187 0.07099997 -0.06836867 -0.02834963 0.0636205 -0.08097994 -0.02800786 0.06252926 -0.08017456 -0.02729624 0.06169354 -0.07934856 -0.02656877 0.06124085 -0.07886046 -0.02577871 0.06102198 -0.07858127 -0.02548676 0.05933231 -0.08417594 -0.03026467 0.06300067 -0.08254808 -0.02990126 0.0630899 -0.08429616 -0.03000605 0.06212919 -0.08273142 -0.02988606 0.06218695 -0.08357125 -0.02897006 0.06320369 -0.08575779 -0.02961093 0.06216633 -0.08429658 -0.02935159 0.06222081 -0.08484429 -0.02950203 0.06121665 -0.0829426 -0.0287702 0.06236553 -0.0856738 -0.02919924 0.06130111 -0.08415836 -0.02906709 0.06065559 -0.08289891 -0.02787274 0.06278961 -0.08654457 -0.02852374 0.06125378 -0.08513623 -0.02862316 0.06042265 -0.08366364 -0.02798515 0.06155878 -0.08588993 -0.02838045 0.06048917 -0.08431065 -0.02852231 0.06013059 -0.08279824 -0.02729213 0.06216639 -0.08661544 -0.02680844 0.06281578 -0.08701819 -0.02782022 0.06024652 -0.08462411 -0.02767598 0.0595588 -0.08264958 -0.02717274 0.06127971 -0.08618104 -0.02759331 0.06072986 -0.08543497 -0.02804899 0.05990058 -0.08339184 -0.02651125 0.06208276 -0.08685249 -0.02740818 0.05961608 -0.08370023 -0.02576035 0.0626406 -0.08717662 -0.02549415 0.06351345 -0.08735483 -0.02685171 0.06016653 -0.08524 -0.02578711 0.06191492 -0.08690798 -0.02672755 0.06069278 -0.08587735 -0.02594417 0.06119716 -0.08649349 -0.02674436 0.05974298 -0.08463156 -0.02671241 0.05918496 -0.08275359 -0.0258069 0.06055963 -0.08598977 -0.02660536 0.05944645 -0.0840528 -0.02628147 0.05921792 -0.08358186 -0.025783 0.06005662 -0.08543646 -0.02573078 0.05964386 -0.08482003 -0.02573335 0.05901181 -0.08274239 -0.02551925 0.05909466 -0.08335131 -0.02640306 0.06117612 -0.04021531 -0.02700579 0.06148505 -0.03987133 -0.02761465 0.06199288 -0.0393452 -0.02818483 0.06293052 -0.03847491 -0.02835649 0.06373363 -0.03799331 -0.02836412 0.06400001 -0.04036867 -0.02613079 0.06383234 -0.03346455 -0.02667576 0.06372445 -0.03367519 -0.02574515 0.0633037 -0.03345876 -0.02656239 0.06329739 -0.03369349 -0.02713048 0.06357991 -0.03395652 -0.02609527 0.06289082 -0.03366214 -0.02755165 0.06358981 -0.03433001 -0.02708989 0.06285989 -0.0341717 -0.02788108 0.06369125 -0.03474682 -0.02815222 0.06374484 -0.03525787 -0.02778351 0.06301993 -0.03486394 -0.02812719 0.06329751 -0.03542101 -0.0283184 0.06374651 -0.03587794 -0.02718931 0.06286853 -0.0318281 -0.02584367 0.06262505 -0.0315684 -0.02578735 0.06192851 -0.03182375 -0.02691268 0.06217277 -0.03195804 -0.0281431 0.06286239 -0.03235799 -0.02897006 0.06320375 -0.03297954 -0.02772873 0.06191486 -0.03246456 -0.02579838 0.06127315 -0.03218448 -0.02670681 0.06136459 -0.03231954 -0.02848225 0.06215608 -0.03289431 -0.02892565 0.06232964 -0.03326261 -0.02932423 0.06253623 -0.03365409 -0.02575892 0.06053066 -0.03276365 -0.02994012 0.06341516 -0.03438258 -0.02733498 0.0608974 -0.03296196 -0.02801299 0.06126463 -0.033118 -0.02660804 0.06060785 -0.03290307 -0.02862602 0.06140267 -0.03358834 -0.02968716 0.06234031 -0.03445404 -0.02626913 0.06002992 -0.03344148 -0.02934598 0.06166207 -0.03440421 -0.02800679 0.06065678 -0.03372597 -0.02726542 0.06023633 -0.03364968 -0.03016537 0.06307256 -0.03525394 -0.02900338 0.0610007 -0.03464078 -0.02978587 0.06188493 -0.03529322 -0.02622503 0.05954009 -0.03423535 -0.02704411 0.05978316 -0.03424137 -0.02790069 0.06010532 -0.03449743 -0.0285235 0.06041365 -0.03484803 -0.03010421 0.06239199 -0.0360049 -0.02908676 0.06067728 -0.03584009 -0.02573823 0.05930107 -0.03465688 -0.02958112 0.06131267 -0.035986 -0.0267685 0.05930477 -0.03527879 -0.02766156 0.05966788 -0.03528445 -0.02853316 0.06013935 -0.03594046 -0.02781552 0.05964386 -0.03600203 -0.02622038 0.05907392 -0.03602296 -0.02712661 0.05931663 -0.0361303 -0.03036415 0.06400001 -0.04036867 -0.0459674 0.08999997 -0.02812016 -0.04595464 0.09299999 -0.02835714 -0.04550421 0.08999997 -0.03018265 -0.0454483 0.09299999 -0.0302937 -0.04478228 0.09299999 -0.03171819 -0.04438513 0.08999997 -0.03237044 -0.04387784 0.09299999 -0.0329864 -0.04286301 0.08999997 -0.03401678 -0.04276603 0.09299999 -0.03409862 -0.041242 0.08999997 -0.03518426 -0.04133063 0.09299999 -0.03511947 -0.04598176 0.09299999 -0.02576971 -0.03974407 0.08999997 -0.02272975 -0.0443167 0.08999997 -0.02164131 -0.040641 0.08999997 -0.02377504 -0.03846144 0.08999997 -0.02198463 -0.04525858 0.08999997 -0.02313774 -0.04121738 0.08999997 -0.02525633 -0.04576122 0.08999997 -0.02449429 -0.03721225 0.08999997 -0.02174621 -0.04598754 0.08999997 -0.02584904 -0.04121327 0.08999997 -0.02660459 -0.03605043 0.08999997 -0.02183997 -0.04090672 0.08999997 -0.02772581 -0.03465062 0.08999997 -0.02242535 -0.04027992 0.08999997 -0.0287128 -0.03372007 0.08999997 -0.02328711 -0.0395165 0.08999997 -0.02944374 -0.03309327 0.08999997 -0.02427411 -0.03278666 0.08999997 -0.02539545 -0.03819137 0.08999997 -0.03010827 -0.03991317 0.08999997 -0.03657251 -0.03657454 0.08999997 -0.0302518 -0.03888112 0.08999997 -0.03855603 -0.03524637 0.08999997 -0.02988624 -0.03411972 0.08999997 -0.02915358 -0.03851521 0.08999997 -0.04036951 -0.03314393 0.08999997 -0.027857 -0.04454684 0.08999997 -0.06490081 -0.03980469 0.08999997 -0.06777024 -0.0431112 0.08999997 -0.06317865 -0.04074734 0.08999997 -0.06895929 -0.04528278 0.08999997 -0.06629055 -0.03852748 0.08999997 -0.06701761 -0.04136681 0.08999997 -0.06190687 -0.04577481 0.08999997 -0.06776851 -0.04122751 0.08999997 -0.0703628 -0.04598695 0.08999997 -0.06924933 -0.04035413 0.08999997 -0.06095725 -0.03707242 0.08999997 -0.06672304 -0.03927034 0.08999997 -0.05937099 -0.04115355 0.08999997 -0.07202231 -0.04597061 0.08999997 -0.07246005 -0.03550767 0.08999997 -0.06699818 -0.04560279 0.08999997 -0.07416886 -0.04492455 0.08999997 -0.07581245 -0.03855663 0.08999997 -0.05715185 -0.04059606 0.08999997 -0.07328456 -0.03449088 0.08999997 -0.06756168 -0.04378384 0.08999997 -0.07743567 -0.03999334 0.08999997 -0.07402604 -0.03378456 0.08999997 -0.06820493 -0.0426712 0.08999997 -0.07849854 -0.03916108 0.08999997 -0.07467722 -0.03304517 0.08999997 -0.06936991 -0.04138803 0.08999997 -0.07937425 -0.03955513 0.08999997 -0.08015322 -0.03777635 0.08999997 -0.07520651 -0.03772908 0.08999997 -0.08048141 -0.03547251 0.08999997 -0.07498234 -0.03650057 0.08999997 -0.07522702 -0.03272467 0.08999997 -0.07099997 -0.03305613 0.08999997 -0.07266247 -0.03375869 0.08999997 -0.0737589 -0.03445303 0.08999997 -0.07441526 -0.03275758 0.08999997 -0.02642446 -0.04597359 0.09299999 -0.06892234 -0.04562604 0.09299999 -0.06723707 -0.04505634 0.09299999 -0.06578713 -0.04422569 0.09299999 -0.06445187 -0.04303973 0.09299999 -0.06312733 -0.03851521 0.09299999 -0.05663043 -0.03888106 0.09299999 -0.05844396 -0.03981095 0.09299999 -0.06026846 -0.04110622 0.09299999 -0.06171268 -0.04032093 0.09299999 -0.03608381 -0.03956359 0.09299999 -0.0371384 -0.03891307 0.09299999 -0.03849005 -0.03852713 0.09299999 -0.04020869 -0.03165251 0.09299999 -0.07626181 -0.0289269 0.09299516 -0.08050125 -0.03265696 0.09299999 -0.07713711 -0.0307089 0.09299999 -0.07513236 -0.03413116 0.09299999 -0.07794195 -0.02983242 0.09299999 -0.07326978 -0.0377472 0.09299999 -0.08048343 -0.03593575 0.09299999 -0.07845127 -0.02949398 0.09299999 -0.07143098 -0.03817927 0.09299999 -0.07843393 -0.03968238 0.09299999 -0.0801146 -0.04014343 0.09299999 -0.07782965 -0.04149705 0.09299999 -0.07931244 -0.04188257 0.09299999 -0.0767284 -0.04275667 0.09299999 -0.07842838 -0.04386568 0.09299999 -0.07734084 -0.04309725 0.09299999 -0.0753836 -0.04487299 0.09299999 -0.07588922 -0.04393035 0.09299999 -0.07392138 -0.0455777 0.09299999 -0.07426905 -0.04596817 0.09299999 -0.07243925 -0.04436624 0.09299999 -0.07244133 -0.04451018 0.09299999 -0.0711342 -0.04441493 0.09299999 -0.06983476 -0.04406267 0.09299999 -0.06842929 -0.04314512 0.09299999 -0.06665354 -0.03909039 0.09299999 -0.06377804 -0.04046577 0.09299999 -0.06434208 -0.03742736 0.09299999 -0.06350076 -0.04173135 0.09299999 -0.06515705 -0.03611308 0.09299999 -0.06354659 -0.03483664 0.09299999 -0.06380689 -0.03189212 0.09299999 -0.06549519 -0.03323948 0.09299999 -0.06448662 -0.03158587 0.09299999 -0.0312066 -0.03089946 0.09299999 -0.06661409 -0.03258043 0.09299999 -0.03206688 -0.0304526 0.09299999 -0.02971291 -0.03007417 0.09299999 -0.06808054 -0.03385651 0.09299999 -0.03282964 -0.02975517 0.09299999 -0.02798336 -0.03545975 0.09299999 -0.03335177 -0.02960067 0.09299999 -0.06969529 -0.02948832 0.09299999 -0.02631849 -0.03731715 0.09299999 -0.03352022 -0.03921467 0.09299999 -0.03317958 -0.04097431 0.09299999 -0.03239208 -0.04250955 0.09299999 -0.03111213 -0.04360502 0.09299999 -0.02959692 -0.04422885 0.09299999 -0.02803391 -0.04450601 0.09299999 -0.0264309 -0.04442894 0.09299999 -0.02492743 -0.04568892 0.09299999 -0.02421647 -0.04402762 0.09299999 -0.02330428 -0.02969944 0.09299999 -0.02414101 -0.03058236 0.09299999 -0.02207833 -0.03175199 0.09299999 -0.02061957 -0.03323954 0.09299999 -0.0194866 -0.03496432 0.09299999 -0.01876491 -0.036439 0.09299999 -0.0185135 -0.03793454 0.09299999 -0.01854234 -0.03934615 0.09299999 -0.01887011 -0.0405457 0.09299999 -0.01937812 -0.04486739 0.09299999 -0.02240306 -0.04312962 0.09299999 -0.02165848 -0.04390549 0.09299999 -0.0212087 -0.04197651 0.09299999 -0.02036088 -0.02952134 0.092 -0.07174831 -0.02986299 0.092 -0.07334184 -0.03038573 0.092 -0.07454848 -0.03120464 0.092 -0.07578951 -0.03242248 0.092 -0.07695543 -0.03369319 0.092 -0.07774436 -0.03509503 0.092 -0.07826578 -0.03694176 0.092 -0.07852667 -0.03916299 0.092 -0.0782094 -0.04091787 0.092 -0.07741105 -0.04252243 0.092 -0.07612407 -0.04377615 0.092 -0.07426321 -0.04440963 0.092 -0.07230651 -0.04447156 0.092 -0.07006365 -0.04397261 0.092 -0.06820648 -0.0433802 0.092 -0.06704616 -0.04247289 0.092 -0.06584507 -0.04134351 0.092 -0.0648784 -0.0402112 0.092 -0.06420964 -0.03898787 0.092 -0.06376206 -0.0376951 0.092 -0.06352078 -0.03639233 0.092 -0.06351864 -0.03509503 0.092 -0.06373417 -0.03369319 0.092 -0.06425565 -0.03211736 0.092 -0.06527161 -0.03090268 0.092 -0.06661641 -0.030236 0.092 -0.06774258 -0.02975517 0.092 -0.06901663 -0.02952677 0.092 -0.07029926 -0.03436642 0.092 -0.06764483 -0.03349453 0.092 -0.06857013 -0.03547245 0.092 -0.06701761 -0.03293406 0.092 -0.06971132 -0.03692752 0.092 -0.06672304 -0.03275042 0.092 -0.07075774 -0.03279882 0.092 -0.07170826 -0.03849226 0.092 -0.06699818 -0.03322714 0.092 -0.07301574 -0.03965836 0.092 -0.06766664 -0.03400659 0.092 -0.07402604 -0.04037469 0.092 -0.06840604 -0.03483891 0.092 -0.07467722 -0.04088467 0.092 -0.06924706 -0.03622359 0.092 -0.07520651 -0.04120111 0.092 -0.07029163 -0.04124951 0.092 -0.07124221 -0.03749936 0.092 -0.07522702 -0.04106587 0.092 -0.07228863 -0.03852742 0.092 -0.07498234 -0.04056143 0.092 -0.07333821 -0.0397194 0.092 -0.07429325 -0.02948886 0.092 -0.02581268 -0.02961212 0.092 -0.0273565 -0.03002738 0.092 -0.02879351 -0.0306198 0.092 -0.02995383 -0.03173983 0.092 -0.03139299 -0.03373283 0.092 -0.03278428 -0.03556376 0.092 -0.03337275 -0.037 0.092 -0.03350949 -0.03867357 0.092 -0.03333234 -0.04042887 0.092 -0.0326882 -0.04168081 0.092 -0.03186953 -0.04266679 0.092 -0.03093034 -0.04372429 0.092 -0.02938193 -0.04438024 0.092 -0.02743452 -0.0445066 0.092 -0.0256254 -0.04427534 0.092 -0.02414762 -0.04377162 0.092 -0.02273893 -0.04298442 0.092 -0.02146697 -0.04197317 0.092 -0.02036464 -0.04075366 0.092 -0.01949828 -0.03939366 0.092 -0.01887536 -0.03737527 0.092 -0.01847928 -0.03508633 0.092 -0.01872038 -0.03324204 0.092 -0.01949095 -0.03206861 0.092 -0.02034121 -0.03100478 0.092 -0.0214588 -0.03007417 0.092 -0.02308052 -0.02965223 0.092 -0.02446681 -0.0246185 0.08713108 -0.08050125 -0.02631014 0.08460086 -0.08050125 -0.02817308 0.0868166 -0.08050125 -0.0228734 0.08568686 -0.08050125 -0.02426314 0.08299803 -0.08050125 -0.02606844 0.08916097 -0.08050125 -0.02135151 0.08484089 -0.08050125 -0.0292555 0.0888468 -0.08050125 -0.0216602 0.08171921 -0.08050125 -0.02693563 0.09128952 -0.08050125 -0.03045082 0.0898416 -0.08050125 -0.03120344 0.08999937 -0.08050125 -0.02972096 0.08938908 -0.08050125 -0.0197438 0.0842964 -0.08050125 -0.02788698 0.0925861 -0.08050125 -0.02724087 0.09193336 -0.08050125 -0.01838439 0.08100873 -0.08050125 -0.01798582 0.0840035 -0.08050125 0.03917539 0.08402603 -0.08050125 0.03893208 0.08100199 -0.08050125 0.0414468 0.08135396 -0.08050125 0.04145753 0.08447456 -0.08050125 0.04415547 0.08237153 -0.08050125 0.04367673 0.08555024 -0.08050125 0.04607164 0.08356511 -0.08050125 0.04523593 0.08677494 -0.08050125 0.04776465 0.08505982 -0.08050125 0.04638916 0.08810609 -0.08050125 0.04932993 0.08708256 -0.08050125 0.04740738 0.08981317 -0.08050125 0.05025535 0.08884769 -0.08050125 0.05076736 0.08943206 -0.08050125 0.04807603 0.09168457 -0.08050125 0.04870408 0.0924403 -0.08050125 0.04940402 0.09284245 -0.08050125 0.05008113 0.09299808 -0.08050125 0.0522024 0.08999943 -0.08050125 0.05150282 0.08985769 -0.08050125 0.05828636 0.08999997 -0.08047866 0.06366932 0.09299999 -0.07807224 0.06243318 0.09299999 -0.07618659 0.06483274 0.09299999 -0.07674235 0.06130337 0.09299999 -0.07715642 0.06226891 0.09299999 -0.07914954 0.06334936 0.09299999 -0.07501316 0.06590116 0.09299999 -0.07481551 0.06000465 0.09299999 -0.07788425 0.06026762 0.09299999 -0.08009803 0.06401616 0.09299999 -0.07368206 0.05858778 0.09299999 -0.07834166 0.06440728 0.09299999 -0.07224559 0.06646412 0.09299999 -0.07250207 0.05818951 0.09299999 -0.08048582 0.05710852 0.09299999 -0.07851064 0.06449615 0.09299999 -0.07025355 0.06648457 0.09299999 -0.06945341 0.05562478 0.09299999 -0.07838451 0.06609767 0.09299999 -0.06737768 0.06401616 0.09299999 -0.06831789 0.06334936 0.09299999 -0.06698679 0.05419522 0.09299999 -0.07796818 0.05287587 0.09299999 -0.07727807 0.06515133 0.09299999 -0.06537818 0.06243318 0.09299999 -0.06581336 0.06407636 0.09299999 -0.06397861 0.05171847 0.09299999 -0.07634121 0.06130337 0.09299999 -0.06484353 0.05076867 0.09299999 -0.07519447 0.06291759 0.09299999 -0.06294667 0.04999399 0.09298747 -0.07372641 0.06128126 0.09299999 -0.06186103 0.06000471 0.09299999 -0.0641157 0.05858761 0.09299999 -0.06365823 0.06004315 0.09299999 -0.06057506 0.0571084 0.09299999 -0.06348931 0.05901437 0.09299999 -0.0588265 0.05562478 0.09299999 -0.06361544 0.05852645 0.09299999 -0.05678069 0.05419528 0.09299999 -0.06403177 0.05287593 0.09299999 -0.06472188 0.05171853 0.09299999 -0.06565868 0.06407636 0.09299999 -0.03302139 0.06243318 0.09299999 -0.03118664 0.06539422 0.09299999 -0.03124463 0.06130343 0.09299999 -0.03215634 0.06334936 0.09299999 -0.03001314 0.06291759 0.09299999 -0.03405326 0.06155931 0.09299999 -0.03494471 0.06000459 0.09299999 -0.03288429 0.06401616 0.09299999 -0.02868205 0.06613582 0.09299999 -0.02941644 0.06038826 0.09299999 -0.03599745 0.06647425 0.09299999 -0.02775281 0.05858767 0.09299999 -0.0333417 0.06446593 0.09299999 -0.0269308 0.05943691 0.09299999 -0.03734737 0.06647115 0.09299999 -0.02559411 0.0571084 0.09299999 -0.03351068 0.06442326 0.09299999 -0.02475655 0.058851 0.09299999 -0.03869611 0.06595891 0.09299999 -0.02352505 0.05562484 0.09299999 -0.0333845 0.05852138 0.09299999 -0.04025417 0.05419528 0.09299999 -0.03296822 0.06387448 0.09299999 -0.02297312 0.06475782 0.09299999 -0.02157181 0.05287587 0.09299999 -0.03227806 0.06314247 0.09299999 -0.02167677 0.05171859 0.09299999 -0.03134125 0.06216919 0.09299999 -0.02055019 0.05076867 0.09299999 -0.06680554 0.05076867 0.09299999 -0.03019446 0.06099259 0.09299999 -0.01963758 0.05965924 0.09299999 -0.01897501 0.04995197 0.09299558 -0.007709622 0.05822157 0.09299999 -0.01858854 0.05673569 0.09299999 -0.01849317 0.05526018 0.09299999 -0.01869273 0.05385297 0.09299999 -0.01917952 0.05256938 0.09299999 -0.01993429 0.05145996 0.09299999 -0.02092742 0.05028927 0.09300655 -0.0225746 0.04999631 0.09298819 -0.02873218 0.06651729 0.08999997 -0.02600133 0.06636989 0.08999997 -0.02845871 0.06581056 0.08999997 -0.03036755 0.06483656 0.08999997 -0.03209352 0.06367576 0.08999997 -0.0334227 0.06217902 0.08999997 -0.03454434 0.06647741 0.08999997 -0.06935662 0.0660547 0.08999997 -0.06724733 0.06484782 0.08999997 -0.06489121 0.06317889 0.08999997 -0.06313258 0.06131124 0.08999997 -0.06188017 0.06010723 0.08999997 -0.06065732 0.05905902 0.08999997 -0.05893439 0.05852437 0.08999997 -0.05679804 0.0585606 0.08999997 -0.03980684 0.05922615 0.08999997 -0.03773933 0.06045126 0.08999997 -0.03590101 0.05374526 0.08999997 -0.02322429 0.05197805 0.08999556 -0.009600639 0.05489605 0.08999997 -0.02228975 0.05300337 0.08999997 -0.0245102 0.05587613 0.08999997 -0.02189457 0.05703365 0.08999997 -0.02172917 0.05818164 0.08999997 -0.02191084 0.06457579 0.08999997 -0.02138346 0.05906546 0.08999997 -0.02227371 0.06008076 0.08999997 -0.02304196 0.0609067 0.08999997 -0.02427411 0.0654118 0.08999997 -0.02250224 0.06611067 0.08999997 -0.02397519 0.06121331 0.08999997 -0.02539545 0.06122452 0.08999997 -0.02667123 0.06077653 0.08999997 -0.02797192 0.05805337 0.08999997 -0.03013694 0.05678755 0.08999997 -0.03025656 0.0590108 0.08999997 -0.02974802 0.05996221 0.08999997 -0.02908587 0.05540543 0.08999997 -0.02996921 0.054237 0.08999997 -0.02924299 0.05333226 0.08999997 -0.02820122 0.05397254 0.08999997 -0.0680024 0.05489605 0.08999997 -0.06728971 0.05325257 0.08999997 -0.06895929 0.05618667 0.08999997 -0.06680715 0.05777633 0.08999997 -0.0667935 0.059161 0.08999997 -0.06732273 0.06014895 0.08999997 -0.0681231 0.06075239 0.08999997 -0.06899082 0.05483889 0.08999997 -0.07467722 0.05370134 0.08999997 -0.07372331 0.05306619 0.08999997 -0.07262563 0.05277758 0.08999997 -0.071603 0.06110966 0.08999997 -0.06987679 0.06125253 0.08999997 -0.07081776 0.05622363 0.08999997 -0.07520651 0.05749934 0.08999997 -0.07522702 0.06646054 0.08999997 -0.07260739 0.06119 0.08999997 -0.07177114 0.05852746 0.08999997 -0.07498234 0.06018233 0.08999997 -0.0801146 0.06074017 0.08999997 -0.07307571 0.06599885 0.08999997 -0.07448363 0.0621947 0.08999997 -0.07920479 0.06537294 0.08999997 -0.07588934 0.05971944 0.08999997 -0.07429325 0.06408804 0.08999997 -0.07767874 0.05273133 0.08999997 -0.02585983 0.05286782 0.08999997 -0.02702122 0.05279582 0.08999997 -0.07025873 0.06444656 0.092 -0.07198435 0.06410467 0.092 -0.07343798 0.0634821 0.092 -0.07479518 0.06260329 0.092 -0.07600241 0.06150305 0.092 -0.077012 0.060225 0.092 -0.07778388 0.05881947 0.092 -0.07828778 0.05734211 0.092 -0.07850366 0.05585116 0.092 -0.07842314 0.05440545 0.092 -0.07804918 0.05306243 0.092 -0.07739681 0.05187499 0.092 -0.07649159 0.05089014 0.092 -0.07536959 0.05006444 0.092 -0.07390111 0.04952919 0.09199994 -0.07191777 0.04958343 0.09289741 -0.07217168 0.04949361 0.09286737 -0.07056337 0.04954618 0.092 -0.0700792 0.04990607 0.09297746 -0.06848037 0.04982 0.092 -0.06880825 0.05031347 0.092 -0.06757831 0.05111521 0.092 -0.06633168 0.05215477 0.092 -0.06525999 0.05338567 0.092 -0.06441515 0.0547595 0.092 -0.06383037 0.05622172 0.092 -0.06352889 0.05771499 0.092 -0.06352257 0.05917978 0.092 -0.06381171 0.06055843 0.092 -0.06438487 0.0617966 0.092 -0.06521946 0.06284523 0.092 -0.06628251 0.06366294 0.092 -0.06753212 0.06421726 0.092 -0.0689187 0.06449246 0.092 -0.07043981 0.06010407 0.092 -0.06807476 0.05937385 0.092 -0.06747066 0.06077653 0.092 -0.06902801 0.05852746 0.092 -0.06701761 0.06111729 0.092 -0.06992048 0.05749934 0.092 -0.06677293 0.06126511 0.092 -0.07096695 0.05622363 0.092 -0.0667935 0.06110966 0.092 -0.07212316 0.05483895 0.092 -0.06732273 0.06065654 0.092 -0.07319581 0.05379921 0.092 -0.06817519 0.05999338 0.092 -0.07402604 0.05916106 0.092 -0.07467722 0.05297821 0.092 -0.06953608 0.05777633 0.092 -0.07520651 0.05273133 0.092 -0.07114011 0.05650061 0.092 -0.07522702 0.05297166 0.092 -0.07238698 0.05547249 0.092 -0.07498234 0.05343854 0.092 -0.07333821 0.05428051 0.092 -0.07429325 0.04948562 0.092866 -0.02655917 0.04964423 0.09291595 -0.02447354 0.04917734 0.09274208 -0.006986677 0.04854112 0.09229415 -0.006392896 0.04803752 0.09159153 -0.005922853 0.05086332 0.08952218 -0.00856024 0.05024844 0.08883392 -0.007986366 0.04900157 0.08656746 -0.006822645 0.04715049 0.08445119 -0.005094945 0.04512953 0.0829153 -0.003208696 0.04310488 0.08190792 -0.001318991 0.04129379 0.08133983 3.7127e-4 0.03954976 0.08104968 0.002053618 0.03819197 0.08099955 0.004060149 0.06444656 0.092 -0.02698433 0.06410473 0.092 -0.02843797 0.0634821 0.092 -0.02979516 0.06260329 0.092 -0.0310024 0.06150317 0.092 -0.03201192 0.06022506 0.092 -0.03278386 0.05881947 0.092 -0.03328776 0.05734199 0.092 -0.03350371 0.0558511 0.092 -0.03342312 0.05440557 0.092 -0.03304922 0.05306255 0.092 -0.03239685 0.05187505 0.092 -0.03149169 0.05089014 0.092 -0.03036957 0.05006444 0.092 -0.0289011 0.04952919 0.09199994 -0.02691775 0.04954618 0.092 -0.02507919 0.04982 0.092 -0.02380824 0.05031347 0.092 -0.02257829 0.05111515 0.092 -0.02133172 0.05215471 0.092 -0.02026003 0.05338561 0.092 -0.01941514 0.0547595 0.092 -0.01883035 0.05622184 0.092 -0.01852887 0.05771487 0.092 -0.01852256 0.05917978 0.092 -0.01881176 0.06055861 0.092 -0.01938498 0.0617966 0.092 -0.0202195 0.06284523 0.092 -0.02128249 0.063663 0.092 -0.02253216 0.06421726 0.092 -0.02391868 0.06449246 0.092 -0.02543985 0.04011309 0.08416223 0.001477897 0.04187399 0.08463412 -1.70255e-4 0.04385489 0.08566623 -0.002019047 0.04538631 0.08692252 -0.003448367 0.0465213 0.08829027 -0.00450772 0.04749369 0.09000909 -0.00541526 -0.0204522 0.08136755 6.75691e-4 -0.01933836 0.08420163 0.001749932 -0.02062505 0.08456224 5.28793e-4 -0.02260351 0.08212429 -0.001317739 -0.0221191 0.08522033 -8.65689e-4 -0.02446967 0.08313077 -0.003059506 -0.0237385 0.08632856 -0.002377092 -0.02649605 0.08478301 -0.004950761 -0.02497589 0.08757632 -0.003531992 -0.02598136 0.08900588 -0.004470467 -0.02797776 0.08656221 -0.006333708 -0.02666211 0.09046828 -0.005105793 -0.02931326 0.08893501 -0.007580161 -0.02700924 0.09152442 -0.005429744 -0.02746886 0.09222161 -0.005858778 -0.02823805 0.09278041 -0.006576657 -0.02995449 0.0895794 -0.008178651 -0.02907419 0.0929991 -0.00735706 -0.03097534 0.08999437 -0.009131431 -0.04004877 0.092 -0.02302604 -0.03916102 0.092 -0.02232271 -0.04072993 0.092 -0.0239312 -0.03818166 0.092 -0.02191084 -0.0412321 0.092 -0.02536207 -0.03721237 0.092 -0.02174341 -0.04120433 0.092 -0.02666401 -0.03626096 0.092 -0.02180922 -0.04095411 0.092 -0.02758616 -0.03534448 0.092 -0.02207279 -0.04037994 0.092 -0.02860152 -0.03434163 0.092 -0.02266663 -0.03963035 0.092 -0.02934634 -0.03336787 0.092 -0.02374047 -0.03881973 0.092 -0.02985221 -0.03288269 0.092 -0.02492046 -0.03781288 0.092 -0.03018212 -0.03272962 0.092 -0.0260728 -0.03643423 0.092 -0.03023993 -0.03295999 0.092 -0.02735728 -0.0349279 0.092 -0.02973461 -0.03365182 0.092 -0.02867007 0.053851 0.092 -0.02312308 0.05483895 0.092 -0.02232271 0.05319434 0.092 -0.02408474 0.05581831 0.092 -0.02191084 0.05278819 0.092 -0.02529156 0.0569663 0.092 -0.02172917 0.05279988 0.092 -0.0267747 0.05812382 0.092 -0.02189457 0.05327004 0.092 -0.02806878 0.05900943 0.092 -0.02224326 0.06003379 0.092 -0.0229938 0.05390036 0.092 -0.02891713 0.05462646 0.092 -0.02953797 0.06077653 0.092 -0.02402806 0.05577331 0.092 -0.03009098 0.06122452 0.092 -0.02532869 0.05703186 0.092 -0.03026026 0.06118708 0.092 -0.02681273 0.05797636 0.092 -0.0301429 0.05907201 0.092 -0.02973461 0.06076145 0.092 -0.02801084 0.06007194 0.092 -0.02895194 -0.01885688 0.08108937 0.002307355 -0.01754456 0.08099901 0.004310846 0.02852517 0.08099997 -0.004620134 0.0290209 0.08099997 -0.004067778 0.02779686 0.08099997 -0.004913449 0.02926242 0.08099997 -0.003366768 0.02701228 0.08099997 -0.004874289 0.02915245 0.08099997 -0.002545118 0.02877342 0.08099997 -0.001958489 0.03729659 0.08099997 0.006265819 0.02812433 0.08099997 -0.00151664 0.02004432 0.08099997 0.004779875 0.0262233 0.08099997 -0.001968204 0.0193147 0.08099997 0.004050672 0.02671569 0.08099997 -0.001607477 0.02589178 0.08099997 -0.002481758 0.01825875 0.08099997 0.003550648 0.02052414 0.08099997 0.005899012 0.02729982 0.08099997 -0.001427114 0.02575224 0.08099997 -0.003031253 0.03697824 0.08099997 0.01064848 0.03693187 0.08099997 0.008442223 0.02581769 0.08099997 -0.003682196 0.03345197 0.08099997 0.02433073 0.03397458 0.08099997 0.02485775 0.03427034 0.08099997 0.0256322 0.03270989 0.08099997 0.02407413 0.03197121 0.08099997 0.02414172 0.03754752 0.08099997 0.01296794 0.02054172 0.08099997 0.01896095 0.03122657 0.08099997 0.02459681 0.0202412 0.08099997 0.01987266 0.03726202 0.08099752 0.036471 0.0341469 0.08099997 0.02645307 0.0308026 0.08099997 0.02535927 0.03415584 0.08099997 0.03420424 0.03374946 0.08099997 0.02707898 0.00326395 0.08099997 0.003507256 0.01977574 0.08099997 0.02053451 -0.005436897 0.08099997 -0.004597365 0.02622658 0.08099997 -0.004403114 -0.004936516 0.08099997 -0.003991067 0.03171992 0.08099997 0.03293168 0.03299742 0.08099997 0.02752131 -0.006160199 0.08099997 -0.004902899 -0.004736721 0.08099997 -0.003322482 -0.006902456 0.08099997 -0.004896759 0.002430677 0.08099997 0.003704965 -0.004823684 0.08099997 -0.002629518 0.02873063 0.08099997 0.03181105 0.03208166 0.08099997 0.02754384 0.001385092 0.08099997 0.004392206 -0.007568001 0.08099997 -0.004569888 -0.005119502 0.08099997 -0.002079427 0.03138506 0.08099997 0.02717953 -0.008030176 0.08099997 -0.00404632 -0.005542576 0.08099997 -0.001701712 0.03096479 0.08099997 0.0266782 8.24485e-4 0.08099997 0.005262136 -0.006089448 0.08099997 -0.001462459 5.8347e-4 0.08099997 0.00603646 0.02452021 0.08099997 0.03104257 0.03076165 0.08099997 0.02605593 0.01808989 0.08099997 0.02146905 0.0190922 0.08099997 0.02109611 -0.008233726 0.08099997 -0.003424763 -0.008224546 0.08099997 -0.002857446 -0.007969498 0.08099997 -0.002207279 -0.007509291 0.08099997 -0.001742601 -0.01669085 0.08099997 0.006716847 -0.006874501 0.08099997 -0.001449823 -0.0163812 0.08099997 0.009239912 -0.01669085 0.08099997 0.01176291 -0.00309205 0.08099997 0.03102993 0.002053976 0.08099997 0.02111357 0.003100335 0.08099997 0.02147781 0.001372277 0.08099997 0.02055513 -0.01047831 0.08099997 0.02438527 5.78382e-4 0.08099997 0.01888221 -0.009949445 0.08099997 0.02496546 8.5553e-4 0.08099997 0.01983475 -0.01124531 0.08099997 0.02406954 -0.01719337 0.08099997 0.01331901 -0.009720861 0.08099997 0.0258975 -0.0120694 0.08099997 0.02415841 -0.005555808 0.08099997 0.03133529 -0.01277339 0.08099997 0.02459681 -0.01323848 0.08099997 0.02548581 -0.008618652 0.08099997 0.03209042 -0.01007086 0.08099997 0.02688413 -0.01075792 0.08099997 0.02742314 -0.01152586 0.08099997 0.0333144 -0.01161336 0.08099997 0.02759534 -0.01240026 0.08099997 0.02733129 -0.01428407 0.08099997 0.0349223 -0.01286137 0.08099997 0.0269308 -0.01681941 0.08099919 0.03701955 -0.01317399 0.08099997 0.0263561 -0.01824462 0.0840426 0.003153979 -0.01739937 0.08399975 0.004657208 0.03882926 0.08400243 0.002987563 0.03830009 0.08399999 -0.01796108 0.03830009 0.08399999 -0.01807087 0.0285815 0.08399999 -0.004574298 0.02912563 0.08399999 -0.003891944 0.02795225 0.08399999 -0.004877209 0.02926242 0.08399999 -0.002986133 0.02738714 0.08399999 -0.004928767 0.03829979 0.08399999 -0.01801598 0.02675211 0.08399999 -0.004772245 0.02904069 0.08399999 -0.002324581 0.0286597 0.08399999 -0.001846551 0.03779488 0.08399999 0.004903793 0.03719991 0.08399999 0.006676435 0.02809327 0.08399999 -0.001519203 0.03691291 0.08399999 0.008707642 0.02622658 0.08399999 -0.001949787 0.01973253 0.08399999 0.004399955 0.0190252 0.08399999 0.003874361 0.02581769 0.08399999 -0.002670705 0.02027148 0.08399999 0.005192995 0.02685064 0.08399999 -0.001546561 0.01814579 0.08399999 0.003532528 0.02054172 0.08399999 0.00603646 0.02744686 0.08399999 -0.001416087 0.0257672 0.08399999 -0.003542542 0.0370025 0.08399999 0.01075714 0.03859513 0.08399921 0.0151422 0.03374946 0.08399999 0.02456796 0.03418189 0.08399999 0.02527505 0.03291416 0.08399999 0.02409547 0.03425824 0.08399999 0.02592456 0.0374974 0.08399999 0.0128256 0.03199833 0.08399999 0.02413332 0.02055597 0.08399999 0.01874166 0.0314204 0.08399999 0.02444195 0.02040851 0.08399999 0.01949214 0.03103512 0.08399999 0.02485769 0.03785938 0.08399814 0.03705841 0.03413683 0.08399999 0.02647882 0.03528434 0.08399999 0.0349223 0.03378641 0.08399999 0.02703177 0.0198639 0.08399999 0.02045249 0.003228962 0.08399999 0.003510653 0.0332939 0.08399999 0.0273925 0.03150284 0.08399999 0.03280645 0.03275328 0.08399999 0.02756446 0.02616465 0.08399999 -0.004319369 -0.005319118 0.08399999 -0.004487752 -0.004902124 0.08399999 -0.003928005 -0.00604397 0.08399999 -0.004889726 -0.004730939 0.08399999 -0.003206253 0.03201228 0.08399999 0.02752131 -0.006829977 0.08399999 -0.004902899 0.002457797 0.08399999 0.003698289 -0.004908561 0.08399999 -0.002396523 -0.007438898 0.08399999 -0.004663586 0.001456081 0.08399999 0.004321217 0.0312944 0.08399999 0.02710723 0.02848333 0.08399999 0.03176957 -0.005441069 0.08399999 -0.001761436 0.03087639 0.08399999 0.02649462 7.6887e-4 0.08399999 0.005366802 -0.006159424 0.08399999 -0.00144428 0.02592796 0.08399999 0.0312252 5.73227e-4 0.08399999 0.006186068 0.03073936 0.08399999 0.0256322 0.02355426 0.08399999 0.03101295 0.01906633 0.08399999 0.02110666 0.01809692 0.08399999 0.02147054 0.003035306 0.08399999 0.02146905 -0.007568001 0.08399999 -0.001783013 -0.008078157 0.08399999 -0.002381086 -0.008256375 0.08399999 -0.003190517 -0.00804764 0.08399999 -0.004038453 -0.01672577 0.08399999 0.006572663 -0.006944239 0.08399999 -0.001470148 -0.01643127 0.08399999 0.008454918 -0.01643812 0.08399999 0.01008999 -0.01672577 0.08399999 0.0119071 -0.002886474 0.08399999 0.03101891 0.001837849 0.08399999 0.02098953 5.90772e-4 0.08399999 0.01903295 -0.01021677 0.08399999 0.02459681 9.89247e-4 0.08399999 0.0200684 -0.01096147 0.08399999 0.02414172 -0.009792804 0.08399999 0.02535927 -0.0118761 0.08399999 0.02408903 -0.009771108 0.08399999 0.02623176 -0.006531476 0.08399999 0.0314992 -0.01271921 0.08399999 0.02454799 -0.0101816 0.08399999 0.02700161 -0.01316308 0.08399999 0.02524811 -0.01078355 0.08399999 0.0274347 -0.01078337 0.08399999 0.03293138 -0.01133346 0.08399999 0.0275703 -0.01198768 0.08399999 0.02752137 -0.01263612 0.08399999 0.02716171 -0.014535 0.08399999 0.03509974 -0.01300072 0.08399999 0.02672773 -0.01324528 0.08399999 0.0260728 -0.01733535 0.08399689 0.0375297 0.04097878 0.08435565 0.01779532 0.04058879 0.08119165 0.0174809 0.03984284 0.08411735 0.01671987 0.03872495 0.08099937 0.01534783 0.04623848 0.08790123 0.02134376 0.04832082 0.08569061 0.02273201 0.04707139 0.08440059 0.02189904 0.04480254 0.08636868 0.02038645 0.04568636 0.08328163 0.0209757 0.04740637 0.08979052 0.02212232 0.04958486 0.0875222 0.0235747 0.04993295 0.09299427 0.02380675 0.05128479 0.08975839 0.02470797 0.05072253 0.08939045 0.02433311 0.05205225 0.08999657 0.02521961 0.05025124 0.08884137 0.02401894 0.04277122 0.08503144 0.01903349 0.04315072 0.08189904 0.01928943 0.04882645 0.09255123 0.02306908 0.04807496 0.09167933 0.0225681 0.06548511 0.09299999 0.03757512 0.06544458 0.08999997 0.0370596 0.06512725 0.09299999 0.03578108 0.06495076 0.08999997 0.03536611 0.0642789 0.08999997 0.03406423 0.06431514 0.09299999 0.03413236 0.06304955 0.09299999 0.03260791 0.06298035 0.08999997 0.03255784 0.05216777 0.08999848 0.04686576 0.05397391 0.08999997 0.04199337 0.05471539 0.08999997 0.04259604 0.05326533 0.08999997 0.04107201 0.05524665 0.08999997 0.04742956 0.05557245 0.08999997 0.04300993 0.05283045 0.08999997 0.03987544 0.05650186 0.08999997 0.04323118 0.05752956 0.08999997 0.04322594 0.05892175 0.08999997 0.04746586 0.05862635 0.08999997 0.04294294 0.06065422 0.08999997 0.04702514 0.06213039 0.08999997 0.0462802 0.05957067 0.08999997 0.04239392 0.06340366 0.08999997 0.0452156 0.06033337 0.08999997 0.04165834 0.06461822 0.08999997 0.04360252 0.0610153 0.08999997 0.04046142 0.06544786 0.08999997 0.04115438 0.06125372 0.08999997 0.03921228 0.05544292 0.08999997 0.03503268 0.05448716 0.08999997 0.03555947 0.05357527 0.08999997 0.036448 0.05303883 0.08999997 0.03744512 0.06114089 0.08999997 0.03794556 0.06045299 0.08999997 0.0364753 0.05946099 0.08999997 0.03552228 0.05842775 0.08999997 0.03498083 0.05689322 0.08999997 0.03471887 0.0527482 0.08999997 0.03857451 0.06548345 0.09299999 0.04060614 0.04954564 0.08744382 0.04604804 0.04827731 0.08564925 0.04551398 0.04652398 0.08389669 0.04462891 0.04475355 0.08271062 0.04349511 0.0433498 0.08201009 0.04242652 0.04158985 0.08141028 0.04079681 0.03961724 0.08105963 0.03881585 0.04755997 0.0901978 0.04516965 0.0468105 0.08873391 0.04477697 0.04589986 0.0874871 0.04424899 0.04478728 0.08637541 0.04351961 0.04361629 0.08552289 0.0426402 0.042342 0.08484315 0.04153263 0.04016041 0.08413815 0.03935903 -0.02043312 0.0844863 0.01777648 -0.02095848 0.08151155 0.01815867 -0.01923143 0.08113521 0.01662802 -0.01886355 0.08411747 0.01617693 -0.01787531 0.08100962 0.01474779 -0.01758205 0.08399945 0.01423203 -0.03102505 0.0899958 0.02486813 -0.02652955 0.08482611 0.02187114 -0.02496439 0.08755028 0.02082771 -0.02819418 0.08685076 0.02298092 -0.02634578 0.08965283 0.02174866 -0.02365124 0.08626276 0.01995229 -0.02494633 0.08347082 0.02081567 -0.02899664 0.09299719 0.02351588 -0.03001099 0.08962088 0.02419215 -0.02219563 0.08526289 0.01898187 -0.02315181 0.08237612 0.01961928 -0.0292961 0.08891868 0.02371549 -0.02824348 0.09277272 0.02301377 -0.02702248 0.09155756 0.0221998 -0.02755117 0.09231084 0.02255225 -0.04497551 0.08999997 0.03739887 -0.04497343 0.09299999 0.03741627 -0.0444833 0.09299999 0.03536605 -0.04443842 0.08999997 0.03525793 -0.043343 0.09299999 0.03346818 -0.04327255 0.08999997 0.03338247 -0.0421707 0.09299999 0.03231644 -0.04215717 0.08999997 0.03230947 -0.03126811 0.09299999 0.03450238 -0.03258287 0.09299999 0.03324365 -0.03384548 0.09299999 0.03244972 -0.03007555 0.09299999 0.03673404 -0.03591459 0.09299999 0.03179889 -0.02972418 0.09299999 0.03905624 -0.03802931 0.09299999 0.03180545 -0.04120141 0.09299999 0.03305959 -0.0396049 0.09299999 0.03222233 -0.0299763 0.09299999 0.04084128 -0.02897191 0.09299445 0.04620563 -0.03063708 0.09299999 0.04252898 -0.03183531 0.09299999 0.04411339 -0.0425291 0.09299999 0.03429347 -0.03157848 0.09299999 0.04698795 -0.03325682 0.09299999 0.04522967 -0.04344236 0.09299999 0.03563606 -0.03490984 0.09299999 0.04596072 -0.04402363 0.09299999 0.03715866 -0.03507864 0.09299999 0.04747062 -0.04427576 0.09299999 0.03894376 -0.03705739 0.09299999 0.04628551 -0.04494786 0.09299999 0.04115426 -0.04404896 0.09299999 0.04074192 -0.03842175 0.09299999 0.04746586 -0.0391941 0.09299999 0.04592859 -0.04349201 0.09299999 0.04226702 -0.04015427 0.09299999 0.04702514 -0.04427212 0.09299999 0.04326295 -0.04115146 0.09299999 0.04498726 -0.04163038 0.09299999 0.0462802 -0.04259502 0.09299999 0.04362785 -0.04316121 0.09299999 0.04495775 -0.02642565 0.08982563 0.04510515 -0.02494132 0.08751374 0.04427796 -0.02350604 0.08614683 0.04331934 -0.02217662 0.08525764 0.04228109 -0.02049052 0.08450144 0.04069811 -0.01880371 0.0841093 0.03900253 -0.02853143 0.08742958 0.04604208 -0.02717548 0.0855152 0.04546976 -0.02551919 0.08391231 0.04461884 -0.0235657 0.08258551 0.04337501 -0.02145755 0.08167058 0.04164612 -0.01892745 0.08107692 0.03912627 -0.04345321 0.08999997 0.04457849 -0.04038405 0.08999997 0.04160559 -0.04244548 0.08999997 0.04565179 -0.03954595 0.08999997 0.04241102 -0.04109269 0.08999997 0.04660248 -0.04431951 0.08999997 0.04316282 -0.03862637 0.08999997 0.04294294 -0.0449447 0.08999997 0.04113644 -0.04100483 0.08999997 0.04045766 -0.03955364 0.08999997 0.0472235 -0.03749805 0.08999997 0.04323118 -0.03815537 0.08999997 0.04747986 -0.04128241 0.08999997 0.03899997 -0.03647041 0.08999997 0.04322594 -0.03434318 0.08999997 0.04744273 -0.04101425 0.08999997 0.0375728 -0.03537356 0.08999997 0.04294294 -0.0404247 0.08999997 0.03644806 -0.03442925 0.08999997 0.04239392 -0.03094977 0.08998984 0.04681271 -0.03366655 0.08999997 0.04165828 -0.03959387 0.08999997 0.03562521 -0.03298461 0.08999997 0.04046142 -0.03865742 0.08999997 0.03506803 -0.0374245 0.08999997 0.03475755 -0.03274619 0.08999997 0.03921228 -0.03283995 0.08999997 0.03805053 -0.03332275 0.08999997 0.03683888 -0.0342766 0.08999997 0.03570139 -0.03547322 0.08999997 0.03502249 -0.03639543 0.08999997 0.0347867 0.06175363 0.09299999 0.03351134 0.06274425 0.09299999 0.03455859 0.06057572 0.09299999 0.03268045 0.06350851 0.09299999 0.03578102 0.05925685 0.09299999 0.03209865 0.06401622 0.09299999 0.03713035 0.05784893 0.09299999 0.03178882 0.06424731 0.09299999 0.03855317 0.05646514 0.09299999 0.03176063 0.06419271 0.09299999 0.03999364 0.05510473 0.09299999 0.03199082 0.06385463 0.09299999 0.04139512 0.06525272 0.09299999 0.04195159 0.05376762 0.09299999 0.03249824 0.06457638 0.09299999 0.04365831 0.06324642 0.09299999 0.04270207 0.05255579 0.09299999 0.03325796 0.06239193 0.09299999 0.04386317 0.06347566 0.09299999 0.04513996 0.05151629 0.09299999 0.03424066 0.06132483 0.09299999 0.04483258 0.06192421 0.09299999 0.04643213 0.05068963 0.09299999 0.03540807 0.0600872 0.09299999 0.0455721 0.0600537 0.09299999 0.0472235 0.05872803 0.09299999 0.04605245 0.05865538 0.09299999 0.04747986 0.05730062 0.09299999 0.04625487 0.05616271 0.09299999 0.04747772 0.05586135 0.09299999 0.0461713 0.05446702 0.09299999 0.04580503 0.05256843 0.09299999 0.04698729 0.05317252 0.09299999 0.04517048 0.05202877 0.09299999 0.04429256 0.05009961 0.09299749 0.04624897 0.05108112 0.09299999 0.04320609 0.05036807 0.09300267 0.04195594 0.05005419 0.09299194 0.03686326 0.04993081 0.09297406 0.04065352 0.04972326 0.09293335 0.03885489 0.0494008 0.09284693 0.04598951 0.04868096 0.09241724 0.04569262 0.04808223 0.09169626 0.04542291 -0.02987217 0.08952575 0.04650568 -0.02925837 0.08885079 0.04630345 0.05138528 0.08981329 0.04665869 0.05060082 0.08928489 0.0464186 0.05019074 0.08872842 0.04627972 -0.02809214 0.09270238 0.04586595 -0.02744263 0.09218758 0.04558777 -0.02701574 0.09153926 0.04539114 0.05849754 0.092 0.03186988 0.06035441 0.092 0.03256022 0.06156259 0.092 0.03335154 0.06259036 0.092 0.0343663 0.06339693 0.092 0.03556454 0.06395035 0.092 0.03689861 0.06422877 0.092 0.03831583 0.0642212 0.092 0.03975999 0.06392794 0.092 0.04117417 0.06336057 0.092 0.04250234 0.06254154 0.092 0.04369199 0.06150323 0.092 0.04469603 0.06028693 0.092 0.04547452 0.05894041 0.092 0.04599708 0.05751723 0.092 0.04624271 0.0560736 0.092 0.04620182 0.05466657 0.092 0.04587602 0.05335187 0.092 0.04527819 0.05218154 0.092 0.04443204 0.0512017 0.092 0.0433709 0.05045235 0.092 0.04213893 0.04996633 0.092 0.04080134 0.04974693 0.092 0.03936165 0.04990208 0.092 0.03735589 0.05061477 0.092 0.03554272 0.05142241 0.092 0.03435087 0.05244946 0.092 0.0333417 0.05365544 0.092 0.0325551 0.05499327 0.092 0.03202182 0.05646055 0.092 0.03175717 0.05393195 0.092 0.04195034 0.05466181 0.092 0.04256147 0.05323314 0.092 0.04101294 0.055516 0.092 0.04298937 0.05281782 0.092 0.03981292 0.05643862 0.092 0.04322326 0.05276 0.092 0.03843426 0.05774194 0.092 0.04320812 0.05309098 0.092 0.03732329 0.05894297 0.092 0.04278999 0.0535562 0.092 0.03648346 0.05987685 0.092 0.04214894 0.05428713 0.092 0.03572005 0.06061857 0.092 0.04124867 0.05536991 0.092 0.0350452 0.06103587 0.092 0.04035598 0.06125563 0.092 0.03928577 0.05671334 0.092 0.0347492 0.05766397 0.092 0.03479564 0.06111544 0.092 0.03784203 0.05858618 0.092 0.03504586 0.06053799 0.092 0.03662645 0.0596891 0.092 0.0356819 -0.03687489 0.092 0.03172504 -0.0349099 0.092 0.03203922 -0.03294336 0.092 0.03294801 -0.0314362 0.092 0.03433144 -0.03036201 0.092 0.03600478 -0.02979558 0.092 0.03804224 -0.02977013 0.092 0.03967195 -0.03015995 0.092 0.04148966 -0.03110092 0.092 0.04324114 -0.03203165 0.092 0.04428791 -0.03316402 0.092 0.04517292 -0.03480583 0.092 0.04592859 -0.0369426 0.092 0.04628551 -0.03891706 0.092 0.04600334 -0.04058921 0.092 0.04532909 -0.04203307 0.092 0.04423356 -0.04307532 0.092 0.04298871 -0.04393595 0.092 0.04119831 -0.04424923 0.092 0.03941309 -0.04414266 0.092 0.03761339 -0.04349201 0.092 0.03573298 -0.04259502 0.092 0.03437209 -0.04129272 0.092 0.03312528 -0.03920221 0.092 0.03205502 -0.03985118 0.092 0.04217988 -0.04063415 0.092 0.04122084 -0.0386871 0.092 0.04291737 -0.04110747 0.092 0.0401557 -0.03756135 0.092 0.04322326 -0.04126328 0.092 0.03868049 -0.03625804 0.092 0.04320812 -0.04096323 0.092 0.03744435 -0.03505694 0.092 0.04278999 -0.04050201 0.092 0.0365737 -0.034042 0.092 0.04208081 -0.03958141 0.092 0.03559201 -0.03327375 0.092 0.04106551 -0.03835731 0.092 0.03496003 -0.03282046 0.092 0.03987914 -0.03728657 0.092 0.0347492 -0.03275769 0.092 0.03860753 -0.03633594 0.092 0.03479564 -0.03309881 0.092 0.03723967 -0.03531283 0.092 0.03508257 -0.034092 0.092 0.03586596 0.03829985 0.08399999 -0.01802134 0.03830009 0.08399999 -0.01796108 0.03829985 0.08399999 -0.01802134 0.03830009 0.08399999 -0.01796108 0.01970785 0.06299996 -0.0308507 0.01976984 0.06901836 -0.02730822 0.01974123 0.06928759 -0.02647966 0.01957142 0.06963384 -0.02521568 0.01919466 0.06299996 -0.02902477 0.01949483 0.07003271 -0.02450501 0.01895678 0.0703637 -0.02296233 0.01847976 0.06299996 -0.02772319 0.01818388 0.07051056 -0.02170884 0.0172916 0.06299996 -0.02650094 0.01772403 0.07113534 -0.02072709 0.0166406 0.07103633 -0.02007675 0.01563876 0.06299996 -0.02572429 0.01522296 0.0714671 -0.01930779 -0.04126113 0.07499998 0.03857356 -0.04127693 0.078 0.03907245 -0.04104155 0.078 0.03764206 -0.04085224 0.07499998 0.0371803 -0.0404247 0.078 0.03644806 -0.04021966 0.07499998 0.03620249 -0.03940361 0.078 0.03547435 -0.03916454 0.07499998 0.03531813 -0.03835642 0.078 0.03496271 -0.03797912 0.07499998 0.03485363 -0.03721272 0.078 0.03473824 -0.03668069 0.07499998 0.03473889 -0.03570652 0.078 0.03492265 -0.03544396 0.07499998 0.03503531 -0.03453892 0.07499998 0.03552228 -0.03448712 0.078 0.03555953 -0.03382855 0.07499998 0.03616106 -0.03364479 0.078 0.03636652 -0.03327375 0.07499998 0.03693443 -0.03301763 0.078 0.03747242 -0.03278505 0.07499998 0.03825682 -0.03271752 0.078 0.03899997 -0.03280538 0.07499998 0.03977304 -0.03301763 0.078 0.04052752 -0.03321957 0.07499998 0.04097509 -0.03370666 0.078 0.04171937 -0.03409206 0.07499998 0.04213398 -0.03466176 0.078 0.04256141 -0.03531283 0.07499998 0.04291737 -0.03594392 0.078 0.04314756 -0.03664726 0.07499998 0.04325634 -0.03745746 0.078 0.0432406 -0.03812426 0.07499998 0.04312032 -0.03888666 0.078 0.04283899 -0.03940361 0.07499998 0.04252558 -0.04028058 0.078 0.04175263 -0.04047119 0.07499998 0.04149568 -0.04100483 0.078 0.04045766 -0.04110747 0.07499998 0.04015564 -0.04120647 0.078 -0.02677631 -0.0409823 0.07499998 -0.02752751 -0.04067718 0.078 -0.02816104 -0.04022973 0.07499998 -0.02880465 -0.03980064 0.078 -0.02922445 -0.03922003 0.07499998 -0.02963298 -0.03862637 0.078 -0.02994298 -0.03815621 0.07499998 -0.0301094 -0.03717905 0.078 -0.03027379 -0.03692561 0.07499998 -0.03025972 -0.03556901 0.07499998 -0.03003108 -0.03581535 0.078 -0.03009235 -0.03474789 0.078 -0.02962219 -0.03425723 0.07499998 -0.02926874 -0.03393197 0.078 -0.02895039 -0.03352648 0.07499998 -0.02846014 -0.03328973 0.078 -0.02810394 -0.03298842 0.07499998 -0.02746009 -0.03292775 0.078 -0.02722805 -0.03274428 0.078 -0.02628576 -0.03274655 0.07499998 -0.02624416 -0.03283447 0.07499998 -0.02508306 -0.03283047 0.078 -0.02512449 -0.03321957 0.078 -0.02402484 -0.03316694 0.07499998 -0.02415436 -0.03386068 0.07499998 -0.0230872 -0.0338779 0.078 -0.02310305 -0.03468775 0.078 -0.02241986 -0.03521275 0.07499998 -0.02212095 -0.03567337 0.078 -0.02195137 -0.03633594 0.07499998 -0.02179563 -0.037 0.078 -0.0217247 -0.03763788 0.07499998 -0.02176785 -0.03832656 0.078 -0.02195137 -0.03906875 0.07499998 -0.02227002 -0.03955543 0.078 -0.02256965 -0.04022973 0.07499998 -0.02319532 -0.04070651 0.078 -0.02386003 -0.0409823 0.07499998 -0.02447247 -0.041206 0.078 -0.0252918 -0.04128241 0.07499998 -0.02599996 0.05272305 0.078 0.03907245 0.05289453 0.07499998 0.03787618 0.05295842 0.078 0.037642 0.05340468 0.07499998 0.03667795 0.05357527 0.078 0.03644806 0.05445098 0.07499998 0.03558021 0.0545963 0.078 0.03547435 0.055444 0.07499998 0.03503531 0.05564355 0.078 0.03496271 0.05657517 0.07499998 0.03475415 0.05678725 0.078 0.03473824 0.05815982 0.07499998 0.03487759 0.05829346 0.078 0.03492265 0.05972331 0.07499998 0.03570139 0.05951279 0.078 0.03555947 0.06035512 0.078 0.03636646 0.06073462 0.07499998 0.03692793 0.06098228 0.078 0.03747242 0.06124669 0.07499998 0.03846776 0.06128245 0.078 0.03899997 0.06113696 0.07499998 0.04005336 0.06098228 0.078 0.04052752 0.06065183 0.07499998 0.04119426 0.06029325 0.078 0.04171943 0.05985116 0.07499998 0.04217988 0.05933815 0.078 0.04256141 0.05868715 0.07499998 0.04291737 0.05838704 0.078 0.04302823 0.05735272 0.07499998 0.04325634 0.05721271 0.078 0.0432617 0.05587565 0.07499998 0.04312026 0.05591559 0.078 0.04312509 0.05484223 0.078 0.04267352 0.05459636 0.07499998 0.04252558 0.0537194 0.078 0.04175263 0.0537374 0.07499998 0.04173773 0.05307757 0.07499998 0.04068994 0.05299514 0.078 0.04045772 0.05272471 0.07499998 0.0391407 0.05274659 0.078 -0.02624416 0.05283445 0.07499998 -0.02691692 0.0529108 0.078 -0.02718156 0.05338829 0.07499998 -0.02829194 0.05332273 0.078 -0.02816104 0.05397397 0.078 -0.02899342 0.054241 0.07499998 -0.0292412 0.05480414 0.078 -0.02965658 0.0551486 0.07499998 -0.0298444 0.05615288 0.078 -0.03019052 0.05667996 0.07499998 -0.03027045 0.05784797 0.078 -0.03019505 0.05843096 0.07499998 -0.03003108 0.05925208 0.078 -0.02962219 0.05974274 0.07499998 -0.02926874 0.06006795 0.078 -0.02895039 0.0607025 0.07499998 -0.02813756 0.06071019 0.078 -0.02810394 0.06107217 0.078 -0.02722811 0.06116944 0.07499998 -0.02687543 0.06125563 0.078 -0.02628576 0.06125658 0.07499998 -0.02578753 0.06116944 0.078 -0.02512449 0.06100171 0.07499998 -0.02450764 0.06078034 0.078 -0.02402484 0.06033337 0.07499998 -0.02334165 0.06012207 0.078 -0.02310305 0.05948781 0.07499998 -0.02253955 0.05931216 0.078 -0.02241986 0.05815982 0.07499998 -0.02187758 0.05832654 0.078 -0.02195137 0.05699998 0.078 -0.0217247 0.05636209 0.07499998 -0.02176785 0.05567336 0.078 -0.02195137 0.05493116 0.07499998 -0.02227002 0.05444449 0.078 -0.02256965 0.05408287 0.07499998 -0.02290028 0.05347865 0.078 -0.02359914 0.05333811 0.07499998 -0.0238018 0.05287319 0.078 -0.02487426 0.05276536 0.07499998 -0.02536177 0.05820584 0.078 -0.03494828 0.05768334 0.07300001 -0.03498482 -0.04597145 0.07300001 -0.0269984 -0.04596108 0.078 -0.0269984 -0.04558062 0.078 -0.02878433 -0.04554432 0.07300001 -0.02886873 -0.04472339 0.07300001 -0.0306614 -0.04454267 0.078 -0.0309664 -0.04336923 0.07300001 -0.03238844 -0.04295152 0.078 -0.03277933 -0.04145461 0.07300001 -0.03385573 -0.041332 0.078 -0.03390371 -0.03977602 0.078 -0.0345726 -0.03941529 0.07300001 -0.0346834 -0.0377503 0.078 -0.03499758 -0.0375207 0.07300001 -0.03499597 -0.04598253 0.078 0.04023766 -0.04599469 0.07300001 0.03982645 0.05953264 0.07300001 -0.03465813 0.06027406 0.078 -0.0343973 0.06154352 0.07300001 -0.03379321 0.06183588 0.078 -0.03360575 0.06328678 0.07300001 -0.03246951 0.0635423 0.078 -0.03222507 0.06465989 0.07300001 -0.03076487 0.06483072 0.078 -0.0304625 0.06558197 0.07300001 -0.02877974 0.06546533 0.078 -0.02907574 0.0659852 0.078 -0.02700418 0.06596106 0.07300001 -0.0269984 0.06596887 0.078 0.04042631 0.06597131 0.07300001 0.04044687 0.05122017 0.07499998 -0.02121108 0.05213129 0.07499998 -0.02028006 0.0504685 0.07499998 -0.0222904 0.05336111 0.07499998 -0.01942884 0.0497992 0.07499998 -0.0238378 0.05508631 0.07499998 -0.01872038 0.04948836 0.07499998 -0.02568149 0.05731695 0.07499998 -0.01847976 0.04958498 0.07499998 -0.02716511 0.05898785 0.07499998 -0.01876199 0.04995447 0.07499998 -0.02862429 0.06037986 0.07499998 -0.01928412 0.06178742 0.07499998 -0.02021193 0.05092281 0.07499998 -0.03044092 0.05221259 0.07499998 -0.03178805 0.06307715 0.07499998 -0.021559 0.05378669 0.07499998 -0.03280651 0.06397247 0.07499998 -0.02320623 0.05569493 0.07499998 -0.03340178 0.06446099 0.07499998 -0.02500629 0.05718713 0.07499998 -0.03350508 0.0644595 0.07499998 -0.02688127 0.05854022 0.07499998 -0.03335177 0.06408393 0.07499998 -0.02851855 0.06026452 0.07499998 -0.03277879 0.06333833 0.07499998 -0.03003066 0.06212168 0.07499998 -0.03151988 0.06451815 0.07300001 -0.02605623 0.0642718 0.07300001 -0.02790951 0.06357568 0.07300001 -0.02964496 0.06271964 0.07300001 -0.03086054 0.06168609 0.07300001 -0.0318762 0.06009322 0.07300001 -0.03285539 0.05843621 0.07300001 -0.03337275 0.05656659 0.07300001 -0.03351438 0.0547353 0.07300001 -0.03316181 0.05302566 0.07300001 -0.03239208 0.0513181 0.07300001 -0.03093665 0.05020189 0.07300001 -0.02921122 0.04957753 0.07300001 -0.02724963 0.04952478 0.07300001 -0.02519536 0.04989677 0.07300001 -0.02355748 0.05043053 0.07300001 -0.02236926 0.05116063 0.07300001 -0.02127528 0.05221253 0.07300001 -0.02021193 0.0536201 0.07300001 -0.01928412 0.05519795 0.07300001 -0.01870793 0.05686885 0.07300001 -0.01848274 0.05891364 0.07300001 -0.01872038 0.06063884 0.07300001 -0.01942884 0.06186866 0.07300001 -0.02028012 0.0631451 0.07300001 -0.02165347 0.06401127 0.07300001 -0.02330499 0.06436622 0.07300001 -0.02455854 -0.04277974 0.07499998 -0.02121102 -0.04173141 0.07499998 -0.02015709 -0.04353141 0.07499998 -0.0222904 -0.04046595 0.07499998 -0.01934212 -0.04420071 0.07499998 -0.0238378 -0.03891366 0.07499998 -0.01872038 -0.04451161 0.07499998 -0.02568149 -0.03723394 0.07499998 -0.01849764 -0.04441493 0.07499998 -0.02716517 -0.03574991 0.07499998 -0.01858627 -0.04404544 0.07499998 -0.02862429 -0.0339592 0.07499998 -0.01912397 -0.04338014 0.07499998 -0.02995383 -0.03250694 0.07499998 -0.01998054 -0.04247289 0.07499998 -0.03115487 -0.03140336 0.07499998 -0.02099007 -0.04103159 0.07499998 -0.03234601 -0.0306198 0.07499998 -0.02204614 -0.02988374 0.07499998 -0.02354764 -0.03969836 0.07499998 -0.0330041 -0.03830504 0.07499998 -0.03340178 -0.02951371 0.07499998 -0.02538573 -0.03681284 0.07499998 -0.03350508 -0.02952677 0.07499998 -0.02670067 -0.03545975 0.07499998 -0.03335177 -0.02984672 0.07499998 -0.028342 -0.03373545 0.07499998 -0.03277879 -0.03075647 0.07499998 -0.03018862 -0.03202342 0.07499998 -0.03163903 -0.02951371 0.07300001 -0.02661418 -0.02988374 0.07300001 -0.02845233 -0.0306198 0.07300001 -0.02995383 -0.03140342 0.07300001 -0.03100991 -0.03246569 0.07300001 -0.03198605 -0.03390669 0.07300001 -0.03285539 -0.03556376 0.07300001 -0.03337275 -0.03743332 0.07300001 -0.03351438 -0.03926467 0.07300001 -0.03316181 -0.04097431 0.07300001 -0.03239208 -0.04254943 0.07300001 -0.03107237 -0.04342895 0.07300001 -0.0298739 -0.04408395 0.07300001 -0.02851855 -0.04450994 0.07300001 -0.02650439 -0.04435789 0.07300001 -0.02445513 -0.04384493 0.07300001 -0.02291136 -0.04299515 0.07300001 -0.02145874 -0.04193127 0.07300001 -0.02034121 -0.04087126 0.07300001 -0.01956301 -0.03969842 0.07300001 -0.01899582 -0.03825002 0.07300001 -0.01858627 -0.03676599 0.07300001 -0.01849764 -0.03527212 0.07300001 -0.01868283 -0.03369307 0.07300001 -0.01925569 -0.03242236 0.07300001 -0.02004462 -0.0313332 0.07300001 -0.02106958 -0.03057098 0.07300001 -0.02212607 -0.02998858 0.07300001 -0.02330523 -0.0295574 0.07300001 -0.02493518 0.05122017 0.07499998 0.04378885 0.05213129 0.07499998 0.04471987 0.0504685 0.07499998 0.04270952 0.0535199 0.07499998 0.04566442 0.0497992 0.07499998 0.04116213 0.05509501 0.07499998 0.04626578 0.04952681 0.07499998 0.03970062 0.05694174 0.07499998 0.04652667 0.04952478 0.07499998 0.03819537 0.05880206 0.07499998 0.046292 0.04984146 0.07499998 0.03674274 0.06037986 0.07499998 0.0457158 0.05034011 0.07499998 0.03552609 0.06178742 0.07499998 0.044788 0.05116063 0.07499998 0.03427523 0.05221259 0.07499998 0.03321188 0.06307715 0.07499998 0.04344093 0.05328762 0.07499998 0.0324763 0.06397253 0.07499998 0.0417937 0.05448085 0.07499998 0.03192359 0.06446099 0.07499998 0.03999364 0.05630844 0.07499998 0.03150492 0.0644595 0.07499998 0.03811866 0.05817204 0.07499998 0.03158056 0.06408393 0.07499998 0.03648144 0.0600984 0.07499998 0.03213316 0.0631451 0.07499998 0.03465354 0.06182944 0.07499998 0.03324431 0.06451815 0.07300001 0.0389437 0.0642718 0.07300001 0.03709042 0.06357568 0.07300001 0.03535497 0.06226015 0.07300001 0.033607 0.06059336 0.07300001 0.03240156 0.05934619 0.07300001 0.03187012 0.05806708 0.07300001 0.03156477 0.05619263 0.07300001 0.03151649 0.05425411 0.07300001 0.03200358 0.05245339 0.07300001 0.03299748 0.05109441 0.07300001 0.03435826 0.05020195 0.07300001 0.03578865 0.04971468 0.07300001 0.03719335 0.04947417 0.07300001 0.03887051 0.04968887 0.07300001 0.04072302 0.05015504 0.07300001 0.04208862 0.05100482 0.07300001 0.04354125 0.05221253 0.07300001 0.044788 0.0536201 0.07300001 0.0457158 0.05519789 0.07300001 0.046292 0.05705821 0.07300001 0.04652667 0.05890494 0.07300001 0.04626578 0.06047999 0.07300001 0.04566442 0.06186866 0.07300001 0.04471981 0.0631451 0.07300001 0.04334646 0.06401127 0.07300001 0.04169493 0.06436622 0.07300001 0.04044145 -0.04242867 0.07499998 0.04421377 -0.04362952 0.07499998 0.04254615 -0.04096174 0.07499998 0.0453816 -0.03961867 0.07499998 0.04604011 -0.04418605 0.07499998 0.04116779 -0.04445946 0.07499998 0.03988134 -0.03799068 0.07499998 0.04645282 -0.03648567 0.07499998 0.04648828 -0.04447513 0.07499998 0.03819531 -0.03519785 0.07499998 0.046292 -0.04404544 0.07499998 0.03637564 -0.03345131 0.07499998 0.04563784 -0.04307717 0.07499998 0.03455901 -0.03192991 0.07499998 0.04454213 -0.04178738 0.07499998 0.03321194 -0.03104507 0.07499998 0.04356926 -0.04071229 0.07499998 0.0324763 -0.03034013 0.07499998 0.04247379 -0.03951913 0.07499998 0.03192359 -0.0297839 0.07499998 0.04108548 -0.03769147 0.07499998 0.03150492 -0.02951371 0.07499998 0.0396142 -0.0295574 0.07499998 0.03793519 -0.03582793 0.07499998 0.03158056 -0.0340774 0.07499998 0.03206682 -0.02998858 0.07499998 0.03630524 -0.03075647 0.07499998 0.03481137 -0.03215968 0.07499998 0.03323167 -0.02951371 0.07300001 0.03838574 -0.02988374 0.07300001 0.03654766 -0.03081989 0.07300001 0.03471839 -0.03192991 0.07300001 0.03345781 -0.03328967 0.07300001 0.03246092 -0.03465378 0.07300001 0.03187012 -0.03593289 0.07300001 0.03156477 -0.03780728 0.07300001 0.03151649 -0.0397458 0.07300001 0.03200352 -0.04107308 0.07300001 0.0326935 -0.04242867 0.07300001 0.03378623 -0.04342901 0.07300001 0.03512609 -0.04408395 0.07300001 0.03648144 -0.04450994 0.07300001 0.03849554 -0.04435789 0.07300001 0.0405448 -0.04384493 0.07300001 0.04208862 -0.04299509 0.07300001 0.04354125 -0.04178744 0.07300001 0.044788 -0.04037988 0.07300001 0.0457158 -0.03880208 0.07300001 0.046292 -0.03694176 0.07300001 0.04652667 -0.03509503 0.07300001 0.04626578 -0.03351992 0.07300001 0.04566442 -0.03198301 0.07300001 0.04459965 -0.03064572 0.07300001 0.04303461 -0.02986299 0.07300001 0.04134184 -0.02954047 0.07300001 0.03988122 0.06558698 0.078 0.04223674 0.06554853 0.07300001 0.04235458 0.06479817 0.078 0.04403352 0.06494045 0.07300001 0.04374974 0.06410771 0.07300001 0.04504072 0.06362152 0.078 0.04561328 0.06273984 0.07300001 0.04645794 0.06214666 0.078 0.04690736 0.0607022 0.07300001 0.04773551 0.06041216 0.078 0.04784077 0.05873835 0.078 0.0483424 0.05861651 0.07300001 0.04836547 0.05662959 0.078 0.04852038 0.05715656 0.07300001 0.04850262 -0.04586374 0.07300001 0.04117494 -0.045677 0.078 0.04193651 -0.04528111 0.07300001 0.0430563 -0.04494762 0.078 0.0437662 -0.04443895 0.07300001 0.04458743 -0.04383027 0.078 0.04537922 -0.04316729 0.07300001 0.04608207 -0.04273927 0.078 0.04644006 -0.04121822 0.07300001 0.04748356 -0.04147952 0.078 0.04731959 -0.03967696 0.078 0.04811322 -0.03895783 0.07300001 0.04830455 -0.03759384 0.078 0.04849725 -0.03662961 0.07300001 0.04852038 0.04498434 0.078 0.01682788 0.04500907 0.07300001 0.03852427 0.04506379 0.078 0.03933686 -0.03524851 0.078 0.04838305 -0.03384858 0.07300001 0.04809999 -0.03282088 0.078 0.04778689 -0.03121036 0.07300001 0.04711049 -0.03055197 0.078 0.04673779 -0.0288673 0.07300001 0.04556483 -0.02828925 0.078 0.04507672 -0.0275399 0.07300001 0.04428791 -0.02503061 0.07300001 0.0389176 -0.02504247 0.078 0.03914719 -0.02540636 0.07300001 0.04071396 -0.02559053 0.078 0.04123961 -0.02628403 0.07300001 0.04268872 -0.02647966 0.078 0.042979 0.05524855 0.07300001 0.04838305 0.05384856 0.078 0.04809999 0.05338871 0.07300001 0.04795575 0.05166131 0.07300001 0.04731702 0.05179768 0.078 0.04736953 0.04987168 0.078 0.04631119 0.04924952 0.07300001 0.04588085 0.0480042 0.078 0.04478567 0.04705429 0.07300001 0.04376262 0.04669964 0.078 0.04327529 0.04524219 0.07300001 0.04014778 0.04578614 0.078 0.04172629 0.04591178 0.07300001 0.04197907 0.01523983 0.06299996 -0.04565799 0.01526153 0.06599688 -0.04341489 0.01621675 0.06299996 -0.04541051 0.01624709 0.06592226 -0.04320317 0.01737004 0.06299996 -0.04477983 0.01714223 0.0664919 -0.04232013 0.01775115 0.06640005 -0.04188358 0.01841145 0.06299996 -0.04369926 0.01834523 0.06701862 -0.04077351 0.01862692 0.06742626 -0.04012691 0.01910787 0.06299996 -0.04252129 0.01943993 0.06787127 -0.03797179 0.01969742 0.06299996 -0.04058212 0.01964336 0.06777948 -0.03712767 0.01974427 0.06873023 -0.03576135 -0.004662036 0.07299941 -0.0379787 -0.004075586 0.07295578 -0.03696656 -0.00330311 0.07277083 -0.03613477 -0.003025412 0.07265764 -0.02734196 -0.002521395 0.07241863 -0.03601634 -0.001965582 0.07205712 -0.0361945 -0.001703321 0.07182645 -0.02716886 -0.001149952 0.07123208 -0.02703553 -7.29135e-4 0.07056397 -0.03581017 -7.36531e-4 0.07057613 -0.02706074 -4.88981e-4 0.06999981 -0.02704352 -3.66051e-4 0.06957924 -0.03577667 -2.42752e-4 0.06871163 -0.03583657 -2.72539e-4 0.06906622 -0.02736794 0.01479762 0.07295858 -0.01659846 0.009197771 0.07287943 -0.01694285 0.004187464 0.07297563 -0.01644098 0.01471805 0.07269972 -0.01753932 0.00411868 0.07272648 -0.01748764 0.003861606 0.07236677 -0.01824259 0.01524144 0.07228749 -0.01835197 0.003989994 0.07201844 -0.01874279 0.01516711 0.07183206 -0.01894855 0.004416584 0.07154124 -0.01923829 0.02374565 0.07298535 -0.02783828 0.02267104 0.07277148 -0.02551376 0.02208775 0.07256615 -0.02524918 0.02254652 0.07267361 -0.02779746 0.02322304 0.0729525 -0.02412271 0.02315896 0.07299995 -0.0219205 0.01915097 0.07095515 -0.02264708 0.01886224 0.07134824 -0.02173191 0.02110606 0.07249611 -0.02277535 0.02146655 0.07229644 -0.02479141 0.02013528 0.07225412 -0.02180147 0.02171313 0.0728361 -0.02192598 0.0188241 0.07207816 -0.02047979 0.01822549 0.07169443 -0.02053707 0.02032375 0.07270157 -0.0204752 0.01660186 0.07152521 -0.01963037 0.01851892 0.07258385 -0.01906782 0.02070444 0.07293635 -0.01967173 0.017232 0.07208561 -0.0192793 0.01933151 0.07298904 -0.01770764 0.01866507 0.072833 -0.01840728 0.02010595 0.07058531 -0.02597886 0.02026444 0.07062494 -0.02730244 0.01986032 0.07085901 -0.02432012 0.02070063 0.07139086 -0.02625745 0.02073496 0.07173848 -0.02480673 0.0200327 0.07137197 -0.02376782 0.01993328 0.07169634 -0.02279156 0.0163145 0.07187712 -0.01914328 0.01639986 0.07249206 -0.01824629 0.01743489 0.07290631 -0.01738232 0.01667183 0.07299429 -0.01627099 0.01995706 0.06987696 -0.0270611 0.02085393 0.0714569 -0.02747517 0.02138638 0.07200485 -0.02673757 0.02164626 0.07217884 -0.02741253 0.02278542 0.07276672 -0.03618264 0.02177613 0.07229441 -0.03636968 0.02140969 0.07200217 -0.03515112 0.02083671 0.07146263 -0.03598856 0.02024668 0.07060348 -0.035986 0.01990228 0.06973165 -0.03579342 0.001061737 0.06703191 -0.04064375 0.001548886 0.06730926 -0.04114222 -0.001972258 0.07283222 -0.04149973 -0.002831459 0.07297229 -0.04149806 -1.5582e-4 0.0688911 -0.03678262 2.29291e-5 0.06760406 -0.03802955 9.56844e-5 0.06856644 -0.03792178 1.23616e-4 0.06914132 -0.03825145 4.20167e-4 0.06788456 -0.03899937 7.98116e-4 0.06772106 -0.03987729 9.58973e-4 0.06828898 -0.04002326 5.47933e-4 0.06702625 -0.03979384 1.69665e-4 0.06990069 -0.03883635 4.34163e-4 0.06991291 -0.03949254 7.32932e-4 0.06900918 -0.03965568 0.001167654 0.06779366 -0.0404607 -1.70018e-4 0.07011163 -0.03805714 -7.87513e-4 0.07136625 -0.0386182 -2.91963e-4 0.07136106 -0.0398091 -0.001560926 0.07195025 -0.03794771 -0.003299593 0.07285773 -0.03840088 -0.002725422 0.0726099 -0.03750389 -0.001641392 0.072232 -0.03906869 -8.63972e-4 0.07206898 -0.0403192 -0.002333343 0.07263225 -0.03937351 -0.0025599 0.07284712 -0.04041618 -0.001383483 0.07250809 -0.0408343 -3.70394e-4 0.06989324 -0.03671985 -7.4128e-4 0.07088017 -0.03739321 -0.001341462 0.07146668 -0.03626269 1.4381e-4 0.07056945 -0.03954946 0.001471102 0.06642341 -0.04158043 0.004650294 0.06607896 -0.04337167 0.002264738 0.06651651 -0.0422374 0.002231597 0.06704866 -0.04193282 0.003203213 0.06699573 -0.04259091 0.003003537 0.06595909 -0.04307115 0.003207504 0.06645536 -0.04284316 0.003997266 0.0662595 -0.04319375 0.00426793 0.06702387 -0.04289352 0.0152266 0.06702381 -0.04289358 0.01798355 0.06732362 -0.04110288 0.01556015 0.06640738 -0.04310715 0.01620358 0.06699913 -0.04262751 0.01645588 0.06647652 -0.04275161 0.01715391 0.06703019 -0.04203408 -0.01321971 0.07249999 -0.04403752 -0.01452028 0.07249999 -0.04523748 -0.01366037 0.07249999 -0.04351216 -0.01503843 0.07249999 -0.04460734 -0.01383793 0.07249999 -0.04569017 -0.01541244 0.07249999 -0.04379582 -0.01306891 0.07249999 -0.04596042 -0.01257354 0.07249999 -0.04426628 -0.01374816 0.07249999 -0.04277992 -0.01549816 0.07249999 -0.04268556 -0.01195579 0.07249999 -0.04596972 -0.0151844 0.07249999 -0.04161816 -0.01199239 0.07249999 -0.04414904 -0.01085269 0.07249999 -0.04553014 -0.01340878 0.07249999 -0.0421136 -0.01158303 0.07249999 -0.0438646 -0.01444482 0.07249999 -0.04069066 -0.01000434 0.07249999 -0.04469913 -0.01126569 0.07249999 -0.04329234 -0.01340496 0.07249999 -0.04011964 -0.01286119 0.07249999 -0.04179483 -0.009542107 0.07249999 -0.04360526 -0.01222532 0.07249999 -0.03999334 -0.0122385 0.07249999 -0.04175877 -0.009509265 0.07249999 -0.04271221 -0.01128619 0.07249999 -0.04266893 -0.009671151 0.07249999 -0.04196608 -0.01108819 0.07249999 -0.0403313 -0.01158469 0.07249999 -0.04212176 -0.01018542 0.07249999 -0.0410639 -0.01369845 0.078 -0.04257488 -0.01331633 0.078 -0.04204273 -0.01276147 0.078 -0.04175877 -0.01198649 0.078 -0.04183661 -0.01140671 0.078 -0.04235678 -0.0112335 0.078 -0.0431267 -0.01153129 0.078 -0.04381281 -0.01205849 0.078 -0.04418301 -0.01270955 0.078 -0.04424798 -0.01333802 0.078 -0.04394948 -0.01372003 0.078 -0.04334324 -0.009900391 0.07300001 -0.04149901 -0.01030528 0.07300001 -0.04093915 -0.01113212 0.07300001 -0.04030847 -0.01212751 0.07300001 -0.04001247 -0.01301795 0.07300001 -0.04003423 -0.01406615 0.07300001 -0.04041272 -0.0149818 0.07300001 -0.04128068 -0.01545286 0.07300001 -0.04237079 -0.01545739 0.07300001 -0.04363322 -0.01497596 0.07300001 -0.04471969 -0.01403087 0.07300001 -0.04560995 -0.01399952 0.07699996 -0.0456013 -0.01344728 0.07699996 -0.04585415 -0.01249629 0.07699996 -0.04601913 -0.0113334 0.07699996 -0.04578465 -0.01035058 0.07699996 -0.04512017 -0.009699642 0.07699996 -0.04412841 -0.009481072 0.07699996 -0.04296243 -0.009637057 0.07699996 -0.04208862 -0.009894609 0.07699996 -0.04150021 0.02232629 0.07298016 -0.04149985 0.02989965 0.07699996 -0.04150003 0.02990192 0.07300001 -0.04149997 0.0214675 0.07283163 -0.04149985 0.03140133 0.07249999 -0.04362249 0.03033024 0.07249999 -0.04509973 0.03180772 0.07249999 -0.04405313 0.03131294 0.07249999 -0.04577624 0.02968627 0.07249999 -0.04409545 0.0322721 0.07249999 -0.04423528 0.03125065 0.07249999 -0.04312497 0.03248101 0.07249999 -0.04601925 0.02948158 0.07249999 -0.04292017 0.03281176 0.07249999 -0.0442245 0.03128623 0.07249999 -0.04266887 0.03353178 0.07249999 -0.04582965 0.0296992 0.07249999 -0.04189461 0.03152805 0.07249999 -0.04219764 0.03328287 0.07249999 -0.04398161 0.0345183 0.07249999 -0.04525268 0.03023517 0.07249999 -0.04100298 0.03361892 0.07249999 -0.04358518 0.03203731 0.07249999 -0.04182112 0.03125214 0.07249999 -0.04024463 0.03526026 0.07249999 -0.04422372 0.03551882 0.07249999 -0.04305803 0.03376632 0.07249999 -0.04288369 0.03249311 0.07249999 -0.03998053 0.03276145 0.07249999 -0.04175877 0.03530532 0.07249999 -0.04188323 0.03366416 0.07249999 -0.040214 0.03343921 0.07249999 -0.04214268 0.03465306 0.07249999 -0.04088312 0.03133255 0.078 -0.04253101 0.0316416 0.078 -0.04207497 0.03218817 0.078 -0.0417754 0.03287351 0.078 -0.04178887 0.03350728 0.078 -0.04222387 0.03377491 0.078 -0.04302132 0.0334981 0.078 -0.04378271 0.03294146 0.078 -0.04418301 0.03229039 0.078 -0.04424798 0.03158628 0.078 -0.04389113 0.03124016 0.078 -0.04314744 0.03400331 0.07300001 -0.04560101 0.03474462 0.07300001 -0.04501932 0.03535097 0.07300001 -0.04399406 0.03551357 0.07300001 -0.04281407 0.03520721 0.07300001 -0.04166305 0.03447949 0.07300001 -0.04072004 0.03344374 0.07300001 -0.04013186 0.03226095 0.07300001 -0.03999006 0.03111547 0.07300001 -0.0403167 0.03023773 0.07300001 -0.04100716 0.02965044 0.07699996 -0.0420385 0.02948069 0.07699996 -0.04298996 0.02971094 0.07699996 -0.04415643 0.03037369 0.07699996 -0.0451436 0.03136622 0.07699996 -0.0457983 0.03253442 0.07699996 -0.04601901 0.03341042 0.07699996 -0.04586321 0.03399902 0.07699996 -0.04560571 0.03399968 0.07699996 -0.08539962 0.03401464 0.07300001 -0.08539086 0.03149271 0.07249999 -0.0887506 0.03073787 0.07249999 -0.09044623 0.03015029 0.07249999 -0.08987265 0.03183543 0.07249999 -0.08906823 0.02979081 0.07249999 -0.08930599 0.03126049 0.07249999 -0.08825057 0.03182166 0.07249999 -0.09094762 0.03242641 0.07249999 -0.0892663 0.02951931 0.07249999 -0.08845263 0.03301566 0.07249999 -0.09097039 0.02955472 0.07249999 -0.08733475 0.03132712 0.07249999 -0.08750563 0.03304612 0.07249999 -0.08913409 0.03406554 0.07249999 -0.09058189 0.03004235 0.07249999 -0.08624589 0.03342032 0.07249999 -0.08885407 0.03189933 0.07249999 -0.0868752 0.03494393 0.07249999 -0.08977311 0.03091359 0.07249999 -0.08543092 0.03371012 0.07249999 -0.08837324 0.0354402 0.07249999 -0.08868712 0.03203254 0.07249999 -0.08501702 0.03263586 0.07249999 -0.08674454 0.03547662 0.07249999 -0.08749359 0.03373456 0.07249999 -0.08775043 0.03332215 0.07249999 -0.08508735 0.03312772 0.07249999 -0.08691257 0.03504753 0.07249999 -0.08637928 0.0335052 0.07249999 -0.08723855 0.03433549 0.07249999 -0.08561348 0.03133255 0.078 -0.08753103 0.03166323 0.078 -0.08705186 0.03236258 0.078 -0.08673226 0.03309488 0.078 -0.08688616 0.03362989 0.078 -0.08740901 0.03375416 0.078 -0.08814686 0.03350949 0.078 -0.08876466 0.03296196 0.078 -0.08917707 0.03221678 0.078 -0.08924084 0.03161275 0.078 -0.08889508 0.03132522 0.078 -0.08845025 0.03124386 0.078 -0.0879901 0.03327363 0.07699996 -0.08508157 0.03208696 0.07699996 -0.08500909 0.03096425 0.07699996 -0.08540046 0.03007966 0.07699996 -0.08619493 0.0295704 0.07699996 -0.0872693 0.02951544 0.07699996 -0.0884571 0.02988421 0.07699996 -0.08949583 0.02990049 0.07300001 -0.0895006 0.03038907 0.07300001 -0.09015882 0.03118759 0.07300001 -0.09070587 0.03196531 0.07300001 -0.09096288 0.03300768 0.07300001 -0.09097635 0.03391915 0.07300001 -0.09065145 0.03469568 0.07300001 -0.09007251 0.03532636 0.07300001 -0.08906203 0.03551715 0.07300001 -0.08788627 0.03523838 0.07300001 -0.08672821 0.03473532 0.07300001 -0.08599239 -0.00988394 0.07699996 -0.08949339 -0.009519755 0.07699996 -0.08848327 -0.009563624 0.07699996 -0.08729773 -0.01006084 0.07699996 -0.08622068 -0.01087403 0.07699996 -0.08546149 -0.01183152 0.07699996 -0.08506041 -0.01309144 0.07699996 -0.08502811 -0.01399976 0.07699996 -0.08539879 -0.01400333 0.07300001 -0.08539867 -0.01321977 0.07249999 -0.08903747 -0.01476466 0.07249999 -0.08999663 -0.01366037 0.07249999 -0.08851218 -0.01401305 0.07249999 -0.09059888 -0.01538711 0.07249999 -0.08890062 -0.01304364 0.07249999 -0.09097504 -0.01257354 0.07249999 -0.0892663 -0.01375406 0.07249999 -0.08792752 -0.01548773 0.07249999 -0.08749443 -0.01193219 0.07249999 -0.09095656 -0.013619 0.07249999 -0.08741486 -0.01195383 0.07249999 -0.08913409 -0.01102513 0.07249999 -0.09062916 -0.01508021 0.07249999 -0.08645522 -0.01452022 0.07249999 -0.08576244 -0.01155722 0.07249999 -0.08883208 -0.01018542 0.07249999 -0.08993607 -0.0132516 0.07249999 -0.08699107 -0.01383781 0.07249999 -0.08530968 -0.01127272 0.07249999 -0.0883125 -0.009731769 0.07249999 -0.08916997 -0.01261651 0.07249999 -0.08673018 -0.01306891 0.07249999 -0.08503955 -0.009494423 0.07249999 -0.08828657 -0.01210397 0.07249999 -0.08501547 -0.01127403 0.07249999 -0.08772015 -0.009616374 0.07249999 -0.08710533 -0.01192539 0.07249999 -0.08687913 -0.01111072 0.07249999 -0.08531939 -0.01149475 0.07249999 -0.08723855 -0.01018446 0.07249999 -0.08606249 -0.01469421 0.07300001 -0.08593273 -0.01533102 0.07300001 -0.08693593 -0.01551258 0.07300001 -0.08811074 -0.01527142 0.07300001 -0.08919769 -0.01459515 0.07300001 -0.09017384 -0.0137943 0.07300001 -0.09071445 -0.01294541 0.07300001 -0.09098148 -0.01198029 0.07300001 -0.09096539 -0.01093375 0.07300001 -0.09058719 -0.00989139 0.07300001 -0.08953738 -0.0136674 0.078 -0.08753103 -0.01333671 0.078 -0.08705186 -0.01263737 0.078 -0.08673226 -0.01187616 0.078 -0.08689892 -0.01134204 0.078 -0.08746606 -0.0112611 0.078 -0.08827215 -0.0115562 0.078 -0.08883297 -0.01203799 0.078 -0.08917707 -0.01278316 0.078 -0.08924084 -0.01338726 0.078 -0.08889502 -0.01367473 0.078 -0.08845025 -0.01375609 0.078 -0.0879901 -0.02496874 0.07300001 0.01620316 -0.02497708 0.078 0.01670318 0.003687679 0.07146686 -0.01942414 0.002867043 0.07136368 -0.01981222 0.002172112 0.07212591 -0.01927196 0.002905964 0.07271075 -0.01778686 0.002066135 0.07158917 -0.02007013 0.001890063 0.07093447 -0.02080243 0.001578927 0.07268214 -0.01844656 0.002292871 0.0730046 -0.01606088 0.001402199 0.07295227 -0.01740938 6.64464e-4 0.07191741 -0.02081853 9.5234e-4 0.07076966 -0.02194392 -6.73663e-5 0.07299023 -0.01790106 5.54073e-4 0.07002288 -0.02320635 1.51937e-4 0.07262146 -0.0197606 -3.83716e-5 0.07145971 -0.0225588 7.76282e-5 0.07059705 -0.02362805 -8.60145e-4 0.0723946 -0.02167534 -0.001225292 0.07294094 -0.01964777 -4.55036e-4 0.07193249 -0.02230596 -0.001424193 0.07277762 -0.02099364 -0.002713501 0.07298749 -0.02096909 -5.30997e-4 0.07121622 -0.02409428 -0.001041591 0.07177513 -0.02401846 -0.00198394 0.07261717 -0.02291309 -0.001566052 0.07228028 -0.02361416 -0.004785239 0.07299953 -0.02613258 -0.00404793 0.07294601 -0.02627837 1.28758e-5 0.06975346 -0.02477604 -3.76453e-4 0.07032763 -0.02543902 -2.1398e-4 0.06933987 -0.02623808 -9.33586e-4 0.07126283 -0.02541106 -0.00285536 0.07276093 -0.02421593 -0.001749515 0.07207077 -0.02531963 -0.002254426 0.07245612 -0.02481406 -0.002293586 0.07228106 -0.02683013 -0.003588378 0.07284373 -0.02720397 -0.02472156 0.078 0.01360678 -0.02452564 0.07300001 0.01228898 -0.02410542 0.078 0.01018375 -0.02379459 0.07300001 0.008946835 -0.02315294 0.078 0.006839632 -0.02274054 0.07300001 0.00569117 -0.02187365 0.078 0.003606975 -0.02137333 0.07300001 0.002553343 -0.02028024 0.078 5.17582e-4 -0.01970607 0.07300001 -4.36257e-4 -0.0183888 0.078 -0.002398014 -0.01775443 0.07300001 -0.003249168 -0.01621776 0.078 -0.005111455 -0.01553684 0.07300001 -0.0058586 -0.01378875 0.078 -0.007596015 -0.01307463 0.07300001 -0.00823915 -0.01112544 0.078 -0.009827494 -0.01039171 0.07300001 -0.01036763 -0.008254349 0.078 -0.01178383 -0.007513463 0.07300001 -0.01222389 -0.005203366 0.078 -0.01344597 -0.004467427 0.07300001 -0.01379013 -0.002002537 0.078 -0.01479762 -0.001283109 0.07300001 -0.01505112 0.001316606 0.078 -0.01582533 0.00478965 0.078 -0.0165317 0.008269906 0.078 -0.01687562 0.01168882 0.078 -0.016878 0.01522558 0.07799994 -0.01652729 0.01863056 0.078 -0.01583892 0.01943624 0.07300001 -0.01562362 0.02195483 0.078 -0.01481503 0.02270066 0.07300001 -0.01453429 0.02516108 0.078 -0.01346635 0.02584236 0.07300001 -0.01312977 0.02821791 0.078 -0.01180607 0.02883094 0.07300001 -0.01142358 0.03109484 0.078 -0.009850502 0.03163725 0.07300001 -0.009432494 0.03376388 0.078 -0.007618904 0.03423452 0.07300001 -0.007175505 0.03619819 0.078 -0.00513339 0.03659749 0.07300001 -0.004674851 0.03837412 0.078 -0.00241816 0.03870338 0.07300001 -0.001954495 0.04026979 0.078 4.99738e-4 0.04053193 0.07300001 9.59024e-4 0.04186671 0.078 0.003591954 0.04206556 0.07300001 0.004037559 0.04314881 0.078 0.006827652 0.04328954 0.07300001 0.007251262 0.04410332 0.078 0.0101751 0.04419225 0.07300001 0.01056927 0.04472082 0.078 0.01360112 0.04492312 0.07300001 0.01525557 0.0132265 0.06299996 -0.04567611 0.006066799 0.06702923 -0.0429182 0.006257951 0.06622987 -0.04327112 0.0134263 0.06702721 -0.0429092 0.01323652 0.06613594 -0.04333573 0.0063681 0.06699538 -0.04256135 0.006265223 0.06299996 -0.04566967 0.007031142 0.0670607 -0.04186689 0.007143497 0.06299996 -0.04482787 0.007797181 0.06729793 -0.04118311 0.008309602 0.06299996 -0.04415845 0.008249998 0.06442552 -0.04313844 0.00916785 0.06440466 -0.04288274 0.008251488 0.06759691 -0.04069215 0.009881794 0.06299996 -0.04389882 0.01040899 0.06440591 -0.04291206 0.01154279 0.06299996 -0.04430085 0.01124924 0.06442403 -0.04313462 0.01125043 0.06751459 -0.04081559 0.01197856 0.06719148 -0.04141712 0.01268839 0.06299996 -0.04510736 0.01296508 0.06698793 -0.04236739 0.008249998 0.078 -0.03165447 0.01124995 0.078 -0.03165447 0.01124995 0.06490582 -0.04152339 0.01124995 0.07177752 -0.04008138 0.01124995 0.078 -0.03540682 0.01124995 0.07106441 -0.03967505 0.01124995 0.06991767 -0.03948295 0.01124995 0.06793189 -0.04030174 0.01124995 0.06450343 -0.04221373 0.01124995 0.06440275 -0.04284864 0.01124995 0.06885123 -0.03971326 0.008249938 0.06440275 -0.04266136 0.008249998 0.06460863 -0.04197543 0.008249998 0.06497108 -0.04146009 0.008249998 0.078 -0.03540682 0.008249998 0.07177257 -0.04005593 0.008249998 0.06838285 -0.03995132 0.008249998 0.07066047 -0.03955537 0.008249998 0.06948709 -0.03952407 0.0508756 0.07300001 -0.06602221 0.05087453 0.078 -0.06602823 0.05058544 0.078 -0.06517654 0.05056554 0.07300001 -0.06514191 0.04984635 0.078 -0.06434619 0.04983514 0.07300001 -0.06434214 0.04952269 0.07300001 -0.03612554 0.04971849 0.078 -0.0360524 0.05191761 0.07300001 -0.03543877 0.0520724 0.078 -0.03540539 0.05440402 0.07300001 -0.03504407 0.05460059 0.078 -0.03503006 0.04704672 0.078 -0.03734225 0.04686754 0.07300001 -0.03745353 0.04467552 0.078 -0.03913688 0.04452174 0.07300001 -0.0392813 0.04292702 0.078 -0.04108071 0.04281538 0.07300001 -0.04122972 0.04185515 0.078 -0.04271179 0.04143983 0.07300001 -0.04345339 0.04088348 0.078 -0.04471963 0.04038226 0.07300001 -0.04623287 0.04007858 0.078 -0.04758262 0.03993391 0.07300001 -0.04878383 0.03987175 0.078 -0.05103385 0.03990662 0.07300001 -0.05129265 0.04041594 0.07300001 -0.05422282 0.04042339 0.078 -0.05422073 0.04119658 0.078 -0.05631309 0.04150676 0.07300001 -0.05698937 0.04224848 0.078 -0.05827981 0.04267686 0.07300001 -0.05888831 0.04360091 0.078 -0.0600537 0.04409575 0.07300001 -0.06060951 0.04526144 0.078 -0.06169652 0.04657185 0.07300001 -0.06269007 0.04763191 0.078 -0.06331187 0.04865652 0.07300001 -0.07025039 0.04715651 0.078 -0.07025039 0.04715651 0.07300001 -0.07025039 0.04865652 0.078 -0.07025039 0.04865652 0.078 -0.06725043 0.04865652 0.07300001 -0.06725043 0.04715651 0.07300001 -0.06725043 0.04715651 0.078 -0.06725043 0.03915649 0.07300001 -0.07025039 0.03765648 0.078 -0.07025039 0.03765648 0.07300001 -0.07025039 0.03915649 0.078 -0.07025039 0.03915649 0.078 -0.06725043 0.03915649 0.07300001 -0.06725043 0.03765648 0.07300001 -0.06725043 0.03765648 0.078 -0.06725043 -0.01671767 0.07300001 -0.09204155 -0.01720887 0.07300001 -0.09130561 -0.01590025 0.07300001 -0.09266936 -0.01747912 0.07300001 -0.0904622 -0.01495516 0.07300001 -0.09297788 -0.01753968 0.07300001 -0.05150228 -0.03316897 0.07300001 -0.03508532 -0.03016501 0.07300001 -0.03575474 -0.02769804 0.07300001 -0.03672379 0.03305363 0.07300001 -0.09299188 -0.01850211 0.07300001 -0.04699623 -0.01791554 0.07300001 -0.04909181 -0.01975393 0.07300001 -0.04418456 -0.02501785 0.07300001 -0.03829485 0.03522223 0.07300001 -0.09279686 -0.02150505 0.07300001 -0.0416184 -0.02302843 0.07300001 -0.03997439 0.03740626 0.07300001 -0.09231317 0.04001897 0.07300001 -0.09138512 0.04236119 0.07300001 -0.09009099 0.04422646 0.07300001 -0.08873921 0.04650622 0.07300001 -0.0865035 0.04857677 0.07300001 -0.08351969 0.04986333 0.07300001 -0.08063012 0.05046623 0.07300001 -0.07847613 0.05085259 0.07300001 -0.07599872 0.0241785 0.07299929 -0.03787308 -0.03497689 0.078 -0.03494733 0.03347575 0.078 -0.09297692 0.03632706 0.078 -0.09260481 0.03937345 0.078 -0.09164804 0.04144471 0.078 -0.09064036 0.04333072 0.078 -0.08943825 0.0450949 0.078 -0.08795768 0.04663276 0.078 -0.08633291 0.04798442 0.078 -0.08446782 0.04908114 0.078 -0.08251839 0.05007708 0.078 -0.07998299 0.05061209 0.078 -0.07774281 0.05087387 0.078 -0.07560378 -0.03209429 0.078 -0.03527146 -0.02992641 0.078 -0.03583991 -0.02789807 0.078 -0.03662919 -0.02522277 0.078 -0.03815054 -0.02136629 0.078 -0.04177147 -0.0231415 0.078 -0.03986674 -0.01966565 0.078 -0.0443713 -0.01872974 0.078 -0.04640775 -0.01805323 0.078 -0.04847604 -0.01753562 0.078 -0.05146598 -0.01745152 0.078 -0.09067243 -0.01693493 0.078 -0.09177684 -0.01601427 0.078 -0.09262406 -0.01489073 0.078 -0.09298527 0.01842898 0.06798952 -0.04025894 0.01860171 0.06847971 -0.03990882 0.01891821 0.0677399 -0.03942883 0.01920545 0.06836163 -0.03856712 0.01884353 0.06926614 -0.0395711 0.01922774 0.0702902 -0.03950279 0.01955521 0.06879287 -0.03732299 0.01936048 0.06940001 -0.03838938 0.01967918 0.07050436 -0.03863984 0.01973289 0.07125967 -0.03975921 0.02005237 0.07171964 -0.04002755 0.02081161 0.07216936 -0.03966736 0.02014213 0.07088917 -0.03782957 0.02081823 0.07248395 -0.04078185 0.01969456 0.06972426 -0.03744608 0.02176576 0.07264417 -0.03964525 0.02221566 0.0728743 -0.040425 0.0226317 0.07278782 -0.03779029 0.02158635 0.07231819 -0.03797107 0.02356916 0.07295387 -0.0366857 0.02049571 0.07133489 -0.03770202 0.02099251 0.07185655 -0.03779685 0.02295333 0.07296115 -0.03981202 0.004419147 0.06299996 -0.0256716 -2.25778e-4 0.06299996 -0.03109067 1.34956e-4 0.06299996 -0.02947908 8.55701e-4 0.06299996 -0.02794557 0.002116382 0.06299996 -0.02657073 0.003427803 0.06299996 -0.02586984 -2.35558e-4 0.06299996 -0.0400173 -1.80573e-5 0.06299996 -0.0413472 4.39089e-4 0.06299996 -0.04261279 0.001257419 0.06299996 -0.04393333 0.00248754 0.06299996 -0.04502266 0.003984749 0.06299996 -0.04563438 0.0570904 0.0731734 -0.02223777 0.0574693 0.07304549 -0.02217006 0.05731534 0.07300376 -0.02205526 0.0578261 0.07318258 -0.02233052 0.05784219 0.07306635 -0.0222634 0.05848872 0.07318741 -0.02254563 0.05839604 0.07300335 -0.02229624 0.05852615 0.07306456 -0.02248746 0.0591436 0.07305234 -0.02279949 0.05909943 0.07316631 -0.02287888 0.05923509 0.07300341 -0.02273368 0.05944734 0.07314622 -0.02313733 0.05987644 0.07318633 -0.02357733 0.05980616 0.07300889 -0.02326172 0.05998325 0.07309412 -0.02363044 0.06033885 0.07301121 -0.02393448 0.06031101 0.0731678 -0.02421152 0.06045532 0.07305902 -0.02432674 0.06051564 0.07316672 -0.02466392 0.06087237 0.07300567 -0.02514809 0.06073051 0.07305103 -0.02504467 0.06066662 0.07316601 -0.02515786 0.06073755 0.07318502 -0.02562391 0.06081122 0.07306194 -0.02562141 0.06076115 0.07316523 -0.02609223 0.06084924 0.07304912 -0.02619063 0.06094044 0.07300406 -0.02639603 0.06071138 0.07314908 -0.02664214 0.06073826 0.07304555 -0.02696007 0.06054174 0.07316744 -0.0272746 0.06051254 0.07300108 -0.02795177 0.06046414 0.07309663 -0.02756553 0.06045436 0.07302474 -0.02780771 0.06025719 0.07314699 -0.02789157 0.05999493 0.07318472 -0.02826738 0.05989408 0.07306182 -0.02852153 0.05962193 0.0731827 -0.02869719 0.05947369 0.07300359 -0.02909493 0.05932015 0.07306671 -0.02904707 0.05903649 0.07318902 -0.02916127 0.05822932 0.07300543 -0.02977478 0.05863612 0.07306116 -0.02947127 0.05845546 0.07317769 -0.02946656 0.05794447 0.07315385 -0.02964538 0.05777436 0.07303845 -0.02979409 0.05757498 0.07316935 -0.02971482 0.05709254 0.0731883 -0.0297594 0.05700099 0.07309061 -0.02980852 0.05680078 0.07300978 -0.02992355 0.05635952 0.07316756 -0.02970921 0.056499 0.07305753 -0.02980852 0.05586642 0.07301408 -0.02973407 0.05587285 0.07316464 -0.02958923 0.05545699 0.07318502 -0.02942484 0.05526638 0.07307642 -0.02940529 0.05492401 0.0730068 -0.02935528 0.05495798 0.07318931 -0.02915757 0.05469864 0.07308942 -0.02903413 0.05446696 0.07317221 -0.02877879 0.05411952 0.07306623 -0.02852821 0.05417728 0.07318758 -0.0284807 0.05385476 0.07300424 -0.02842062 0.05385679 0.07317167 -0.02806359 0.0536046 0.0731824 -0.02761822 0.05365419 0.07303756 -0.02793604 0.05342656 0.07305651 -0.02741748 0.05338436 0.07314807 -0.02705842 0.05319082 0.07300359 -0.02707457 0.05323982 0.07307267 -0.02666348 0.05326992 0.07318532 -0.02645891 0.05302983 0.07300329 -0.02580767 0.05316543 0.07305943 -0.02609574 0.05324155 0.07317423 -0.02599173 0.05327051 0.07318747 -0.02553856 0.05320858 0.07306206 -0.0254237 0.05334109 0.07317155 -0.02513295 0.05334061 0.07306128 -0.02486187 0.05348926 0.07314914 -0.02463537 0.05333131 0.07301014 -0.02460944 0.0537312 0.07316863 -0.02414 0.05370193 0.07305246 -0.02401709 0.05394858 0.07318615 -0.02380651 0.05391895 0.07300382 -0.02349823 0.05404561 0.07308375 -0.02359718 0.05439186 0.07318484 -0.02329075 0.05439758 0.07307064 -0.02320599 0.05480629 0.07311433 -0.02290832 0.05496203 0.07321214 -0.02284288 0.05473875 0.07302272 -0.02283114 0.05522549 0.07300955 -0.0225045 0.05548655 0.07308053 -0.02249383 0.05562448 0.07317972 -0.02249896 0.05598938 0.07300376 -0.02217566 0.05620884 0.07306259 -0.02225011 0.05634015 0.07316797 -0.02229404 0.05684876 0.07304662 -0.02215749 0.05711477 0.09382998 -0.0297625 0.05772167 0.09380877 -0.02968668 0.05811887 0.09379774 -0.02958518 0.0585395 0.09383457 -0.02943068 0.05896687 0.09382295 -0.02920436 0.05942082 0.0938546 -0.02888679 0.05989384 0.09380722 -0.02839988 0.06025338 0.09382236 -0.02788442 0.06048339 0.09382069 -0.02741074 0.06064742 0.09381264 -0.02691549 0.0607469 0.09381228 -0.0262869 0.06074166 0.09380906 -0.02562648 0.06062918 0.09384554 -0.02499574 0.06046181 0.0938152 -0.02454173 0.06025868 0.09382236 -0.02412468 0.0599913 0.09381163 -0.02372866 0.0597133 0.09382027 -0.02339732 0.05927079 0.09380847 -0.02300643 0.05888348 0.09381097 -0.02275061 0.05845779 0.09379696 -0.02253848 0.05794441 0.09384447 -0.02235549 0.05737781 0.09383046 -0.02225774 0.05690735 0.0938152 -0.02224469 0.05635577 0.09381026 -0.02229523 0.0556218 0.09382778 -0.02249801 0.05495542 0.09381109 -0.02284389 0.05430972 0.09380078 -0.02336901 0.05378365 0.09383195 -0.02404445 0.05346775 0.09381163 -0.02470958 0.05326241 0.09381496 -0.02562391 0.05324172 0.09382599 -0.02619248 0.05334258 0.09382838 -0.02687865 0.0534684 0.09381061 -0.02727818 0.05369234 0.09381318 -0.02778941 0.05424708 0.09381508 -0.02855587 0.05465704 0.093804 -0.02894026 0.05528438 0.09380221 -0.02934479 0.05579036 0.09382653 -0.02955865 0.05637401 0.09379965 -0.02970659 0.0574693 0.09395444 -0.02982985 0.05719327 0.09399634 -0.02995258 0.05801975 0.0939027 -0.02966552 0.05818933 0.09399116 -0.02973687 0.05886238 0.09398877 -0.02944231 0.05899834 0.09393864 -0.02927076 0.05970793 0.09397912 -0.02881878 0.05980235 0.09388643 -0.02854841 0.06018626 0.09394764 -0.02814149 0.06046915 0.09399622 -0.02795726 0.06050014 0.0939247 -0.02752643 0.06071162 0.09391015 -0.02685093 0.06089842 0.09399276 -0.02657389 0.06082779 0.09393662 -0.02619749 0.06079196 0.09389007 -0.02583098 0.06088238 0.09398877 -0.02546375 0.06064277 0.09394335 -0.02478539 0.06071436 0.09399646 -0.02464383 0.0603646 0.0939303 -0.02417856 0.06037324 0.09399533 -0.02395135 0.05990451 0.09394353 -0.02348023 0.05983328 0.09399664 -0.02323555 0.05944252 0.09392887 -0.0230621 0.05897295 0.09399026 -0.02260583 0.0588085 0.09390574 -0.02264612 0.05801224 0.09399598 -0.02217584 0.0581128 0.09394311 -0.02232784 0.05745613 0.09394806 -0.02217781 0.05694615 0.09399592 -0.02204161 0.05696129 0.09393608 -0.02217155 0.05645322 0.09389269 -0.02224498 0.05624216 0.09399229 -0.02215111 0.05568271 0.09393054 -0.02240377 0.05550378 0.09399539 -0.02234202 0.05492234 0.09395807 -0.02275657 0.05466246 0.09390288 -0.02299803 0.0544396 0.09398967 -0.02303302 0.05413466 0.09390449 -0.02348983 0.05389529 0.09399145 -0.02359622 0.0536288 0.0939421 -0.02416288 0.05334657 0.09396773 -0.02467542 0.05343329 0.09389734 -0.0247004 0.05312961 0.09399706 -0.02508896 0.05332827 0.09383177 -0.02518492 0.05319702 0.09393846 -0.02552229 0.05316799 0.09393829 -0.0261802 0.05309796 0.09398871 -0.02638745 0.05327326 0.09395182 -0.02698093 0.05332982 0.09399193 -0.02739858 0.05359011 0.09392863 -0.02773576 0.0539596 0.09383136 -0.02821385 0.05384969 0.09399622 -0.02840363 0.05404549 0.09394222 -0.02845299 0.05453759 0.09399074 -0.02905803 0.05456107 0.09389883 -0.02891296 0.05520689 0.09389221 -0.0293501 0.05540275 0.09398984 -0.02958738 0.05585163 0.09394204 -0.02966141 0.05631816 0.09389477 -0.02973675 0.05655491 0.09397143 -0.02986055 0.05249297 0.07475 -0.02580887 0.05249822 0.078 -0.02633732 0.05262655 0.07475 -0.02715033 0.0527178 0.078 -0.02740514 0.05324357 0.078 -0.02851784 0.05328375 0.07475 -0.02857673 0.05416107 0.078 -0.02950567 0.05421394 0.07475 -0.02954781 0.05501598 0.078 -0.03004664 0.05507332 0.07475 -0.03007423 0.05617964 0.078 -0.03044712 0.05624985 0.07475 -0.03045952 0.0577501 0.078 -0.03045952 0.05782026 0.07475 -0.03044712 0.0593307 0.078 -0.02988344 0.05887776 0.07475 -0.03009343 0.05975455 0.07475 -0.02957874 0.06065618 0.078 -0.02867311 0.06068706 0.07475 -0.02860778 0.06136953 0.07475 -0.02719181 0.06130051 0.078 -0.02736181 0.06151658 0.078 -0.02611261 0.06149601 0.07475 -0.02551424 0.06139272 0.078 -0.02499735 0.06114351 0.07475 -0.02421665 0.06107878 0.078 -0.02407312 0.06046253 0.07475 -0.02309447 0.06026738 0.078 -0.02286356 0.05926215 0.07475 -0.02208173 0.05886077 0.078 -0.02187597 0.05786055 0.07475 -0.02156656 0.05733776 0.078 -0.02149248 0.05628919 0.07475 -0.02152693 0.05602914 0.078 -0.02159464 0.05507332 0.078 -0.02192568 0.05480951 0.07475 -0.02205061 0.05412387 0.078 -0.02251803 0.05391126 0.07475 -0.02271801 0.05327153 0.078 -0.02345794 0.05327397 0.07475 -0.02345961 0.0527172 0.07475 -0.0245611 0.05263042 0.078 -0.0248081 0.06151872 0.08899998 -0.02577447 0.06151449 0.09224998 -0.02577471 0.06128215 0.09224998 -0.02459484 0.06119108 0.08899998 -0.02431762 0.06075638 0.09224998 -0.02348208 0.06064057 0.08899998 -0.02334332 0.05987602 0.08899998 -0.02251803 0.05975455 0.09224998 -0.02242118 0.05882441 0.08899998 -0.02187436 0.05877989 0.09224998 -0.02185952 0.05781656 0.09224998 -0.02156347 0.05774998 0.08899998 -0.02155172 0.05647301 0.09224998 -0.02150857 0.05640232 0.08899998 -0.02151745 0.05496865 0.09224998 -0.02195966 0.05511397 0.08899998 -0.02190214 0.05407041 0.08899998 -0.02256298 0.05387443 0.09224998 -0.02274721 0.05325388 0.08899998 -0.02348679 0.0531494 0.09224998 -0.02364695 0.05266833 0.08899998 -0.02470117 0.05257648 0.09224998 -0.02502739 0.05249565 0.08899998 -0.02588766 0.05253374 0.09224998 -0.02670919 0.05258941 0.08899998 -0.02697086 0.05293703 0.09224998 -0.02795666 0.05302226 0.08899998 -0.02812767 0.05375587 0.09224998 -0.02916413 0.05361992 0.08899998 -0.02898287 0.05463957 0.08899998 -0.02986264 0.05517262 0.09224998 -0.03013652 0.05617964 0.08899998 -0.03044712 0.0566622 0.09224998 -0.03050744 0.05767333 0.08899998 -0.03046751 0.0578618 0.09224998 -0.03042364 0.05892789 0.09224998 -0.03008389 0.05885463 0.08899998 -0.03011053 0.05990409 0.08899998 -0.02946096 0.06024408 0.09224998 -0.02916413 0.06074607 0.08899998 -0.02851313 0.06096845 0.09224998 -0.0281291 0.06131929 0.08899998 -0.02733224 0.06135666 0.09224998 -0.02718949 0.06448829 0.09360945 -0.02639347 0.06444638 0.09373134 -0.02582097 0.06437438 0.0937969 -0.02676171 0.06429821 0.09391641 -0.02617001 0.06403034 0.09399121 -0.0270847 0.06436556 0.0936461 -0.02735364 0.06421434 0.09389448 -0.02723693 0.06422013 0.09356999 -0.02802723 0.06411212 0.09380078 -0.02809667 0.06359052 0.09399968 -0.0285623 0.06386274 0.09395962 -0.02822166 0.06392151 0.09358686 -0.02889233 0.06379711 0.09380066 -0.02896529 0.06341838 0.09395933 -0.02929764 0.06341123 0.09364646 -0.0298773 0.06324946 0.09388035 -0.02984213 0.06294816 0.09379243 -0.03042829 0.06232625 0.09399706 -0.0307067 0.06286382 0.09359306 -0.03067117 0.06271326 0.09394258 -0.03045493 0.06247234 0.0938155 -0.03098446 0.0623781 0.09357851 -0.03122526 0.06195414 0.09396213 -0.03123557 0.06195479 0.09377002 -0.03154069 0.06164842 0.09361326 -0.03188306 0.06140589 0.09393578 -0.03177124 0.06116521 0.09382301 -0.03210294 0.06091088 0.09361666 -0.03239232 0.06066876 0.09399867 -0.03205233 0.06037807 0.09380102 -0.03259682 0.06021708 0.09360116 -0.03277045 0.06011712 0.09392714 -0.03258013 0.05971252 0.09398162 -0.03263103 0.05936408 0.09359657 -0.03311854 0.05953449 0.09373307 -0.03300523 0.05904334 0.09391355 -0.03300201 0.05851215 0.09377014 -0.03328037 0.0584473 0.09357851 -0.03335744 0.05788671 0.09399515 -0.033068 0.05753976 0.09364485 -0.03347307 0.05766975 0.09391623 -0.03326272 0.05677956 0.09382981 -0.0333839 0.05644291 0.09360533 -0.03347855 0.05637705 0.0939812 -0.03313279 0.05610096 0.09390866 -0.03324222 0.05572175 0.09383141 -0.03327679 0.05549424 0.0936172 -0.03334087 0.05482161 0.09366905 -0.03315985 0.05473619 0.09399121 -0.0327742 0.05468899 0.09388822 -0.03295129 0.05408072 0.09360957 -0.03290295 0.05413872 0.09379726 -0.03283262 0.05321663 0.09361004 -0.0324741 0.05353313 0.09384572 -0.03251665 0.05322748 0.09399288 -0.0320459 0.05303126 0.09387207 -0.03218275 0.05245721 0.09359359 -0.03196376 0.05254614 0.09378272 -0.03193378 0.05189591 0.09360957 -0.03148823 0.05230057 0.09395408 -0.03149485 0.05177867 0.09383505 -0.03122735 0.05136561 0.09359371 -0.03094542 0.05133581 0.09399032 -0.03035163 0.05117273 0.09383779 -0.03053337 0.05092108 0.09359049 -0.03038817 0.05077791 0.09375393 -0.03007239 0.05050379 0.09359776 -0.02974104 0.05072242 0.09392046 -0.02968966 0.05029088 0.09378814 -0.0291776 0.05007374 0.09360343 -0.02887642 0.05061352 0.09399741 -0.02905172 0.05030602 0.09394907 -0.02874207 0.04991221 0.09379154 -0.02819222 0.04972326 0.09358936 -0.02782142 0.04982769 0.09386318 -0.02766084 0.05010312 0.09399473 -0.02772629 0.04953318 0.09359878 -0.0267024 0.04985588 0.09395581 -0.02703112 0.0496186 0.09378463 -0.02679842 0.04950457 0.09358763 -0.02581715 0.0498718 0.09399342 -0.02591627 0.04961365 0.0938366 -0.02590078 0.04958111 0.09360653 -0.02490192 0.04985761 0.09396117 -0.02499461 0.04968386 0.09380924 -0.02483183 0.04978138 0.09362769 -0.02399504 0.04997348 0.09388041 -0.02386903 0.05040895 0.09399092 -0.02323937 0.05001801 0.09355884 -0.02325987 0.05013149 0.09377562 -0.02316164 0.05040979 0.09363669 -0.02243548 0.05047535 0.09386289 -0.02261132 0.05073159 0.09362316 -0.02189511 0.05082952 0.09388804 -0.02204197 0.05129855 0.09399765 -0.02177464 0.05115282 0.09360462 -0.02131026 0.05128043 0.09386068 -0.02136093 0.05173981 0.09361863 -0.02066075 0.05165904 0.0937677 -0.02083384 0.05195575 0.09394913 -0.02080708 0.05218899 0.09356939 -0.02024739 0.05235868 0.09377032 -0.02019774 0.0527606 0.09357762 -0.01981455 0.05288302 0.09387952 -0.01992201 0.05274069 0.09399139 -0.02028101 0.05330675 0.09373295 -0.0195263 0.05357998 0.09398108 -0.01970469 0.05340623 0.0935679 -0.01941764 0.05408531 0.09361642 -0.01909619 0.05402874 0.09385395 -0.01925736 0.05468493 0.09391564 -0.01908105 0.05498296 0.09360903 -0.01877731 0.05484735 0.09374195 -0.01887565 0.05467629 0.09399861 -0.01932013 0.05569231 0.0938192 -0.01871848 0.05587464 0.09360587 -0.01858979 0.05604487 0.09394985 -0.01881265 0.05661821 0.09357982 -0.01851111 0.05645209 0.09399384 -0.01889747 0.05667144 0.09378194 -0.0185855 0.05736446 0.09367394 -0.01852595 0.0572552 0.09390485 -0.0187 0.05814695 0.09364891 -0.01860034 0.0580753 0.09399241 -0.01894629 0.0582779 0.09383493 -0.01872849 0.0590853 0.09358537 -0.01879388 0.0588383 0.09371149 -0.01876944 0.05916863 0.09391248 -0.01903027 0.05958282 0.09377056 -0.01903748 0.05954587 0.09398448 -0.01932752 0.05994808 0.09362429 -0.01911199 0.06052696 0.09383112 -0.01950472 0.06056135 0.0936011 -0.01940411 0.06025427 0.0939598 -0.01955693 0.06122493 0.09356319 -0.0198031 0.06119412 0.09375458 -0.01985591 0.06131696 0.09395366 -0.02019947 0.06132787 0.09399926 -0.02038127 0.06183892 0.09360301 -0.02027571 0.06172156 0.09378314 -0.02027797 0.06203609 0.09396165 -0.02083605 0.06236523 0.09360951 -0.02076673 0.06218075 0.0938338 -0.02073806 0.06254589 0.0939055 -0.02124685 0.06288129 0.093589 -0.02134978 0.06278973 0.09377807 -0.02135163 0.06298112 0.09399676 -0.02216184 0.06339758 0.09357982 -0.02208149 0.06336462 0.09375417 -0.02214509 0.06318217 0.09388589 -0.02206552 0.06392139 0.09362256 -0.02311998 0.06348276 0.09396237 -0.02285969 0.06365472 0.09383016 -0.02279299 0.06386822 0.09387725 -0.02341598 0.0642516 0.09364223 -0.02411222 0.06391656 0.09399187 -0.02427446 0.06411534 0.09390038 -0.02429062 0.06432735 0.09381437 -0.02493357 0.06446009 0.0936011 -0.025231 0.06409722 0.09399503 -0.02547115 0.0644837 0.0926007 -0.02634382 0.06439918 0.09259641 -0.02715498 0.06422257 0.0926156 -0.0279898 0.06402736 0.09260076 -0.02859067 0.06372731 0.0926001 -0.02929145 0.06330275 0.09266394 -0.030061 0.06273716 0.09264451 -0.0308299 0.06208616 0.09259688 -0.03149467 0.06155771 0.09263724 -0.03194963 0.06079995 0.09257537 -0.03244847 0.06026035 0.09266388 -0.03275173 0.05958324 0.09264534 -0.03303629 0.05885797 0.09266394 -0.03326386 0.05736958 0.09264522 -0.03348636 0.05660384 0.09264904 -0.03348553 0.0557124 0.09266632 -0.03339058 0.05374294 0.09266877 -0.03275394 0.05260443 0.09268248 -0.03208112 0.05175918 0.09263408 -0.03136211 0.05100792 0.09265834 -0.03051227 0.05052059 0.09266185 -0.02977222 0.05009067 0.09262895 -0.02890908 0.04979288 0.09264713 -0.02805989 0.04961991 0.09260541 -0.02727288 0.04952973 0.09261208 -0.02655059 0.04959219 0.09261935 -0.02486962 0.04982811 0.09263288 -0.02381312 0.05017447 0.092633 -0.02290666 0.05060541 0.09265476 -0.02207958 0.0511285 0.09262192 -0.02134633 0.05163699 0.09264516 -0.02076351 0.0521903 0.09265643 -0.020249 0.05275422 0.09266936 -0.01981973 0.05340701 0.09266388 -0.01941913 0.05425637 0.09266132 -0.01901793 0.05489617 0.09258902 -0.01881796 0.05549877 0.09265506 -0.01865524 0.05642074 0.09265637 -0.0185216 0.05738174 0.09266692 -0.01851159 0.05811369 0.09267705 -0.01858389 0.05867427 0.09261709 -0.01869618 0.05944162 0.09259265 -0.01892155 0.06020772 0.09262716 -0.01922851 0.06092554 0.09265041 -0.01961368 0.06171298 0.09264284 -0.02016711 0.06234771 0.09264695 -0.02074754 0.06285315 0.09268939 -0.02131074 0.06330931 0.09264951 -0.02195239 0.06366258 0.09258645 -0.02258855 0.06404095 0.09267383 -0.02340835 0.06435143 0.09264606 -0.02451902 0.06447023 0.0926178 -0.02543562 0.06433594 0.09238064 -0.02551573 0.06418693 0.09228086 -0.02602171 0.06405866 0.09226679 -0.02478849 0.06430518 0.09245502 -0.02476048 0.06402015 0.09231227 -0.02414131 0.06416076 0.09249782 -0.02398449 0.06394737 0.09245032 -0.02341419 0.06356084 0.09225445 -0.0232293 0.06351613 0.09235173 -0.02266597 0.06291359 0.09227031 -0.02195382 0.06310272 0.09249776 -0.021739 0.06282496 0.09236055 -0.02155888 0.06258291 0.09250873 -0.02107495 0.06192648 0.09232711 -0.02062857 0.06210315 0.09225219 -0.02108216 0.06187897 0.0924744 -0.02040022 0.06122374 0.09250617 -0.01987153 0.06099504 0.09225422 -0.02012306 0.0610035 0.09234118 -0.01989567 0.06055045 0.09246647 -0.01948475 0.05991637 0.0922895 -0.01939481 0.05966222 0.09242081 -0.01910626 0.05860102 0.09225195 -0.01910096 0.05866748 0.09242433 -0.01880186 0.05837625 0.09232079 -0.01885485 0.05756896 0.09250199 -0.01857733 0.05721318 0.09239858 -0.01863908 0.05746102 0.09227901 -0.0188297 0.05646151 0.09250134 -0.01857757 0.05623781 0.09234201 -0.01873469 0.05621004 0.09225755 -0.01891809 0.05553317 0.09246945 -0.01872575 0.05492252 0.09234523 -0.01898944 0.05485516 0.09225201 -0.0192539 0.05412799 0.09250521 -0.01913386 0.05428707 0.09232389 -0.01924681 0.05343598 0.09226405 -0.01978182 0.05335998 0.09245097 -0.01954311 0.05282539 0.09248673 -0.01984912 0.05299127 0.09230476 -0.0199691 0.05222457 0.09247392 -0.02031707 0.05211669 0.09230744 -0.02063375 0.05175316 0.09225255 -0.02123564 0.05146974 0.09243297 -0.02108079 0.05110955 0.09230643 -0.02177542 0.05073881 0.09249168 -0.02199226 0.05064111 0.09231489 -0.0224871 0.05031758 0.09248286 -0.02274566 0.05063617 0.09225261 -0.02287095 0.05025786 0.09233129 -0.02324706 0.04994064 0.09243452 -0.02377361 0.04999327 0.09228664 -0.02429771 0.04995161 0.09225285 -0.02517825 0.04971563 0.09244799 -0.02466648 0.04968976 0.09236043 -0.02545481 0.0495131 0.09260892 -0.0256868 0.04964542 0.09240072 -0.02643465 0.04978913 0.0922982 -0.02654916 0.0500456 0.09225684 -0.02758449 0.04982095 0.09238338 -0.02760303 0.04989421 0.09247153 -0.02815526 0.05026507 0.09236264 -0.02888554 0.05037957 0.09225553 -0.02862918 0.05040866 0.09248459 -0.02942967 0.05080765 0.09240031 -0.03000622 0.05094921 0.09228736 -0.02991688 0.0512824 0.09242969 -0.03070181 0.05181491 0.09225714 -0.03090476 0.05193722 0.09241986 -0.03138154 0.05250597 0.09249621 -0.03192603 0.05335474 0.09225511 -0.03212904 0.05259597 0.09232896 -0.03179806 0.05311048 0.09261804 -0.03240096 0.0533064 0.0923925 -0.03236758 0.05367869 0.09247452 -0.03264451 0.05444598 0.09232026 -0.03281754 0.05458003 0.09260368 -0.03309094 0.05521738 0.09226667 -0.03294175 0.05517643 0.09243714 -0.03317517 0.05603766 0.09251296 -0.03338545 0.05622613 0.09238582 -0.03331667 0.05649745 0.09228438 -0.03317826 0.0571475 0.09249657 -0.03343933 0.05781894 0.09238886 -0.03331679 0.05754166 0.09225475 -0.03310102 0.0581088 0.09262245 -0.03340959 0.05883729 0.09233665 -0.03306365 0.05884814 0.09248161 -0.0331946 0.05961334 0.09225934 -0.03265118 0.05973869 0.09247839 -0.03290659 0.06028646 0.09233623 -0.03252053 0.0612151 0.09247124 -0.03211647 0.06135535 0.09225738 -0.03166007 0.06184893 0.09239959 -0.03154855 0.06217384 0.09228521 -0.03101044 0.06259888 0.09243619 -0.0308445 0.06299602 0.09242951 -0.03033208 0.06289523 0.09226912 -0.03006541 0.06336659 0.09242409 -0.02975505 0.06347697 0.09225815 -0.02899867 0.06385952 0.09238684 -0.02867013 0.06395709 0.09228199 -0.02783238 0.06422305 0.09239828 -0.0274443 0.06401318 0.09225577 -0.02728188 0.06430435 0.09236729 -0.02662396 0.06449663 0.07341909 -0.02583807 0.06443452 0.07325398 -0.02561259 0.06430107 0.07308822 -0.02612471 0.0644378 0.07339525 -0.02507185 0.06418102 0.07302987 -0.02554333 0.06431931 0.07317286 -0.02499377 0.06390196 0.07300364 -0.02434921 0.06425595 0.07340365 -0.02410137 0.06425172 0.07322174 -0.02440214 0.06406325 0.07311117 -0.02401638 0.06396782 0.07340824 -0.02323305 0.06386291 0.07323282 -0.02314484 0.06356877 0.07300609 -0.02324652 0.06357127 0.0733869 -0.02238869 0.06341576 0.07305949 -0.02260005 0.06335455 0.07319349 -0.02219134 0.06305867 0.07337683 -0.02159154 0.06282258 0.07307404 -0.02163684 0.0623762 0.07300406 -0.02136158 0.0625329 0.07319539 -0.02107065 0.06262546 0.07339489 -0.02104687 0.06222909 0.07308161 -0.02093046 0.06197732 0.07339346 -0.02038997 0.0617941 0.07325601 -0.0203067 0.06157517 0.07311177 -0.02027672 0.06160205 0.07302421 -0.02049893 0.0612142 0.07343089 -0.0197969 0.06106668 0.07325118 -0.01976507 0.06063312 0.07315093 -0.01958161 0.06058871 0.07340067 -0.01941859 0.06078946 0.07300418 -0.01998597 0.05971944 0.07339 -0.01901155 0.0600115 0.07306665 -0.01938742 0.05972808 0.07322049 -0.01909607 0.05904638 0.07300555 -0.01918447 0.05882221 0.07310831 -0.01890313 0.05884772 0.07335281 -0.01874315 0.05794847 0.07340735 -0.01855927 0.05808234 0.07324236 -0.01864469 0.05716466 0.07300889 -0.0188598 0.05782806 0.0730766 -0.01876908 0.05717062 0.07317608 -0.01860469 0.05699998 0.0734049 -0.01850306 0.05625748 0.07341933 -0.01853847 0.05608612 0.07323926 -0.01861816 0.05607414 0.07310038 -0.01874351 0.05532133 0.07339835 -0.01869094 0.05540204 0.07312691 -0.01882833 0.05507606 0.07300734 -0.01913386 0.05462002 0.07323372 -0.01895874 0.05427062 0.07339859 -0.01901417 0.05439978 0.07307755 -0.01919972 0.05382889 0.07320064 -0.0193057 0.05374699 0.07300442 -0.01967531 0.05342787 0.0733422 -0.01942294 0.05290108 0.07337123 -0.01972466 0.05326813 0.07307815 -0.01974284 0.05249655 0.07315307 -0.02015757 0.05220794 0.07336479 -0.02024227 0.05233746 0.07300615 -0.0206266 0.05151796 0.07340139 -0.02088141 0.05189621 0.07308113 -0.02080279 0.05152267 0.07323592 -0.02097338 0.05136001 0.07308155 -0.0213859 0.05091506 0.07332515 -0.02164512 0.05134129 0.0730111 -0.02167159 0.05076247 0.07309961 -0.02218192 0.05049943 0.0734052 -0.02226579 0.05043894 0.07325059 -0.02248632 0.05076235 0.07300311 -0.02259773 0.05010288 0.0733599 -0.02307492 0.05019652 0.07313972 -0.02320033 0.05033975 0.07304239 -0.02323108 0.04984641 0.07336884 -0.02376878 0.04991394 0.07313698 -0.02402865 0.04968428 0.07342123 -0.0243535 0.05010598 0.07300591 -0.02423673 0.04970091 0.07321548 -0.02467823 0.04956454 0.07337284 -0.02508157 0.04985433 0.07306689 -0.02471178 0.04965406 0.07315266 -0.02544248 0.04950577 0.07336199 -0.025985 0.04978024 0.0730375 -0.02601659 0.04961073 0.07318949 -0.02643966 0.04991453 0.073004 -0.02651149 0.0495752 0.07335638 -0.02698087 0.0497564 0.07310348 -0.0270341 0.04969304 0.07339042 -0.02766788 0.0497967 0.07318204 -0.02766746 0.04993808 0.07339793 -0.02852541 0.05002564 0.0730341 -0.02776795 0.0500276 0.07313543 -0.02834618 0.05044609 0.0730068 -0.02879637 0.05013489 0.07329481 -0.0289309 0.05029612 0.07313263 -0.0290054 0.05043429 0.07340216 -0.02962541 0.05058789 0.07318168 -0.02968287 0.05112534 0.07300323 -0.02997797 0.05098927 0.07306802 -0.03009372 0.05091589 0.07340073 -0.03037923 0.05099451 0.07321184 -0.03034901 0.05138176 0.07333558 -0.03094583 0.05163758 0.07317793 -0.03109127 0.05189597 0.07300591 -0.03096985 0.05201596 0.07332742 -0.03158402 0.05223095 0.07309585 -0.0315358 0.05248779 0.07339423 -0.03198504 0.05300348 0.0730049 -0.0319094 0.05286884 0.0731768 -0.0321294 0.05307197 0.07340908 -0.03238582 0.05363637 0.07321453 -0.0326206 0.05393707 0.07340455 -0.03284686 0.05368673 0.07305419 -0.03243595 0.05464804 0.0732091 -0.03303414 0.05478686 0.07339519 -0.03316128 0.05465894 0.07304906 -0.03284943 0.05549502 0.073327 -0.03333014 0.05568152 0.07307887 -0.03317105 0.05625498 0.07300603 -0.03310227 0.05640608 0.07335871 -0.03346991 0.05662864 0.07316809 -0.03337448 0.0570656 0.07300329 -0.03309488 0.05738174 0.07342559 -0.03348916 0.0573762 0.07323193 -0.03342086 0.05755466 0.07309067 -0.03327763 0.05808264 0.0733329 -0.03340566 0.05836206 0.07303518 -0.03308033 0.0588783 0.07336187 -0.03325086 0.05866068 0.07315087 -0.03317874 0.05951666 0.0730015 -0.03265064 0.05957168 0.07340222 -0.03304147 0.05951565 0.07314693 -0.03292858 0.06026041 0.0734139 -0.03275173 0.06032967 0.07322472 -0.03263866 0.06104397 0.07340079 -0.0323165 0.06048411 0.07308971 -0.03241938 0.061324 0.07324576 -0.03205573 0.06102645 0.073022 -0.03192353 0.06162625 0.07316899 -0.03175771 0.06184756 0.07338672 -0.03171533 0.06176143 0.07304638 -0.03144329 0.06247544 0.07341593 -0.03112787 0.06258153 0.07322478 -0.03090888 0.06248992 0.07310396 -0.03084188 0.0630775 0.07339805 -0.03038763 0.0626713 0.07300597 -0.03032612 0.06326985 0.07317078 -0.02991527 0.06349498 0.07339042 -0.02974003 0.06383901 0.07339423 -0.02906721 0.06332921 0.07300561 -0.02926951 0.06374222 0.07314682 -0.02898085 0.06411004 0.07335203 -0.02835017 0.06378388 0.07302576 -0.02833205 0.06406271 0.07311111 -0.02794551 0.06434249 0.0733571 -0.02749502 0.0640282 0.0730015 -0.02687054 0.06422573 0.07310122 -0.02716946 0.06446051 0.0733242 -0.02657264 0.06449437 0.07432818 -0.02635204 0.06437349 0.074395 -0.02730995 0.06420964 0.07435464 -0.0280503 0.0639677 0.074395 -0.02874517 0.06365025 0.07437109 -0.02945256 0.06329125 0.07435953 -0.0300734 0.06285393 0.07438188 -0.03067457 0.06227391 0.07441383 -0.0313133 0.06180661 0.07434099 -0.03175359 0.06105434 0.0743348 -0.03231185 0.06027305 0.07435047 -0.03274369 0.05935245 0.07435101 -0.03312134 0.05848878 0.07436639 -0.03334444 0.05772346 0.07437771 -0.03345704 0.05683428 0.07435202 -0.03349786 0.05567932 0.07436096 -0.03338098 0.05475777 0.07439792 -0.03314483 0.05409705 0.07437747 -0.03290683 0.05342203 0.07435357 -0.03258657 0.05275958 0.07433164 -0.032184 0.05206751 0.07438224 -0.03164333 0.05140453 0.0744217 -0.03096908 0.05076932 0.07432371 -0.03017926 0.0503385 0.07433915 -0.02944034 0.04996013 0.07434725 -0.02858752 0.04969877 0.07439035 -0.0276705 0.04954409 0.07438308 -0.02676171 0.04951226 0.07438832 -0.02580493 0.04958045 0.07432246 -0.02488201 0.04979956 0.07440084 -0.02394616 0.05001503 0.07435071 -0.02327907 0.05032956 0.07436639 -0.02258479 0.0506947 0.07430553 -0.0219379 0.05115723 0.07435256 -0.02130436 0.05165565 0.07436394 -0.02074629 0.05218172 0.07435041 -0.02025777 0.05278956 0.07442969 -0.01981532 0.05343228 0.07434368 -0.01940643 0.05427736 0.07432854 -0.01900929 0.0551415 0.07431751 -0.01873415 0.05607271 0.07435834 -0.01855903 0.05771976 0.07433778 -0.01853686 0.05832493 0.07438486 -0.0186249 0.05924379 0.07434076 -0.01884639 0.05990457 0.07439595 -0.01909762 0.06057542 0.07433116 -0.01940906 0.06125575 0.07439571 -0.01983767 0.06181609 0.07437366 -0.02026039 0.06248652 0.07433873 -0.02088421 0.06306809 0.07436299 -0.02160125 0.06347191 0.07442015 -0.0222423 0.06389904 0.07432234 -0.0230512 0.06427234 0.07441967 -0.02422755 0.06446009 0.07435107 -0.025231 0.06441152 0.07451397 -0.02656579 0.0644012 0.07455706 -0.02564835 0.06425845 0.07466989 -0.02670997 0.06397897 0.07474058 -0.02751582 0.06416273 0.0745753 -0.02782499 0.063887 0.07463079 -0.02852821 0.06353324 0.07471954 -0.02901846 0.06358957 0.07458662 -0.02932429 0.06320452 0.07460379 -0.02997225 0.06315314 0.07474941 -0.02950459 0.06264728 0.0747202 -0.030447 0.06276392 0.07460218 -0.03058189 0.06204515 0.07466346 -0.03128099 0.06127065 0.07474344 -0.03170573 0.06140893 0.07458335 -0.03193187 0.06078457 0.07451552 -0.03239923 0.06024485 0.07474792 -0.03230047 0.06024855 0.07467216 -0.03251862 0.05967402 0.07453435 -0.03292685 0.0593689 0.07473003 -0.03277069 0.05863451 0.07455027 -0.03322678 0.05862665 0.07468986 -0.03307098 0.0570783 0.07474893 -0.03307479 0.0577594 0.07457292 -0.03334826 0.05744433 0.07471054 -0.033203 0.05685192 0.07457941 -0.03338837 0.05608665 0.07453811 -0.03336399 0.05608552 0.07468938 -0.03319126 0.05532711 0.07474434 -0.03291577 0.05520302 0.07457375 -0.03316766 0.05474245 0.07464408 -0.03297269 0.05388909 0.07467752 -0.03257739 0.05354213 0.07457095 -0.03253787 0.05369198 0.07474672 -0.03227019 0.0528258 0.0745216 -0.03214389 0.0530073 0.07468301 -0.03206306 0.05234915 0.07474416 -0.03139001 0.05225419 0.07464134 -0.03158289 0.05162656 0.07458209 -0.03107172 0.05143296 0.07472294 -0.03053462 0.05095863 0.07447057 -0.03037071 0.05107545 0.07460856 -0.03035968 0.05063855 0.07465833 -0.02958929 0.05044549 0.07449251 -0.02953594 0.05081832 0.0747466 -0.02948313 0.05033922 0.07471829 -0.02871412 0.05011212 0.0745753 -0.02867817 0.04989171 0.07454973 -0.02809536 0.04983353 0.07464587 -0.02752608 0.04997587 0.07474672 -0.02714192 0.04977697 0.07470858 -0.02619981 0.04963403 0.07458037 -0.02649635 0.0495854 0.07453405 -0.02560925 0.05004638 0.0747447 -0.02448856 0.04979008 0.07467365 -0.02499216 0.04966694 0.07449054 -0.02471286 0.04990619 0.07463192 -0.02413547 0.05009394 0.07453161 -0.02328747 0.05027705 0.07467067 -0.02320009 0.05069273 0.07474428 -0.02268117 0.05045849 0.07459616 -0.022601 0.05080419 0.07450348 -0.0218755 0.05101972 0.07464212 -0.02177143 0.05163604 0.07474452 -0.02134019 0.05150318 0.07461261 -0.0211029 0.0521472 0.07459688 -0.0204432 0.05229592 0.07474446 -0.02065348 0.05316632 0.07468783 -0.01982772 0.05343323 0.07452708 -0.01949048 0.05424857 0.0744968 -0.01908189 0.05434107 0.07464939 -0.01918691 0.05399954 0.07474523 -0.01956123 0.05536812 0.07450193 -0.0187385 0.05511355 0.0746904 -0.01898717 0.0561248 0.07461869 -0.01870483 0.05600696 0.07474112 -0.01893335 0.05682063 0.07441115 -0.01851487 0.05705749 0.07460284 -0.01863443 0.05766469 0.07474851 -0.01895391 0.05751317 0.0747143 -0.018808 0.05780035 0.0745694 -0.01864773 0.05861091 0.07464015 -0.01885777 0.05881202 0.07449519 -0.01877909 0.05913299 0.07471567 -0.01912289 0.05945885 0.07458144 -0.019037 0.05994457 0.07474535 -0.01952832 0.06028676 0.07462882 -0.01943778 0.06068855 0.0745269 -0.01955449 0.06124019 0.07471907 -0.0201866 0.06113308 0.07462978 -0.01994425 0.0621829 0.07474517 -0.02110242 0.06182599 0.07460474 -0.02043676 0.06237155 0.07451015 -0.02086186 0.06262093 0.07464611 -0.02132034 0.06295734 0.07448911 -0.02152276 0.06328654 0.07469272 -0.02236372 0.06298291 0.07474172 -0.02212607 0.06368654 0.07456135 -0.02281844 0.06377875 0.07474219 -0.02381491 0.06395775 0.07463753 -0.02368593 0.06410384 0.07438433 -0.02362948 0.06427252 0.07458513 -0.02474683 0.06417399 0.0747022 -0.02507466 0.06407099 0.07474827 -0.02557235 0.06298971 0.08859664 -0.02633893 0.06298285 0.08799999 -0.02659863 0.06287449 0.08860188 -0.02721357 0.06270956 0.08799999 -0.02787351 0.06268543 0.08859306 -0.02790629 0.06246459 0.08861643 -0.02846145 0.0621556 0.08799999 -0.02909773 0.06210911 0.08865278 -0.02912694 0.06167435 0.08863931 -0.02974498 0.06133127 0.08799999 -0.03016519 0.06119292 0.08860492 -0.03028911 0.06041997 0.08799999 -0.03094094 0.06049668 0.08859747 -0.0308746 0.0598632 0.08861082 -0.03126615 0.05896526 0.08799999 -0.03170031 0.05906593 0.08859437 -0.03163725 0.05804306 0.08859711 -0.03190743 0.05734187 0.08799999 -0.03199934 0.05653774 0.08862286 -0.03197729 0.05570465 0.08799999 -0.03188878 0.05580449 0.0885744 -0.03187811 0.055197 0.08862334 -0.03171467 0.05466383 0.08859777 -0.03152209 0.05376863 0.08799999 -0.03109055 0.05401623 0.08861339 -0.03119999 0.05340933 0.08863246 -0.03080093 0.05283147 0.08863013 -0.0303052 0.05242151 0.08799999 -0.02990055 0.05238717 0.08858317 -0.02983778 0.05179649 0.08858746 -0.02899652 0.05146247 0.08799999 -0.02838575 0.05142587 0.08862859 -0.02819699 0.05119836 0.08865004 -0.02749276 0.05098044 0.08799999 -0.02634793 0.05101335 0.08858948 -0.026461 0.0510317 0.08862107 -0.02542728 0.05113226 0.08799999 -0.02470421 0.05120098 0.08862286 -0.02447801 0.05150526 0.08799999 -0.02356737 0.05152469 0.08859688 -0.02353769 0.05226325 0.08799999 -0.02228212 0.05200022 0.08865624 -0.02270787 0.05249154 0.08860415 -0.02203792 0.05368876 0.08799999 -0.02096092 0.05360561 0.08863472 -0.02106416 0.05426305 0.08866912 -0.0206778 0.05479234 0.08856844 -0.02041864 0.05522829 0.08799999 -0.02025628 0.05565232 0.0885899 -0.02015328 0.05640172 0.08799999 -0.02002221 0.05640906 0.08866959 -0.02004605 0.05715304 0.08860063 -0.02000325 0.05770319 0.08799999 -0.0200265 0.05786615 0.08864957 -0.02007555 0.05848038 0.0885744 -0.02018707 0.05919808 0.08799999 -0.02039909 0.05905252 0.08864402 -0.02037376 0.05962461 0.08863729 -0.02061587 0.06022858 0.08865344 -0.02095454 0.06075757 0.08799999 -0.02128797 0.06085836 0.08857578 -0.02140748 0.06138324 0.08863574 -0.02191287 0.06185406 0.08799999 -0.02245777 0.062249 0.08862859 -0.02310496 0.06258815 0.08799999 -0.02375692 0.06261324 0.08867532 -0.02392971 0.06281477 0.08858835 -0.02452099 0.06296408 0.08799999 -0.02525258 0.06296938 0.08860248 -0.02541416 0.06300884 0.07899999 -0.02614969 0.06297945 0.07840687 -0.02645176 0.06278365 0.07899999 -0.02767562 0.06286263 0.07840412 -0.02729195 0.06254118 0.07841169 -0.02830129 0.06225544 0.07899999 -0.02890473 0.06220394 0.07842957 -0.02898395 0.06177693 0.07838726 -0.02962517 0.06148386 0.07899999 -0.0300191 0.06085544 0.07834309 -0.03057926 0.06034988 0.07899999 -0.03098875 0.06024634 0.07840567 -0.03104579 0.05932033 0.07840991 -0.03153777 0.05915534 0.07899999 -0.03161519 0.05755323 0.07899999 -0.03199601 0.05777901 0.07840949 -0.0319491 0.05713784 0.07836443 -0.03198999 0.05591124 0.07899999 -0.0319153 0.055395 0.0784558 -0.03178513 0.05462676 0.07899999 -0.0315206 0.05465745 0.07838147 -0.03152173 0.05373978 0.07840198 -0.03103601 0.05345249 0.07899999 -0.03085714 0.05315262 0.078368 -0.0305922 0.05258667 0.07841295 -0.03006517 0.05246645 0.07899999 -0.02994412 0.05212903 0.07838517 -0.02949249 0.05177491 0.07899999 -0.02896779 0.05182915 0.07833653 -0.02901333 0.05155462 0.07837849 -0.02850198 0.05129039 0.07899999 -0.02787357 0.05136519 0.07836478 -0.02803719 0.05101084 0.07899999 -0.02655398 0.05101078 0.07837426 -0.02626729 0.05103993 0.07841712 -0.02526569 0.05104291 0.07899999 -0.02521073 0.05119669 0.07836365 -0.02450889 0.0514118 0.07899999 -0.02375692 0.05145514 0.07843083 -0.02370303 0.05188876 0.07840585 -0.02285701 0.05241173 0.07899999 -0.02208793 0.05231356 0.07834309 -0.02227544 0.05270886 0.07841861 -0.02180957 0.05338329 0.07839655 -0.02120971 0.05377465 0.07899999 -0.02092319 0.05407363 0.07833951 -0.02077788 0.05467271 0.07836902 -0.0204792 0.055085 0.07899999 -0.02030026 0.0553503 0.07839924 -0.02023261 0.05621612 0.07899999 -0.02004659 0.05612605 0.07837402 -0.0200724 0.05697441 0.07839131 -0.01999747 0.05759978 0.07899999 -0.02000588 0.05778443 0.07835203 -0.02006214 0.05865132 0.0784015 -0.02023303 0.0594787 0.07899999 -0.0205065 0.05947464 0.07843023 -0.02053171 0.06082999 0.07899999 -0.02136963 0.06083768 0.07841306 -0.02138191 0.06189107 0.07899999 -0.02248346 0.06203866 0.07838255 -0.0227552 0.06240105 0.07841497 -0.02338463 0.06259238 0.07899999 -0.02380526 0.06272912 0.07838737 -0.0242291 0.06291025 0.07899999 -0.02491474 0.06290793 0.07840943 -0.02497142 0.06298565 0.07836061 -0.02571392 0.06285744 0.07814282 -0.02600473 0.06269955 0.07804685 -0.02536249 0.06284397 0.07823431 -0.02495849 0.06271868 0.07811522 -0.0248785 0.06253039 0.07810622 -0.02417397 0.06229597 0.07800668 -0.02412128 0.06241214 0.07824057 -0.02355051 0.06210196 0.07809633 -0.0232284 0.06168526 0.07800942 -0.02285259 0.06187659 0.07816511 -0.02271258 0.06162363 0.07835006 -0.02219045 0.06133747 0.07824707 -0.02193868 0.06127011 0.0780633 -0.02213919 0.06083148 0.0780487 -0.02172499 0.0608021 0.07822757 -0.02145314 0.06025689 0.0781998 -0.0210703 0.06001549 0.07800269 -0.02128654 0.06011497 0.07838362 -0.02087968 0.05998182 0.07809531 -0.02101695 0.0594325 0.07825458 -0.0205754 0.05908566 0.07806491 -0.02062183 0.05845338 0.07824516 -0.02023851 0.05813598 0.07814234 -0.02025121 0.05820572 0.07800507 -0.02050733 0.05732631 0.07810378 -0.02018624 0.05690616 0.0782575 -0.02005392 0.05649399 0.0780071 -0.02037769 0.05612325 0.07813405 -0.02021002 0.05574488 0.07802623 -0.02045571 0.05542892 0.07818621 -0.0203076 0.05448859 0.07814681 -0.02069729 0.05453598 0.07800954 -0.02091634 0.05373245 0.07812213 -0.02116024 0.05362915 0.07801145 -0.02147918 0.05316179 0.07819342 -0.0215094 0.05296611 0.07806253 -0.02189892 0.05273967 0.07820528 -0.02189695 0.05229854 0.07810175 -0.02257275 0.05252248 0.07800287 -0.02262294 0.0519101 0.0782476 -0.02293205 0.0516324 0.07824254 -0.02344977 0.05190449 0.07804542 -0.02338504 0.05139875 0.07825189 -0.02401363 0.05147337 0.07807505 -0.02430701 0.05164909 0.07800382 -0.02434909 0.05127984 0.07814764 -0.02471494 0.05108839 0.07824623 -0.02543014 0.05120044 0.07810336 -0.02552831 0.05133783 0.078018 -0.02585899 0.05113732 0.07815575 -0.02634799 0.0510599 0.07837527 -0.02677863 0.05143773 0.07800847 -0.02692121 0.05120623 0.07816284 -0.02699857 0.05116403 0.078377 -0.0273602 0.05133962 0.078175 -0.0276302 0.05157917 0.07804846 -0.02785158 0.05164444 0.07814788 -0.02839905 0.05208814 0.07800948 -0.02877169 0.05225449 0.07811808 -0.02940464 0.05258488 0.07821226 -0.02995353 0.05298608 0.07800662 -0.02994483 0.05290597 0.07813942 -0.03019064 0.05346262 0.07819241 -0.03072261 0.05362123 0.07804733 -0.03062337 0.05401265 0.0782541 -0.03113979 0.0540803 0.07812124 -0.03105223 0.05453729 0.0780099 -0.03107565 0.05478847 0.07815247 -0.03143709 0.05515247 0.07811141 -0.03153645 0.05602425 0.07800221 -0.03153628 0.05565631 0.07824367 -0.03178656 0.05622047 0.07838314 -0.03194546 0.05599999 0.07805532 -0.03165715 0.0565918 0.07821172 -0.03190493 0.05689477 0.07804507 -0.03172802 0.05728107 0.07814592 -0.03185391 0.05785876 0.07825368 -0.03187888 0.05784404 0.07806932 -0.03170818 0.05849874 0.07800495 -0.03140759 0.05849903 0.07837194 -0.03180098 0.05840796 0.07814234 -0.03168773 0.05897861 0.07814431 -0.03152501 0.05965536 0.07821059 -0.03129053 0.0596826 0.07804584 -0.03106498 0.06024444 0.07823938 -0.03097254 0.06053495 0.07809722 -0.03060638 0.06048798 0.07800304 -0.03039306 0.06108868 0.07812249 -0.0301727 0.06130844 0.07836532 -0.03016197 0.06184071 0.07823634 -0.02944278 0.06143361 0.07804918 -0.0296384 0.06183844 0.07800561 -0.02883285 0.06212812 0.07809674 -0.02874624 0.06227982 0.07823705 -0.02870708 0.06258851 0.07828068 -0.02806478 0.06241953 0.0780186 -0.0276286 0.0625683 0.07813435 -0.02780598 0.06273508 0.07818645 -0.02738219 0.06259715 0.07800096 -0.02623254 0.0627501 0.07807803 -0.02662605 0.06289732 0.07822448 -0.02657699 0.06294387 0.08875101 -0.02590298 0.06285047 0.08886557 -0.02600818 0.0627048 0.08894884 -0.02663302 0.06285953 0.08880287 -0.02674001 0.06277132 0.08872705 -0.02745974 0.06262266 0.08889365 -0.02752095 0.06246215 0.08899438 -0.02724111 0.06245899 0.08879029 -0.02828216 0.062155 0.0889889 -0.02830839 0.06210911 0.08887594 -0.02882707 0.06173056 0.08895581 -0.02922004 0.06164228 0.08885771 -0.0295735 0.06113696 0.08880674 -0.03021383 0.0610193 0.08899861 -0.02987098 0.06101107 0.08892953 -0.03014016 0.06035983 0.08897155 -0.03059303 0.06051665 0.08882057 -0.03073585 0.05987554 0.08884507 -0.03112161 0.05907362 0.08890682 -0.03142905 0.05912089 0.08873856 -0.03155606 0.05893564 0.08899748 -0.03126263 0.0583449 0.08879125 -0.03176331 0.05788648 0.0889731 -0.0316202 0.05742454 0.08862972 -0.03197777 0.05757695 0.08888101 -0.03180998 0.05702692 0.08876633 -0.03193068 0.05652344 0.08891803 -0.03177618 0.05648058 0.0889976 -0.03155446 0.05581003 0.08875006 -0.03182452 0.05558323 0.08895736 -0.03154188 0.05535894 0.08884561 -0.03163576 0.05508977 0.08899772 -0.03125345 0.05442225 0.08876466 -0.03134709 0.05450779 0.08890247 -0.03124982 0.05342423 0.08879077 -0.03071856 0.05391609 0.08895367 -0.03084117 0.05334973 0.08899289 -0.03027397 0.05280005 0.08888578 -0.03005141 0.05214977 0.08876723 -0.02942126 0.05255961 0.08896929 -0.02958083 0.052037 0.08895057 -0.02887976 0.05173254 0.08878821 -0.02869451 0.05155277 0.08888083 -0.02810275 0.05164343 0.08899873 -0.02765053 0.05138999 0.08891129 -0.02747261 0.05114215 0.08878862 -0.02683335 0.05121868 0.08889991 -0.026582 0.05106407 0.08875244 -0.02614945 0.0513029 0.08896809 -0.02603065 0.05115741 0.08885806 -0.02553617 0.05143976 0.08899831 -0.02555948 0.05115431 0.08873713 -0.02490633 0.05143225 0.08896011 -0.02467197 0.05143725 0.08883756 -0.02408158 0.05189967 0.08890652 -0.02320998 0.05178785 0.0887829 -0.02319276 0.05204057 0.08899343 -0.02335673 0.05351245 0.08899813 -0.02161288 0.05237054 0.08880025 -0.02233082 0.05254685 0.08896207 -0.02242535 0.05300074 0.08880513 -0.02165043 0.05307137 0.08862787 -0.02147454 0.05320048 0.08893126 -0.02165383 0.05381232 0.08880931 -0.02103424 0.05416631 0.08891475 -0.02094829 0.05519127 0.08899694 -0.02068632 0.05476456 0.08890491 -0.02064251 0.05509573 0.08877688 -0.02038443 0.05548274 0.08895635 -0.02048045 0.05571329 0.0887627 -0.02020692 0.0562269 0.08888822 -0.02022868 0.05678653 0.08897256 -0.0203225 0.05691611 0.08883321 -0.02011442 0.0574485 0.08879488 -0.02010506 0.05775618 0.0889514 -0.02031517 0.05835318 0.08877128 -0.02022701 0.05874222 0.08892613 -0.02048081 0.05769872 0.08899819 -0.02044785 0.05920416 0.08886259 -0.02057516 0.05957883 0.08899676 -0.02102637 0.0597521 0.08890634 -0.0208863 0.06033927 0.08890342 -0.02125155 0.06071335 0.08876538 -0.02137279 0.06081199 0.08899211 -0.02185636 0.06106883 0.08886694 -0.02179491 0.06149649 0.08890235 -0.02231049 0.06180417 0.08865314 -0.02242541 0.06192392 0.08886116 -0.02283674 0.06179672 0.08897697 -0.02297884 0.06230455 0.08884823 -0.02347648 0.06229054 0.08899456 -0.02408641 0.06253004 0.088907 -0.02424889 0.06281256 0.08878111 -0.02484869 0.06273692 0.08892381 -0.02527225 0.06258171 0.08899748 -0.02570939 0.06399798 0.08756119 -0.02582943 0.06396782 0.08700001 -0.02687317 0.0639705 0.08763992 -0.02651846 0.06386303 0.08759212 -0.02738046 0.06354397 0.08700001 -0.02851498 0.06356835 0.0876218 -0.02840906 0.06317353 0.08766472 -0.02926915 0.06291586 0.08700001 -0.02976185 0.06278222 0.08761942 -0.02993905 0.06193703 0.08700001 -0.03098654 0.06215721 0.08766728 -0.03071182 0.06164854 0.08766633 -0.03121608 0.06123673 0.08757865 -0.03157013 0.06083744 0.08700001 -0.031861 0.06048512 0.08760315 -0.03206956 0.05961245 0.08700001 -0.03251266 0.0597012 0.08761465 -0.03245121 0.0590443 0.08758199 -0.03269273 0.05758088 0.08700001 -0.03301048 0.05839163 0.08762001 -0.03285199 0.05788445 0.0876249 -0.03293818 0.0571413 0.08760607 -0.03299713 0.05630332 0.08758604 -0.03296285 0.05565929 0.08700001 -0.0328812 0.05563145 0.08764815 -0.03285288 0.05494856 0.08759367 -0.03268921 0.0541619 0.08700001 -0.03241759 0.05427801 0.08757609 -0.03244757 0.05352056 0.08759796 -0.03207373 0.05266606 0.08700001 -0.03151881 0.05249238 0.08757203 -0.03136551 0.05163228 0.08700001 -0.03050392 0.05175554 0.08758085 -0.03063356 0.05119854 0.08758032 -0.02992022 0.05083936 0.08700001 -0.02935492 0.05076938 0.08758604 -0.02918535 0.05043959 0.08760881 -0.02843666 0.05016332 0.08700001 -0.0276162 0.05017757 0.0875923 -0.02755296 0.05003702 0.08759492 -0.02672022 0.04999065 0.08700001 -0.02552926 0.05000835 0.08757221 -0.02560728 0.05012696 0.08766084 -0.0247507 0.05038821 0.08700001 -0.02364945 0.05033278 0.087628 -0.0238828 0.05063354 0.08764493 -0.0231167 0.05108416 0.08700001 -0.02223807 0.0510199 0.08760011 -0.02236044 0.05154675 0.08760094 -0.02161777 0.05230391 0.08700001 -0.02076244 0.05201327 0.08761394 -0.02109599 0.05250912 0.08759778 -0.0206353 0.05304515 0.08761262 -0.02023124 0.05406612 0.08700001 -0.0196256 0.05365169 0.08761644 -0.01985991 0.05427592 0.08761817 -0.0195589 0.0549395 0.08763533 -0.01932013 0.05607026 0.08700001 -0.01902717 0.05571681 0.0876578 -0.01913118 0.0565024 0.08758741 -0.01901668 0.05737781 0.0876705 -0.01902669 0.05821889 0.08700001 -0.01908707 0.05809354 0.08767974 -0.01910513 0.05873787 0.08759301 -0.01922243 0.05938416 0.08761435 -0.01942467 0.05976861 0.08700001 -0.0195592 0.06017571 0.08763372 -0.01976799 0.06124013 0.08700001 -0.02040225 0.06105864 0.08760023 -0.02029746 0.06189668 0.08763736 -0.02100634 0.06278079 0.08700001 -0.02199167 0.06259572 0.08760511 -0.0217961 0.06306529 0.08759301 -0.02251178 0.06337219 0.08763313 -0.02312445 0.06374764 0.08700001 -0.0240451 0.06363672 0.08758991 -0.02378255 0.0638175 0.0875926 -0.02442586 0.06394213 0.08758157 -0.02511847 0.0639832 0.08700001 -0.02547675 0.06400948 0.07999998 -0.02587479 0.06396698 0.07941561 -0.02669328 0.06386739 0.07999998 -0.02744191 0.06381577 0.07937282 -0.02755993 0.06359195 0.07941257 -0.02835786 0.06315112 0.07999998 -0.02941286 0.06314074 0.07938617 -0.02935492 0.06270009 0.07939022 -0.03005379 0.0622518 0.07941395 -0.03062433 0.0616129 0.07999998 -0.03131085 0.06164991 0.07939261 -0.03123128 0.06106895 0.07934141 -0.031681 0.0603435 0.07941871 -0.0321477 0.05983799 0.07999998 -0.03241759 0.05970567 0.07942086 -0.03245413 0.05905181 0.07934921 -0.03267967 0.05834066 0.07999998 -0.0328812 0.05837285 0.0794329 -0.03286343 0.05768734 0.07935863 -0.03295558 0.05695044 0.07999998 -0.03301042 0.05681854 0.07940512 -0.03299784 0.05593895 0.07936418 -0.03290945 0.05538731 0.07999998 -0.03282928 0.05512505 0.07941204 -0.03274524 0.05427581 0.07938557 -0.03244161 0.053752 0.07999998 -0.03222018 0.05363833 0.07939606 -0.03213477 0.0529173 0.07936537 -0.03167861 0.05245584 0.07999998 -0.03133845 0.05226743 0.07940906 -0.03115373 0.0516231 0.07939499 -0.03048086 0.05115669 0.07999998 -0.0299167 0.05111843 0.07940512 -0.02978938 0.05077588 0.07940369 -0.02919536 0.05050653 0.07937502 -0.02859538 0.0503388 0.07999998 -0.02818578 0.05031889 0.07935678 -0.02805799 0.05011445 0.07940858 -0.02724385 0.04999065 0.07999998 -0.02647066 0.05002355 0.0794208 -0.02655249 0.05001664 0.07934242 -0.02579838 0.05007934 0.07999998 -0.02491247 0.05008101 0.07937878 -0.02496325 0.05031436 0.07938832 -0.02393329 0.05042415 0.07999998 -0.02355074 0.05060893 0.07941216 -0.02315074 0.05093699 0.0794022 -0.02250891 0.05111229 0.07999998 -0.02219736 0.0513246 0.07939624 -0.02190977 0.05197995 0.07999998 -0.0211035 0.05186218 0.07939553 -0.02124768 0.05262899 0.07941377 -0.02053087 0.05319404 0.07999998 -0.02010726 0.05334979 0.07937967 -0.02003484 0.05396467 0.07939958 -0.01969701 0.05492842 0.07999998 -0.01928418 0.05471169 0.07934731 -0.0193966 0.05529332 0.0794081 -0.01921439 0.05596184 0.0793718 -0.01908564 0.05687755 0.07999998 -0.0189839 0.05660372 0.07937651 -0.01901853 0.05790764 0.07941675 -0.01905745 0.05856096 0.07999998 -0.01916098 0.06046909 0.07999998 -0.01988035 0.06020617 0.07941097 -0.01977646 0.06146836 0.07934999 -0.02062779 0.0618925 0.07999998 -0.02098393 0.06214982 0.07939875 -0.0212596 0.06279599 0.07999998 -0.02204835 0.0626797 0.07939291 -0.02191656 0.06306105 0.07942557 -0.02250045 0.06343835 0.07999998 -0.02323859 0.06369757 0.07940006 -0.02396601 0.06383669 0.07999998 -0.02443951 0.06389361 0.07940816 -0.02480292 0.0639925 0.07942414 -0.02562373 0.06394779 0.07927137 -0.02565473 0.06385594 0.07914543 -0.02568387 0.06361877 0.07902878 -0.02506035 0.06377083 0.07918423 -0.02466005 0.06333196 0.0790022 -0.02415531 0.06331795 0.07903838 -0.0237053 0.06351739 0.07920372 -0.02368593 0.06339043 0.07937598 -0.02316081 0.06316715 0.07921028 -0.02286052 0.06277287 0.07907712 -0.0224502 0.06282716 0.07922261 -0.02226185 0.0625506 0.07900875 -0.02238988 0.06232565 0.07913696 -0.0216757 0.06196004 0.07924747 -0.02114868 0.0616768 0.07900625 -0.02130413 0.06136709 0.07910412 -0.02075654 0.06094646 0.07933771 -0.02023601 0.06014537 0.07900524 -0.0201736 0.06057459 0.07910031 -0.02020335 0.06032645 0.07923901 -0.01991897 0.05985343 0.07909524 -0.0198183 0.05950826 0.07932496 -0.01948255 0.05892157 0.07900327 -0.01965647 0.0587089 0.07914918 -0.01934462 0.05871796 0.07938528 -0.01922029 0.05795627 0.0790714 -0.01929461 0.05785745 0.07921892 -0.01913017 0.05714774 0.07932221 -0.01902216 0.05675697 0.07902038 -0.01933139 0.05664014 0.07913327 -0.01915365 0.05566334 0.07912826 -0.01927852 0.05495744 0.07900249 -0.01970678 0.05483484 0.07913953 -0.01949238 0.05418312 0.07909125 -0.01981174 0.05369192 0.0792061 -0.01992386 0.05357265 0.07904708 -0.02020961 0.05282717 0.07919096 -0.02049916 0.05290794 0.079014 -0.02075344 0.05232143 0.07917898 -0.02093267 0.05198866 0.07903802 -0.02153897 0.05179125 0.07917845 -0.02148747 0.05139601 0.07915729 -0.02201372 0.05145221 0.0790047 -0.02239882 0.05089092 0.07925659 -0.02269345 0.05098682 0.07910776 -0.02277946 0.05080842 0.07900339 -0.0236777 0.05055487 0.07922774 -0.02346897 0.05064296 0.07908272 -0.02362227 0.05029648 0.07917898 -0.02437561 0.05041331 0.07902806 -0.02485698 0.05012279 0.07917314 -0.02550172 0.05024212 0.07907497 -0.02549666 0.05039799 0.0790053 -0.02628237 0.05008572 0.0792604 -0.02669715 0.05018109 0.07912296 -0.02653795 0.05035591 0.07906079 -0.02723938 0.05024653 0.07924544 -0.02757984 0.05046278 0.07913225 -0.02804374 0.05068975 0.07900387 -0.02795588 0.05089586 0.07904231 -0.02881735 0.05079382 0.07917642 -0.02899563 0.05108892 0.07917004 -0.02953863 0.05146372 0.07900935 -0.02966558 0.05148416 0.0792579 -0.0302248 0.05177116 0.07909679 -0.03035497 0.05203175 0.07923984 -0.0308389 0.05234968 0.07900518 -0.03071248 0.05252158 0.07913893 -0.0312004 0.05314719 0.07903683 -0.03148317 0.05328333 0.07917559 -0.03180366 0.05402511 0.07918298 -0.03222787 0.05411988 0.07906252 -0.03211629 0.05471855 0.07900309 -0.03220659 0.05510097 0.0791983 -0.03264677 0.05517864 0.07905972 -0.03249561 0.05628037 0.07912176 -0.0328074 0.05631041 0.07902574 -0.03263765 0.05683451 0.07924699 -0.03293693 0.05720496 0.07900649 -0.03261983 0.05757331 0.07912689 -0.03282129 0.05842107 0.07923054 -0.03278511 0.05826264 0.07904696 -0.03260672 0.05892413 0.07900524 -0.03233027 0.05902779 0.07912766 -0.03253436 0.05971258 0.07920086 -0.03235948 0.05993264 0.07904398 -0.03205066 0.06030839 0.0790013 -0.03168767 0.06042861 0.07921057 -0.03201031 0.06109708 0.07910633 -0.03145825 0.0616849 0.07926875 -0.03113341 0.06111967 0.07903921 -0.03129392 0.06190234 0.07900321 -0.03042322 0.06187528 0.07909148 -0.03073978 0.06239396 0.07922518 -0.03035306 0.06249463 0.07909888 -0.03003102 0.06263136 0.07903236 -0.02961558 0.06300079 0.07915556 -0.02935338 0.06306624 0.07901525 -0.02874296 0.06333208 0.07925862 -0.02885013 0.0634905 0.07917863 -0.02833569 0.06337922 0.07900512 -0.02771878 0.06365036 0.0791158 -0.02758741 0.06386917 0.07918518 -0.02669841 0.06372565 0.07904583 -0.02630311 0.06359642 0.07900655 -0.02639645 0.06393599 0.08774805 -0.02564626 0.06383222 0.08788788 -0.02620875 0.06361824 0.08799088 -0.02656054 0.06374496 0.08778667 -0.02756905 0.06366711 0.08791399 -0.02729225 0.06339371 0.08796775 -0.0280134 0.06327402 0.08787852 -0.02873545 0.06287705 0.08799558 -0.02901136 0.06280905 0.0878933 -0.02958273 0.06240558 0.08779722 -0.0303108 0.06226778 0.0879665 -0.03013288 0.06162941 0.08787578 -0.03104132 0.06154412 0.08799344 -0.03083342 0.06092804 0.08779448 -0.03169238 0.06036722 0.08795017 -0.0318458 0.05999565 0.08779722 -0.03223156 0.05979812 0.08799397 -0.03200185 0.05901879 0.08790212 -0.03250706 0.05888891 0.08776515 -0.03267288 0.05809396 0.08798909 -0.03255724 0.0580219 0.08782958 -0.03280693 0.05716085 0.08787029 -0.0328533 0.05642473 0.08799546 -0.03259015 0.05648446 0.08790057 -0.03278958 0.05598253 0.08779913 -0.03284227 0.05554193 0.08794963 -0.03257584 0.05495238 0.08778423 -0.03260833 0.05451065 0.08792662 -0.03230106 0.05432552 0.08776801 -0.03239309 0.05418974 0.08799505 -0.03197735 0.05351805 0.08777362 -0.03199011 0.05331665 0.08791244 -0.03172099 0.05280232 0.08775609 -0.03152221 0.05272948 0.08799415 -0.03107225 0.05223816 0.08781433 -0.03100007 0.05171477 0.08778208 -0.0304718 0.05172681 0.08794796 -0.03019857 0.05127954 0.08776408 -0.02992337 0.05133825 0.08799487 -0.02941846 0.05111312 0.08793669 -0.02931499 0.05084925 0.08778059 -0.02917373 0.05061674 0.087866 -0.02849805 0.05032157 0.08775615 -0.02790343 0.05069541 0.08797347 -0.02819907 0.05037856 0.08791834 -0.02747094 0.05017602 0.08785331 -0.02679193 0.05054903 0.08799666 -0.02740168 0.05003845 0.08770203 -0.02615392 0.05033868 0.08798587 -0.02597635 0.05009818 0.08780431 -0.02565318 0.05021923 0.0878812 -0.02515798 0.05048704 0.08795672 -0.02431988 0.05031126 0.08781635 -0.02430182 0.0508145 0.08799731 -0.02370315 0.0506711 0.08784919 -0.02333515 0.05096453 0.08797806 -0.02312839 0.05106532 0.08773529 -0.0223807 0.05116754 0.08791553 -0.02252423 0.05147439 0.08782637 -0.02188324 0.05190026 0.08799439 -0.02176958 0.05194246 0.08785337 -0.02135074 0.0524519 0.08783978 -0.0208379 0.05285274 0.08798027 -0.02078163 0.05299794 0.08776891 -0.02034205 0.05370455 0.08798903 -0.02023196 0.05344527 0.08784246 -0.02010709 0.05425703 0.08784431 -0.01969707 0.05469137 0.08795982 -0.01969808 0.05499309 0.08785444 -0.01943945 0.05563086 0.08799821 -0.01955127 0.0558089 0.08788365 -0.01926821 0.05664509 0.08781242 -0.01910793 0.05681771 0.08797883 -0.01932865 0.05762529 0.08789777 -0.01920819 0.05825018 0.08799648 -0.01951539 0.05902564 0.08777379 -0.01936954 0.05885118 0.08792686 -0.019481 0.05963993 0.08795583 -0.01981371 0.06033658 0.08782351 -0.01996564 0.06098514 0.08799701 -0.02071809 0.06056183 0.08796006 -0.02030867 0.06125628 0.08779072 -0.02054297 0.06136655 0.08792221 -0.02081334 0.06202292 0.08784675 -0.02131646 0.06184297 0.08799362 -0.02147907 0.06252801 0.08775937 -0.02180904 0.0624994 0.08792334 -0.02202957 0.06298297 0.08779263 -0.0225358 0.06276249 0.0879954 -0.02278161 0.06307601 0.08793675 -0.02304857 0.06339597 0.08778059 -0.02334856 0.06330484 0.08795261 -0.02363312 0.06366479 0.08777076 -0.02411925 0.0635544 0.0879215 -0.02425754 0.06378608 0.08781129 -0.02472633 0.06346243 0.08799856 -0.02474832 0.06368452 0.08795052 -0.02518409 0.06499099 0.08662486 -0.02582937 0.06496328 0.08599996 -0.02699792 0.06495511 0.08663243 -0.0267989 0.06477308 0.08666926 -0.02782326 0.06447881 0.08599996 -0.02887433 0.06456214 0.08668059 -0.02855294 0.06419014 0.08659821 -0.02950847 0.06365972 0.08599996 -0.03046786 0.06370633 0.08659297 -0.0303564 0.06323671 0.08662903 -0.03099751 0.06235128 0.08599996 -0.03197306 0.06273138 0.08658003 -0.03157919 0.06214821 0.08657157 -0.03212249 0.06152492 0.08658838 -0.03259456 0.06104648 0.08599996 -0.03290849 0.06081682 0.08659774 -0.03302681 0.05979347 0.08599996 -0.03350937 0.05988419 0.08659803 -0.03346252 0.05895674 0.08659416 -0.03375387 0.05843949 0.08599996 -0.03387588 0.05798703 0.08658778 -0.03394073 0.05686008 0.08599996 -0.03401833 0.05699163 0.08658611 -0.03399789 0.05626308 0.08666813 -0.03394764 0.05577993 0.08657646 -0.0339052 0.05507785 0.08599996 -0.03377813 0.05486088 0.08657705 -0.03371167 0.05321484 0.08599996 -0.03308045 0.05388599 0.0865978 -0.0333653 0.05297499 0.08658671 -0.03291594 0.05208891 0.0866689 -0.03229659 0.05159199 0.08599996 -0.03191173 0.05141067 0.08659535 -0.03172433 0.05028957 0.08599996 -0.03040796 0.05076122 0.08658283 -0.03100472 0.05029678 0.0865876 -0.03036272 0.04979711 0.08659082 -0.02948474 0.04947501 0.08599996 -0.02873891 0.04935669 0.08660495 -0.02836155 0.04906123 0.08599996 -0.02713584 0.04909312 0.08660292 -0.02721798 0.04900789 0.08661609 -0.0261771 0.04902279 0.08599996 -0.02520173 0.04902589 0.08659619 -0.02539813 0.04915022 0.08659517 -0.02445244 0.04950386 0.08599996 -0.02312457 0.05008804 0.08661609 -0.0219838 0.05035674 0.08599996 -0.02153128 0.05050438 0.08659297 -0.02133506 0.05122494 0.08599996 -0.0204463 0.05098831 0.08659946 -0.02072727 0.05157411 0.08655965 -0.02012085 0.05259859 0.08599996 -0.0192961 0.05218374 0.0865792 -0.01961392 0.05286306 0.08660125 -0.01915723 0.05368655 0.08659821 -0.01871776 0.05402839 0.08599996 -0.01856547 0.054614 0.08664703 -0.01837617 0.05535697 0.08599996 -0.01815807 0.05559176 0.08658885 -0.01812285 0.05713987 0.08599996 -0.01798158 0.05661022 0.08660954 -0.01801449 0.05742555 0.08663535 -0.01802039 0.05817657 0.08664143 -0.01809751 0.05878186 0.08599996 -0.01819276 0.05893099 0.08665591 -0.01824998 0.05971592 0.08667576 -0.01849335 0.06016415 0.08599996 -0.01863908 0.06050848 0.0866577 -0.01882559 0.06117343 0.0865966 -0.0191785 0.06201016 0.08599996 -0.01971733 0.06183063 0.08661067 -0.01962983 0.06259936 0.08658051 -0.0202822 0.06371039 0.08599996 -0.02159196 0.06326335 0.08658325 -0.02102619 0.06370306 0.08658844 -0.02163755 0.06410187 0.08659899 -0.02232468 0.06444996 0.08599996 -0.02307611 0.06444215 0.08658289 -0.02307027 0.06465226 0.08664911 -0.02369862 0.06491726 0.08599996 -0.0246669 0.06491136 0.08658665 -0.02480024 0.06501084 0.08099997 -0.02585691 0.06498539 0.08035391 -0.02624183 0.06490927 0.08099997 -0.02724277 0.06476217 0.08039629 -0.02793681 0.06451517 0.08099997 -0.02879923 0.06445717 0.08039867 -0.02888572 0.06412696 0.08043944 -0.02963447 0.06359207 0.08099997 -0.0305671 0.06371432 0.08039516 -0.03034138 0.06325721 0.08040219 -0.03097909 0.06273031 0.08040219 -0.03157746 0.06240797 0.08099997 -0.03191167 0.06217151 0.08041042 -0.03210031 0.06163668 0.08033406 -0.03250342 0.0613017 0.08099997 -0.03275251 0.06066048 0.08036756 -0.03310793 0.0600599 0.08099997 -0.03340476 0.05976206 0.08041983 -0.03350645 0.05853211 0.08099997 -0.03386425 0.05714976 0.08099997 -0.03400492 0.05639821 0.08039575 -0.03397715 0.05574989 0.08099997 -0.03391402 0.05420649 0.08099997 -0.03350937 0.05373764 0.08039957 -0.03330487 0.05277395 0.08099997 -0.03280699 0.05282884 0.08042556 -0.03282546 0.05219662 0.08040958 -0.03239423 0.05166494 0.08099997 -0.03196984 0.05159282 0.08038777 -0.0318886 0.05074179 0.08045381 -0.03100103 0.0505712 0.08099997 -0.03079426 0.05007326 0.08039605 -0.02999413 0.04976493 0.08099997 -0.02942866 0.0497207 0.08039534 -0.02930802 0.04927211 0.08099997 -0.02811539 0.04915827 0.08041381 -0.02759367 0.04900622 0.08099997 -0.02654236 0.04905015 0.08037865 -0.02680802 0.04900097 0.08038884 -0.02596986 0.04907912 0.08099997 -0.02474534 0.04906469 0.08039462 -0.02501839 0.04919898 0.08039563 -0.02424722 0.04943174 0.08035153 -0.02343887 0.04949373 0.08099997 -0.02321469 0.04970306 0.08039534 -0.022731 0.05015909 0.08099997 -0.02181965 0.05007869 0.08035379 -0.02201008 0.0505135 0.0804094 -0.02132159 0.05126279 0.08099997 -0.0204041 0.05114072 0.08038401 -0.02055621 0.05187803 0.08035182 -0.01986956 0.05298215 0.08099997 -0.01904082 0.05265039 0.08038645 -0.01928716 0.05355423 0.08035069 -0.01879334 0.05425667 0.08041387 -0.01848727 0.05502241 0.08099997 -0.01823347 0.05499494 0.08038663 -0.01826107 0.05665707 0.08099997 -0.01799517 0.05659711 0.08040064 -0.01801377 0.0581938 0.08099997 -0.01807928 0.05758601 0.08037555 -0.01802438 0.05858373 0.08036679 -0.01816719 0.05987393 0.08099997 -0.01851302 0.05954408 0.08040004 -0.01841503 0.06044292 0.08036392 -0.01878875 0.06168293 0.08099997 -0.0194863 0.06119716 0.0804196 -0.0191912 0.06185787 0.08040875 -0.01964718 0.06244146 0.08039188 -0.02014219 0.06300586 0.08099997 -0.02069979 0.06299412 0.08038789 -0.02071017 0.06346744 0.08038628 -0.02129942 0.06394052 0.08099997 -0.02199268 0.06393307 0.08041858 -0.02201163 0.06429761 0.08035403 -0.02274924 0.06474518 0.08099997 -0.0238853 0.06457996 0.08040243 -0.02345323 0.06495743 0.08040344 -0.02516674 0.06493443 0.08024495 -0.02580207 0.0647971 0.08009642 -0.02565503 0.06462818 0.08000719 -0.02588164 0.06484502 0.08019703 -0.02502661 0.06464552 0.08010178 -0.02436995 0.06478834 0.08034783 -0.02422624 0.06434553 0.08000689 -0.02386873 0.0644536 0.0801776 -0.02339804 0.06399446 0.08001589 -0.02285915 0.0638439 0.08016091 -0.02207845 0.06310743 0.08000111 -0.02149617 0.06366622 0.0802654 -0.02166664 0.06328344 0.08002817 -0.02156275 0.0630483 0.08017003 -0.02093613 0.06258118 0.08007669 -0.02058213 0.06225788 0.08014506 -0.02014571 0.06187653 0.08000719 -0.02014744 0.06177854 0.08024263 -0.01966381 0.06128853 0.08007323 -0.01950395 0.06096655 0.08024221 -0.01912415 0.06021207 0.08011358 -0.01886028 0.05974245 0.08000677 -0.01887106 0.05952858 0.0802375 -0.01847964 0.05908942 0.08013683 -0.01842731 0.05799722 0.08004271 -0.01833856 0.0578022 0.08016663 -0.01815247 0.05705189 0.08000326 -0.01839286 0.05662643 0.08014118 -0.018139 0.05616611 0.0801118 -0.01821821 0.05580401 0.08035624 -0.01810061 0.05571174 0.08000302 -0.01851457 0.05539739 0.08018803 -0.01826548 0.05527526 0.08005648 -0.0184518 0.05444091 0.08017593 -0.01852917 0.05412018 0.08000516 -0.01894444 0.05394965 0.08011692 -0.01878994 0.05330312 0.08005422 -0.01919883 0.05322122 0.08016669 -0.01908391 0.0526275 0.08017212 -0.01943492 0.05208283 0.08000665 -0.02015721 0.05213534 0.08009845 -0.01989185 0.05149716 0.08015912 -0.02036303 0.05103248 0.0800777 -0.02100777 0.05066001 0.08023685 -0.02122843 0.05052655 0.08000195 -0.02199637 0.05047595 0.08012074 -0.02165776 0.05032449 0.080042 -0.02212828 0.04988265 0.08016961 -0.02259916 0.04971963 0.08010053 -0.02317142 0.0497542 0.0800023 -0.02368474 0.04940032 0.08021211 -0.02375972 0.04949378 0.08004903 -0.02415531 0.04921722 0.08019655 -0.02461791 0.04917234 0.08013975 -0.02527081 0.04935848 0.08002376 -0.02534288 0.04910027 0.08018845 -0.02634441 0.04935163 0.0800125 -0.02629566 0.04921931 0.08024382 -0.02758032 0.04932993 0.08010053 -0.02751648 0.04971837 0.08000558 -0.02825319 0.04943174 0.08036106 -0.02856242 0.04954707 0.08014017 -0.02848404 0.04985022 0.08016955 -0.02933222 0.05012631 0.08001393 -0.02937257 0.05025851 0.080181 -0.03011196 0.0508331 0.08007633 -0.03075832 0.05053824 0.08025544 -0.03062176 0.05088704 0.08000433 -0.03051328 0.05117273 0.08025032 -0.03140079 0.05157774 0.08003091 -0.03146266 0.05185514 0.08010041 -0.03187775 0.05192136 0.08022469 -0.03208392 0.05259978 0.0801658 -0.03254753 0.05238527 0.08000624 -0.03205537 0.05330586 0.08000755 -0.03267294 0.05334228 0.08023685 -0.03304231 0.05345171 0.08010202 -0.0329613 0.05426537 0.08018845 -0.03340911 0.05461615 0.08000224 -0.03320837 0.05465567 0.08004385 -0.03336155 0.05466216 0.08037114 -0.03364247 0.05506408 0.08014744 -0.03362083 0.05540841 0.08037251 -0.03383213 0.05591529 0.08013027 -0.03377795 0.05659395 0.08002346 -0.03367304 0.05662709 0.08020466 -0.03390198 0.05738973 0.08034926 -0.03397846 0.05772006 0.08000409 -0.03357344 0.05753099 0.08010041 -0.0337978 0.05820041 0.08036679 -0.03390061 0.05825853 0.08009827 -0.03371667 0.05908793 0.08033245 -0.03370785 0.05925577 0.08009046 -0.03347593 0.05949842 0.0800029 -0.03316324 0.06003749 0.08021694 -0.03331363 0.06056207 0.08011168 -0.03296589 0.06053966 0.08001053 -0.03276836 0.06116116 0.08025586 -0.03276818 0.06135678 0.08009839 -0.03248369 0.06226676 0.08015644 -0.03186064 0.06216472 0.08000785 -0.03162562 0.06291776 0.08020162 -0.03124701 0.06306016 0.08006721 -0.03085666 0.06342118 0.08022385 -0.03063911 0.06340539 0.08000946 -0.03015357 0.06373006 0.08008402 -0.02993518 0.06389194 0.08025401 -0.02994972 0.06422978 0.08020895 -0.02923983 0.06415629 0.08004277 -0.02890217 0.06466567 0.08027213 -0.0281105 0.06427538 0.08000177 -0.02815186 0.06449854 0.08009946 -0.02819359 0.0648297 0.08017879 -0.02704167 0.06469506 0.08006179 -0.02700299 0.06493043 0.08036684 -0.02698427 0.0648877 0.0868197 -0.02623164 0.06473827 0.08694845 -0.02578938 0.06456702 0.08699762 -0.02672809 0.06475812 0.08687794 -0.02717691 0.06441175 0.08694612 -0.02826327 0.06405401 0.08699887 -0.02875846 0.06422024 0.08689737 -0.02898335 0.06422412 0.08678436 -0.02924811 0.06376522 0.08694201 -0.02978831 0.06384968 0.08676862 -0.02999013 0.0634306 0.08682978 -0.0305649 0.06314861 0.08699238 -0.03052252 0.06277364 0.08678519 -0.03142607 0.06276297 0.08695238 -0.03114825 0.06235402 0.0867995 -0.03182339 0.06199967 0.08690065 -0.03200805 0.06161367 0.08675968 -0.03246307 0.06182622 0.08699464 -0.03187388 0.06111449 0.08695465 -0.03254032 0.06081318 0.08682543 -0.03290647 0.0602104 0.08678215 -0.03324484 0.05942654 0.08699697 -0.0332151 0.05994564 0.08694112 -0.03317373 0.05917048 0.08683568 -0.03358083 0.05851042 0.08678889 -0.03377079 0.05800455 0.08693689 -0.03369975 0.0578103 0.08699959 -0.03351461 0.05762225 0.0867443 -0.03392124 0.056827 0.08683067 -0.03388613 0.05651921 0.08691245 -0.03379178 0.05634462 0.08699351 -0.03358817 0.05546122 0.08680748 -0.03375446 0.05497682 0.08693593 -0.0334959 0.05460381 0.08674579 -0.0335738 0.05432641 0.08698952 -0.0331608 0.05393141 0.08682978 -0.0332669 0.05304908 0.08673697 -0.03289753 0.05322217 0.08699709 -0.03259742 0.05327159 0.08688664 -0.03288096 0.05247187 0.08692485 -0.03233522 0.0517134 0.08699524 -0.03146463 0.0516296 0.08687925 -0.03171193 0.05092048 0.08674681 -0.03111791 0.05087882 0.08689326 -0.03087908 0.05052304 0.0869683 -0.03017991 0.05021172 0.08678036 -0.03009074 0.04980432 0.08680844 -0.02928006 0.05002695 0.08699291 -0.02910578 0.04942888 0.08678025 -0.02833652 0.04954642 0.08690768 -0.0283026 0.04950869 0.08696746 -0.02779442 0.04916948 0.08681243 -0.02709525 0.0494095 0.08699405 -0.0267381 0.04913473 0.08685576 -0.02610403 0.04936689 0.08698517 -0.02559798 0.04911375 0.08679652 -0.02538335 0.04937636 0.08695483 -0.02474564 0.04926949 0.08683651 -0.02444344 0.04937696 0.08666747 -0.0236175 0.04962605 0.08686923 -0.02331274 0.04979747 0.08699172 -0.02346801 0.04965788 0.08665138 -0.02284896 0.05005097 0.08683997 -0.02227616 0.05028951 0.08697479 -0.02227526 0.05069118 0.08699649 -0.02173715 0.05067539 0.08678472 -0.02123081 0.05088019 0.08692508 -0.02119302 0.0513373 0.08676731 -0.02044236 0.05236184 0.08699953 -0.02002954 0.05172097 0.08696079 -0.02037411 0.05188256 0.0867784 -0.01994669 0.05245435 0.08695262 -0.01974964 0.05253475 0.08677238 -0.01944994 0.05319678 0.08693635 -0.01923286 0.05336642 0.08683258 -0.01900166 0.0540685 0.08699762 -0.01899206 0.05390661 0.08673888 -0.01868277 0.05428683 0.08690023 -0.01867288 0.05509859 0.08680152 -0.01832652 0.05545991 0.08694922 -0.0184077 0.05581146 0.08676445 -0.01815706 0.05692666 0.08699905 -0.01841014 0.05678302 0.08681577 -0.01810431 0.05706876 0.08695334 -0.01826566 0.05800539 0.08684211 -0.01818984 0.05870378 0.08690279 -0.01836979 0.05915427 0.08698165 -0.0186491 0.06010925 0.08689081 -0.01881271 0.06082111 0.08699584 -0.01940578 0.06123822 0.08682924 -0.01934313 0.06188869 0.08699196 -0.02014631 0.06208378 0.08690696 -0.02007073 0.06243598 0.08675932 -0.0202111 0.06282258 0.08693343 -0.02085661 0.06320005 0.08676999 -0.02105826 0.06292992 0.08699655 -0.02127373 0.06338506 0.08691263 -0.02152895 0.06376421 0.08678269 -0.02187466 0.06368333 0.08699506 -0.02233767 0.06389242 0.08689606 -0.02232038 0.06422597 0.08675611 -0.02271908 0.0641663 0.08696484 -0.02317851 0.06442236 0.08688795 -0.02350062 0.06472629 0.08674699 -0.0241577 0.06445223 0.08699566 -0.02454274 0.06463462 0.08693045 -0.02454441 0.06488484 0.08677995 -0.02517825 0.06599491 0.08141237 -0.0257712 0.06591176 0.08119726 -0.02596569 0.06573945 0.08105176 -0.02616852 0.06590867 0.08139556 -0.0247159 0.06558746 0.08100283 -0.02609354 0.06585317 0.08122575 -0.02487498 0.06567275 0.08108943 -0.02447992 0.06549817 0.08100277 -0.02468377 0.06575357 0.08134317 -0.02397394 0.06555205 0.08117079 -0.02358967 0.06551784 0.08136993 -0.02311897 0.06525391 0.08102864 -0.02330291 0.06524395 0.08115553 -0.02271366 0.06511604 0.08140707 -0.02210545 0.06464672 0.08100318 -0.02205824 0.06487125 0.0810703 -0.02214127 0.06485259 0.08119785 -0.02178919 0.06445437 0.0813781 -0.02096009 0.06418859 0.08103018 -0.02109402 0.06418925 0.08120328 -0.02073591 0.06358647 0.08109235 -0.02014714 0.06372052 0.08135294 -0.02003026 0.06297546 0.08139455 -0.01926976 0.06295633 0.08100378 -0.01981019 0.06305861 0.08119803 -0.01947462 0.0624392 0.08109223 -0.01907688 0.06241095 0.08125972 -0.01887804 0.06208759 0.08143442 -0.01857548 0.06190526 0.08102411 -0.01884752 0.06169116 0.08125293 -0.01838535 0.06109315 0.08100485 -0.01841634 0.06165027 0.08111685 -0.01849257 0.06129491 0.08140218 -0.01809448 0.0608766 0.08122783 -0.01796138 0.06083786 0.08108389 -0.0180931 0.06051856 0.08140051 -0.01771992 0.05983012 0.08134061 -0.01746773 0.0598427 0.08112382 -0.01762783 0.05949062 0.08100557 -0.0177353 0.05919438 0.08134102 -0.01728743 0.05880635 0.08118027 -0.01729172 0.05838 0.08138906 -0.01711094 0.05838418 0.08103442 -0.01740586 0.05786782 0.08134162 -0.01705706 0.05785655 0.08115863 -0.01716852 0.05697286 0.0810815 -0.01720833 0.05674338 0.08138757 -0.01700413 0.05700862 0.08123385 -0.01707142 0.05607402 0.08101141 -0.0173943 0.05601209 0.08120208 -0.01714307 0.05561608 0.08139938 -0.01711058 0.05513471 0.08113884 -0.01733738 0.05481106 0.08131897 -0.01729285 0.05432718 0.08145534 -0.01740419 0.05471795 0.08100509 -0.01769417 0.05400633 0.08123081 -0.01758313 0.0535382 0.08108097 -0.01791828 0.05347728 0.08141201 -0.01772022 0.05300086 0.08100432 -0.01837503 0.05311727 0.08123093 -0.01796197 0.05247819 0.08138173 -0.01822 0.05245828 0.08104771 -0.01853877 0.0520026 0.08116972 -0.0186454 0.05155181 0.08137106 -0.01884597 0.05104058 0.08100497 -0.0197767 0.05122071 0.0810694 -0.01940727 0.05087745 0.08140057 -0.01940792 0.05093538 0.08120578 -0.01947027 0.05027973 0.08131277 -0.0200439 0.05027478 0.0810849 -0.02033227 0.04998147 0.08137589 -0.02037709 0.04972612 0.08124423 -0.02080982 0.04942369 0.08140885 -0.02114641 0.04976582 0.0810045 -0.02134561 0.04962259 0.08109259 -0.02120065 0.04919797 0.08132702 -0.02154898 0.04912602 0.08110618 -0.0220195 0.04880213 0.08136552 -0.02230668 0.04898101 0.08101409 -0.02278071 0.04879206 0.08111512 -0.02273762 0.04848557 0.08136552 -0.0231105 0.04840964 0.08117878 -0.02368164 0.04822677 0.08143091 -0.02399277 0.04872101 0.08100581 -0.02356332 0.04822641 0.08120232 -0.02441275 0.04804575 0.08138251 -0.02511167 0.04834961 0.08104908 -0.02480745 0.04808264 0.08121949 -0.02560245 0.04841852 0.08100295 -0.02570992 0.04822176 0.08107501 -0.02603101 0.04800915 0.08138793 -0.02627229 0.04816186 0.08116072 -0.02685922 0.04810452 0.08136618 -0.02733957 0.04840481 0.08102864 -0.02727389 0.04835361 0.08119881 -0.02816081 0.04834038 0.08140385 -0.02844101 0.04882133 0.08100235 -0.02867096 0.04857957 0.08107757 -0.02848738 0.04869252 0.08141118 -0.02946847 0.04870963 0.08119684 -0.02925372 0.04902964 0.08104825 -0.02957707 0.04900658 0.08122169 -0.02996999 0.04930394 0.08140075 -0.03066855 0.04950881 0.08108484 -0.0306071 0.04949486 0.08125507 -0.03086245 0.04994744 0.08100312 -0.03090399 0.04996281 0.08140695 -0.03160643 0.05002933 0.08121663 -0.03156483 0.05038166 0.08108502 -0.03179454 0.05050837 0.08133816 -0.03221058 0.05102211 0.08100187 -0.03218346 0.05088621 0.08141392 -0.03260225 0.05100393 0.08118677 -0.03257685 0.05155599 0.08138668 -0.03316015 0.05147409 0.08104991 -0.03275603 0.05178117 0.08115553 -0.03318065 0.05232322 0.08137243 -0.03368073 0.05258655 0.08123564 -0.03376895 0.05253887 0.08101981 -0.03342688 0.05317884 0.08110594 -0.03395462 0.05311614 0.08140701 -0.03411597 0.05353164 0.08122771 -0.03422331 0.0541293 0.08140677 -0.03453207 0.05374443 0.08100455 -0.03396737 0.05459773 0.08120262 -0.03458607 0.05449885 0.08105164 -0.0343787 0.05547755 0.08137589 -0.03486788 0.05565541 0.08113658 -0.03475111 0.05592268 0.08100539 -0.03454995 0.05682814 0.08139109 -0.03499823 0.05654424 0.08121562 -0.03490942 0.05701005 0.08104467 -0.03473466 0.05743503 0.08118414 -0.03488332 0.05789119 0.08138442 -0.03495013 0.05829113 0.08118808 -0.03480333 0.05874741 0.08105665 -0.03457564 0.05897933 0.08138602 -0.03477919 0.05892354 0.08100455 -0.03440243 0.05919063 0.08121562 -0.03464794 0.06009775 0.08138364 -0.03444397 0.06021213 0.08118057 -0.03429585 0.06044858 0.08104681 -0.03402787 0.06108129 0.08137971 -0.03401947 0.06125682 0.08120983 -0.03383135 0.06175339 0.08100223 -0.03315502 0.06167626 0.08106738 -0.03341549 0.06221973 0.08137953 -0.03332978 0.0622875 0.08120238 -0.03317826 0.06314402 0.08139824 -0.03257149 0.06284874 0.0810818 -0.03255891 0.06326901 0.08126288 -0.03239119 0.06354981 0.08100265 -0.03161251 0.06376689 0.08141976 -0.03193187 0.06349611 0.08105945 -0.03187119 0.06407171 0.0811842 -0.03140872 0.06432694 0.08139044 -0.03121817 0.064296 0.08106589 -0.03085166 0.06480056 0.08138287 -0.03047734 0.06469708 0.08120685 -0.03048831 0.06470668 0.0810219 -0.02997344 0.0649296 0.08110243 -0.02984702 0.06522041 0.08139884 -0.02965527 0.06513166 0.08123582 -0.02969896 0.06553828 0.08139699 -0.02883332 0.06540828 0.08116912 -0.02888256 0.06581968 0.081393 -0.02779585 0.06535518 0.08100748 -0.02821224 0.06570881 0.08122241 -0.02795583 0.06558662 0.08107364 -0.02780979 0.06582081 0.08117616 -0.02714133 0.06597191 0.08139598 -0.02665871 0.06599515 0.08559173 -0.02621561 0.0659216 0.08561635 -0.02714115 0.06575888 0.08567428 -0.02799504 0.06553745 0.08558875 -0.02884149 0.06518965 0.08565562 -0.02970165 0.06469666 0.08561867 -0.030662 0.06403928 0.08556908 -0.03160762 0.06342422 0.0856046 -0.03229731 0.06264269 0.08561921 -0.03300958 0.06152343 0.08559775 -0.0337823 0.0604875 0.08557438 -0.03429615 0.05940634 0.08559113 -0.0346747 0.05834531 0.08559244 -0.03489637 0.05725729 0.0856589 -0.03498506 0.05650264 0.08563196 -0.03497797 0.05567747 0.08564811 -0.03489094 0.05477154 0.08562129 -0.03471308 0.05390262 0.08566445 -0.03443473 0.05308973 0.08563309 -0.03409683 0.05228048 0.08565962 -0.03364741 0.05133384 0.08559411 -0.0329945 0.05036985 0.08562135 -0.03208351 0.04967886 0.08561116 -0.03122603 0.04907506 0.08559638 -0.03026884 0.04862087 0.0855723 -0.02928376 0.04833996 0.08562129 -0.02842664 0.04813921 0.08556997 -0.02757591 0.04803073 0.08559966 -0.02670049 0.04800623 0.08560389 -0.02579593 0.04806977 0.08559215 -0.02490115 0.04827564 0.08561283 -0.02378803 0.04871165 0.08562612 -0.02249753 0.04922229 0.08565688 -0.02149713 0.04968833 0.08557951 -0.02075397 0.05023831 0.08556938 -0.02006053 0.05088621 0.08558607 -0.01939773 0.05174183 0.08558249 -0.01869177 0.05269312 0.08559304 -0.01810026 0.05374854 0.0856142 -0.0176084 0.05477607 0.08560472 -0.0172832 0.05569738 0.08564913 -0.01710623 0.0565986 0.08560925 -0.01701366 0.05750119 0.08566588 -0.01702886 0.05858325 0.08559554 -0.01713848 0.05964112 0.08565068 -0.01740843 0.06051504 0.0856046 -0.0177192 0.06127166 0.08565598 -0.01809287 0.06207078 0.08561074 -0.01857054 0.06278091 0.08565586 -0.0191183 0.06344687 0.08559775 -0.01972454 0.06404775 0.08564895 -0.02042132 0.06466048 0.08560359 -0.02127432 0.06528311 0.08560246 -0.02247744 0.06566238 0.08561319 -0.02357667 0.0658617 0.08560401 -0.02445119 0.06597381 0.08559352 -0.02535259 0.06589221 0.08582085 -0.02628004 0.06579387 0.08591091 -0.02583289 0.06557047 0.08599585 -0.02701574 0.0655831 0.08599811 -0.02619642 0.06580787 0.08584517 -0.02707403 0.06556487 0.08591502 -0.02798068 0.06543904 0.08579045 -0.02888494 0.06511944 0.08597081 -0.02911752 0.06497865 0.08585083 -0.02987003 0.06462204 0.08596831 -0.03017574 0.06438404 0.08584469 -0.03093105 0.06406193 0.08599877 -0.03089809 0.06386655 0.08575224 -0.03172862 0.06362605 0.08594584 -0.03171473 0.06293618 0.08597773 -0.03232198 0.0629028 0.08586072 -0.03261071 0.0623368 0.08579128 -0.03314417 0.06136822 0.08599919 -0.0333755 0.06180256 0.08595734 -0.03327679 0.06148946 0.08584648 -0.03365737 0.06084996 0.085774 -0.03405481 0.06050473 0.08596211 -0.03397166 0.06007808 0.08578771 -0.03437232 0.05914866 0.08593463 -0.03450214 0.05923312 0.08577585 -0.03464126 0.05874764 0.08599847 -0.03441619 0.05810946 0.0858035 -0.03484141 0.05765086 0.08595603 -0.03469687 0.05675166 0.08588552 -0.03483045 0.05588072 0.08598715 -0.03458571 0.05565494 0.08584088 -0.03476905 0.05471742 0.08588558 -0.0345388 0.05392867 0.08599686 -0.03406542 0.05341887 0.0859636 -0.03395009 0.05330085 0.08584958 -0.03405928 0.05222809 0.08585321 -0.03347188 0.05159139 0.08591198 -0.03294271 0.05161094 0.08572292 -0.03315114 0.05144274 0.08598709 -0.03263849 0.05072498 0.08578681 -0.03234249 0.05053901 0.08586013 -0.03206211 0.05024564 0.08598947 -0.0314067 0.04998296 0.08580225 -0.03148263 0.04937487 0.08578759 -0.03063106 0.04958093 0.08594238 -0.03063058 0.04910558 0.085927 -0.02983319 0.04873502 0.08576577 -0.02939462 0.04873406 0.0858879 -0.02910363 0.04925751 0.08599811 -0.02968937 0.04868608 0.08599442 -0.02827125 0.04843223 0.0858072 -0.02840834 0.04845929 0.08593761 -0.02792161 0.04818099 0.0857824 -0.02737897 0.04827469 0.08593523 -0.02679544 0.04806751 0.08577263 -0.02600961 0.04843431 0.08599728 -0.02642524 0.04823338 0.08592838 -0.02559173 0.04814702 0.0857678 -0.02483594 0.04838758 0.08591139 -0.02421516 0.04849261 0.08599317 -0.02459329 0.04833471 0.08576261 -0.02380907 0.0485112 0.08581936 -0.02333986 0.04888343 0.08594721 -0.02273309 0.04910248 0.0859937 -0.02255642 0.04883688 0.08577179 -0.02238595 0.0493564 0.08588498 -0.0215826 0.04980707 0.08599722 -0.0212593 0.04989933 0.08575552 -0.02056586 0.0498147 0.08587354 -0.02084445 0.0503394 0.08594626 -0.02033632 0.05057883 0.08578288 -0.0198009 0.05113261 0.08599078 -0.01965534 0.05125308 0.08580732 -0.01919621 0.0520302 0.08595788 -0.01882708 0.05199217 0.0857774 -0.01861333 0.0527547 0.08579784 -0.01816534 0.05313444 0.0859186 -0.01810467 0.0537334 0.08578616 -0.01769715 0.05360698 0.0859968 -0.01810967 0.05410104 0.08594131 -0.01774704 0.05496174 0.0858522 -0.01736474 0.05537253 0.08599704 -0.01755666 0.05609273 0.08594256 -0.01729005 0.05670994 0.08578562 -0.01708126 0.0574932 0.08592516 -0.01723229 0.05812823 0.08599519 -0.01745432 0.05833089 0.08576458 -0.01716786 0.05901795 0.0858733 -0.01738208 0.05965465 0.08599525 -0.01781934 0.06029325 0.08581703 -0.01773375 0.06020039 0.08595478 -0.01788181 0.06128454 0.08589023 -0.01828378 0.06180936 0.08599275 -0.0188319 0.061984 0.08584618 -0.01865828 0.06258481 0.08590954 -0.01919978 0.0632379 0.08581566 -0.01965141 0.06343889 0.08592927 -0.02004396 0.06322747 0.08599787 -0.02010381 0.06412643 0.08580881 -0.0206601 0.06410437 0.08595609 -0.0209397 0.06471949 0.08575606 -0.02149689 0.06485247 0.08590674 -0.02200466 0.0645647 0.08599531 -0.02187013 0.06514543 0.08577519 -0.02235132 0.06541103 0.08582478 -0.02311176 0.06523621 0.08599084 -0.02340567 0.06568503 0.08581024 -0.02405637 0.065611 0.08595794 -0.02456611 0.06585186 0.08582264 -0.02508789 0.05747187 0.07318484 -0.06726861 0.05694222 0.07317245 -0.06724125 0.05776101 0.0730918 -0.06726276 0.05727857 0.07300037 -0.06699502 0.05768448 0.07302218 -0.06715661 0.05810451 0.07319223 -0.0674088 0.05853915 0.07315731 -0.06756645 0.05875241 0.07300519 -0.06746488 0.05877041 0.0730496 -0.06757837 0.05904006 0.07316642 -0.06783598 0.05947744 0.0730611 -0.06806921 0.05964529 0.0730037 -0.06805324 0.05960446 0.07318055 -0.06828653 0.05986684 0.07308274 -0.06849718 0.0600509 0.07319968 -0.06880891 0.06049627 0.07300359 -0.06910949 0.06014078 0.0730732 -0.06883358 0.06030184 0.07316815 -0.069202 0.06049442 0.07306575 -0.06942701 0.06052196 0.07318025 -0.06968063 0.06074661 0.07303124 -0.07000631 0.06066757 0.0731647 -0.07015883 0.06104511 0.07299977 -0.07102 0.06088936 0.07302612 -0.07085305 0.06073737 0.07316792 -0.07058542 0.06075513 0.07319766 -0.07109761 0.06080275 0.07309377 -0.07109606 0.06067776 0.07319003 -0.07178908 0.06076729 0.07307016 -0.07163566 0.06068885 0.07304751 -0.0721184 0.06049615 0.07313358 -0.07240986 0.06055873 0.07300722 -0.07271379 0.06026756 0.07316613 -0.07286334 0.06013822 0.07303583 -0.07327634 0.06004679 0.07318717 -0.07319968 0.05985683 0.07314252 -0.07346028 0.05960363 0.07300972 -0.07393199 0.05942362 0.07314497 -0.0738846 0.05895608 0.073192 -0.07420796 0.05897003 0.07300674 -0.07440871 0.05891644 0.07306402 -0.07431548 0.05845797 0.07320165 -0.07446146 0.05820471 0.07306897 -0.07463103 0.05801838 0.07318472 -0.07461571 0.05768102 0.0730018 -0.07492995 0.05756092 0.07315385 -0.07472324 0.05749726 0.07302951 -0.07484871 0.0570001 0.07315421 -0.07476514 0.05626916 0.07300436 -0.07490426 0.05648565 0.0730443 -0.07482361 0.05644142 0.07317018 -0.07471942 0.05603039 0.07316386 -0.07463431 0.05574452 0.07303261 -0.07466936 0.05545109 0.07320231 -0.07442474 0.05562657 0.07311272 -0.07453024 0.05504012 0.07306909 -0.07428812 0.05480659 0.07317101 -0.07405877 0.05473291 0.07300662 -0.07422757 0.05437737 0.07316815 -0.07369387 0.05430912 0.07303929 -0.07376945 0.05400079 0.07317715 -0.07327198 0.05410379 0.07307881 -0.07347786 0.05372971 0.07300966 -0.07318758 0.05375075 0.0730586 -0.07304263 0.05361336 0.07318222 -0.07263743 0.05339533 0.07305973 -0.07231849 0.05333596 0.07318693 -0.07186067 0.05313229 0.07300269 -0.07191383 0.05323368 0.07306075 -0.07168292 0.05323368 0.07311654 -0.07137638 0.05324274 0.07318544 -0.07106804 0.05317735 0.07306981 -0.07100605 0.05325859 0.07316815 -0.07062923 0.05306887 0.07300525 -0.07051628 0.05321538 0.07306599 -0.07041895 0.05335623 0.0731849 -0.070068 0.05330741 0.07302099 -0.06973683 0.05347883 0.07314306 -0.06965464 0.05366498 0.07300704 -0.0689311 0.05374008 0.07316929 -0.06912374 0.0537765 0.07307803 -0.0689432 0.05411958 0.07318514 -0.06858158 0.05416166 0.07300937 -0.06828105 0.0543366 0.07305711 -0.06823265 0.05465692 0.07317376 -0.06805521 0.05491995 0.07305979 -0.06777441 0.05502128 0.07300776 -0.06759166 0.05511873 0.07316857 -0.06774491 0.05548322 0.07314449 -0.06755238 0.05580163 0.07318508 -0.06743985 0.05595624 0.07300835 -0.06721711 0.05605274 0.07308572 -0.06730753 0.05634623 0.0731886 -0.06729674 0.05662018 0.07309114 -0.06721091 0.05680203 0.07303345 -0.0671252 0.05737704 0.09383022 -0.07474219 0.05811381 0.09379237 -0.07459288 0.05888098 0.09381097 -0.07425618 0.05949008 0.09382754 -0.07382184 0.05991715 0.09383559 -0.07337468 0.06025308 0.0937972 -0.07287722 0.06043767 0.09385293 -0.07253998 0.06064188 0.09380489 -0.07193273 0.06073641 0.09381067 -0.07138049 0.06075614 0.09380793 -0.07090878 0.06068772 0.09382462 -0.07025164 0.06054258 0.09385079 -0.06972593 0.06039226 0.09383326 -0.06937807 0.06021624 0.09385496 -0.06904137 0.05998176 0.09382855 -0.06871026 0.05970603 0.0938152 -0.06839227 0.05940812 0.09382259 -0.06811308 0.0589596 0.09381133 -0.0677936 0.05854493 0.09381538 -0.06757587 0.05804449 0.09383696 -0.06738281 0.0573045 0.09381598 -0.06725156 0.05659013 0.09381592 -0.06726455 0.05600011 0.09380775 -0.06737577 0.05535304 0.09382653 -0.06762009 0.05493587 0.09383046 -0.06785356 0.05448156 0.09384721 -0.0681988 0.05407232 0.09386348 -0.06862562 0.05386078 0.09382742 -0.06893056 0.05364501 0.09383171 -0.06929981 0.05340707 0.09379762 -0.06989508 0.05327123 0.09381163 -0.07053321 0.05324423 0.09381139 -0.07118928 0.05331319 0.09382635 -0.0717315 0.05345797 0.09383547 -0.07227647 0.05374789 0.09380739 -0.07288157 0.05405664 0.09382605 -0.07334035 0.05434739 0.0938279 -0.07366383 0.05469292 0.09382748 -0.07397061 0.05528336 0.09380882 -0.07434552 0.05596405 0.09383028 -0.07461816 0.05677998 0.09382945 -0.07475757 0.05728811 0.09395164 -0.07484352 0.05790442 0.09399563 -0.07486295 0.05784571 0.09392881 -0.07472413 0.05831384 0.09392476 -0.07458156 0.05874007 0.09392905 -0.0743997 0.05901902 0.0939911 -0.07436567 0.0592215 0.09390604 -0.07409399 0.05950605 0.09398633 -0.07399332 0.06010705 0.09399318 -0.07342576 0.06013816 0.09390479 -0.07314777 0.06036072 0.09395438 -0.07289439 0.06060028 0.09399443 -0.0726251 0.06076246 0.09398025 -0.07204967 0.06063646 0.09391242 -0.07212746 0.06075423 0.09389489 -0.0715779 0.06091338 0.09399169 -0.07128715 0.0608071 0.09391075 -0.07090258 0.0608834 0.09398972 -0.07033437 0.06075888 0.09392952 -0.07030272 0.06060934 0.09396016 -0.06962132 0.06038582 0.09398829 -0.06903535 0.05989295 0.09394085 -0.06846839 0.05980038 0.093993 -0.06822496 0.05929499 0.09390336 -0.06796932 0.05893087 0.09399569 -0.06753212 0.05867511 0.09393239 -0.06755483 0.05787092 0.09395343 -0.0672416 0.05745482 0.09399801 -0.06704407 0.05741769 0.09393924 -0.06718868 0.05691307 0.09388089 -0.06721776 0.05647778 0.09392988 -0.06721127 0.0561468 0.09399193 -0.06715989 0.0558685 0.09389919 -0.06736862 0.0552935 0.09395653 -0.06753987 0.0547046 0.09399491 -0.06777274 0.05458676 0.09395992 -0.06797951 0.05390775 0.0939899 -0.06857973 0.0535891 0.09394645 -0.06921392 0.05332732 0.09399616 -0.06953012 0.05334633 0.09388166 -0.06998872 0.05316191 0.09398788 -0.07019942 0.05319672 0.09390568 -0.07081127 0.05305302 0.09399646 -0.0714184 0.05319619 0.09392863 -0.0713455 0.05324941 0.093939 -0.07180333 0.05346465 0.09398901 -0.07269936 0.05365622 0.09393 -0.07285952 0.05410701 0.0939486 -0.07354283 0.0542224 0.09399652 -0.07384318 0.05468726 0.09393912 -0.07406276 0.05518811 0.0939905 -0.07447594 0.0553503 0.09390074 -0.07442432 0.05621486 0.09399604 -0.07489848 0.05603569 0.09393012 -0.07470309 0.05655211 0.09394681 -0.07482129 0.05251485 0.07475 -0.07148271 0.05249822 0.078 -0.07133734 0.05281919 0.078 -0.07272368 0.05284684 0.07475 -0.07278937 0.0536608 0.078 -0.07404965 0.0534963 0.07475 -0.07383477 0.05438923 0.07475 -0.07469242 0.05462282 0.078 -0.07482892 0.05574095 0.078 -0.07534337 0.05580949 0.07475 -0.07536268 0.05730223 0.078 -0.07551205 0.0573734 0.07475 -0.07550674 0.05861657 0.078 -0.07521134 0.05867952 0.07475 -0.07518666 0.05969899 0.078 -0.0746209 0.05975466 0.07475 -0.0745787 0.06071621 0.078 -0.07357674 0.06046795 0.07475 -0.07387322 0.06107246 0.07475 -0.07296121 0.06130051 0.078 -0.07236182 0.06150186 0.07475 -0.07145047 0.06151658 0.078 -0.07111263 0.06137341 0.07475 -0.06984961 0.06139272 0.078 -0.06999737 0.06107878 0.078 -0.06907314 0.06083154 0.07475 -0.06861907 0.06047725 0.078 -0.06812632 0.06022542 0.07475 -0.06785392 0.05945461 0.078 -0.06719934 0.05926209 0.07475 -0.06708174 0.05818909 0.078 -0.06664848 0.05800348 0.07475 -0.06660348 0.05688732 0.078 -0.06648129 0.05669766 0.07475 -0.0664879 0.05580747 0.078 -0.06665718 0.0551725 0.07475 -0.06686347 0.05476987 0.078 -0.06706589 0.05401414 0.07475 -0.06761646 0.05369198 0.078 -0.06793069 0.05327403 0.07475 -0.06845963 0.05291026 0.078 -0.0690701 0.05281639 0.07475 -0.06932395 0.05253779 0.07475 -0.07032746 0.05255621 0.078 -0.07024872 0.06150662 0.08899998 -0.07111239 0.06151449 0.09224998 -0.07077467 0.06139498 0.08899998 -0.06996101 0.0611431 0.09224998 -0.06917017 0.06094545 0.08899998 -0.06881302 0.06040018 0.09224998 -0.06804192 0.06035804 0.08899998 -0.06799417 0.05957275 0.09224998 -0.06728833 0.05951505 0.08899998 -0.067249 0.05857127 0.09224998 -0.06677597 0.05851149 0.08899998 -0.06675416 0.05748438 0.09224998 -0.0665099 0.05730229 0.08899998 -0.0664879 0.05602848 0.09224998 -0.06658339 0.05574095 0.08899998 -0.06665658 0.05457657 0.09224998 -0.06718194 0.05423653 0.08899998 -0.06741154 0.05332052 0.09224998 -0.06835466 0.05325388 0.08899998 -0.0684868 0.05274957 0.08899998 -0.06948894 0.05261963 0.09224998 -0.06988459 0.05252921 0.08899998 -0.07043969 0.05249297 0.09224998 -0.07122486 0.05251699 0.08899998 -0.07156175 0.05275243 0.09224998 -0.07254594 0.05292749 0.08899998 -0.07296115 0.05338382 0.09224998 -0.07369685 0.05361992 0.08899998 -0.07398289 0.0541023 0.09224998 -0.07445335 0.05436754 0.08899998 -0.07466143 0.05504125 0.09224998 -0.07506728 0.05532044 0.08899998 -0.07518666 0.05651307 0.09224998 -0.07550293 0.05666196 0.08899998 -0.07551169 0.05830043 0.09224998 -0.07533842 0.05836945 0.08899998 -0.07531714 0.05972802 0.09224998 -0.07460141 0.05956506 0.08899998 -0.0747056 0.06046253 0.08899998 -0.07390552 0.06075638 0.09224998 -0.07351785 0.06128168 0.08899998 -0.07247668 0.06135666 0.09224998 -0.0721895 0.06449061 0.09358757 -0.07140529 0.06440949 0.09380382 -0.07110428 0.06414401 0.09398782 -0.0713219 0.0643028 0.09384667 -0.0720542 0.06398779 0.09399294 -0.07237464 0.06438332 0.09358435 -0.07230585 0.06419044 0.09375858 -0.07290661 0.06422013 0.09356999 -0.07302725 0.06391888 0.09389722 -0.07338613 0.06392103 0.09358811 -0.07389301 0.06367796 0.09399676 -0.07341778 0.06391745 0.09377652 -0.0736894 0.06355094 0.09379231 -0.07448726 0.06330949 0.09395712 -0.07452291 0.06339156 0.0936535 -0.0749039 0.06297564 0.09364438 -0.07551741 0.0627402 0.09399116 -0.07522827 0.06273049 0.09386098 -0.07562077 0.06258738 0.09363389 -0.0759902 0.06214058 0.09394681 -0.0760985 0.06208401 0.09361737 -0.07650524 0.06203919 0.09381723 -0.07640957 0.06151056 0.09359359 -0.0769881 0.06136286 0.09377235 -0.07701295 0.06116664 0.09399634 -0.07676804 0.06110233 0.09390884 -0.07704347 0.06078636 0.0935865 -0.0774759 0.06042414 0.09375339 -0.07760977 0.05975651 0.09367007 -0.07795977 0.059991 0.09399104 -0.07749414 0.05961269 0.09391564 -0.07780963 0.05903446 0.09359961 -0.07821941 0.05887383 0.09375846 -0.07819777 0.05882227 0.09394437 -0.07801109 0.05793583 0.09360527 -0.07844066 0.05810326 0.09384155 -0.07829362 0.05760782 0.09399098 -0.07812219 0.05734509 0.09381687 -0.07838898 0.05700409 0.09359234 -0.07849705 0.05669707 0.09378629 -0.07841038 0.05624496 0.09362131 -0.07845497 0.05651754 0.09394657 -0.07822698 0.05571687 0.09380978 -0.07829052 0.0555424 0.09364598 -0.07834547 0.05551153 0.09397286 -0.0780403 0.05475556 0.0936017 -0.078152 0.05490314 0.0937826 -0.0781179 0.05414479 0.09389495 -0.07774555 0.05406647 0.09361332 -0.07789623 0.05431354 0.09399515 -0.07758748 0.05399662 0.09378671 -0.0777837 0.05326253 0.0936011 -0.07750225 0.05296891 0.09377801 -0.07723754 0.05309432 0.09393459 -0.07712227 0.05257165 0.09399312 -0.07659363 0.05230975 0.09363371 -0.07684552 0.05205893 0.09384304 -0.07647657 0.0516206 0.0936172 -0.07621711 0.05149656 0.09394192 -0.07572764 0.05136281 0.09399229 -0.07537871 0.05121415 0.09383416 -0.07559603 0.0511499 0.09359258 -0.07568848 0.05077004 0.09363424 -0.07516229 0.05075806 0.09393173 -0.07471024 0.05057919 0.0938065 -0.07468271 0.05031067 0.09364527 -0.0743671 0.05049008 0.09399396 -0.07386219 0.05020475 0.09389269 -0.07373964 0.05002528 0.09360283 -0.07374596 0.04999935 0.09376525 -0.07349979 0.04977655 0.09358143 -0.07301133 0.05011874 0.09399485 -0.07281804 0.04986017 0.0938875 -0.07264417 0.04965001 0.09365445 -0.07243722 0.04963493 0.09379005 -0.07190251 0.04950523 0.09356594 -0.07136493 0.049842 0.0939567 -0.07189774 0.04954349 0.09372305 -0.07104772 0.04970437 0.09391784 -0.07101517 0.04954355 0.09363394 -0.0702461 0.04993093 0.09399616 -0.07018178 0.04975706 0.09389358 -0.06994128 0.04968541 0.09377175 -0.06971621 0.04969143 0.09358739 -0.06932759 0.04986631 0.09380859 -0.06901895 0.04988944 0.09359359 -0.06862372 0.05017018 0.09395843 -0.06864529 0.05009889 0.09376996 -0.06824564 0.05018973 0.09364587 -0.06788313 0.05069017 0.09399586 -0.06774091 0.05060583 0.09387415 -0.06736505 0.05051738 0.09360575 -0.06723749 0.05098515 0.09386914 -0.06676924 0.05091315 0.09361666 -0.06662875 0.0516619 0.09399193 -0.06626707 0.05149918 0.09360808 -0.06590348 0.05153441 0.09387201 -0.06608331 0.0519517 0.09373396 -0.06552475 0.05231279 0.09364217 -0.06515616 0.05245625 0.09388792 -0.06524574 0.05295723 0.0935893 -0.06468069 0.05286461 0.09399402 -0.06522262 0.05302715 0.09373372 -0.06469893 0.05325555 0.09389758 -0.06471562 0.05374294 0.09365266 -0.06425827 0.05400663 0.09382158 -0.06424021 0.05432802 0.09396892 -0.06429165 0.05441093 0.09360086 -0.06396532 0.05463236 0.09399443 -0.06428295 0.05483007 0.09379065 -0.06390917 0.05512791 0.09357935 -0.06373882 0.05565094 0.09373867 -0.06367456 0.05583018 0.09391868 -0.06380027 0.05588692 0.09359902 -0.063587 0.05683356 0.09360289 -0.06350213 0.05683004 0.093997 -0.06389111 0.0564906 0.09381544 -0.06361407 0.05698144 0.09392505 -0.063726 0.05776345 0.09362709 -0.06354659 0.05736857 0.0938102 -0.06361097 0.05802601 0.09396344 -0.06386244 0.05823701 0.09385347 -0.06374061 0.05842572 0.09366911 -0.06365591 0.0590623 0.09363985 -0.06379526 0.0592426 0.09389197 -0.06402862 0.05957788 0.09399437 -0.06436163 0.05991059 0.09362101 -0.06409543 0.06000483 0.09385043 -0.06427162 0.0605601 0.09367114 -0.06441777 0.06089186 0.09360289 -0.06459403 0.06067472 0.09399366 -0.06488949 0.06091225 0.0938242 -0.06472784 0.06169551 0.09357786 -0.06514865 0.06161022 0.09393882 -0.06538671 0.06146317 0.09376776 -0.06505841 0.06201761 0.09379589 -0.06554609 0.06236785 0.0936383 -0.06577605 0.06257492 0.09399783 -0.06661748 0.06254917 0.09384125 -0.06614303 0.06286263 0.09360843 -0.06633013 0.06275641 0.09396022 -0.0666446 0.06301289 0.09382408 -0.06669932 0.06341058 0.09361374 -0.06711125 0.06339287 0.09384006 -0.06732052 0.06383144 0.09362238 -0.06792229 0.06349807 0.09398305 -0.06802058 0.06365031 0.09387779 -0.06787979 0.06398808 0.0938943 -0.06879723 0.06414622 0.09364718 -0.06874847 0.06381857 0.0939967 -0.06901162 0.06425791 0.0937485 -0.06935435 0.06438934 0.09357774 -0.06972366 0.06415665 0.09395879 -0.07007378 0.06435698 0.09382206 -0.07023048 0.06447464 0.09361326 -0.07046037 0.06448698 0.09260922 -0.07079428 0.06446051 0.09257423 -0.07157266 0.06437742 0.0926215 -0.07230472 0.06422257 0.0926156 -0.07298982 0.06396776 0.09264945 -0.07376432 0.06367337 0.09264039 -0.07441151 0.06328439 0.09264951 -0.07508617 0.06288808 0.09262567 -0.07563394 0.06224668 0.09264355 -0.07635813 0.06155383 0.09263873 -0.07695233 0.06090307 0.0926705 -0.07740253 0.06024348 0.09263283 -0.07775539 0.05958318 0.0926454 -0.0780363 0.0588901 0.09264832 -0.07825374 0.05798065 0.09264403 -0.07843464 0.05702096 0.09264534 -0.07849544 0.05629307 0.09264922 -0.07846254 0.05554634 0.09267342 -0.07835644 0.05489766 0.09258037 -0.07818365 0.05410891 0.0926724 -0.07791888 0.05344939 0.0926488 -0.07760167 0.05258667 0.09262079 -0.07705867 0.05190044 0.09260034 -0.0764833 0.05137181 0.09267848 -0.07595598 0.05079275 0.0926584 -0.07521164 0.05032062 0.09267139 -0.07440787 0.05002635 0.09260034 -0.0737276 0.0497809 0.09266853 -0.07302695 0.04958558 0.09266763 -0.07214349 0.04950553 0.09265774 -0.07119917 0.04952597 0.09263908 -0.0704441 0.04964119 0.092646 -0.06955385 0.04989445 0.09264951 -0.06861257 0.05024546 0.09260642 -0.06775707 0.05070912 0.09267228 -0.06691896 0.05175524 0.09267538 -0.06563484 0.05245721 0.09265631 -0.06503623 0.05310213 0.09267079 -0.0645942 0.05363184 0.09260225 -0.06431001 0.05445843 0.09264814 -0.06394815 0.05532604 0.09263044 -0.06369262 0.05627644 0.09264945 -0.06353896 0.05716729 0.09261155 -0.06350803 0.05813574 0.09266078 -0.06358891 0.05898618 0.09266275 -0.06376659 0.06007277 0.09265369 -0.0641582 0.06089639 0.0926696 -0.06459331 0.06151348 0.09265571 -0.06501436 0.06209206 0.09268009 -0.06549423 0.06276416 0.09264689 -0.06620228 0.06329613 0.09260827 -0.06694376 0.06376779 0.09267407 -0.06776118 0.0640456 0.09257805 -0.06847155 0.06431245 0.09263676 -0.06935995 0.06443715 0.0926522 -0.07005959 0.06433057 0.09236794 -0.07072681 0.06433761 0.09245848 -0.06992805 0.06408649 0.09225255 -0.07067865 0.06412237 0.09230077 -0.06971156 0.06413704 0.09244865 -0.0690056 0.06353086 0.0922541 -0.06817758 0.06380254 0.09231573 -0.06843936 0.06360334 0.09248322 -0.06759023 0.06328833 0.09230327 -0.06739836 0.06297814 0.09236282 -0.06674903 0.06264692 0.09248417 -0.06616449 0.06257116 0.09225487 -0.06659501 0.0621019 0.09229743 -0.06587052 0.06206011 0.09249538 -0.06554836 0.06097638 0.09225291 -0.06512147 0.06159549 0.09230917 -0.06539046 0.06136077 0.09249711 -0.06496989 0.06086021 0.09233176 -0.06480818 0.06052768 0.09245073 -0.06448119 0.05973386 0.09241652 -0.06413769 0.05935961 0.09225755 -0.06425935 0.05923175 0.09252041 -0.06389093 0.05845969 0.09236532 -0.06380993 0.05847072 0.09245705 -0.06373518 0.05760633 0.09227579 -0.06383883 0.0577687 0.09246498 -0.06362068 0.05676496 0.09241098 -0.06362468 0.05619364 0.09233981 -0.06373798 0.0558499 0.09250432 -0.0636478 0.05641591 0.09225106 -0.06395101 0.05502521 0.09227252 -0.06410914 0.05499178 0.09240531 -0.06389951 0.05361872 0.09225583 -0.06472396 0.05432611 0.09234285 -0.06420356 0.05413222 0.09248524 -0.06414657 0.05336856 0.09237313 -0.06462121 0.0528512 0.09247958 -0.06483638 0.05235737 0.0923193 -0.06540179 0.05208146 0.09248948 -0.06542158 0.05220937 0.0922535 -0.06577545 0.05146861 0.09243917 -0.06607389 0.0515747 0.09230118 -0.06620478 0.0511285 0.09262192 -0.06634634 0.05091309 0.09234189 -0.06696993 0.05066251 0.09249162 -0.06710696 0.05085217 0.0922538 -0.06744313 0.05046385 0.0923261 -0.0677942 0.05011725 0.09242671 -0.06830585 0.04996675 0.09233093 -0.06908899 0.05029243 0.09225332 -0.06869268 0.04980438 0.09246832 -0.06917339 0.04966723 0.0923894 -0.07031995 0.04992586 0.09225642 -0.07010936 0.04958587 0.092462 -0.0711764 0.04975014 0.0923168 -0.0716207 0.04962635 0.09251832 -0.07207733 0.04989969 0.09227687 -0.07204937 0.0498588 0.09242165 -0.07291966 0.05019205 0.09225559 -0.07310354 0.05017066 0.0923826 -0.07370823 0.05044806 0.09249013 -0.07451862 0.05059427 0.09230363 -0.07439845 0.05130416 0.09225291 -0.07522815 0.0508089 0.0924701 -0.07509928 0.05131775 0.09232503 -0.0755487 0.05132168 0.09247922 -0.07579773 0.05243784 0.09226208 -0.07651156 0.05213379 0.0923745 -0.07649892 0.05296707 0.09242743 -0.07720053 0.05351954 0.09225749 -0.07722967 0.0534892 0.09243124 -0.07751655 0.05411088 0.09249472 -0.0778532 0.05432933 0.09230577 -0.07773333 0.05507475 0.09235578 -0.07806444 0.05539506 0.0922544 -0.07791423 0.05590701 0.09249341 -0.07835465 0.05605643 0.09233105 -0.07822477 0.05664175 0.09246224 -0.07840591 0.05727434 0.09225517 -0.07813012 0.0570814 0.09230637 -0.07824701 0.05744618 0.0924831 -0.07841795 0.05813032 0.09234929 -0.07822746 0.05832654 0.09249693 -0.07832407 0.05905967 0.09229767 -0.07793498 0.05919629 0.09246224 -0.07808184 0.05976158 0.09225594 -0.07757157 0.05985796 0.09240937 -0.07780015 0.06063294 0.09240227 -0.07741636 0.06074255 0.09228396 -0.07715094 0.06104248 0.09249657 -0.07724654 0.06166493 0.09235697 -0.07665067 0.06147903 0.09225398 -0.07650125 0.06237816 0.09251397 -0.07616436 0.06239467 0.09236937 -0.07596695 0.06247347 0.09225958 -0.07557934 0.06299841 0.09238439 -0.07525646 0.06345045 0.09243375 -0.07463121 0.06340742 0.09225881 -0.0741561 0.06371045 0.09233802 -0.07385599 0.06401258 0.09248727 -0.07347923 0.06408536 0.09232854 -0.07272261 0.0642454 0.0924229 -0.07244145 0.06397283 0.09225362 -0.07231599 0.06426095 0.09232234 -0.07145297 0.06449317 0.07341223 -0.07064086 0.06444716 0.07327997 -0.07060921 0.0643422 0.07313096 -0.07084327 0.06419223 0.07303982 -0.07036232 0.06429654 0.0732057 -0.06965166 0.0643531 0.07340377 -0.06952148 0.06391423 0.07300126 -0.06951838 0.06403625 0.0730459 -0.06934082 0.06404983 0.07339394 -0.06844192 0.06398481 0.07318097 -0.06855952 0.06356072 0.07303482 -0.06802886 0.06368905 0.07315653 -0.06788915 0.06357944 0.07333445 -0.06742805 0.06320047 0.07341855 -0.06677669 0.06311178 0.07307803 -0.06703531 0.06304627 0.07326608 -0.06665295 0.06310874 0.07300227 -0.06740862 0.06266546 0.07312315 -0.0663352 0.06261461 0.07343047 -0.06602871 0.06258308 0.07323193 -0.06609469 0.06228023 0.07303369 -0.06609785 0.06148421 0.07300013 -0.06551557 0.06210106 0.07339149 -0.06550848 0.06194818 0.07315146 -0.06553494 0.06139248 0.07341694 -0.06491881 0.06119507 0.07323455 -0.06485772 0.06123161 0.07306534 -0.06510096 0.06042057 0.07338756 -0.06432712 0.0605216 0.07304644 -0.06468105 0.06022232 0.07321023 -0.06432521 0.05959141 0.0730769 -0.06418949 0.05953502 0.07340961 -0.06394433 0.05939936 0.07325226 -0.06395387 0.05903095 0.07301115 -0.06414532 0.05885779 0.07340574 -0.06373715 0.05861234 0.07316166 -0.0637933 0.05792301 0.07339078 -0.06355786 0.0579496 0.07308101 -0.06377655 0.05777132 0.07322251 -0.06361502 0.05756223 0.07300209 -0.06394112 0.05678218 0.07340145 -0.06350302 0.05703783 0.07326859 -0.06355255 0.05698221 0.07310205 -0.06368392 0.05628091 0.07300555 -0.06391668 0.05625784 0.07315289 -0.06366503 0.05585467 0.07337623 -0.06359517 0.05536836 0.07322633 -0.06375032 0.05511987 0.07341843 -0.06374144 0.05514484 0.07303792 -0.06402307 0.05480605 0.07314103 -0.06398153 0.05447059 0.07336258 -0.06394964 0.05410784 0.07314032 -0.06423062 0.05376476 0.07339918 -0.06423789 0.05371469 0.07300496 -0.06469494 0.05339717 0.07309824 -0.06463652 0.05323553 0.07334578 -0.06452482 0.052859 0.07320749 -0.06484389 0.05231243 0.07339453 -0.06514626 0.05229854 0.07306194 -0.06547409 0.05227094 0.07318454 -0.06531286 0.05229634 0.07300323 -0.06568044 0.05164933 0.07336461 -0.06575763 0.05165714 0.07311207 -0.06597775 0.05114805 0.07337033 -0.0663222 0.05121028 0.07316815 -0.06642287 0.05121988 0.07302653 -0.06674134 0.05059838 0.07339578 -0.06709277 0.05072736 0.07324922 -0.06700056 0.0507608 0.07310557 -0.06717735 0.05036979 0.07325387 -0.06762105 0.05007731 0.07340556 -0.06811356 0.05048698 0.07300752 -0.06807345 0.05017656 0.0731607 -0.06818473 0.04978579 0.07334053 -0.0689997 0.04993414 0.07308048 -0.06919199 0.04997682 0.07300239 -0.06989592 0.04961442 0.07338863 -0.06972652 0.04970544 0.07317274 -0.06981641 0.04952925 0.07332694 -0.07055097 0.04968148 0.07310169 -0.07090544 0.04950404 0.07341653 -0.07117891 0.04983103 0.07302927 -0.07151705 0.04959446 0.07322382 -0.07153123 0.04956215 0.07339513 -0.07192802 0.0497294 0.07313877 -0.07215911 0.04972982 0.07338809 -0.07283586 0.05005866 0.07300329 -0.07246685 0.04987812 0.07317376 -0.0729745 0.05024492 0.07302093 -0.07342934 0.05003464 0.07334315 -0.07374477 0.05018937 0.07309746 -0.07365345 0.05039715 0.07333463 -0.07452785 0.05049008 0.07310265 -0.07433938 0.05070734 0.07340216 -0.07507413 0.05105119 0.0730068 -0.07492703 0.05091267 0.07315373 -0.07516258 0.05117034 0.07335448 -0.07570087 0.05162769 0.07340508 -0.07622873 0.05149245 0.07305955 -0.07573187 0.05172169 0.07317984 -0.07618069 0.05219662 0.07338279 -0.07675188 0.0522437 0.07315355 -0.0766319 0.05255722 0.07300448 -0.076563 0.05279517 0.07331937 -0.07718783 0.05304771 0.07305997 -0.07708674 0.05340605 0.07343244 -0.07758229 0.05343604 0.0732308 -0.0775209 0.05413979 0.07309389 -0.07772737 0.05406242 0.07335215 -0.07788813 0.05425798 0.07300412 -0.07754701 0.05469304 0.07319205 -0.07803481 0.05479896 0.07339042 -0.07816433 0.05538743 0.07304233 -0.07804143 0.05554634 0.07342338 -0.07835644 0.05546241 0.07323592 -0.07827436 0.05608218 0.07322978 -0.07837426 0.05629593 0.07339876 -0.07846283 0.05719405 0.07339984 -0.07849752 0.05667126 0.07307738 -0.07827645 0.05654013 0.0730037 -0.07808601 0.05735975 0.07322627 -0.07842409 0.05812549 0.07340222 -0.0784114 0.05789643 0.0730881 -0.07823759 0.05789995 0.07301026 -0.07806861 0.05882185 0.07335394 -0.0782637 0.05862742 0.07319283 -0.07822602 0.05885589 0.07303637 -0.07796049 0.06014686 0.07300144 -0.07736551 0.05955058 0.07340949 -0.07805007 0.05986773 0.07321929 -0.07785272 0.05967718 0.07308161 -0.07777881 0.06025117 0.07337868 -0.07775098 0.06077694 0.07331925 -0.07745438 0.06058061 0.07307749 -0.07733744 0.06124037 0.07341831 -0.07718396 0.06132549 0.07318067 -0.0770002 0.06181985 0.07337737 -0.07673692 0.06150859 0.07303637 -0.07662302 0.06209319 0.07313966 -0.07631164 0.06237125 0.07332605 -0.0762099 0.06211048 0.07300758 -0.07596284 0.06285816 0.07342779 -0.07568174 0.06280875 0.07323634 -0.07563871 0.06287467 0.07309275 -0.07533985 0.06329458 0.07334315 -0.07505315 0.06305766 0.07300347 -0.07471132 0.06342929 0.07310885 -0.07452183 0.06367659 0.07338529 -0.07440358 0.06397265 0.07341033 -0.07375538 0.06386739 0.07322984 -0.07383877 0.06375819 0.07308363 -0.07373046 0.06420886 0.07336002 -0.07303249 0.06381714 0.07301908 -0.07317388 0.06406927 0.07312554 -0.07298332 0.0640105 0.07300049 -0.07195407 0.06438839 0.07340824 -0.07227212 0.06432187 0.07319575 -0.07215577 0.06417602 0.07304728 -0.07189029 0.06447625 0.07342183 -0.07157778 0.06440609 0.07321059 -0.07145369 0.06448483 0.07441443 -0.07088565 0.06447243 0.07435172 -0.07159167 0.06434834 0.07434451 -0.07250422 0.06409841 0.07433849 -0.07341331 0.06382501 0.07435572 -0.07409828 0.06350201 0.07436209 -0.07472693 0.06309145 0.07431912 -0.0753743 0.06263387 0.07432818 -0.07594847 0.06210404 0.07435637 -0.07648885 0.06150311 0.07432907 -0.07699567 0.06089067 0.07435542 -0.07740652 0.06025022 0.07442426 -0.07774007 0.05958616 0.07432729 -0.07803863 0.05880749 0.07437312 -0.07827144 0.05796056 0.07435375 -0.07843834 0.05701315 0.07440215 -0.07848757 0.0562613 0.07432919 -0.078462 0.05509674 0.07441747 -0.07823824 0.05426335 0.07435524 -0.07798212 0.05339771 0.07439076 -0.07756662 0.05282264 0.07442837 -0.0772069 0.05218964 0.074368 -0.0767458 0.05163949 0.07437849 -0.07623398 0.05117708 0.07439392 -0.07570743 0.05079048 0.07433182 -0.07520985 0.05033493 0.07434052 -0.07443308 0.05002528 0.0743528 -0.07374596 0.04978913 0.07437849 -0.07303285 0.04957997 0.07436782 -0.07207447 0.04950076 0.07435429 -0.07102161 0.04956096 0.0743553 -0.07008033 0.04969143 0.07433742 -0.06932759 0.04993957 0.07434034 -0.06846565 0.05032736 0.07430404 -0.06757438 0.05080723 0.07437223 -0.0667755 0.05152636 0.07435429 -0.06587374 0.05218899 0.07431936 -0.06524741 0.05292171 0.07436269 -0.06470775 0.0539121 0.07436132 -0.06416708 0.05564785 0.07434481 -0.06362247 0.05681234 0.07436209 -0.0635038 0.05773091 0.07430773 -0.06353521 0.05862843 0.07436138 -0.06368064 0.05956035 0.07434296 -0.06395375 0.06040149 0.07435113 -0.06431615 0.06137084 0.07438302 -0.06491166 0.06207698 0.0743432 -0.06548398 0.06272459 0.07434946 -0.06615376 0.06329786 0.07438313 -0.06694358 0.0637468 0.07430726 -0.06771564 0.06422197 0.07433289 -0.0689848 0.06441617 0.07438969 -0.06992268 0.06432873 0.07463121 -0.07134312 0.06434518 0.07451295 -0.07215082 0.06375479 0.07474654 -0.07324784 0.06415247 0.07468754 -0.07224029 0.0641095 0.07452446 -0.07315152 0.06397241 0.07464879 -0.0732097 0.06371897 0.07461333 -0.07400673 0.06314462 0.0747469 -0.07456141 0.06341654 0.07453417 -0.07472211 0.06312304 0.07465952 -0.07497972 0.06303733 0.07450366 -0.07534563 0.06237614 0.07470595 -0.07583194 0.06254291 0.07451993 -0.07594841 0.06190389 0.07461017 -0.07649433 0.06130921 0.07474583 -0.07667464 0.06149256 0.0745238 -0.07691532 0.06093412 0.07468026 -0.0771082 0.06088042 0.07454681 -0.07731139 0.06005644 0.07469147 -0.07758146 0.0593726 0.07450574 -0.07805186 0.05920469 0.07465833 -0.07796221 0.05894082 0.07474482 -0.07783973 0.0584492 0.07456547 -0.0782507 0.05751544 0.07474863 -0.07806098 0.0580039 0.07470136 -0.07816004 0.05776298 0.07451808 -0.0783953 0.05704653 0.0746513 -0.07831418 0.05631089 0.0746923 -0.07821965 0.056297 0.07453691 -0.07838308 0.05573779 0.07441878 -0.07837414 0.0559625 0.07473605 -0.07805931 0.05535614 0.07460772 -0.07817155 0.05399966 0.0747475 -0.07744467 0.05480837 0.07469189 -0.07791483 0.05428516 0.0745297 -0.07790881 0.05361223 0.07463538 -0.07750338 0.05295294 0.07470023 -0.07699733 0.05233949 0.07460838 -0.07670193 0.05237203 0.07474374 -0.07640039 0.05167573 0.07463693 -0.07604426 0.05118036 0.07474172 -0.07513993 0.05096393 0.0745483 -0.07531279 0.05076819 0.07464933 -0.0748251 0.05039441 0.07453578 -0.07437771 0.05028921 0.07465863 -0.07386797 0.05026364 0.0747289 -0.07345747 0.04997438 0.07455933 -0.0733506 0.05002921 0.07474988 -0.07215005 0.04992944 0.07470124 -0.07250434 0.04971301 0.0745452 -0.07235121 0.04970651 0.07463198 -0.07177358 0.04982572 0.07472729 -0.07096207 0.04961192 0.07457864 -0.07112312 0.04961842 0.07453817 -0.07024514 0.04970699 0.07464057 -0.07032752 0.04975849 0.07452178 -0.06935328 0.04999643 0.0747438 -0.06979256 0.05000233 0.07467567 -0.06897395 0.049959 0.07448619 -0.06857711 0.05021119 0.07448935 -0.06793725 0.05051618 0.07474547 -0.06806355 0.05040484 0.07464867 -0.06784451 0.05051177 0.07449591 -0.06735235 0.05074673 0.07470327 -0.06737762 0.05093008 0.07460767 -0.06683886 0.0511887 0.07446777 -0.06633019 0.0515263 0.07473766 -0.06640082 0.05164563 0.07463419 -0.06598603 0.052127 0.07450419 -0.06537777 0.05240851 0.07469177 -0.06538736 0.05280774 0.07460725 -0.06494802 0.0531162 0.07474744 -0.06505858 0.05344283 0.07452285 -0.06448251 0.05350542 0.07467395 -0.06461828 0.05412799 0.07463419 -0.06425279 0.05465227 0.07440489 -0.06388872 0.05469954 0.0747469 -0.06427556 0.05484223 0.07464814 -0.06401276 0.05514138 0.07454615 -0.06382358 0.05605608 0.07473164 -0.06390047 0.05590647 0.07448327 -0.06363123 0.05607759 0.07462197 -0.06370532 0.05693584 0.07451921 -0.06357258 0.05727273 0.07468622 -0.06373995 0.05791026 0.0745117 -0.06361687 0.05810385 0.07474929 -0.06401473 0.05831968 0.07470679 -0.06389552 0.05902326 0.07453465 -0.0638585 0.05897164 0.07466411 -0.06398105 0.05968838 0.07473927 -0.0643872 0.05996191 0.07458668 -0.06423521 0.06068021 0.07452923 -0.06455188 0.06102275 0.07468545 -0.06494373 0.06153494 0.07474505 -0.06551533 0.06182634 0.07460737 -0.06543242 0.06245958 0.07447522 -0.06591933 0.06262868 0.07464343 -0.06631982 0.06261456 0.07473754 -0.0665698 0.06313383 0.07450324 -0.06678241 0.06331825 0.07468813 -0.06741416 0.06362926 0.07456088 -0.06769317 0.06374049 0.07474792 -0.0687623 0.06403863 0.07442045 -0.06846213 0.06395488 0.07467061 -0.06880587 0.06424397 0.0745247 -0.06935912 0.0642746 0.07464343 -0.0701434 0.06414133 0.07473975 -0.07086956 0.06299859 0.08860075 -0.07097685 0.06298285 0.08799999 -0.07159864 0.06293451 0.08859086 -0.07188272 0.06257444 0.08799999 -0.07329815 0.06258207 0.08856284 -0.07319849 0.06231969 0.08865022 -0.07374793 0.06194531 0.08856803 -0.07440125 0.06163626 0.08799999 -0.0748316 0.0610544 0.08861327 -0.07541441 0.06031119 0.08799999 -0.07603901 0.06061428 0.08859777 -0.07578414 0.0600028 0.0885933 -0.07619404 0.05924624 0.0886467 -0.07655185 0.05881166 0.08799999 -0.07672947 0.05875056 0.08858156 -0.07673656 0.05804377 0.08862298 -0.07690238 0.05734658 0.08799999 -0.07701152 0.05726081 0.08857375 -0.07700002 0.05629223 0.08867305 -0.07694143 0.0554127 0.08799999 -0.07681691 0.05570679 0.08864951 -0.07684749 0.05509972 0.08856993 -0.07669329 0.05440628 0.08861541 -0.0764032 0.05351889 0.08799999 -0.0759232 0.05364477 0.08860164 -0.07597732 0.05268812 0.08860808 -0.07517439 0.05204504 0.08799999 -0.07443577 0.05205357 0.08858996 -0.07439613 0.05159217 0.08861416 -0.07359141 0.05131745 0.08799999 -0.07295399 0.05122339 0.08859306 -0.07263475 0.05104291 0.08799999 -0.0717892 0.05101084 0.08799999 -0.07044595 0.05103212 0.08858966 -0.07038044 0.05119282 0.08858048 -0.06948679 0.05129039 0.08799999 -0.06912636 0.05148696 0.08858281 -0.06863075 0.05177491 0.08799999 -0.06803214 0.05180805 0.08858746 -0.06799829 0.05212312 0.08864611 -0.06752502 0.05246645 0.08799999 -0.06705582 0.05261236 0.08855962 -0.06690341 0.05333787 0.08799999 -0.06623572 0.05308228 0.08865803 -0.06647294 0.05361688 0.08868318 -0.06606876 0.05461817 0.08799999 -0.06546956 0.05413645 0.0886082 -0.06573355 0.05467444 0.08859914 -0.06547355 0.05551743 0.08857828 -0.06518095 0.05610418 0.08799999 -0.06505638 0.05730676 0.08859384 -0.06500357 0.05779677 0.08799999 -0.06502324 0.05831027 0.08859932 -0.0651462 0.05904906 0.08863097 -0.06537002 0.05947297 0.08799999 -0.06551933 0.05984979 0.08858907 -0.06571531 0.06083476 0.08799999 -0.06635743 0.06083703 0.08859544 -0.06638294 0.06161433 0.08857858 -0.06716322 0.06185406 0.08799999 -0.06745779 0.06212747 0.08858317 -0.06788271 0.06258815 0.08799999 -0.06875687 0.06241583 0.08866703 -0.06845325 0.06268221 0.08863747 -0.06910431 0.06291484 0.0885967 -0.06997138 0.06296408 0.08799999 -0.07025259 0.06300884 0.07899999 -0.07114964 0.06300055 0.07841736 -0.07100683 0.06295228 0.07832342 -0.07161247 0.06278365 0.07899999 -0.07267564 0.06259733 0.07843887 -0.07318025 0.06225544 0.07899999 -0.07390475 0.06186127 0.07840967 -0.07451128 0.06157845 0.07899999 -0.07490056 0.0614162 0.0784102 -0.07506155 0.06088435 0.07839816 -0.07556712 0.06035345 0.07899999 -0.07600128 0.06048125 0.07837426 -0.07587844 0.0597341 0.07840597 -0.07634031 0.05887275 0.07899999 -0.0767157 0.05890649 0.07839572 -0.07668715 0.05818068 0.07840514 -0.0768789 0.05725365 0.07899999 -0.07701617 0.05747944 0.07840818 -0.07698118 0.05659288 0.07837951 -0.0769819 0.05532127 0.07899999 -0.07679116 0.05568718 0.07841086 -0.07685458 0.05469673 0.07839727 -0.07654321 0.0538305 0.07899999 -0.07610523 0.05389219 0.07838362 -0.07612466 0.05337691 0.07839596 -0.07577651 0.052657 0.07899999 -0.07517099 0.05194586 0.07843053 -0.07424485 0.05177491 0.07899999 -0.07396781 0.05154806 0.07837629 -0.07348662 0.05129039 0.07899999 -0.07287359 0.05127191 0.0784071 -0.0727846 0.05098062 0.07899999 -0.07130032 0.05100548 0.07841163 -0.07117384 0.05102068 0.07840192 -0.07055187 0.05113995 0.07899999 -0.06966245 0.05111396 0.07840585 -0.06984072 0.05136156 0.07833981 -0.06898587 0.05154019 0.07899999 -0.06849002 0.05158513 0.07839936 -0.06841856 0.0519526 0.07840704 -0.06776237 0.05232131 0.07899999 -0.06720936 0.05337095 0.07841527 -0.06621581 0.05340552 0.07899999 -0.06618446 0.05401265 0.07835739 -0.0658074 0.05479818 0.07899999 -0.06538975 0.0549044 0.07841682 -0.0653727 0.05592358 0.07842755 -0.06509566 0.05650568 0.07899999 -0.0650056 0.0568366 0.0784313 -0.06499993 0.05819356 0.07899999 -0.06509542 0.05777549 0.07841747 -0.06504935 0.05877363 0.0784229 -0.06526219 0.05960667 0.07899999 -0.06558734 0.05960488 0.07840359 -0.06559926 0.0602681 0.07840812 -0.06596869 0.06071484 0.07899999 -0.06626957 0.06086868 0.0784235 -0.0664159 0.06145334 0.07836705 -0.0669865 0.06157571 0.07899999 -0.06711149 0.06196135 0.0783959 -0.06762963 0.06236058 0.07899999 -0.06825172 0.06234318 0.07834517 -0.06830024 0.06257975 0.07835179 -0.06882727 0.06276434 0.07836681 -0.06936889 0.0628935 0.07899999 -0.06980854 0.06293147 0.07840043 -0.07010251 0.06292194 0.07822525 -0.07074081 0.06274884 0.07806193 -0.07059073 0.06251513 0.07800137 -0.07025265 0.0628243 0.07820898 -0.06998389 0.06264942 0.07811534 -0.06954002 0.062433 0.07803618 -0.06925225 0.06234174 0.07811743 -0.06865036 0.06188958 0.07800471 -0.06823486 0.06193429 0.07815361 -0.06780546 0.06123524 0.07800954 -0.06726688 0.0614311 0.07817596 -0.06712234 0.06086534 0.07822453 -0.06650573 0.06085592 0.07807761 -0.06669753 0.06023597 0.07816272 -0.06608706 0.0599125 0.07800817 -0.06616771 0.05972754 0.07821279 -0.06574565 0.05937778 0.07806605 -0.06575179 0.05900436 0.07821989 -0.06542581 0.05863261 0.07806026 -0.06548005 0.05834209 0.07825976 -0.06520742 0.058142 0.07810699 -0.06529384 0.05771154 0.07800298 -0.06544679 0.05760288 0.07823437 -0.06509441 0.05717366 0.07807934 -0.0652163 0.05701303 0.07826203 -0.06505352 0.05627048 0.07826507 -0.06509476 0.05624115 0.07813203 -0.06520283 0.05636024 0.07800865 -0.06539738 0.05522841 0.07825088 -0.06532227 0.05563211 0.07805514 -0.06541663 0.05478751 0.07806432 -0.0656715 0.0543121 0.07821738 -0.06572479 0.05428344 0.07805335 -0.06594246 0.05373728 0.07811301 -0.06617236 0.05327999 0.07824623 -0.0663706 0.05391806 0.07800269 -0.0663051 0.05325162 0.07809144 -0.06657308 0.052724 0.07837331 -0.06680268 0.05260717 0.07815992 -0.06709212 0.05258721 0.07804006 -0.06737035 0.05230599 0.07835924 -0.06727999 0.05226677 0.07799917 -0.06803905 0.05184453 0.07824552 -0.06804162 0.05195844 0.07811611 -0.06806951 0.05189394 0.0780391 -0.06844335 0.05155706 0.07809996 -0.06896001 0.0512759 0.0782333 -0.06943655 0.05143988 0.07802426 -0.06980234 0.05118858 0.07818901 -0.06998366 0.05144655 0.07800036 -0.07142746 0.0511009 0.07818591 -0.0707665 0.05131202 0.0780369 -0.0705583 0.05114072 0.07818055 -0.07169485 0.05131095 0.07803779 -0.07151037 0.0510773 0.07837516 -0.07192879 0.05146592 0.07805913 -0.0725556 0.05130708 0.078206 -0.07259929 0.05174028 0.0780043 -0.07291382 0.05154627 0.07818329 -0.07324272 0.05185705 0.07804137 -0.07350099 0.05201226 0.07825672 -0.07424825 0.05209088 0.07804602 -0.07397449 0.05249655 0.07810032 -0.07467049 0.05253571 0.07833015 -0.07498383 0.05289006 0.07800269 -0.07479971 0.05311119 0.07809013 -0.07531368 0.05294471 0.07834833 -0.07540476 0.05343741 0.07818043 -0.07569468 0.05396014 0.07800406 -0.07570874 0.05416846 0.07820135 -0.07619386 0.05424588 0.07807517 -0.07607746 0.05520284 0.07824879 -0.07666742 0.0549817 0.07806098 -0.07639199 0.05552524 0.07813155 -0.07665753 0.05606293 0.07800513 -0.07655012 0.05625659 0.07821041 -0.07686948 0.05645811 0.07814013 -0.07684016 0.05731195 0.07828527 -0.07695102 0.05730479 0.07805776 -0.07674896 0.05796635 0.07814383 -0.07678931 0.05858629 0.07821691 -0.07670605 0.05857163 0.07800233 -0.07638406 0.05895835 0.07807374 -0.07643276 0.05929064 0.07818484 -0.07643419 0.05988472 0.07818955 -0.07615488 0.05974578 0.07800775 -0.07591462 0.06031262 0.07812148 -0.07580965 0.06078755 0.0781691 -0.07550311 0.06095707 0.07803869 -0.07512927 0.06116706 0.07819283 -0.07518756 0.06148332 0.07800191 -0.07434982 0.06159704 0.07819479 -0.07470422 0.06181031 0.07811111 -0.07428485 0.06213265 0.07833862 -0.07408154 0.06229168 0.07824414 -0.07369494 0.06214296 0.07806336 -0.07359367 0.06253999 0.07823765 -0.0731309 0.0623697 0.07801061 -0.07273811 0.06256675 0.07811242 -0.07272028 0.0628128 0.07833743 -0.07242983 0.06284141 0.0782026 -0.07192128 0.06257611 0.07800704 -0.07166606 0.06276428 0.07809203 -0.07168483 0.06292694 0.08875846 -0.07139492 0.06276088 0.08890485 -0.07175576 0.06278538 0.08866608 -0.07253324 0.06254935 0.08899575 -0.07181304 0.06260657 0.08889329 -0.07255661 0.06232368 0.08897346 -0.07300722 0.06252664 0.08877062 -0.0731526 0.06221091 0.08887308 -0.07363802 0.06175506 0.08899921 -0.07391959 0.06201243 0.0887348 -0.07420355 0.06172162 0.08896631 -0.0741983 0.06169891 0.08887779 -0.07446932 0.0615831 0.0886532 -0.07485437 0.06103372 0.08884042 -0.07528179 0.06115561 0.08891099 -0.07503616 0.06042075 0.08899253 -0.07548332 0.06048244 0.0888068 -0.07576799 0.06043916 0.08892965 -0.07563024 0.0599364 0.08875823 -0.07615846 0.05944716 0.08892929 -0.0762335 0.05911558 0.08883464 -0.07648563 0.05859369 0.08899587 -0.07637119 0.05841565 0.08873581 -0.0767768 0.05828392 0.08891886 -0.0766434 0.05779266 0.08884263 -0.07681983 0.0570324 0.08876311 -0.07693678 0.0568335 0.08899259 -0.07663267 0.0572592 0.08893275 -0.07675158 0.05640536 0.0888772 -0.07681131 0.05577385 0.0889821 -0.07651978 0.0553357 0.08889544 -0.07658058 0.05497008 0.08875453 -0.07658386 0.05437785 0.08886814 -0.07623392 0.05470168 0.08899599 -0.07611155 0.05376464 0.08878356 -0.07595729 0.05376064 0.08898311 -0.07563495 0.05341529 0.08891737 -0.075549 0.05318015 0.08874243 -0.07555472 0.0527932 0.0888409 -0.07509803 0.0529015 0.08899724 -0.07479757 0.05245608 0.08894997 -0.0745117 0.05229383 0.08879125 -0.07458251 0.05192446 0.08873027 -0.07410818 0.05175936 0.08885371 -0.07364618 0.05174362 0.08895951 -0.07326287 0.05182617 0.08899921 -0.07306742 0.05140334 0.08880531 -0.07288777 0.05128014 0.08884954 -0.0723055 0.05107057 0.08862119 -0.07188034 0.05139982 0.08896994 -0.07199376 0.05116742 0.08885741 -0.07159399 0.05101805 0.08865022 -0.07128763 0.05108582 0.08877187 -0.07054793 0.05138415 0.08899426 -0.0709992 0.05119508 0.08889955 -0.07085567 0.05126363 0.08889412 -0.07002639 0.05147778 0.08899492 -0.06993824 0.05120259 0.08873951 -0.0696699 0.05150771 0.08893853 -0.06930369 0.05146175 0.08878016 -0.0688802 0.05188661 0.08892482 -0.06829172 0.05185091 0.08897435 -0.06860315 0.05194115 0.08880722 -0.06795161 0.05247521 0.08874446 -0.06714099 0.05265569 0.08899301 -0.06742447 0.05261439 0.08889907 -0.06718528 0.05321735 0.0888918 -0.06656712 0.05329203 0.08899468 -0.06678444 0.05390763 0.08892905 -0.06612294 0.0542885 0.08880704 -0.06575721 0.054686 0.08896118 -0.06577301 0.05502587 0.08878421 -0.06541216 0.05559521 0.08899396 -0.06554996 0.05570292 0.0888428 -0.06527018 0.05626004 0.08861953 -0.06505143 0.05642074 0.08892732 -0.0652554 0.05655014 0.08876955 -0.0650866 0.05727422 0.08898919 -0.06537413 0.05713409 0.08876907 -0.06507033 0.05766159 0.08890956 -0.06523197 0.05817937 0.08877432 -0.06518596 0.05852001 0.08899503 -0.06558996 0.05886417 0.08887505 -0.06546443 0.05952125 0.08878082 -0.06564033 0.05964016 0.0889644 -0.0659343 0.06030696 0.08878481 -0.06608307 0.06051188 0.08890914 -0.06638252 0.06059569 0.08899575 -0.06669902 0.06120306 0.0887804 -0.06681948 0.06138396 0.0889433 -0.06728267 0.06181746 0.08877319 -0.06753557 0.06143057 0.08899742 -0.0676009 0.06209725 0.08889812 -0.0681917 0.06206184 0.08899313 -0.06855231 0.06252992 0.08883732 -0.06901389 0.06247305 0.08895897 -0.06934607 0.06277221 0.08880376 -0.06972688 0.06288802 0.08878821 -0.07041293 0.06261539 0.08899223 -0.070611 0.06279724 0.08889919 -0.07054781 0.06399595 0.08758842 -0.07114905 0.06396782 0.08700001 -0.07187312 0.06391924 0.08763062 -0.0720123 0.06381177 0.08760076 -0.07259404 0.06354397 0.08700001 -0.07351499 0.06363421 0.08762425 -0.07320928 0.06336563 0.0875914 -0.07390439 0.06273549 0.08700001 -0.07505661 0.06304377 0.08764076 -0.07451105 0.06268537 0.08759188 -0.07507836 0.06225734 0.08756721 -0.07562083 0.06166815 0.08700001 -0.07622361 0.06090641 0.08756494 -0.07681775 0.06055384 0.08700001 -0.07705062 0.05985856 0.08762162 -0.07738554 0.05911374 0.08700001 -0.07768434 0.05903804 0.0875808 -0.07769477 0.05835705 0.08759039 -0.07786422 0.05740439 0.08700001 -0.07801342 0.05770039 0.0876047 -0.07796019 0.05701375 0.0875678 -0.07799935 0.05628401 0.08758193 -0.07796126 0.05565947 0.08700001 -0.07788127 0.05546247 0.0876587 -0.0778163 0.05473482 0.0875985 -0.077623 0.05384016 0.08700001 -0.07728487 0.05383622 0.08766496 -0.07722872 0.05334073 0.08758062 -0.07696527 0.05262255 0.08764529 -0.07645237 0.05213814 0.08700001 -0.07605993 0.05199098 0.08762258 -0.07587939 0.05139601 0.08762383 -0.0751881 0.05113786 0.08700001 -0.07484501 0.05085396 0.08761143 -0.074346 0.05042415 0.08700001 -0.07344919 0.05055296 0.08765178 -0.07369965 0.05030697 0.08765494 -0.07301169 0.04999876 0.08700001 -0.07157903 0.05002427 0.08762222 -0.07148545 0.05000364 0.08758205 -0.07083708 0.05008745 0.08700001 -0.06983125 0.05006557 0.08761191 -0.0700863 0.05018109 0.08766555 -0.06948781 0.05045598 0.08700001 -0.06848496 0.05037271 0.0876038 -0.06876033 0.05062597 0.08756005 -0.06810653 0.05126446 0.08700001 -0.0669434 0.05093061 0.08764517 -0.0675351 0.05142182 0.08762204 -0.0667774 0.05284869 0.08700001 -0.06532096 0.05228573 0.08767843 -0.06585031 0.05279588 0.08765017 -0.06541824 0.05333369 0.08765757 -0.06505304 0.0539568 0.08759415 -0.06469976 0.05487746 0.08700001 -0.06430315 0.05461871 0.08764499 -0.06442928 0.05530369 0.08760178 -0.06421303 0.05615818 0.08758014 -0.06404894 0.05660128 0.08700001 -0.06400072 0.05698567 0.08760195 -0.0640043 0.05851131 0.08700001 -0.06412976 0.05770522 0.08763313 -0.06404465 0.05854117 0.08760666 -0.06417298 0.05938428 0.08761537 -0.06442493 0.06030929 0.08700001 -0.06481957 0.06020665 0.08761543 -0.06478071 0.06109797 0.0875945 -0.06532484 0.06146836 0.08700001 -0.06559789 0.06174486 0.08760082 -0.06585896 0.06236767 0.08700001 -0.06649607 0.06227028 0.08762311 -0.06640428 0.06264948 0.08766013 -0.06689137 0.06327599 0.08700001 -0.06784343 0.06302326 0.08766597 -0.06746405 0.06345391 0.08759731 -0.0682891 0.06373077 0.08762031 -0.06910181 0.06392759 0.08700001 -0.06983357 0.06389462 0.0875793 -0.06980007 0.06397265 0.08762854 -0.07048618 0.06400483 0.07999998 -0.07035481 0.06399697 0.07942783 -0.07083314 0.06386739 0.07999998 -0.07244193 0.06388688 0.07939797 -0.0722289 0.06368345 0.07940036 -0.07307994 0.06322646 0.07999998 -0.0742532 0.06324845 0.07943958 -0.07417374 0.06236565 0.07932627 -0.07547342 0.06199091 0.07999998 -0.07594394 0.06200492 0.07939523 -0.0758872 0.0615015 0.07942378 -0.07635879 0.06015974 0.07999998 -0.07728493 0.06024098 0.07936 -0.07719689 0.0593701 0.07943093 -0.07758575 0.05870312 0.07939946 -0.07778537 0.05834043 0.07999998 -0.07788127 0.057693 0.07942533 -0.07797324 0.05641901 0.07999998 -0.07801049 0.05665129 0.0793904 -0.077986 0.05577421 0.07941251 -0.07789272 0.05475169 0.07938706 -0.07762664 0.05455571 0.07999998 -0.07757073 0.05399054 0.07940858 -0.0773167 0.05284875 0.07999998 -0.07667905 0.05358058 0.07932859 -0.07708597 0.05289924 0.07940953 -0.07667392 0.05225229 0.07940888 -0.0761398 0.05187094 0.07934737 -0.07574778 0.05126446 0.07999998 -0.07505661 0.05134177 0.07940113 -0.0751146 0.05095475 0.07940024 -0.07452118 0.05046862 0.07942163 -0.07353794 0.05052763 0.07999998 -0.07368081 0.05011177 0.07999998 -0.07233899 0.05018264 0.07937151 -0.07255202 0.05003565 0.07940834 -0.07171177 0.04999381 0.07999998 -0.07065045 0.05000406 0.07941913 -0.07082158 0.05005973 0.07939147 -0.07012611 0.05033791 0.07999998 -0.0687617 0.05020248 0.07931858 -0.06941145 0.05111229 0.07999998 -0.06719738 0.05119621 0.07942044 -0.06708294 0.05197995 0.07999998 -0.06610351 0.05164182 0.07936918 -0.06650596 0.05237054 0.07940733 -0.06574875 0.05338335 0.07999998 -0.06497734 0.05381286 0.07938653 -0.06477063 0.0547806 0.07941997 -0.06435889 0.05498093 0.07999998 -0.06428635 0.05652821 0.07999998 -0.06399869 0.0564261 0.07937037 -0.06402838 0.0575639 0.07941198 -0.06402128 0.05861937 0.07999998 -0.06415438 0.05841267 0.07943409 -0.06414455 0.05894178 0.07934933 -0.06428623 0.05974417 0.07941001 -0.06456363 0.06023484 0.07999998 -0.06478601 0.0604971 0.07936805 -0.06494235 0.06137377 0.07999998 -0.06551557 0.06176698 0.07939523 -0.06588035 0.06245011 0.07999998 -0.06659036 0.06234598 0.07939845 -0.066482 0.06297117 0.0794152 -0.06734383 0.06340605 0.07999998 -0.06810939 0.06366711 0.07932925 -0.06891852 0.06382614 0.07939881 -0.06946825 0.06393897 0.07940953 -0.07010018 0.0639171 0.07921868 -0.07062828 0.06376165 0.0790643 -0.07083815 0.06358134 0.07900577 -0.07174247 0.06378829 0.07917284 -0.06982922 0.06360125 0.07903069 -0.06993502 0.06356751 0.07911145 -0.06915575 0.06332504 0.07900547 -0.06904917 0.0633338 0.07912802 -0.06839245 0.06336587 0.07936012 -0.06811332 0.06284976 0.07926237 -0.06723928 0.06277084 0.079032 -0.06760621 0.06283622 0.07914233 -0.06739628 0.06228411 0.07917755 -0.06656813 0.06229674 0.07900488 -0.06701141 0.06160318 0.07906889 -0.06603777 0.06158226 0.07917946 -0.06584852 0.06069952 0.07900041 -0.06553179 0.06125986 0.07936465 -0.06545698 0.06089824 0.07922488 -0.06527489 0.06057846 0.07905435 -0.06528306 0.06009304 0.07918423 -0.0648328 0.05938947 0.07924509 -0.06448721 0.05936932 0.07904869 -0.06468886 0.05849248 0.07914894 -0.0642966 0.05841934 0.07904821 -0.06442803 0.05752313 0.07900506 -0.06440353 0.05783712 0.07929575 -0.06408357 0.0576685 0.07910209 -0.06422001 0.05703896 0.07928651 -0.06404089 0.05660247 0.07910925 -0.06418007 0.05612134 0.07900416 -0.06445598 0.05555695 0.07932335 -0.06416827 0.0553323 0.07909828 -0.06439125 0.05462116 0.07923948 -0.06448525 0.05503576 0.0790106 -0.06465816 0.05420094 0.07915079 -0.06472402 0.05377227 0.07903891 -0.06510192 0.05352383 0.07900363 -0.06538438 0.05309933 0.07921874 -0.06527191 0.05308955 0.07937735 -0.06520241 0.05268287 0.07908076 -0.06575763 0.05225491 0.079171 -0.0660004 0.05226999 0.07900458 -0.0664016 0.05180472 0.07925486 -0.06639283 0.05163532 0.07906198 -0.06688547 0.05123776 0.07917714 -0.06721323 0.05140596 0.07900202 -0.0675348 0.05071419 0.07938271 -0.06792616 0.05079257 0.07916438 -0.06803059 0.05085933 0.0790559 -0.06820344 0.0504136 0.07935059 -0.06866139 0.05063974 0.07901108 -0.06907945 0.05045807 0.07913339 -0.06896442 0.05019974 0.0791459 -0.07003277 0.0504176 0.07900726 -0.0702784 0.05016106 0.07912701 -0.07072257 0.050062 0.07924228 -0.07101142 0.05020916 0.07909405 -0.07140582 0.0504266 0.07900327 -0.07170784 0.05012655 0.07923519 -0.07187294 0.05032896 0.07907706 -0.07221639 0.05030697 0.07920867 -0.07274448 0.05075305 0.07900661 -0.07316559 0.05056381 0.07908928 -0.07316666 0.05054193 0.07925456 -0.07355213 0.05091911 0.07911616 -0.07412433 0.05080837 0.07925218 -0.07414144 0.05101972 0.07903504 -0.07402205 0.05138635 0.07922196 -0.07506489 0.05192756 0.07900291 -0.07522284 0.05163204 0.07906877 -0.07511883 0.05206185 0.07909506 -0.07568842 0.05263048 0.07916492 -0.07632094 0.05307072 0.07900738 -0.07635152 0.05311417 0.0792464 -0.0767461 0.05352705 0.07907611 -0.07682216 0.05434471 0.07914912 -0.07734078 0.0544725 0.07902532 -0.07717788 0.05585539 0.07900142 -0.07748597 0.05540966 0.07922726 -0.07774573 0.05523395 0.0791139 -0.07759189 0.05576545 0.07904428 -0.07761114 0.05641669 0.07919478 -0.07788676 0.05680984 0.07900971 -0.07763957 0.05747836 0.07925134 -0.07792812 0.05747199 0.07908087 -0.077766 0.05814963 0.07916373 -0.07778191 0.05853587 0.07927161 -0.07778382 0.05829679 0.07900488 -0.0774756 0.05878871 0.07907265 -0.07754266 0.05927163 0.07901418 -0.07725989 0.05951952 0.07926237 -0.07747709 0.06003099 0.07911223 -0.07712286 0.06094574 0.07936686 -0.07677102 0.06070327 0.07900416 -0.07647222 0.06092941 0.0791139 -0.07659071 0.06143981 0.07921838 -0.07631158 0.06184339 0.07902234 -0.07558441 0.06169748 0.07913476 -0.07599401 0.06230437 0.07909429 -0.07526797 0.06276726 0.07934749 -0.07494217 0.06270396 0.07916289 -0.07484626 0.06266093 0.07900875 -0.07446336 0.06327104 0.07924211 -0.07397305 0.06310105 0.07909208 -0.0740047 0.0633676 0.07900226 -0.07272261 0.06339746 0.07903307 -0.07299959 0.06355142 0.0791943 -0.07318013 0.06375688 0.07918024 -0.07240104 0.06382769 0.07914257 -0.07166868 0.06397294 0.07936477 -0.07149606 0.06392443 0.08776998 -0.07133287 0.06378185 0.08791995 -0.07124996 0.06359618 0.08799648 -0.07101923 0.0637747 0.08783268 -0.07224667 0.06350737 0.0879901 -0.07229608 0.0635057 0.087893 -0.07305932 0.06337213 0.08776825 -0.07372403 0.06314754 0.08786052 -0.07403713 0.06305164 0.08797186 -0.07383781 0.0623123 0.08799827 -0.07492977 0.06260263 0.08789747 -0.07489001 0.06247252 0.08777952 -0.07524484 0.06185764 0.0876373 -0.07602906 0.06193667 0.08784657 -0.07577478 0.06157439 0.08795875 -0.07591474 0.06122094 0.08775216 -0.07651901 0.06124657 0.0878672 -0.07637459 0.06050956 0.08799844 -0.0765661 0.06057482 0.08794373 -0.07672375 0.0602647 0.08776533 -0.0771178 0.05951368 0.08795005 -0.07725477 0.05946666 0.08779352 -0.07746338 0.05846887 0.08799928 -0.07741868 0.05857592 0.0878207 -0.07771772 0.05817133 0.08794736 -0.07763546 0.05758601 0.08783406 -0.07785934 0.05709761 0.08796405 -0.07771307 0.05696606 0.08775061 -0.07794159 0.05618512 0.08777195 -0.07788175 0.05592352 0.08799141 -0.07753485 0.05612975 0.08788907 -0.07776874 0.05531513 0.08790367 -0.077596 0.05439543 0.08799427 -0.07709646 0.05449336 0.08777558 -0.07745724 0.05469912 0.08794307 -0.07734239 0.05382531 0.08788752 -0.07704311 0.05312311 0.08782392 -0.07670164 0.05330872 0.08799189 -0.07650452 0.05255782 0.08789098 -0.07618111 0.05226647 0.08799642 -0.07561898 0.05189734 0.0877729 -0.07568907 0.05178737 0.08789896 -0.07539945 0.05120098 0.08782178 -0.074723 0.05111551 0.08795976 -0.07425087 0.05126482 0.08799535 -0.07427722 0.05081284 0.08785521 -0.0739718 0.05042165 0.08787792 -0.07289004 0.05058878 0.08799183 -0.07269692 0.05014181 0.08765304 -0.07234448 0.05013799 0.08779406 -0.07183247 0.05030405 0.08795928 -0.07157039 0.05012112 0.08784282 -0.07087045 0.0504139 0.08799314 -0.07021784 0.05009597 0.08776164 -0.07034176 0.05028522 0.08788853 -0.06980925 0.05039823 0.08780485 -0.06897324 0.05061197 0.08795267 -0.06886047 0.0506646 0.08775061 -0.06816202 0.05086672 0.08791679 -0.06809908 0.05104702 0.08799642 -0.06815189 0.0511673 0.08783119 -0.06733822 0.05165195 0.08795869 -0.06692284 0.05253082 0.08799958 -0.0661329 0.05163693 0.08784854 -0.06671196 0.05184626 0.0876587 -0.06628674 0.052199 0.08788347 -0.06614142 0.0527125 0.0879718 -0.06587529 0.052863 0.08787387 -0.06555265 0.05372583 0.08787781 -0.06499087 0.05362421 0.0879653 -0.06521844 0.05399286 0.08778226 -0.06476825 0.05457621 0.08799409 -0.06484216 0.05498367 0.08783572 -0.06441235 0.05525761 0.08794724 -0.06448715 0.05609792 0.08772861 -0.06410557 0.05623573 0.08789545 -0.06421995 0.056683 0.08799082 -0.06436568 0.05727314 0.08781641 -0.06410378 0.05778336 0.08799129 -0.0644086 0.05817937 0.08784556 -0.06423026 0.05870395 0.08775365 -0.06427425 0.05891567 0.08795857 -0.06455123 0.05965441 0.08782535 -0.0646367 0.06032717 0.08799809 -0.06529301 0.06013315 0.08795875 -0.06505978 0.06061178 0.08780384 -0.06511396 0.06118148 0.08792209 -0.06565022 0.06124061 0.08781099 -0.06555151 0.06200808 0.08780789 -0.06624543 0.0618264 0.0879929 -0.06646752 0.06224554 0.08793735 -0.06674087 0.062738 0.08787816 -0.0672757 0.06277549 0.08799487 -0.0677703 0.06327223 0.08779704 -0.06808578 0.06314265 0.08795511 -0.06828004 0.0635131 0.08782678 -0.06875967 0.06347429 0.08795469 -0.06917774 0.06378275 0.08779531 -0.06964969 0.06348454 0.08799642 -0.0697304 0.06385183 0.08783352 -0.07036948 0.06365644 0.08795857 -0.0700832 0.06498819 0.08663886 -0.07118999 0.06500309 0.08599996 -0.07159966 0.06492859 0.0866481 -0.07197654 0.06478273 0.08665353 -0.07279682 0.06466519 0.08599996 -0.07331222 0.06457471 0.08665072 -0.07353609 0.06415539 0.08599996 -0.07460474 0.06427562 0.08665686 -0.0742945 0.06389963 0.08664768 -0.07502651 0.06329929 0.08599996 -0.07595103 0.0634889 0.08658605 -0.07567548 0.06288009 0.08661079 -0.07642287 0.06233519 0.08599996 -0.07696968 0.06225895 0.08665519 -0.07701402 0.06122606 0.08599996 -0.07780694 0.06152361 0.08660084 -0.07759356 0.06079107 0.0866487 -0.07803148 0.05997163 0.08599996 -0.07843446 0.0599358 0.08661139 -0.07844054 0.05864298 0.08599996 -0.07884186 0.05899113 0.08660084 -0.07874423 0.05819118 0.08662134 -0.07890397 0.05686002 0.08599996 -0.07901835 0.05738967 0.08660948 -0.07898551 0.0566014 0.08657443 -0.07898914 0.0557726 0.08664792 -0.07889372 0.05507785 0.08599996 -0.07877814 0.0548405 0.08660393 -0.07870292 0.0535748 0.08599996 -0.07824307 0.05386418 0.08660179 -0.07835543 0.05313789 0.08664578 -0.07799339 0.05204695 0.08599996 -0.07730722 0.05247539 0.08661204 -0.07759106 0.05171132 0.08659124 -0.07700449 0.05064368 0.08599996 -0.07588994 0.05087763 0.08658593 -0.07615232 0.05028527 0.0865792 -0.0753467 0.04972028 0.08599996 -0.07434672 0.0498901 0.08659046 -0.07466173 0.04961878 0.08666163 -0.07405215 0.04908996 0.08599996 -0.07239466 0.04930001 0.0865978 -0.07315754 0.04909092 0.08660799 -0.07220321 0.04900681 0.08660191 -0.07121443 0.04903668 0.08599996 -0.07000201 0.04902482 0.08660316 -0.07042479 0.04912579 0.0865792 -0.06959462 0.04935806 0.08658432 -0.0686258 0.04965645 0.08599996 -0.06775456 0.04971331 0.08658605 -0.06770288 0.05006539 0.08665651 -0.06703758 0.05070066 0.08599996 -0.06604886 0.05050987 0.08659929 -0.0663287 0.05103486 0.08664792 -0.06568634 0.05210286 0.08599996 -0.06463772 0.0516662 0.08662497 -0.06504517 0.05235159 0.08663058 -0.06449449 0.05318647 0.08663308 -0.0639773 0.05406904 0.08599996 -0.06353217 0.05391395 0.08660459 -0.06362384 0.05466264 0.08664083 -0.06335979 0.05559235 0.08659714 -0.063124 0.05580615 0.08599996 -0.06307929 0.05657327 0.08660095 -0.06301516 0.05734294 0.08599996 -0.06299519 0.05740725 0.0866096 -0.06301534 0.05819624 0.08657598 -0.06309115 0.05911415 0.08599996 -0.06326407 0.05900621 0.08661347 -0.06326138 0.05986213 0.08665865 -0.06354212 0.06101119 0.08599996 -0.06405246 0.06070351 0.08661824 -0.06391155 0.06147921 0.08661323 -0.06437849 0.06213569 0.08656764 -0.0648663 0.06244826 0.08599996 -0.06512814 0.06273204 0.08657443 -0.06542062 0.06371039 0.08599996 -0.06659191 0.06326156 0.08660578 -0.06602829 0.06371945 0.08657443 -0.06666016 0.06412005 0.08667039 -0.06738746 0.06457668 0.08599996 -0.0683946 0.06451493 0.08659684 -0.06825298 0.06480234 0.08658182 -0.06924027 0.06491845 0.08599996 -0.06980627 0.0649625 0.08659249 -0.07021516 0.06501084 0.08099997 -0.07085692 0.06499701 0.08037716 -0.07096946 0.06491738 0.08039289 -0.07214206 0.06490927 0.08099997 -0.07224279 0.0646978 0.08044165 -0.07317936 0.06457668 0.08099997 -0.07360541 0.06443488 0.08038866 -0.07393902 0.06412482 0.08039534 -0.07462859 0.06391018 0.08099997 -0.07505506 0.06371665 0.080419 -0.07534301 0.06322699 0.08032822 -0.0759961 0.06296974 0.08099997 -0.07634383 0.06200259 0.08042097 -0.07724642 0.06195265 0.08099997 -0.07729071 0.06130003 0.08035004 -0.0777347 0.06078201 0.08099997 -0.0780633 0.05972135 0.08040952 -0.07852017 0.05892091 0.08099997 -0.07879549 0.05880659 0.08041822 -0.07879579 0.05756622 0.08036816 -0.07897549 0.05694335 0.08099997 -0.07901191 0.05641764 0.08038222 -0.07897692 0.055157 0.08099997 -0.07880491 0.0554558 0.08039927 -0.07884562 0.05463755 0.08044272 -0.07864373 0.05310583 0.08099997 -0.07802104 0.05373382 0.08038663 -0.07830107 0.0526399 0.08039003 -0.07770627 0.05184775 0.08040994 -0.07711666 0.05166476 0.08099997 -0.07696974 0.05138486 0.08032757 -0.07667666 0.0505712 0.08099997 -0.07579427 0.0507583 0.08040577 -0.07599931 0.05020177 0.08035808 -0.0752052 0.04976493 0.08099997 -0.07442867 0.04970419 0.08040952 -0.07427567 0.04942601 0.08040696 -0.07356685 0.04927211 0.08099997 -0.0731154 0.04920417 0.08037507 -0.07276302 0.04908186 0.0803194 -0.0720039 0.04900622 0.08099997 -0.07154238 0.04900091 0.08039069 -0.07097536 0.04907912 0.08099997 -0.06974536 0.0490663 0.0804069 -0.06999301 0.04941517 0.08040767 -0.06846499 0.04949373 0.08099997 -0.06821471 0.04978364 0.08040267 -0.06754517 0.05015915 0.08099997 -0.0668196 0.05088782 0.08039051 -0.06583976 0.05139845 0.08099997 -0.06525701 0.05155467 0.08040219 -0.06514388 0.05316174 0.08099997 -0.06395179 0.05303937 0.08040481 -0.06404781 0.05390828 0.08037179 -0.06363004 0.05502235 0.08099997 -0.06323349 0.05504131 0.08043324 -0.06324368 0.05582463 0.08037501 -0.06309419 0.05645143 0.08099997 -0.06301242 0.0565927 0.08039039 -0.06301534 0.0573616 0.08041286 -0.06301045 0.05819606 0.08099997 -0.06306403 0.05818694 0.08037972 -0.06309497 0.05898958 0.08041685 -0.06325316 0.06005996 0.08099997 -0.06359517 0.06049013 0.0804001 -0.0638054 0.06168293 0.08099997 -0.06448626 0.06119751 0.08039921 -0.06419414 0.06184649 0.08037507 -0.06464439 0.06242001 0.08038669 -0.06512337 0.06300586 0.08099997 -0.06569981 0.0631448 0.08041107 -0.06587469 0.06394052 0.08099997 -0.0669927 0.06372201 0.08040565 -0.06666839 0.06438356 0.08035975 -0.06793594 0.06474518 0.08099997 -0.06888526 0.06469732 0.08037281 -0.06884878 0.06490772 0.08039325 -0.0697931 0.06489264 0.08017671 -0.0710262 0.06478148 0.08007782 -0.0712682 0.06483846 0.08020973 -0.0698738 0.06454831 0.08000326 -0.07005602 0.06473737 0.08010876 -0.0698235 0.064493 0.08005964 -0.06903272 0.06453365 0.0801571 -0.06870728 0.06394279 0.08000952 -0.06780272 0.06418049 0.08010202 -0.06791299 0.06409537 0.08034449 -0.06733685 0.06373816 0.08014082 -0.06694096 0.06329995 0.08000582 -0.06672292 0.06345325 0.08020889 -0.06641781 0.06299573 0.08008068 -0.06603682 0.06293058 0.0802055 -0.06575816 0.06237506 0.08000606 -0.06560415 0.06241166 0.08021277 -0.06522458 0.06218302 0.08008038 -0.06519478 0.06159025 0.08017581 -0.06458014 0.06126946 0.08001393 -0.06464278 0.06082499 0.08023232 -0.06405442 0.06071597 0.08004206 -0.06422185 0.05990058 0.08034473 -0.06355607 0.0598995 0.0801028 -0.06373965 0.05912929 0.08021301 -0.06336832 0.05942171 0.0800029 -0.06379914 0.05876016 0.08006018 -0.06345474 0.05764716 0.08000046 -0.06343656 0.05816429 0.08014404 -0.06322407 0.05748665 0.08022564 -0.0630874 0.05724543 0.08006912 -0.06323224 0.05647444 0.08014923 -0.06314593 0.05595296 0.08002603 -0.06338787 0.05554878 0.08023202 -0.06320178 0.05527174 0.0800724 -0.06342071 0.05455094 0.08032703 -0.06340509 0.05471414 0.08007657 -0.0635522 0.05432397 0.08000242 -0.06388866 0.0539146 0.08017122 -0.06374573 0.05338686 0.08007693 -0.06411004 0.05316781 0.08023989 -0.06405371 0.0523107 0.0803647 -0.06452691 0.05265933 0.08000987 -0.0647068 0.05259191 0.08014929 -0.06448709 0.05193728 0.08016759 -0.06495308 0.05172234 0.08002287 -0.06541639 0.05137109 0.08016926 -0.06547743 0.05124288 0.08000153 -0.06605875 0.0507223 0.08019739 -0.06618744 0.05081403 0.08008325 -0.06626695 0.05030739 0.08036756 -0.0666328 0.0501554 0.0801897 -0.06704729 0.0502395 0.08001136 -0.06741619 0.04982787 0.08013802 -0.06777834 0.04950553 0.08020269 -0.06846737 0.0496416 0.0800476 -0.06864267 0.04921048 0.08035397 -0.06922686 0.04947644 0.08000242 -0.06993889 0.04935634 0.0801258 -0.06925112 0.04929184 0.08004778 -0.07033944 0.04914587 0.08018189 -0.07015633 0.04909032 0.08020538 -0.07120829 0.04942643 0.08000373 -0.07163429 0.04926019 0.08008062 -0.07184004 0.04934453 0.08020055 -0.07299774 0.04951441 0.08004778 -0.0729441 0.04964345 0.08017969 -0.07386493 0.04986977 0.08007031 -0.07408171 0.0499258 0.08025085 -0.07460796 0.05018538 0.0800057 -0.07441645 0.0503931 0.08008533 -0.07514941 0.05073165 0.08017617 -0.07579952 0.05165565 0.08000528 -0.07644641 0.05125182 0.08009868 -0.07629436 0.05224066 0.08009481 -0.07719546 0.05234825 0.08023428 -0.07742828 0.05294406 0.08000242 -0.07741487 0.05321943 0.08024591 -0.07797747 0.0533691 0.08009773 -0.07791477 0.05389642 0.08003371 -0.07805609 0.05410748 0.0801596 -0.078327 0.054838 0.08024895 -0.07864493 0.05591881 0.0800032 -0.07855093 0.05530244 0.08004474 -0.07854235 0.05580496 0.08018255 -0.07880324 0.05659431 0.08008223 -0.07878035 0.05658513 0.08022278 -0.07891303 0.05738174 0.08015418 -0.07885831 0.05807137 0.08000332 -0.07853168 0.05811619 0.08006441 -0.07868194 0.05836594 0.08020669 -0.07879978 0.05938392 0.08009195 -0.07843583 0.05931627 0.08023178 -0.07858151 0.06031554 0.08034068 -0.07826805 0.05993419 0.08000349 -0.07800567 0.06059855 0.08009666 -0.07793641 0.06081169 0.08026731 -0.07797819 0.06131505 0.08000761 -0.07727777 0.06147706 0.08011066 -0.07742029 0.06211394 0.08024358 -0.07706683 0.06218171 0.08009093 -0.07683551 0.06271743 0.08000952 -0.07607567 0.06273955 0.08033019 -0.07654988 0.06303673 0.08012402 -0.07600164 0.06366813 0.08021521 -0.07527458 0.06343555 0.08002775 -0.07521367 0.06398576 0.0801385 -0.07460939 0.06420445 0.08000594 -0.07352232 0.06435441 0.08013546 -0.07377302 0.06470406 0.08026319 -0.07296949 0.06461197 0.08008521 -0.07267951 0.06482607 0.08018946 -0.07209175 0.06455826 0.08000475 -0.07185322 0.06486481 0.08684635 -0.0711919 0.06453394 0.08699572 -0.07200974 0.064767 0.08689963 -0.07189041 0.06459915 0.08689016 -0.07287687 0.06414222 0.08699035 -0.07370859 0.06433963 0.08688491 -0.07372975 0.06397742 0.08686447 -0.07459944 0.06361776 0.08690297 -0.07514727 0.06349527 0.0869944 -0.07495659 0.06320422 0.08675992 -0.07596021 0.06304657 0.08695632 -0.07580673 0.06242859 0.08690142 -0.07662296 0.06223934 0.0869978 -0.07647728 0.06158804 0.08678019 -0.07746261 0.0616514 0.08693951 -0.077201 0.06085616 0.08699697 -0.07755494 0.06077641 0.0869013 -0.0778439 0.05971658 0.08679765 -0.0784353 0.05947685 0.08693361 -0.07836556 0.05868208 0.08699643 -0.07841223 0.0584172 0.08677732 -0.07879847 0.05824905 0.08692306 -0.07868319 0.05738824 0.08682644 -0.07887828 0.05601507 0.08699601 -0.0785728 0.05665093 0.08696287 -0.07870572 0.056611 0.08679199 -0.07890802 0.05573594 0.0868712 -0.07874399 0.05490553 0.0868417 -0.0785982 0.05433464 0.08696603 -0.07822132 0.05411368 0.08680248 -0.07836472 0.05283993 0.08699625 -0.07739454 0.05345594 0.08694905 -0.07787537 0.05327743 0.08682841 -0.07794845 0.05259954 0.08683514 -0.07753932 0.05188852 0.0869984 -0.07660931 0.05173796 0.0867933 -0.07691621 0.05187308 0.08692646 -0.07684028 0.05107772 0.08681052 -0.07623589 0.05097132 0.0869807 -0.07573676 0.05067217 0.08683162 -0.07571858 0.05008345 0.08679717 -0.07484692 0.04996591 0.08699536 -0.07390379 0.05022209 0.0869444 -0.07474541 0.04961967 0.08690756 -0.0735467 0.04942268 0.08680146 -0.07326704 0.04960209 0.08699494 -0.07276344 0.04915529 0.08677047 -0.0721786 0.04930526 0.08692574 -0.07211631 0.04939556 0.08699464 -0.07111513 0.04909402 0.08680832 -0.07100319 0.04922133 0.08692234 -0.0710029 0.04913926 0.08677792 -0.06999742 0.04933243 0.08692413 -0.06967383 0.04955381 0.08699709 -0.06946909 0.04927873 0.08678382 -0.0692324 0.04950261 0.08681559 -0.06850266 0.04978412 0.08696156 -0.06828558 0.04976809 0.08678585 -0.06777459 0.05006951 0.08690732 -0.06742173 0.05059409 0.08699274 -0.06684827 0.05047005 0.08680355 -0.06653898 0.05060279 0.08692371 -0.06657838 0.05122959 0.08681505 -0.06560456 0.05131864 0.08693307 -0.06571382 0.05200427 0.08699506 -0.06524443 0.05195587 0.08684569 -0.06495606 0.05259704 0.08682662 -0.06445795 0.05277371 0.08695501 -0.06453877 0.05325788 0.08686923 -0.06410127 0.05425363 0.08699083 -0.06386595 0.05390727 0.08683794 -0.06375104 0.05467027 0.08685803 -0.06349617 0.05555254 0.08684009 -0.0632534 0.05584955 0.08696496 -0.06338167 0.05638736 0.08699887 -0.06343996 0.05642563 0.08673638 -0.06306886 0.05680811 0.08692657 -0.06322389 0.05736893 0.08680599 -0.06310665 0.057738 0.08695727 -0.06331312 0.05836945 0.08675765 -0.06317836 0.05851447 0.0868873 -0.06331646 0.05895805 0.08699434 -0.06364613 0.05935627 0.08678698 -0.06344044 0.05992883 0.08686751 -0.06371599 0.06028908 0.08695644 -0.06400376 0.06096231 0.08683192 -0.06418216 0.0609737 0.08699744 -0.06453067 0.06158632 0.0869354 -0.06474506 0.06178677 0.08678454 -0.06468939 0.06253415 0.08675163 -0.06530064 0.06227225 0.08699476 -0.06549829 0.062608 0.08690088 -0.06555157 0.06318241 0.08679902 -0.06606954 0.06334716 0.0869503 -0.06658053 0.06366926 0.08677721 -0.0667178 0.06399965 0.08699518 -0.06797134 0.06387639 0.0869053 -0.06730765 0.06440711 0.08673542 -0.06811672 0.06430625 0.08690911 -0.06827586 0.06458866 0.08677834 -0.06870937 0.06475549 0.08681964 -0.06949442 0.06456369 0.08697241 -0.06961631 0.06485903 0.08682942 -0.07028591 0.06462621 0.08699262 -0.07074433 0.06599116 0.08138972 -0.0706104 0.06584697 0.08116579 -0.07020467 0.06585663 0.08114004 -0.07121652 0.06574112 0.08106505 -0.07043361 0.0658831 0.08135557 -0.06960618 0.06556147 0.08100306 -0.07021057 0.06553769 0.08104306 -0.06919461 0.06562733 0.08119124 -0.06876754 0.06559175 0.08141911 -0.06831008 0.0653693 0.08117097 -0.06799387 0.06510287 0.08143401 -0.06707203 0.06503838 0.08100646 -0.06786274 0.06516051 0.08125495 -0.06733769 0.06470543 0.08103066 -0.06694662 0.06474739 0.08124184 -0.06654709 0.06453311 0.08137446 -0.06608802 0.06429445 0.0811305 -0.06598937 0.06390112 0.08105009 -0.06564116 0.06402558 0.08135598 -0.06539112 0.0630865 0.08100032 -0.06494897 0.06349438 0.08116519 -0.0649361 0.06330126 0.08140403 -0.06457197 0.06261926 0.08106601 -0.06426775 0.0628044 0.08123254 -0.06421512 0.06226116 0.08139717 -0.06369656 0.06189239 0.08118939 -0.06356036 0.06146383 0.08100521 -0.06364202 0.06164222 0.08108764 -0.06353509 0.06116312 0.08138233 -0.06302225 0.06073594 0.08124393 -0.06287568 0.06043219 0.08108043 -0.06290638 0.06007277 0.08140087 -0.06254452 0.05938649 0.08100706 -0.06269818 0.05968731 0.08118385 -0.06251931 0.0592066 0.08138364 -0.06228053 0.05892103 0.08123821 -0.06227117 0.05872142 0.08105927 -0.062415 0.05832016 0.08141237 -0.06209909 0.05763983 0.08122473 -0.06209421 0.05734568 0.08111923 -0.06216299 0.05743956 0.08141392 -0.06201249 0.05682611 0.08100223 -0.06239068 0.05653196 0.08134984 -0.06202369 0.05605244 0.08120018 -0.06213903 0.05567502 0.08143258 -0.06209796 0.05593991 0.08105343 -0.06232839 0.05532091 0.08120745 -0.06223893 0.05473744 0.08138817 -0.06229424 0.05488657 0.08102875 -0.06257522 0.05434823 0.0811848 -0.0625056 0.05389088 0.08139818 -0.06255799 0.05345243 0.08100539 -0.06315362 0.05353814 0.08106917 -0.06293576 0.05350857 0.08120876 -0.06279784 0.05307632 0.08140641 -0.06290322 0.05262643 0.0812335 -0.06320995 0.05226945 0.08142167 -0.06334465 0.0518651 0.08100253 -0.06410068 0.05233645 0.08104377 -0.06363016 0.0518046 0.0812112 -0.0637443 0.05155164 0.08142834 -0.06383693 0.05135518 0.08108818 -0.06425797 0.05089062 0.08139467 -0.06439679 0.05089908 0.0812121 -0.06449961 0.05051082 0.08110308 -0.06502777 0.05024421 0.08134835 -0.06507152 0.05053901 0.08100289 -0.0653212 0.04969948 0.08140897 -0.06574058 0.04995352 0.08109068 -0.06573146 0.0497362 0.08123499 -0.06580543 0.0495485 0.08103251 -0.06649965 0.04921329 0.08141785 -0.06648969 0.04926371 0.08121162 -0.06656175 0.04880589 0.08133125 -0.06731504 0.04892343 0.08109611 -0.0674892 0.0484845 0.08138805 -0.068102 0.04905128 0.08100461 -0.06769996 0.04860866 0.08114135 -0.06816029 0.04827749 0.08134615 -0.06882232 0.04857081 0.08100885 -0.06910717 0.04832339 0.08112996 -0.06926864 0.04810619 0.08134144 -0.06969636 0.04827427 0.08104419 -0.07060199 0.04810076 0.08122473 -0.07033884 0.04800564 0.08139824 -0.07081001 0.0481069 0.08117574 -0.07108992 0.0480526 0.08133852 -0.07185214 0.0481953 0.08113384 -0.07192021 0.0481438 0.08142089 -0.07259631 0.04843908 0.08100348 -0.07188582 0.04844719 0.0810554 -0.0728017 0.04830944 0.08119422 -0.07294201 0.04839527 0.08136463 -0.07362323 0.04876947 0.08110564 -0.07418882 0.04889053 0.08100765 -0.07393461 0.04866498 0.08126282 -0.07424992 0.0488792 0.08142161 -0.07488834 0.04902529 0.08126604 -0.07506096 0.04980653 0.08100265 -0.07570075 0.04942154 0.08118677 -0.07566767 0.04962176 0.08104407 -0.07567662 0.04945319 0.08139413 -0.07589596 0.04996168 0.08141899 -0.07660716 0.05003207 0.08122009 -0.07657456 0.05053305 0.08107703 -0.07693475 0.05056381 0.08142554 -0.07729005 0.05081826 0.08100569 -0.07700014 0.05070751 0.08120906 -0.07732266 0.0512166 0.08137154 -0.07788592 0.05154973 0.08105593 -0.07784163 0.05177474 0.08115917 -0.07817739 0.05209904 0.08137637 -0.07854574 0.05309045 0.08100181 -0.0786634 0.0526033 0.08107173 -0.07859188 0.05272048 0.08122622 -0.07883358 0.0531044 0.08140224 -0.07910972 0.05353784 0.08119684 -0.07920581 0.05372947 0.08104991 -0.0790959 0.0541293 0.08140683 -0.07953208 0.05432367 0.0812363 -0.0795207 0.05482923 0.08108967 -0.07953423 0.05524694 0.08143079 -0.07982742 0.05521684 0.08125436 -0.0797646 0.05508363 0.08101081 -0.0794025 0.0560339 0.08134788 -0.07993352 0.05654275 0.08100134 -0.07957708 0.05614095 0.0811063 -0.07978183 0.05684471 0.08141636 -0.08000141 0.05697232 0.08122265 -0.07992428 0.05722087 0.08106356 -0.07976055 0.05786156 0.08133155 -0.07994306 0.05839806 0.08102744 -0.07957214 0.05861771 0.08116239 -0.07973498 0.05876618 0.08138662 -0.07981961 0.05954587 0.08100515 -0.07922333 0.05962562 0.08137673 -0.07960134 0.05965906 0.08119362 -0.07949608 0.05982315 0.08103388 -0.07924193 0.06050294 0.08140218 -0.07928693 0.06044423 0.08115673 -0.07918363 0.06128627 0.08137512 -0.07890576 0.06127095 0.08116596 -0.07878655 0.06122428 0.08100801 -0.0785337 0.06205612 0.08142101 -0.07844424 0.06203722 0.08123534 -0.0783776 0.0621013 0.08105146 -0.07809883 0.06297999 0.08139818 -0.07772725 0.06266152 0.08120775 -0.07788461 0.06317871 0.08112788 -0.07733565 0.06335026 0.08100754 -0.07685387 0.06375795 0.08140909 -0.07694035 0.06367093 0.08122664 -0.07692968 0.0640164 0.08109235 -0.07631975 0.06440788 0.08136928 -0.07610505 0.06454557 0.08120435 -0.07574439 0.06499439 0.08138495 -0.07512187 0.06484413 0.08105134 -0.07486611 0.06466031 0.08100253 -0.07489687 0.06493139 0.08119517 -0.07504522 0.06537252 0.08139526 -0.07429057 0.06527554 0.08116239 -0.07422411 0.06564718 0.08133602 -0.07344275 0.06543815 0.08100616 -0.07281512 0.0654959 0.08111035 -0.07337671 0.06586301 0.08141386 -0.07255381 0.06582576 0.08121627 -0.07233041 0.06571877 0.08108407 -0.07218939 0.06597149 0.08138662 -0.07164615 0.06599301 0.0856046 -0.07123774 0.065916 0.08565688 -0.07212817 0.06576794 0.08565747 -0.07297152 0.06549584 0.08566802 -0.0739234 0.06519544 0.08560955 -0.07470804 0.06477713 0.08559137 -0.07552468 0.06435543 0.08566129 -0.07615715 0.06385219 0.08559632 -0.07683718 0.06309866 0.08558017 -0.07761698 0.06241506 0.08559298 -0.07818543 0.06170517 0.08559042 -0.07866942 0.06089556 0.08559775 -0.07910972 0.05990982 0.08561748 -0.07951521 0.05877262 0.08562135 -0.07981711 0.05790346 0.08565068 -0.07994282 0.05721026 0.08563309 -0.07998639 0.05656069 0.08566254 -0.07997512 0.05568969 0.08562529 -0.07989692 0.05452471 0.08560842 -0.07965296 0.05324643 0.08558934 -0.0791825 0.05232125 0.08556741 -0.07868832 0.05171984 0.08564966 -0.0782777 0.05037409 0.08561098 -0.07709038 0.0496971 0.08559238 -0.07625579 0.04910379 0.08561414 -0.07531732 0.04864507 0.0856707 -0.07430279 0.048343 0.08561652 -0.07344001 0.04810583 0.08560866 -0.07237666 0.04800093 0.08561575 -0.07100415 0.04810321 0.0856083 -0.06963872 0.04834455 0.08564025 -0.06856894 0.0487017 0.08559417 -0.06751185 0.04933977 0.08561283 -0.06627601 0.0500068 0.08564496 -0.06535154 0.05057007 0.08563309 -0.06471467 0.05120766 0.08567297 -0.06413316 0.05210405 0.08561229 -0.06344872 0.05331659 0.08560574 -0.06278771 0.05434978 0.08563286 -0.06240797 0.0554288 0.08559131 -0.06213563 0.05681854 0.08561009 -0.06200182 0.05814689 0.08559471 -0.0620718 0.05947339 0.08560961 -0.06234639 0.06071645 0.08560645 -0.06280303 0.06173205 0.08564454 -0.06335645 0.06241518 0.08560311 -0.06381642 0.06326383 0.08559936 -0.0645352 0.06402021 0.08560281 -0.06537467 0.06454449 0.08558946 -0.06609672 0.06502258 0.08563572 -0.06693971 0.06535488 0.08564698 -0.06768423 0.06566482 0.08560341 -0.06858044 0.06584858 0.08563381 -0.06940358 0.06597071 0.08559596 -0.07031434 0.06589478 0.08581554 -0.07118701 0.06569629 0.08596378 -0.07138693 0.06570202 0.08589583 -0.07246345 0.06531405 0.08599388 -0.07333022 0.06547904 0.08584946 -0.07360702 0.06461697 0.08599776 -0.07497471 0.06510317 0.08581781 -0.07466703 0.06480044 0.08593523 -0.0749973 0.06473106 0.08578664 -0.07544672 0.06418287 0.08584773 -0.07619738 0.06382387 0.08594423 -0.07647562 0.06370651 0.08578592 -0.07687926 0.06306183 0.08598875 -0.07717508 0.06307834 0.08579778 -0.0775212 0.06203764 0.08599346 -0.077995 0.06238347 0.08579242 -0.07810485 0.06217604 0.08591353 -0.07810765 0.06165391 0.0857734 -0.07861745 0.06131213 0.08592003 -0.07865673 0.06087255 0.08582854 -0.07900148 0.06022351 0.08599019 -0.07902616 0.06002992 0.08580267 -0.07937371 0.05940061 0.08591037 -0.07946592 0.0590378 0.08577591 -0.07969391 0.05865907 0.08599632 -0.07942706 0.05821382 0.08590966 -0.07971453 0.0570687 0.08599328 -0.07962924 0.05743765 0.08586645 -0.07983916 0.05667066 0.08592289 -0.07977336 0.05589246 0.08586418 -0.0797851 0.05528056 0.08591902 -0.07962495 0.05520373 0.0857495 -0.07975554 0.05477559 0.08599436 -0.07931876 0.05440473 0.08579343 -0.07952654 0.05407279 0.08598959 -0.07914412 0.05354875 0.08570969 -0.07926875 0.0533809 0.08588618 -0.07905542 0.05254328 0.08579427 -0.07872247 0.05242675 0.08595234 -0.07843637 0.05203121 0.08599704 -0.07801192 0.05141031 0.08589577 -0.07782912 0.05118685 0.08564889 -0.07785338 0.05062317 0.08579283 -0.07722985 0.05079668 0.08597242 -0.07708591 0.04987239 0.08578705 -0.07636433 0.04998826 0.08593434 -0.07626152 0.04978924 0.08599668 -0.07568478 0.04917377 0.08580499 -0.07525634 0.04926115 0.08596122 -0.07501959 0.04877251 0.08589261 -0.07417517 0.04879629 0.08599638 -0.07359391 0.04846197 0.08585613 -0.07338267 0.0484603 0.08596813 -0.07261151 0.04819017 0.08581566 -0.07229548 0.04826527 0.08593386 -0.07167333 0.04841196 0.08599847 -0.07082325 0.04810279 0.0858097 -0.07117998 0.048258 0.08594036 -0.07062488 0.04810887 0.08578485 -0.07031953 0.04835033 0.08594572 -0.06964796 0.04820877 0.08577781 -0.06946766 0.04848563 0.08587235 -0.06860637 0.0489583 0.0859934 -0.06784528 0.04867905 0.0858137 -0.06783813 0.04900652 0.08571726 -0.06695944 0.04915428 0.08590191 -0.06699174 0.04960423 0.08578288 -0.06600224 0.04959106 0.08594596 -0.06635832 0.05028051 0.08598726 -0.06558102 0.05040508 0.08592432 -0.06519609 0.05064028 0.08582973 -0.06480014 0.05179494 0.08599871 -0.064139 0.05145055 0.08591264 -0.06417477 0.05218797 0.08581125 -0.06350857 0.05272209 0.08593189 -0.06334459 0.05334872 0.08582621 -0.0628885 0.05382567 0.08599168 -0.06297463 0.05451279 0.08589702 -0.06253391 0.05525398 0.08582472 -0.06228113 0.0560733 0.08598989 -0.06240481 0.05637401 0.08576661 -0.06208521 0.05627876 0.08586692 -0.062177 0.05746704 0.0857768 -0.06208783 0.05762618 0.08592307 -0.0622425 0.05830651 0.08599573 -0.0624805 0.05834066 0.08580571 -0.0621978 0.05892229 0.08591914 -0.06242513 0.05922579 0.08575624 -0.06234657 0.05996334 0.08589124 -0.06268137 0.06071478 0.0859971 -0.06321716 0.06046319 0.08578175 -0.06278115 0.06104725 0.08596301 -0.06329041 0.06126815 0.08581161 -0.0631901 0.06185984 0.08591264 -0.06366878 0.06239748 0.08580654 -0.06391751 0.06256926 0.08599692 -0.06444692 0.06279319 0.08593392 -0.06442826 0.06326699 0.08578419 -0.06464606 0.06366038 0.08595103 -0.06534272 0.06412863 0.08579069 -0.06564104 0.0641207 0.08599585 -0.06615602 0.06456971 0.08589249 -0.06646996 0.06474018 0.08573728 -0.06651455 0.06515079 0.08591419 -0.06766581 0.06487149 0.08596092 -0.06726598 0.06530892 0.08598893 -0.06861251 0.06552106 0.08582186 -0.06844741 0.06581217 0.08580774 -0.06970942 0.06570535 0.08593004 -0.06992137 0.06558108 0.08599615 -0.07035875 0.06588804 0.08580112 -0.07040119 0.05706578 0.07314419 0.04276543 0.05765235 0.07318943 0.04270333 0.05775451 0.07306736 0.04275614 0.05675256 0.073004 0.0429449 0.05807876 0.07300353 0.04282516 0.05818599 0.07317316 0.04256671 0.05858218 0.07306337 0.04249173 0.05862724 0.07317352 0.04239016 0.05903619 0.07318502 0.04215663 0.0593245 0.07300293 0.04221343 0.05905473 0.07304829 0.04224836 0.05948281 0.07317936 0.0418263 0.05953258 0.07307451 0.04185754 0.05987697 0.07318472 0.04141533 0.06002497 0.07300806 0.04150468 0.0601111 0.07306611 0.04123836 0.06015789 0.07319182 0.04103595 0.06057929 0.07301557 0.04061138 0.06077277 0.07300043 0.0403698 0.06047582 0.07318621 0.0404374 0.06051331 0.07306623 0.0405206 0.0606507 0.07317352 0.03989535 0.06078159 0.07306993 0.03959786 0.06074219 0.0731889 0.03937023 0.06089961 0.07301336 0.03935277 0.0608043 0.07309204 0.03890758 0.06074541 0.07320141 0.03871804 0.06087559 0.0730068 0.03828716 0.06073784 0.07308548 0.03825938 0.0606634 0.07320201 0.03817158 0.06069839 0.07300776 0.03766816 0.06048703 0.07317376 0.03759121 0.06052947 0.07305592 0.03748261 0.06020873 0.07318866 0.0370391 0.06026166 0.07301133 0.03682202 0.06012386 0.07308065 0.03679764 0.05988228 0.07316815 0.03658598 0.05956882 0.07318627 0.03625756 0.05960673 0.0730623 0.0361917 0.05954366 0.07300329 0.03596633 0.05924171 0.07316762 0.03598028 0.05901473 0.07302236 0.0356661 0.05885308 0.07314449 0.03572088 0.05825543 0.07300341 0.03524106 0.05845952 0.07318508 0.03553664 0.05823326 0.07306915 0.03537875 0.05792635 0.07320249 0.03536009 0.0576297 0.07307142 0.03523308 0.05728173 0.07320058 0.03525167 0.05706429 0.07308268 0.03518462 0.05729436 0.07301574 0.03510028 0.05653655 0.07316839 0.03526431 0.05636346 0.07300406 0.03508675 0.05606675 0.07306706 0.03528451 0.0558927 0.0731914 0.03540945 0.05528628 0.07317429 0.03564965 0.05519592 0.07300722 0.03549385 0.0554381 0.07308232 0.03552323 0.0549333 0.07305634 0.03575944 0.05480021 0.07317721 0.03595322 0.05437231 0.07319664 0.03631132 0.05433267 0.07301014 0.03612589 0.05441945 0.07310622 0.03621691 0.05391681 0.07316792 0.03684186 0.05380702 0.0730431 0.03682982 0.05349868 0.07300359 0.03714942 0.05365866 0.07317715 0.0372771 0.05342203 0.0730586 0.03759622 0.05345207 0.07317125 0.03774678 0.05313885 0.0730077 0.03821039 0.05328267 0.07318669 0.03843003 0.05320841 0.07307803 0.03852075 0.05324345 0.07318729 0.03910183 0.05308288 0.07300937 0.0392934 0.05318683 0.07307308 0.03925329 0.05331331 0.07319235 0.03973823 0.0532971 0.07307875 0.03991729 0.05330723 0.07300364 0.04045718 0.05351388 0.07316774 0.04041212 0.05342102 0.07305097 0.04041141 0.0536701 0.07316762 0.04074805 0.053734 0.07303315 0.04108715 0.05389255 0.07316774 0.04111647 0.05425292 0.07321196 0.0415638 0.05421835 0.07311326 0.04157763 0.0543428 0.07300972 0.04188901 0.0546931 0.07313764 0.04198139 0.05503493 0.07318711 0.04220324 0.05514276 0.07301861 0.04243683 0.05519735 0.07311069 0.04233527 0.05565029 0.07318067 0.04251062 0.05565464 0.07306361 0.04258507 0.05592018 0.07300829 0.04277491 0.05612981 0.07314336 0.04266649 0.05663329 0.0731697 0.04274398 0.05679422 0.07304596 0.0428549 0.05699521 0.09382802 0.03523921 0.05765396 0.09380513 0.03529769 0.05828553 0.09379833 0.03547078 0.05866652 0.09384548 0.03562468 0.05911731 0.09381055 0.03589564 0.05948394 0.0938149 0.03618204 0.0598039 0.0938313 0.03649353 0.06009829 0.09381693 0.03686851 0.06059318 0.09384465 0.03786951 0.0607596 0.09380519 0.03900116 0.06070101 0.09385281 0.03970289 0.060588 0.09381109 0.04010999 0.06044846 0.093831 0.04050379 0.06020259 0.09381163 0.04096215 0.05993819 0.09380918 0.04134207 0.0596227 0.0938149 0.04168921 0.05926901 0.09381335 0.04199576 0.05879461 0.09385114 0.0423116 0.05817699 0.09380465 0.04257011 0.05778574 0.09383529 0.04268068 0.05719017 0.09385496 0.04276281 0.05672252 0.09383183 0.0427494 0.05625975 0.09382665 0.04268693 0.05578601 0.09383881 0.04256325 0.05535507 0.09383237 0.04238146 0.05494147 0.09384149 0.0421527 0.0546596 0.0938149 0.04193818 0.05430841 0.09380793 0.0416215 0.0539664 0.0938279 0.04122126 0.05372333 0.09385406 0.04085725 0.05345702 0.09381479 0.04026043 0.0533002 0.09380787 0.03965491 0.05323952 0.09381097 0.03899794 0.05331081 0.09383153 0.03825652 0.05351376 0.09383267 0.03758931 0.05378705 0.09383153 0.03703868 0.05423533 0.09381365 0.0364505 0.05472743 0.09383291 0.03600215 0.05518192 0.09384429 0.03570282 0.05565315 0.09381943 0.03548824 0.05636167 0.09383487 0.03529024 0.05728811 0.09392958 0.03519034 0.05794274 0.09390699 0.0353055 0.05809634 0.09399074 0.03522562 0.05840772 0.09395486 0.03540563 0.05918931 0.09398996 0.03573691 0.05900305 0.09393143 0.03574281 0.0596168 0.09393954 0.03619039 0.06029647 0.0939967 0.03676933 0.06015151 0.09392935 0.03683388 0.06039899 0.09395843 0.03716319 0.06035035 0.09383291 0.03728902 0.0610677 0.0939998 0.03875303 0.06078135 0.09397441 0.03806519 0.06072366 0.0938524 0.03842306 0.06090253 0.09398078 0.03902751 0.06081026 0.09391552 0.03918433 0.06081956 0.09398031 0.03978854 0.06055861 0.09395164 0.04048115 0.06055241 0.09399169 0.04069679 0.06025832 0.09392595 0.04099863 0.0598089 0.09399539 0.0418117 0.0597952 0.09392899 0.04160839 0.05930137 0.09393525 0.04205936 0.05865597 0.09399211 0.04257088 0.05831855 0.09397304 0.04266136 0.05834949 0.09388619 0.04253917 0.05738592 0.09398835 0.04289454 0.05673068 0.09396296 0.04285621 0.05572897 0.09399616 0.04276472 0.05595797 0.09394943 0.04270815 0.05531537 0.09394913 0.0424599 0.0546025 0.09398496 0.04209053 0.05419671 0.09392678 0.0415973 0.05386483 0.09399288 0.0413717 0.05379164 0.09396761 0.04117095 0.05333584 0.09397679 0.04034215 0.05343675 0.09389233 0.0403105 0.05304127 0.09399861 0.03968656 0.05321651 0.09392958 0.03956514 0.05310088 0.09397816 0.03911477 0.05319184 0.09391176 0.03891032 0.05325078 0.09393388 0.03821778 0.05312442 0.0939964 0.03821504 0.0533936 0.09388202 0.03785121 0.05348002 0.09399598 0.03716766 0.05358701 0.09394639 0.03721803 0.05410677 0.0939303 0.03649568 0.05405437 0.09399509 0.03636872 0.05441761 0.09390217 0.03621143 0.05488854 0.09397327 0.0357418 0.05542963 0.0939964 0.03536641 0.05554956 0.09393721 0.03545504 0.05613118 0.09392714 0.03527975 0.05668836 0.0939964 0.03503555 0.05682039 0.09393924 0.03517132 0.05251485 0.07475 0.03851723 0.05249822 0.078 0.03866261 0.05281919 0.078 0.03727626 0.05284684 0.07475 0.03721058 0.0536608 0.078 0.0359503 0.05378299 0.07475 0.03581184 0.05462276 0.078 0.03517109 0.05497217 0.07475 0.0349704 0.05563551 0.078 0.03469491 0.0561394 0.07475 0.03456658 0.05674338 0.078 0.03450042 0.05759769 0.07475 0.03451746 0.05808252 0.078 0.03460204 0.05919772 0.07475 0.03503978 0.05961078 0.078 0.03530758 0.06032967 0.07475 0.03595656 0.06057536 0.078 0.03624933 0.06107246 0.07475 0.0370388 0.06123715 0.078 0.03741985 0.06143951 0.07475 0.03821706 0.06151658 0.078 0.03888738 0.06149601 0.07475 0.03948575 0.06139272 0.078 0.04000258 0.06101375 0.07475 0.04109835 0.06107878 0.078 0.04092681 0.06047719 0.078 0.04187369 0.06004607 0.07475 0.04233419 0.05945467 0.078 0.0428006 0.0591548 0.07475 0.042957 0.0581482 0.07475 0.04336774 0.05840766 0.078 0.04327791 0.05733776 0.078 0.04350745 0.05692124 0.07475 0.04351031 0.05602908 0.078 0.04340529 0.05588752 0.07475 0.04336863 0.05507332 0.078 0.04307425 0.05480951 0.07475 0.04294931 0.05412387 0.078 0.04248189 0.0539112 0.07475 0.04228192 0.05327153 0.078 0.04154199 0.05327403 0.07475 0.04154032 0.05281639 0.07475 0.04067605 0.05263042 0.078 0.04019182 0.05253779 0.07475 0.03967255 0.06151872 0.08899998 0.03922551 0.06151449 0.09224998 0.03922528 0.0611431 0.09224998 0.04082977 0.06119108 0.08899998 0.04068231 0.06037181 0.08899998 0.04202389 0.06025725 0.09224998 0.0421282 0.05909472 0.09224998 0.04300773 0.05932289 0.08899998 0.04286205 0.05840462 0.08899998 0.04328674 0.05770754 0.09224998 0.04346036 0.05741697 0.08899998 0.04348748 0.05636143 0.09224998 0.04347074 0.05629235 0.08899998 0.04346036 0.05496865 0.09224998 0.04304027 0.05511397 0.08899998 0.04309785 0.05392098 0.08899998 0.04231834 0.05362808 0.09224998 0.04202389 0.05297952 0.08899998 0.0410611 0.05284172 0.09224998 0.04075276 0.05250835 0.08899998 0.03956288 0.05256271 0.09224998 0.0397824 0.05249297 0.09224998 0.03877508 0.05258941 0.08899998 0.03802907 0.05278611 0.09224998 0.03734618 0.05302226 0.08899998 0.03687226 0.05375587 0.09224998 0.0358358 0.05361986 0.08899998 0.03601706 0.0543676 0.08899998 0.0353384 0.05504131 0.09224998 0.03493267 0.05545473 0.08899998 0.03475445 0.05607569 0.09224998 0.03458893 0.05655139 0.08899998 0.03451663 0.05722516 0.09224998 0.0344876 0.05767339 0.08899998 0.03453242 0.05835872 0.09224998 0.03470283 0.05877989 0.08899998 0.03485953 0.05945235 0.09224998 0.03520298 0.05984729 0.08899998 0.03548669 0.06067943 0.09224998 0.03635466 0.06074607 0.08899998 0.0364868 0.06131929 0.08899998 0.03766769 0.06135666 0.09224998 0.0378105 0.06448197 0.09366887 0.03881347 0.06425595 0.09390932 0.03816014 0.06434321 0.09386515 0.03936135 0.06443923 0.09359306 0.03807163 0.06409001 0.09399509 0.03854966 0.06432533 0.09375917 0.03768211 0.06431299 0.09360086 0.03735387 0.06381392 0.09399431 0.03691589 0.06399929 0.09388673 0.03681993 0.06410163 0.09365981 0.03663206 0.06376546 0.09359103 0.03576016 0.06377518 0.09374481 0.03592079 0.06347906 0.09391033 0.03562021 0.06336653 0.09365504 0.03505647 0.06302458 0.0939961 0.03524017 0.06303489 0.09377461 0.03467273 0.06287139 0.09357911 0.03433585 0.06271803 0.09394317 0.03454059 0.06258499 0.09378862 0.03411495 0.06237053 0.09358114 0.03376722 0.06204372 0.09376335 0.03353875 0.06183713 0.09399515 0.03380465 0.06178426 0.09363591 0.03323554 0.06193929 0.09392416 0.03366166 0.06137925 0.09391683 0.03316628 0.06121045 0.09358304 0.03279566 0.06118023 0.09376257 0.03285485 0.06059193 0.09360289 0.03242087 0.06056833 0.09384602 0.03254461 0.060184 0.09399706 0.03263127 0.05993509 0.09365755 0.03211206 0.05977267 0.09391862 0.03226107 0.0592451 0.09375411 0.03190106 0.05918318 0.09359967 0.03182882 0.05889034 0.09393531 0.03198665 0.05851012 0.09358859 0.0316562 0.0582695 0.09388053 0.03177565 0.0579164 0.0937224 0.03159749 0.05760663 0.0936017 0.03152459 0.05768674 0.09399491 0.03191721 0.05715143 0.09391343 0.03170228 0.05679452 0.09365904 0.03151488 0.05610942 0.09384781 0.03168076 0.05587869 0.09363186 0.03159296 0.05589407 0.09395146 0.03184896 0.05577272 0.09399873 0.03203499 0.05493402 0.09358835 0.0317887 0.0551387 0.09379702 0.03181976 0.05460774 0.09399151 0.03227865 0.05423718 0.09375274 0.03208863 0.05410337 0.09357035 0.03208261 0.05414456 0.09389078 0.03225493 0.05342388 0.09362715 0.03241634 0.05307525 0.09383243 0.03273868 0.05326575 0.09397345 0.0328601 0.05262774 0.09360414 0.03290694 0.05228549 0.0938304 0.03331404 0.05176883 0.09360373 0.03362613 0.05194938 0.09392666 0.03376013 0.05215048 0.09399777 0.03382247 0.05159056 0.09378665 0.03392177 0.05111771 0.09365868 0.0343694 0.05129724 0.09394383 0.03452211 0.05061614 0.09361678 0.03506797 0.05088758 0.09386724 0.03491568 0.05053269 0.0937801 0.03535342 0.05061042 0.09398746 0.03576058 0.05010956 0.09364742 0.03605735 0.05022484 0.09387254 0.03616642 0.05017691 0.09396356 0.03667175 0.0498383 0.09365212 0.03680753 0.0497843 0.09379225 0.0372616 0.05011308 0.09399884 0.03742235 0.04957473 0.09358578 0.03793334 0.04982054 0.09395784 0.03819566 0.04963165 0.09379881 0.03817069 0.04950541 0.09358727 0.03878688 0.04990524 0.0939961 0.03934895 0.04963171 0.09384888 0.0390315 0.04952776 0.09365344 0.03948986 0.04971402 0.09388387 0.0398572 0.04961627 0.09361267 0.0402832 0.04978805 0.09375822 0.04082262 0.04978466 0.09357309 0.04104268 0.04992866 0.09394246 0.04058957 0.05032444 0.09399688 0.0414381 0.04995113 0.09381675 0.04124033 0.05007708 0.09360516 0.04188561 0.05020833 0.0937193 0.04207581 0.05019176 0.0938878 0.04171782 0.05060702 0.0936324 0.04291188 0.0507878 0.0939387 0.0427618 0.05075007 0.0937851 0.04301202 0.05104744 0.09398734 0.04293411 0.05113708 0.09360396 0.04367017 0.05143624 0.09392988 0.04368573 0.05157518 0.0937637 0.04408538 0.05161499 0.09361165 0.04421246 0.05225175 0.09399265 0.04431843 0.05219119 0.09368032 0.0447309 0.05231314 0.09391605 0.04458802 0.0529226 0.09360027 0.04529571 0.05297607 0.09378069 0.04524236 0.05347031 0.0939961 0.04514926 0.05349731 0.09394353 0.04534482 0.05372017 0.09359318 0.04574126 0.05380523 0.09377676 0.04570353 0.05458557 0.09359467 0.04610127 0.05436694 0.09388482 0.04583829 0.05467778 0.09375154 0.04607033 0.05468851 0.09399414 0.04573285 0.05548453 0.09364503 0.0463342 0.05542051 0.09383779 0.04620724 0.05566895 0.09397804 0.04605948 0.05627453 0.09360468 0.04646027 0.05624788 0.09384214 0.04633933 0.05717951 0.09359288 0.04649871 0.05703878 0.09375554 0.04643541 0.05739772 0.09389853 0.04631024 0.05722248 0.09399503 0.04610681 0.0579223 0.09377688 0.04636961 0.0581513 0.09360247 0.04640662 0.05856227 0.09399121 0.04595232 0.05888855 0.0936563 0.0462448 0.05862247 0.09388381 0.04615098 0.05971437 0.09358912 0.04599261 0.05937033 0.09392762 0.04587149 0.05949693 0.09381502 0.04596382 0.06048887 0.09367209 0.04562133 0.05998259 0.09399485 0.04545271 0.06015509 0.09388387 0.04561549 0.06100773 0.09393483 0.04506766 0.06136423 0.0936011 0.04509943 0.06138497 0.09379291 0.04498112 0.06156146 0.09399539 0.04443866 0.06219428 0.09364008 0.04439818 0.06199663 0.09377956 0.04449236 0.06203967 0.09394103 0.04420757 0.06263756 0.09357517 0.04394489 0.06257325 0.09381437 0.04386663 0.06306105 0.09363585 0.04340147 0.06280225 0.09399175 0.04314416 0.06284677 0.09391868 0.04335993 0.06346994 0.09374302 0.04269474 0.06350809 0.09356939 0.04272615 0.06349784 0.0939083 0.04233807 0.06384086 0.09358328 0.04206919 0.0634458 0.09399509 0.04199635 0.06396007 0.09380578 0.04154092 0.06411516 0.09360086 0.04135876 0.06394386 0.09394472 0.04105591 0.06431305 0.09356111 0.04066491 0.06424778 0.09377008 0.04064339 0.06395268 0.09399777 0.04031705 0.06446379 0.09361797 0.03970628 0.06420272 0.09394782 0.03980797 0.06436735 0.09376209 0.0399692 0.06449419 0.09265643 0.03880488 0.06443852 0.09265071 0.03807193 0.06426239 0.0926494 0.03712719 0.0639835 0.09267556 0.03626781 0.06338948 0.09265834 0.03507065 0.06273758 0.09267306 0.03416591 0.06211245 0.09267795 0.0335136 0.06153368 0.09266394 0.03302818 0.06037706 0.09266775 0.03230136 0.05954283 0.09261536 0.03195393 0.05864351 0.09260761 0.03168922 0.0560745 0.09263962 0.03155863 0.05519384 0.09263586 0.03172653 0.05422371 0.09265172 0.03203266 0.05339992 0.09260022 0.0324341 0.05266231 0.09260404 0.03289073 0.05190217 0.09267747 0.03350007 0.05092358 0.09264713 0.03461092 0.05050432 0.09266853 0.03525424 0.05008566 0.09266215 0.03609108 0.0497809 0.09266853 0.03697299 0.04962116 0.09266185 0.03767138 0.049564 0.09264397 0.03994011 0.04988443 0.09265023 0.04135751 0.05013543 0.09257954 0.0419861 0.05088603 0.09264856 0.0433371 0.05151045 0.09264636 0.04410934 0.0521745 0.09265893 0.04473805 0.05277925 0.09267407 0.04519796 0.05340707 0.09266388 0.0455808 0.05405747 0.09260201 0.04588603 0.05477845 0.0926454 0.0461589 0.05553305 0.0926212 0.04634666 0.05623346 0.09265631 0.04645758 0.05701261 0.09262347 0.04649245 0.05772292 0.09264516 0.04646033 0.05847799 0.09267556 0.04635179 0.05938434 0.09261626 0.04610502 0.06024885 0.09260499 0.04574757 0.06087112 0.0926178 0.04541397 0.06171077 0.09264373 0.04483467 0.06236022 0.09264713 0.04423964 0.06298249 0.09264361 0.04352152 0.06358528 0.09265369 0.04259037 0.06405025 0.09264719 0.04155766 0.06429529 0.09259736 0.04068446 0.06446081 0.09263861 0.03975051 0.06441277 0.09247255 0.03954571 0.06422531 0.09229457 0.03910237 0.06419336 0.09234839 0.04033714 0.06402176 0.0922532 0.04002159 0.06376433 0.0922808 0.04144513 0.06395697 0.09242612 0.04150694 0.06340062 0.09225517 0.04211556 0.06360048 0.09234446 0.04212033 0.06351244 0.09246557 0.04255902 0.06304383 0.09231334 0.0430175 0.06296169 0.09243816 0.04338514 0.06217014 0.09225177 0.04387962 0.06253308 0.09239608 0.04386919 0.06184846 0.0924195 0.044577 0.06171345 0.09230393 0.04450476 0.06116962 0.09244322 0.04512381 0.06029951 0.09225553 0.04529815 0.0604729 0.09233975 0.04542708 0.05968236 0.09241437 0.04587739 0.05912131 0.09225612 0.04581272 0.05884945 0.09249073 0.04620027 0.05862218 0.09234404 0.04612183 0.05797588 0.09244984 0.04634881 0.05761581 0.09229642 0.046202 0.05680811 0.09238135 0.04634988 0.05659437 0.09225708 0.04610586 0.05626207 0.09246808 0.04638338 0.05560517 0.09236466 0.04620236 0.05521953 0.09225559 0.04588752 0.05467236 0.0924493 0.04603362 0.05469375 0.09232914 0.0459063 0.05356478 0.09234213 0.04545408 0.05398458 0.09228438 0.04553455 0.05332213 0.09245926 0.04544168 0.05308455 0.09225088 0.04490858 0.05278372 0.09247213 0.04511284 0.052531 0.09229606 0.04468435 0.05198633 0.09245884 0.04447197 0.05148208 0.09230518 0.04370754 0.05164515 0.09225368 0.04366993 0.05117374 0.09251725 0.04364269 0.05092149 0.09240776 0.04317533 0.05053287 0.09260469 0.04277628 0.05049335 0.09233886 0.04231417 0.05032318 0.0925247 0.0423147 0.05072522 0.09226441 0.04239028 0.05020505 0.09225571 0.04116934 0.04995048 0.09242397 0.04121357 0.04984664 0.09235924 0.04057997 0.04969209 0.09260296 0.04063618 0.04989773 0.09227842 0.04005867 0.04965651 0.09241443 0.03977185 0.04951411 0.09260225 0.03922349 0.04952192 0.09260207 0.03857809 0.04989916 0.09225499 0.03884977 0.04967814 0.09235507 0.03874272 0.04967099 0.09245276 0.0378775 0.04988837 0.09230452 0.03761827 0.04985177 0.09247493 0.03698867 0.05024778 0.09225833 0.03669047 0.05007702 0.092413 0.03642916 0.0503776 0.09245872 0.0356602 0.0509603 0.09225553 0.03522461 0.05075526 0.09230422 0.03531599 0.0508396 0.09248262 0.03484117 0.0514093 0.09234184 0.03429955 0.0513612 0.09261745 0.03406816 0.05163359 0.09243541 0.03390967 0.05190813 0.09225386 0.03406065 0.05207544 0.09247148 0.03343993 0.05221813 0.09230226 0.03356432 0.05295264 0.09233707 0.03292644 0.05385929 0.09225225 0.03261202 0.05372065 0.09241199 0.03238928 0.0543546 0.09229809 0.03226476 0.05463129 0.09248328 0.03195077 0.05520343 0.09240025 0.03185707 0.0559045 0.09231889 0.03181505 0.05593472 0.0924651 0.03165924 0.05602866 0.09225434 0.03196692 0.05694699 0.09240931 0.03161644 0.05701982 0.09259742 0.03151249 0.0570892 0.09228426 0.03180289 0.05777919 0.09258019 0.03155678 0.05828553 0.09237241 0.03177517 0.05824297 0.09225672 0.03198689 0.05918091 0.09232187 0.03206157 0.05914276 0.09242528 0.031928 0.06018245 0.09225392 0.03263223 0.06019085 0.09243911 0.03231525 0.06048047 0.09231263 0.03263264 0.06092208 0.09261626 0.03261971 0.06114321 0.09244287 0.03286212 0.06169182 0.0923323 0.03341144 0.06179046 0.09249651 0.03330886 0.06202697 0.09225153 0.03400611 0.06229704 0.09247297 0.03379732 0.06248909 0.09230148 0.03427296 0.06282037 0.09250867 0.03435921 0.06316614 0.09246945 0.03486502 0.06317442 0.09230071 0.0352106 0.06335496 0.092251 0.03589266 0.06369787 0.09260165 0.03565514 0.06355893 0.09240573 0.03564101 0.06391984 0.09247279 0.03630661 0.06378895 0.09229165 0.0365259 0.0641908 0.09245771 0.03717333 0.06412559 0.09232956 0.03749316 0.0640344 0.09225523 0.03800398 0.06435161 0.09241229 0.03828865 0.06446677 0.07336658 0.03960579 0.06441903 0.07321435 0.03917789 0.06426328 0.07306879 0.03899669 0.06406265 0.07300293 0.03964281 0.06425613 0.07311969 0.04012054 0.06438004 0.07336246 0.04027944 0.06420069 0.07332599 0.04103642 0.06405282 0.07308167 0.04083657 0.06381958 0.0730043 0.04096555 0.06397366 0.07336008 0.0417326 0.06372159 0.07305598 0.04171168 0.06380033 0.07318586 0.04191786 0.06358528 0.07340371 0.04259037 0.06342214 0.0732063 0.04270267 0.06306993 0.07300186 0.04264879 0.06311577 0.07309114 0.04300725 0.0630607 0.07335132 0.0433979 0.06253552 0.0730412 0.04364007 0.06248968 0.07339644 0.04410904 0.06255763 0.07319796 0.04389572 0.06202727 0.07315945 0.04439795 0.06183499 0.07338845 0.04472655 0.0613954 0.07300657 0.04462492 0.06143015 0.07320511 0.04494726 0.06122124 0.07343536 0.04519879 0.0609554 0.07323068 0.04529017 0.0605691 0.07334882 0.04558241 0.06044858 0.0730859 0.04543161 0.05973136 0.07300353 0.0455712 0.05993676 0.07332831 0.04588329 0.05930978 0.07313555 0.04598826 0.05922156 0.0733757 0.04615396 0.05860573 0.07341659 0.04632765 0.05863469 0.07308626 0.04610729 0.05850923 0.07323956 0.04627817 0.05776971 0.07303202 0.04616451 0.05775851 0.0734151 0.04645919 0.05773353 0.07322406 0.04638874 0.05698335 0.07339656 0.04649579 0.05704033 0.07316744 0.04638493 0.05636936 0.07300883 0.04611504 0.05613034 0.07334411 0.04643744 0.05626356 0.07314252 0.046319 0.05535364 0.07333964 0.0463047 0.05541563 0.07313954 0.0461837 0.05475699 0.07339119 0.04615163 0.0549671 0.07306551 0.04596996 0.05424618 0.07300508 0.04557615 0.05431705 0.07316207 0.04587608 0.054111 0.073408 0.04591816 0.05363667 0.07325005 0.04564106 0.05342805 0.07339805 0.04559004 0.05333191 0.07309877 0.04532259 0.05263388 0.07339978 0.045098 0.05250161 0.0732159 0.04490822 0.05237722 0.07304674 0.04457473 0.05175936 0.07338887 0.0443629 0.0522648 0.07300561 0.04430186 0.05164432 0.07317662 0.04409176 0.05115568 0.07332378 0.04367226 0.05127221 0.07307046 0.04348456 0.05094563 0.07300758 0.04277759 0.0507186 0.07339853 0.04309111 0.050655 0.07321566 0.04285562 0.05032658 0.07339042 0.0424115 0.05037987 0.07306092 0.04197102 0.05025571 0.07319819 0.04205948 0.05040812 0.07300388 0.04164481 0.05001682 0.07339417 0.04172265 0.04999202 0.07313549 0.04124742 0.0497421 0.07340633 0.04089391 0.04973602 0.07326751 0.04065418 0.04966896 0.07319265 0.04004114 0.049564 0.073394 0.03994011 0.04985117 0.07304197 0.04008376 0.04951465 0.07335186 0.03921407 0.04964196 0.07313776 0.03880792 0.04953211 0.07334917 0.03844964 0.04987502 0.07300597 0.03907787 0.04963016 0.07332569 0.03770452 0.04987412 0.07303458 0.0379914 0.04986721 0.07310819 0.03732287 0.04980969 0.07333439 0.03692126 0.05031591 0.07300227 0.03651249 0.05023264 0.07303327 0.03654336 0.05002278 0.07335293 0.03628021 0.05020684 0.07317841 0.03608351 0.05040138 0.07339805 0.03543543 0.05053275 0.07309597 0.03560328 0.05056661 0.07325482 0.03525996 0.05092692 0.07307839 0.03498011 0.05091696 0.07339185 0.03462129 0.0510891 0.07326203 0.03446561 0.05144762 0.07300502 0.03456032 0.05149763 0.07311248 0.03415054 0.05140441 0.07341033 0.03401005 0.05168509 0.07322722 0.03381305 0.05193614 0.07338809 0.03347498 0.05226975 0.07304984 0.03352934 0.05227267 0.07319647 0.03330135 0.05326491 0.07300376 0.03293365 0.052459 0.07341033 0.03303426 0.05294752 0.07326716 0.03274601 0.05316084 0.07310742 0.03276193 0.05310982 0.07343369 0.03258818 0.05390459 0.07339775 0.03216904 0.05374169 0.07321459 0.03233891 0.05427622 0.07307982 0.03224331 0.05460655 0.07326823 0.03194272 0.05478227 0.07342004 0.03183704 0.0554642 0.07301062 0.03201687 0.05499106 0.07313162 0.03193235 0.05551868 0.07340073 0.03165155 0.05566734 0.07315111 0.03174602 0.05622684 0.07334244 0.03155356 0.05700856 0.07339036 0.0315051 0.05683964 0.07313007 0.03164589 0.05695468 0.07300251 0.03191721 0.05775064 0.07342749 0.03153854 0.05774378 0.07322698 0.03160917 0.05852347 0.07338643 0.03166222 0.05770057 0.07304245 0.03181296 0.05832928 0.07315981 0.03173947 0.05880832 0.07300478 0.03213119 0.05921131 0.0733205 0.03185266 0.0592907 0.07306903 0.03209471 0.05988621 0.07337504 0.03208506 0.06004458 0.07322382 0.03222215 0.06076014 0.07338809 0.03251278 0.06040102 0.0730077 0.0327363 0.06050783 0.07312875 0.03254646 0.06165784 0.07335972 0.03313195 0.06120002 0.07323551 0.03286784 0.06141448 0.07310307 0.03316199 0.06158351 0.07300525 0.0335505 0.06209564 0.0734384 0.03349679 0.0621429 0.07315582 0.03371655 0.06251829 0.07336539 0.03393155 0.06264954 0.07304394 0.03448158 0.0630052 0.07323437 0.03461086 0.06308031 0.07343357 0.03460973 0.06339144 0.07300609 0.03585499 0.06350332 0.07335203 0.03528743 0.06327986 0.0730983 0.03525781 0.06382244 0.07339954 0.03589433 0.06377476 0.07321506 0.03597342 0.06385022 0.0731005 0.03642684 0.06415903 0.07340055 0.03676408 0.06404846 0.07323795 0.03664302 0.06379246 0.07300382 0.03694671 0.06423372 0.07322251 0.0373274 0.06438595 0.07340818 0.037714 0.06416702 0.07307779 0.03770607 0.06438028 0.07320433 0.03829151 0.0641033 0.07301378 0.03828424 0.06448984 0.07340949 0.0385943 0.06449109 0.07437473 0.03914558 0.0644623 0.07441866 0.03842979 0.06438499 0.07438862 0.0377615 0.06425648 0.07433527 0.03709858 0.06391215 0.07440406 0.03611767 0.06366789 0.07431906 0.03556782 0.06328278 0.07434123 0.0349093 0.06287139 0.07432913 0.03433585 0.06224375 0.07432949 0.03363454 0.0615338 0.07432985 0.03302752 0.06089538 0.07434105 0.0325942 0.06024873 0.07434928 0.03224432 0.05952608 0.07442206 0.03195589 0.05869787 0.07435196 0.03169447 0.05736398 0.07438313 0.03151768 0.05661559 0.07443058 0.03152853 0.05570232 0.07435268 0.03161269 0.05495989 0.07435947 0.03179049 0.05421137 0.07434773 0.03203743 0.05339068 0.07439625 0.03243839 0.05278295 0.07437813 0.03280752 0.05204433 0.07433193 0.03336769 0.05139631 0.0743981 0.03403264 0.05091524 0.0744068 0.0346381 0.05051249 0.07435363 0.03524535 0.05017477 0.07435113 0.03590071 0.04982227 0.07434219 0.03682142 0.04962247 0.07435101 0.0376718 0.04952609 0.07436066 0.0384441 0.04951477 0.07439732 0.03922051 0.04956126 0.07435357 0.03992384 0.04973334 0.07436513 0.04085028 0.05007785 0.07440829 0.04185527 0.05033057 0.07432442 0.04242819 0.05079299 0.07432609 0.04321414 0.051409 0.07436382 0.04399025 0.05188691 0.07439875 0.04447114 0.05246669 0.07434415 0.04497087 0.05306339 0.07439851 0.04537034 0.0537573 0.07432317 0.04576152 0.05456197 0.07434421 0.04609316 0.05549722 0.07442104 0.04633051 0.05592054 0.07437425 0.04641419 0.05661809 0.07435357 0.04648607 0.05735576 0.07435119 0.04648745 0.05810391 0.07437855 0.0464099 0.05849397 0.07443451 0.04632967 0.05918908 0.07438576 0.04616361 0.06011211 0.07434046 0.045825 0.06088906 0.07437598 0.04540359 0.06165605 0.07432585 0.04488295 0.06249254 0.07435691 0.04410594 0.06308358 0.07435482 0.04337859 0.06368118 0.07430183 0.04242849 0.06411027 0.07436412 0.0413677 0.06429302 0.07442969 0.04066985 0.06442046 0.07441955 0.0399717 0.06440091 0.07455134 0.03925943 0.0642929 0.07465547 0.03858512 0.06410366 0.07474398 0.03883725 0.06396681 0.07474344 0.03747498 0.06418043 0.07462799 0.03744745 0.06411051 0.07450294 0.03680211 0.06375271 0.07461601 0.036098 0.06359869 0.0747298 0.03619539 0.06343758 0.07452923 0.0353012 0.0631408 0.07470178 0.03517556 0.06303519 0.07452011 0.03467226 0.06252813 0.07466042 0.03422635 0.06258261 0.07450276 0.03408384 0.06227385 0.07474786 0.03424507 0.06205528 0.07451862 0.03355473 0.06156951 0.07468724 0.03335714 0.06130456 0.07456058 0.03297072 0.0601952 0.0747435 0.03262305 0.06031918 0.07468634 0.03253811 0.06038755 0.07453274 0.03239601 0.05954921 0.07466441 0.03216302 0.05884659 0.07458996 0.0318588 0.05825668 0.07439696 0.03161525 0.05848973 0.07474356 0.03203529 0.0577318 0.07457792 0.03164613 0.05787396 0.07469737 0.03181499 0.05642801 0.07474577 0.03191882 0.05661201 0.07467514 0.03172552 0.05570381 0.07449471 0.03166818 0.05527806 0.07467615 0.0319249 0.05485939 0.07459324 0.03194421 0.0549435 0.07474738 0.03222161 0.05444926 0.07448261 0.03200042 0.05408918 0.07470464 0.03238981 0.05390727 0.07458806 0.03230118 0.05268347 0.0747441 0.03332054 0.05292856 0.07459324 0.03285229 0.05289387 0.07467061 0.03297501 0.05207437 0.07451277 0.03342908 0.05188548 0.07463657 0.0337513 0.05135053 0.07471299 0.03451609 0.05116647 0.07459843 0.03449863 0.05108839 0.07474803 0.03509259 0.05057168 0.07452982 0.03529483 0.05061995 0.07467222 0.03549319 0.05019378 0.0745874 0.03613382 0.05034261 0.07474088 0.03645223 0.04994088 0.07449996 0.03664594 0.04997277 0.07467031 0.03708708 0.04970133 0.0745145 0.03757768 0.04979449 0.07467168 0.03795272 0.04999595 0.07474511 0.03783452 0.04964619 0.07461243 0.03863292 0.04990231 0.07474756 0.03911083 0.04984754 0.07469654 0.0401895 0.04966616 0.07459229 0.03981494 0.04981619 0.07453501 0.04087555 0.05029976 0.07474786 0.04133009 0.05003625 0.07455462 0.04152399 0.05024975 0.07469743 0.04161214 0.05052161 0.07456749 0.04258328 0.0507394 0.07472503 0.04249179 0.05109077 0.07465541 0.04329907 0.05106043 0.07449501 0.04349189 0.05143618 0.07474231 0.04346948 0.05158925 0.07459777 0.04400342 0.05215138 0.07471227 0.04432898 0.05240923 0.07455974 0.04481065 0.05273336 0.07464617 0.04494541 0.05344557 0.07472997 0.04523497 0.05345994 0.07452577 0.0455287 0.05414748 0.0746653 0.04571461 0.05410033 0.07452791 0.04583317 0.05486047 0.0745148 0.0461198 0.05432605 0.0747478 0.04557073 0.05548477 0.07468122 0.04611688 0.05620038 0.07462477 0.04630452 0.05639535 0.07474523 0.04608422 0.05695277 0.07460236 0.04636996 0.05770736 0.0747447 0.04609173 0.05762493 0.07456362 0.04637283 0.05854552 0.07468849 0.04609888 0.05925041 0.07459485 0.046018 0.0598011 0.07474219 0.04554438 0.06000447 0.07450968 0.04580307 0.06003439 0.07465386 0.04564708 0.0608775 0.07462579 0.04523968 0.06103825 0.07474637 0.04484647 0.06166273 0.07449907 0.04480326 0.06147891 0.07468354 0.0447213 0.06219351 0.07461786 0.0442081 0.06254619 0.07473915 0.04350799 0.06287872 0.07456904 0.04349219 0.06321716 0.07463228 0.04288619 0.06342566 0.07450771 0.04274547 0.06346571 0.07470864 0.04221075 0.06361949 0.07474297 0.04163724 0.06381905 0.07452118 0.0419594 0.06399887 0.07459282 0.04131311 0.06408935 0.07468098 0.04060953 0.06398135 0.07474637 0.04028064 0.06426125 0.07466697 0.03971356 0.06299674 0.08857476 0.03885042 0.06299078 0.08799999 0.03855109 0.06293046 0.088611 0.03810817 0.06279581 0.08799999 0.03741323 0.06257706 0.08860951 0.03680247 0.0623036 0.08799999 0.03616303 0.06225544 0.08860033 0.03610789 0.06186383 0.08859777 0.03549367 0.06124395 0.08799999 0.0347169 0.06137418 0.08858674 0.03489279 0.06083494 0.08862805 0.03439658 0.06011998 0.08859235 0.03387027 0.05965447 0.08799999 0.03359514 0.05916202 0.08859586 0.03340393 0.05823224 0.08799999 0.03311854 0.05848354 0.0885815 0.03318858 0.05788481 0.08862131 0.033073 0.05674636 0.08799999 0.03298377 0.05730271 0.08858072 0.03300976 0.0565114 0.08859425 0.03302067 0.05553859 0.08859872 0.03317731 0.05484139 0.08799999 0.03337001 0.05467545 0.08861643 0.03347575 0.05411654 0.0886746 0.03375846 0.05328524 0.08799999 0.03426951 0.05351102 0.08861422 0.03412264 0.05277776 0.08857768 0.03473538 0.05204504 0.08799999 0.03556424 0.05214345 0.08860051 0.03547185 0.05160909 0.08865016 0.03638744 0.05131745 0.08799999 0.03704589 0.05126887 0.08859437 0.03722524 0.05098044 0.08799999 0.038652 0.05107116 0.08863598 0.03812521 0.05099773 0.08856606 0.03898721 0.05104708 0.08864665 0.03965914 0.05113226 0.08799999 0.04029577 0.05122625 0.08859407 0.04064714 0.05162054 0.08799999 0.0417056 0.05166333 0.08858197 0.04175341 0.05213612 0.08859777 0.04250627 0.05237603 0.08799999 0.042831 0.0525884 0.08858901 0.04306668 0.05344176 0.08799999 0.0438677 0.0531578 0.08864498 0.04359352 0.05371141 0.08866369 0.04400116 0.05414503 0.08859115 0.04427349 0.05508369 0.08799999 0.04470342 0.05482673 0.08862608 0.04458701 0.05549854 0.08862763 0.04480022 0.05626916 0.0885961 0.04495441 0.05659538 0.08799999 0.04500102 0.05698412 0.08861541 0.04499346 0.05759006 0.08858025 0.04496896 0.05834102 0.08799999 0.04487568 0.05832737 0.08862334 0.0448451 0.05876094 0.08868348 0.04471707 0.05931246 0.08863651 0.04452568 0.06027293 0.08799999 0.04406744 0.05987226 0.08864498 0.04425472 0.06036144 0.08863651 0.04395794 0.06098026 0.0886358 0.04348033 0.06170594 0.08799999 0.04275286 0.06157213 0.08864849 0.04287141 0.06220984 0.08859276 0.04198402 0.06258815 0.08799999 0.04124307 0.06261056 0.08867001 0.04108083 0.06278192 0.08860111 0.04058605 0.06296408 0.08799999 0.03974735 0.06287461 0.08866435 0.04014837 0.06297463 0.08861136 0.0394805 0.06300884 0.07899999 0.03885024 0.06290471 0.07839047 0.03796696 0.06274753 0.07899999 0.03717738 0.06275099 0.0783174 0.03735977 0.06252634 0.07840365 0.03666448 0.06210416 0.07899999 0.03583699 0.06117594 0.07899999 0.03465056 0.06168341 0.07839298 0.03524696 0.06060761 0.0784074 0.03421002 0.0600211 0.07842117 0.03381478 0.05957061 0.07899999 0.03355473 0.0590586 0.07841229 0.03335934 0.05829954 0.07899999 0.0331375 0.05817371 0.07838648 0.03312224 0.05744779 0.07839602 0.03301858 0.05710488 0.07899999 0.03298622 0.05576765 0.07899999 0.03311854 0.05496251 0.07841044 0.03335261 0.05434548 0.07899999 0.03359514 0.05424988 0.07837003 0.03367555 0.05310493 0.07899999 0.03442412 0.05302482 0.07841652 0.03450489 0.05250281 0.07832849 0.03505396 0.05199152 0.07899999 0.03564274 0.05206149 0.07840085 0.03559452 0.05154091 0.07839912 0.03650319 0.05129045 0.07899999 0.03712636 0.05124181 0.07833015 0.0373739 0.05109643 0.07840228 0.03795129 0.05098062 0.07899999 0.03869962 0.05102688 0.07837861 0.0385167 0.05100691 0.07838958 0.03911775 0.0510835 0.0784198 0.04002934 0.05123549 0.07899999 0.0407781 0.05141019 0.07841265 0.04119271 0.05179756 0.07840698 0.04198205 0.05213814 0.07899999 0.04255264 0.05220282 0.07839816 0.04260128 0.05268394 0.07840889 0.04316318 0.05316996 0.07899999 0.04363036 0.05327796 0.07842069 0.04370766 0.05425697 0.07899999 0.04435062 0.05466109 0.07842528 0.0445317 0.05576121 0.07899999 0.04489272 0.05611693 0.07841533 0.04493188 0.05700469 0.07841455 0.04500478 0.05740457 0.07899999 0.04500102 0.05807018 0.07841563 0.04490429 0.05891627 0.07899999 0.04470342 0.05873996 0.07839697 0.04473716 0.06030094 0.07899999 0.04402792 0.06038308 0.07842558 0.04396206 0.06106841 0.07834398 0.04339164 0.06121945 0.07899999 0.04327237 0.06150901 0.07838654 0.04294896 0.06199485 0.07899999 0.04235082 0.06203711 0.07840144 0.04226583 0.06245911 0.07836776 0.0414679 0.06259232 0.07899999 0.04119473 0.062734 0.07840704 0.04076433 0.06291025 0.07899999 0.04008519 0.06290191 0.07839047 0.04004871 0.06299364 0.0784288 0.03931331 0.06294268 0.07824599 0.03914695 0.06278175 0.07808309 0.03875881 0.06271415 0.07804906 0.03954035 0.06274455 0.07816189 0.04027485 0.06245869 0.07800161 0.04009318 0.06268781 0.07825708 0.0407316 0.06236058 0.0780338 0.04094171 0.06240308 0.07814419 0.04127502 0.06170374 0.07800322 0.04205685 0.06212627 0.07823294 0.04198318 0.06196415 0.07805877 0.04189729 0.06163728 0.07822829 0.04269981 0.06153047 0.07808202 0.04260891 0.06095159 0.07810449 0.04326778 0.06076127 0.07800406 0.04314821 0.06034815 0.07824581 0.04391187 0.06021624 0.07805997 0.04377955 0.05946797 0.07816153 0.04433828 0.0594905 0.07836854 0.0444523 0.05890971 0.0780552 0.04441446 0.05860567 0.07818621 0.04467999 0.05920881 0.07800263 0.0441395 0.05786263 0.07825344 0.04488015 0.05778473 0.07805049 0.0446912 0.05688381 0.07800412 0.04461377 0.05696803 0.07821995 0.04492956 0.05672347 0.0780791 0.0447753 0.05599719 0.07820969 0.04483264 0.05550938 0.07839804 0.04480731 0.0555194 0.07807594 0.04459017 0.05493569 0.07823699 0.0445674 0.05532538 0.07800287 0.04433184 0.05468493 0.0780794 0.04429841 0.05395799 0.07833635 0.04415506 0.05390805 0.0780068 0.04370182 0.05398768 0.07811188 0.04399222 0.05364352 0.07820338 0.04386508 0.05305916 0.07830381 0.04348146 0.05316627 0.07811611 0.04340124 0.05253213 0.07821077 0.04288631 0.05218291 0.07800477 0.04191344 0.05272418 0.07804054 0.04279583 0.05220961 0.07811188 0.04231566 0.05190801 0.07818061 0.04197949 0.05154192 0.07823383 0.04132103 0.05164456 0.07809197 0.04122912 0.05160295 0.07801753 0.04069125 0.05131971 0.07818871 0.04061615 0.05114907 0.07825118 0.04002231 0.05126476 0.0780937 0.03988683 0.05145066 0.07800304 0.03972393 0.05107015 0.07822573 0.03915464 0.05120801 0.07808691 0.03908532 0.05139678 0.07800769 0.03842437 0.05118912 0.07814699 0.03815299 0.05147361 0.07806533 0.037346 0.05150628 0.07820439 0.0368086 0.05215561 0.07800334 0.03615033 0.0518195 0.07812952 0.03627467 0.05206292 0.07822471 0.03572189 0.05245745 0.07807934 0.03541439 0.05294543 0.07810539 0.03482377 0.05307757 0.07826328 0.0345292 0.05324083 0.07800388 0.03485763 0.05346506 0.07812273 0.03435748 0.05365091 0.07837522 0.03403121 0.05381506 0.07825756 0.03397744 0.05389499 0.07802832 0.03423613 0.05411297 0.07813102 0.03391456 0.05500245 0.07800173 0.03378605 0.05471187 0.07810676 0.03363871 0.05536484 0.07819271 0.0333231 0.05548739 0.07804167 0.03348737 0.05593681 0.07834464 0.03310561 0.05653798 0.07811558 0.03317856 0.05658531 0.07833445 0.03302878 0.05734336 0.07800334 0.03338211 0.05693954 0.07803517 0.03329354 0.05756801 0.07819163 0.0331192 0.05798017 0.07806473 0.03333002 0.05878144 0.07824057 0.03333425 0.058685 0.07812094 0.03340947 0.05885398 0.07803529 0.03361254 0.05985152 0.07823544 0.03379166 0.05973392 0.07807463 0.03390306 0.05952632 0.07800126 0.03402137 0.060669 0.078188 0.03437525 0.06076627 0.07805562 0.03465789 0.06109023 0.07836061 0.03462451 0.06088483 0.07800388 0.03496921 0.06142622 0.07815271 0.0351358 0.06162941 0.07803344 0.03566998 0.06212949 0.07838302 0.03589725 0.06211215 0.0781877 0.03604 0.06197649 0.07800406 0.03643947 0.06221663 0.0780788 0.03651309 0.06251388 0.0782392 0.03680199 0.06256496 0.07810252 0.03732091 0.0625751 0.07803368 0.03775483 0.06282663 0.07818174 0.03810632 0.06253623 0.07800203 0.03815114 0.06297349 0.07837599 0.0385254 0.06288433 0.08882451 0.03861045 0.06292867 0.08876562 0.03917253 0.06269061 0.08895647 0.03836226 0.06279677 0.08865839 0.03750127 0.06262588 0.08888763 0.03747391 0.06258749 0.08875858 0.03699493 0.062316 0.08899438 0.03715455 0.0622397 0.08888369 0.03644353 0.06212264 0.08879804 0.03603726 0.06177395 0.0889945 0.03603887 0.06169414 0.08892989 0.03564971 0.06146728 0.08878928 0.03511106 0.06107771 0.08899623 0.03516405 0.06112986 0.08891409 0.03494477 0.0607137 0.0888608 0.03446954 0.06040495 0.0889914 0.03451311 0.0600984 0.08875179 0.03392803 0.05988866 0.08892023 0.0339865 0.05919796 0.08880257 0.03351271 0.05868917 0.08899629 0.03366094 0.05923962 0.08894854 0.03371763 0.05856001 0.0887593 0.03327322 0.05821424 0.08891862 0.03334164 0.05775618 0.08884739 0.03317874 0.05736529 0.0889914 0.03338456 0.05701076 0.0887469 0.03305202 0.05668312 0.08889991 0.03319668 0.05637371 0.08897227 0.03335499 0.05599087 0.08876526 0.03315526 0.05556088 0.08887028 0.03333008 0.05498647 0.08874666 0.03340458 0.05550736 0.0889939 0.03357642 0.05450278 0.08890074 0.03375077 0.05430525 0.08896839 0.03398799 0.05362844 0.08886229 0.0342102 0.05374038 0.0889936 0.03442043 0.05305445 0.08873391 0.03454291 0.05306053 0.0889256 0.03477972 0.05256307 0.08883267 0.03512781 0.05199801 0.08876019 0.03580629 0.05247801 0.08895862 0.03549021 0.0521031 0.08899682 0.03626543 0.0518698 0.08888387 0.0362311 0.05164647 0.08893871 0.03689211 0.0515061 0.08881396 0.03685903 0.05124169 0.08874487 0.03752225 0.05133938 0.08890038 0.03766506 0.05155771 0.08899462 0.03766638 0.0512064 0.0888974 0.03840643 0.05140441 0.08899718 0.03876179 0.05106407 0.08875244 0.03885054 0.0511431 0.08884865 0.03936791 0.05135136 0.08896929 0.03965747 0.05128347 0.08888864 0.04016524 0.05121487 0.0887466 0.04036188 0.0516746 0.0889905 0.04083091 0.05147749 0.0887643 0.04117703 0.0517044 0.08891433 0.04135131 0.05201083 0.0887714 0.04221022 0.05202162 0.08887189 0.04205715 0.05238234 0.08899402 0.04221647 0.05254697 0.08887284 0.0427798 0.05266129 0.08874762 0.04306191 0.05292308 0.08896917 0.04296875 0.05326789 0.08887928 0.04349339 0.05379599 0.08899194 0.04362142 0.05417466 0.08890128 0.04408138 0.05443328 0.08879286 0.04432547 0.05470281 0.08899593 0.04410463 0.05512344 0.08883714 0.04457056 0.0554254 0.08892232 0.04456681 0.05591219 0.08898925 0.04454362 0.05590343 0.08878284 0.04481744 0.05670934 0.08879411 0.04490953 0.05640655 0.08892005 0.04474717 0.05726754 0.08893847 0.04475128 0.05751067 0.088804 0.04488289 0.05802005 0.08876872 0.04484552 0.05847483 0.08891534 0.04460084 0.05817711 0.08899736 0.04448693 0.05934214 0.08896845 0.04419332 0.05940449 0.08887881 0.04432326 0.06003201 0.08886897 0.0439974 0.06086683 0.08899855 0.0430504 0.0606445 0.08893972 0.04346442 0.06057852 0.08879584 0.04370379 0.06129354 0.08883148 0.04302167 0.06153815 0.08895593 0.04249233 0.06188392 0.088777 0.04236066 0.06219488 0.08883368 0.04176497 0.0619775 0.08899319 0.04160732 0.06238365 0.08888131 0.04124361 0.06232851 0.08899128 0.04082083 0.0626133 0.08890581 0.04048842 0.06279611 0.08888804 0.03965342 0.06258082 0.08899593 0.0394203 0.06399089 0.08759033 0.03862297 0.06391251 0.08700001 0.03783124 0.06385248 0.08758783 0.03756618 0.06354397 0.08700001 0.03648495 0.06358706 0.08762997 0.03664594 0.06314605 0.08763277 0.03566402 0.06264078 0.08700001 0.03479689 0.06286138 0.08759039 0.03517854 0.06245583 0.08762747 0.03462719 0.06199431 0.08765679 0.03411448 0.06127244 0.08700001 0.03344166 0.06150597 0.08763229 0.03365677 0.06104993 0.08758282 0.03328883 0.05977874 0.08700001 0.03254777 0.06035929 0.08757865 0.03286057 0.05967545 0.08762556 0.03253966 0.05905181 0.08763313 0.03231686 0.05758082 0.08700001 0.03198945 0.05835938 0.08761256 0.03213912 0.05751901 0.08758944 0.03201842 0.05665516 0.0875808 0.03201031 0.05548965 0.08700001 0.03214728 0.05596214 0.08763349 0.03208798 0.05539387 0.08758538 0.03218561 0.05462419 0.08763647 0.0324257 0.05384552 0.08700001 0.03273183 0.05381244 0.08759891 0.03276783 0.05293852 0.08758586 0.03329724 0.05253165 0.08700001 0.03359782 0.05221533 0.0876013 0.03389626 0.05163228 0.08700001 0.03449606 0.05174732 0.08757442 0.03437477 0.05123358 0.08765828 0.03505313 0.05083936 0.08700001 0.035645 0.05084967 0.08759808 0.03565829 0.050439 0.08764261 0.03658545 0.05016332 0.08700001 0.03738373 0.05025607 0.08761382 0.03714597 0.05011785 0.08765679 0.03779685 0.05001068 0.08759713 0.03861427 0.04999065 0.08700001 0.03947067 0.05022639 0.08759593 0.04076582 0.05038821 0.08700001 0.04135048 0.05054014 0.08764094 0.04167836 0.05135917 0.08700001 0.04320305 0.0509538 0.08761632 0.04251509 0.05143499 0.08758717 0.04324793 0.0521245 0.08758157 0.04402524 0.05286127 0.08700001 0.04466664 0.05280029 0.08767396 0.04457861 0.05351263 0.08759099 0.04507023 0.05470716 0.08700001 0.04565036 0.05459696 0.08757448 0.04558241 0.0555759 0.08764487 0.0458424 0.0566011 0.08700001 0.04599922 0.05628699 0.08764678 0.04595196 0.05701661 0.08760571 0.04599517 0.05799585 0.08700001 0.0459395 0.0577045 0.08758604 0.04596203 0.05859261 0.0876097 0.04581445 0.05956453 0.08700001 0.04553431 0.05940455 0.08758133 0.04557216 0.0602073 0.08758342 0.04522365 0.06124013 0.08700001 0.04459774 0.0609346 0.08759355 0.04478538 0.06160956 0.08759605 0.04426819 0.06278079 0.08700001 0.04300826 0.06224441 0.08758121 0.04363346 0.0627681 0.08760148 0.04296457 0.06322413 0.08757948 0.04219967 0.06362962 0.08700001 0.04127961 0.06346446 0.08764702 0.04164904 0.06368756 0.08762216 0.04105514 0.0640012 0.08700001 0.03957903 0.06388688 0.08760178 0.04022902 0.0639705 0.08764725 0.03949636 0.06400948 0.07999998 0.0391252 0.06398272 0.07934147 0.03879255 0.06386739 0.07999998 0.03755801 0.0638228 0.0794301 0.03743875 0.06322646 0.07999998 0.03574681 0.06332308 0.07939183 0.03600031 0.06246894 0.07941877 0.03463375 0.06222355 0.07999998 0.03432416 0.06105339 0.07999998 0.03327196 0.06121599 0.079382 0.0334202 0.06050318 0.0794025 0.03293967 0.05935156 0.07999998 0.0323801 0.05972468 0.0793904 0.03255778 0.05887365 0.07940167 0.03225564 0.05803918 0.07941848 0.03207945 0.05764859 0.07999998 0.03201943 0.05607533 0.07999998 0.03204399 0.05563414 0.07941395 0.03212898 0.05455565 0.07999998 0.03242927 0.05444663 0.07939285 0.03248411 0.05349755 0.07941257 0.03293764 0.0531488 0.07999998 0.03313404 0.05280143 0.07941132 0.03340232 0.05211246 0.07938784 0.03399193 0.05182045 0.07999998 0.03426575 0.05155646 0.07938808 0.03460806 0.05081242 0.07999998 0.03569018 0.05077588 0.07940369 0.03580456 0.05049192 0.07936006 0.03644996 0.05013912 0.07999998 0.03748959 0.05027484 0.07940149 0.03707164 0.05011445 0.07940858 0.03775608 0.0500071 0.07941311 0.03865748 0.04999876 0.07999998 0.03957903 0.05002045 0.07941186 0.03950178 0.05012226 0.07932418 0.04020255 0.05027145 0.07937246 0.04090118 0.05042415 0.07999998 0.04144918 0.05054259 0.07941895 0.04170811 0.05087864 0.0793786 0.04238384 0.05142617 0.07999998 0.0432915 0.05142688 0.07939034 0.04323261 0.05198574 0.07937288 0.04387265 0.05261981 0.079418 0.04446232 0.05304414 0.07999998 0.04480212 0.05337089 0.0793761 0.04497718 0.05416423 0.0794034 0.04539978 0.05492842 0.07999998 0.04571574 0.05493688 0.07942557 0.04568779 0.05563324 0.07938551 0.04585891 0.05631107 0.07940816 0.0459631 0.05687761 0.07999998 0.04601603 0.0573517 0.0794177 0.04599803 0.05856096 0.07999998 0.04583901 0.05842089 0.07938987 0.04584872 0.0590915 0.0793991 0.04567581 0.06046909 0.07999998 0.04511958 0.05961418 0.07932376 0.04547524 0.06096774 0.07941287 0.04476416 0.06166177 0.07940387 0.04422181 0.06189244 0.07999998 0.04401606 0.06223887 0.0794152 0.04363894 0.06279599 0.07999998 0.04295158 0.06276565 0.07940304 0.04296934 0.06330424 0.07938963 0.04203909 0.06343835 0.07999998 0.04176133 0.06361061 0.07932925 0.04125046 0.06383669 0.07999998 0.04056042 0.0638507 0.07939976 0.04043591 0.06397145 0.07936781 0.03952693 0.06384164 0.0791462 0.03952109 0.0638706 0.07916188 0.03866785 0.06368255 0.07904356 0.03968673 0.06385451 0.07927912 0.04017847 0.06365835 0.07912492 0.04060143 0.06345343 0.07900542 0.04048651 0.06327712 0.07907575 0.04155451 0.06322246 0.07919484 0.04200035 0.06286662 0.07919985 0.04265606 0.06290948 0.07903146 0.04214406 0.06238901 0.07905316 0.04304736 0.06219208 0.07921367 0.04358065 0.06210911 0.07900279 0.04320323 0.06187558 0.07908105 0.04371994 0.06134623 0.07924932 0.04441285 0.06123226 0.07912236 0.04436981 0.0609619 0.07900798 0.04431283 0.06076598 0.07923436 0.04482269 0.06032949 0.07938265 0.0451501 0.06028354 0.07903867 0.04485505 0.0602951 0.0791676 0.04504173 0.05949616 0.07911014 0.0453512 0.05846977 0.07900744 0.04550635 0.05877423 0.07920658 0.0456826 0.05799663 0.07900625 0.04555118 0.05803883 0.07922911 0.0458495 0.05759358 0.07909494 0.04577535 0.05737215 0.07923161 0.04592275 0.05668228 0.07919383 0.045901 0.05667489 0.07903856 0.0457018 0.0561698 0.07921683 0.04587054 0.05547183 0.07900327 0.04541969 0.05563676 0.07908815 0.04566031 0.05494713 0.07922661 0.04562109 0.05465435 0.07912784 0.0454334 0.05448031 0.07904082 0.04521793 0.05396771 0.07927626 0.04525727 0.05364096 0.07909262 0.04492288 0.05344873 0.07900273 0.04456055 0.05308181 0.079225 0.0447098 0.05292731 0.07908421 0.04443383 0.0525729 0.07921296 0.04431748 0.05212843 0.07900559 0.04350465 0.05182951 0.07919067 0.0435791 0.05190813 0.07908487 0.04350376 0.05118477 0.07924246 0.04277688 0.05118566 0.07907259 0.04248994 0.05079877 0.07917666 0.04200446 0.05103909 0.07900583 0.04185515 0.05052721 0.07928764 0.04155743 0.05060124 0.07906544 0.0411942 0.05035078 0.07915019 0.04071825 0.05045157 0.07900321 0.03991925 0.05031287 0.07905226 0.03987377 0.05007231 0.07924216 0.0393843 0.05019414 0.07909232 0.03878778 0.05008512 0.0792638 0.0382995 0.0504601 0.07900285 0.03818202 0.05031812 0.07908749 0.037777 0.0502848 0.07922565 0.03730094 0.05053031 0.07905179 0.03709441 0.05062884 0.07912719 0.03650146 0.05100846 0.0790072 0.03615421 0.05084526 0.07919383 0.03587085 0.05111932 0.07910466 0.03554868 0.0511111 0.07936567 0.03523278 0.05140537 0.0791918 0.03495484 0.05189996 0.07900398 0.03478437 0.05185091 0.07907134 0.03459304 0.05207896 0.07922124 0.03412091 0.05273938 0.07908415 0.03371065 0.05290806 0.07925754 0.03338605 0.05322265 0.07900547 0.03357887 0.05368292 0.07911705 0.03301703 0.05379366 0.0792734 0.03282773 0.05398774 0.07904732 0.03298246 0.05477839 0.07914519 0.03250575 0.05489033 0.07900816 0.03270417 0.05510842 0.07926523 0.03231132 0.05570667 0.07915627 0.03225272 0.05606877 0.07902079 0.03238391 0.05639415 0.07932394 0.03204679 0.05654603 0.07913196 0.03216642 0.05715113 0.07935678 0.03200882 0.0572769 0.07909822 0.03219819 0.0579999 0.07922852 0.03213763 0.0575394 0.07900243 0.03243106 0.05809497 0.07908916 0.03229153 0.05871218 0.07901114 0.03259015 0.05904114 0.07921618 0.03238701 0.05921143 0.07907062 0.0326035 0.05984765 0.07919859 0.03270506 0.06008911 0.07901048 0.03310942 0.06051087 0.07918429 0.03305834 0.06114715 0.07911801 0.03355705 0.06185376 0.07935965 0.03396546 0.06144469 0.07900661 0.03408133 0.06208938 0.07916033 0.03436338 0.06280803 0.07933145 0.03511995 0.06244558 0.0790351 0.03509449 0.0627799 0.07914572 0.0352872 0.06282615 0.07900607 0.03587657 0.06322616 0.07923191 0.03595244 0.06331282 0.07907772 0.03650307 0.06334847 0.07900333 0.03718644 0.06361573 0.07932376 0.03676772 0.0637592 0.07923936 0.03744739 0.06368416 0.0790984 0.03770619 0.06392776 0.07934218 0.03809809 0.06371933 0.07905232 0.03851574 0.06358474 0.07900369 0.03863799 0.06393337 0.08775669 0.03871268 0.06383097 0.08788985 0.03885275 0.06358259 0.08799344 0.038163 0.0638473 0.08773064 0.03780359 0.06374442 0.08783328 0.03760111 0.06352847 0.087861 0.03690713 0.06331819 0.08798998 0.03694117 0.06334006 0.08772766 0.03614997 0.06314194 0.08790677 0.03607279 0.0628879 0.08779412 0.03537589 0.06251847 0.08799266 0.03535038 0.06252038 0.08788204 0.03495615 0.06205385 0.08794069 0.03452557 0.06123024 0.0879985 0.03391188 0.061782 0.08781939 0.03403306 0.06128525 0.08795243 0.03381216 0.06101852 0.08779436 0.03337377 0.06052899 0.08792912 0.03321766 0.06011509 0.08778297 0.03281438 0.05925041 0.0879839 0.03272277 0.05933475 0.08785533 0.03254961 0.05850237 0.08780187 0.03225839 0.05864197 0.08792281 0.03242003 0.057778 0.08791589 0.03225493 0.05735433 0.08774673 0.03206062 0.05744743 0.08799791 0.03243297 0.05692505 0.08792185 0.03221487 0.05631256 0.08779227 0.03211838 0.05603736 0.0879929 0.03243821 0.05542963 0.0877906 0.03226441 0.05547386 0.08790332 0.0323683 0.05460989 0.08798831 0.03279626 0.05463945 0.08784884 0.03255218 0.05368548 0.08776903 0.03290808 0.05389952 0.08791363 0.0329554 0.05320656 0.08799481 0.03359431 0.05321496 0.08791601 0.03336733 0.05267041 0.08776706 0.03358143 0.05221092 0.08791172 0.03416353 0.05181598 0.08779191 0.03441327 0.05217981 0.08799362 0.03447026 0.05134975 0.08791369 0.03522086 0.0510531 0.0879932 0.03605926 0.05075865 0.08784759 0.03611296 0.05067485 0.08773839 0.0361303 0.05041879 0.08789271 0.03717452 0.05039244 0.08798283 0.03808391 0.05041128 0.08799946 0.03921216 0.05027014 0.08790332 0.03797781 0.05009984 0.08780336 0.038652 0.05001556 0.08762872 0.03936642 0.05018573 0.08788847 0.03951245 0.05009704 0.08767068 0.04004263 0.05047237 0.08795422 0.04063159 0.05031883 0.08782762 0.04068744 0.05068355 0.08788383 0.04160517 0.05076515 0.0879901 0.04123294 0.05090951 0.08779692 0.0422666 0.05115687 0.08795678 0.04233855 0.05145406 0.08774554 0.04317885 0.05148643 0.08799684 0.04263204 0.05156159 0.08789831 0.04310864 0.05216211 0.08775782 0.04397332 0.05225551 0.08797925 0.04366934 0.05219578 0.08789658 0.04383546 0.05288016 0.0879116 0.04440301 0.05336809 0.08799618 0.04452413 0.05350571 0.08776837 0.04498583 0.05361121 0.08789443 0.04491513 0.05426639 0.08779108 0.04535382 0.05451387 0.08793729 0.04528743 0.05480182 0.08772993 0.04559653 0.05538028 0.08799582 0.04540288 0.05529868 0.08789104 0.04560607 0.05612736 0.0878852 0.0457831 0.05707532 0.08799773 0.04560589 0.05692517 0.08786344 0.04586058 0.05772966 0.08781647 0.04586172 0.05806618 0.08795166 0.04565095 0.05850058 0.08775693 0.04577332 0.05899727 0.08791041 0.04549944 0.05937808 0.08777362 0.04550498 0.05931138 0.0879969 0.0451802 0.05999994 0.08793514 0.04506677 0.06014871 0.08775788 0.04518228 0.06090104 0.08777111 0.04472261 0.06102484 0.0879414 0.0444312 0.06135636 0.08799815 0.04395103 0.06161004 0.08776009 0.04418283 0.06196159 0.08790332 0.04366844 0.06231254 0.08776307 0.04345548 0.0624026 0.08799457 0.04280728 0.06262588 0.08788794 0.04286962 0.06284749 0.0877363 0.04274833 0.0630173 0.08795678 0.04199975 0.06316071 0.08778429 0.04215276 0.06346774 0.08784109 0.04133343 0.06329488 0.08799332 0.04107773 0.06373161 0.08779209 0.04056793 0.06362462 0.08795779 0.04017418 0.06382244 0.08783 0.0399419 0.06498301 0.08666855 0.03884935 0.06500804 0.08599996 0.03925615 0.06484097 0.08599996 0.03727394 0.06490415 0.08661884 0.03778064 0.06469005 0.08663314 0.03682643 0.0643835 0.08658546 0.03591501 0.06415539 0.08599996 0.0353952 0.06370121 0.08662897 0.03464508 0.06306064 0.08599996 0.0337342 0.06323158 0.08660304 0.0339899 0.06272941 0.0866037 0.0334227 0.06195896 0.08659905 0.03272181 0.06155997 0.08599996 0.03241199 0.06118375 0.08663576 0.03219193 0.06033819 0.08599996 0.03172272 0.06030005 0.08660072 0.03171217 0.05903184 0.08599996 0.03124976 0.05937147 0.08659046 0.03136223 0.05857676 0.08657443 0.03115785 0.05745589 0.08599996 0.03100079 0.05775541 0.08660066 0.03103959 0.05699163 0.08658611 0.03100204 0.05586183 0.08599996 0.03106909 0.05619937 0.08663439 0.03104907 0.05542355 0.08659476 0.03115993 0.05431288 0.08599996 0.03145188 0.05460655 0.0865792 0.03136783 0.05388599 0.0865978 0.03163462 0.05269944 0.08599996 0.03223097 0.0531463 0.08656907 0.03198987 0.05248832 0.08659774 0.03239768 0.05187076 0.08659046 0.03286403 0.05130404 0.08599996 0.03336519 0.05126571 0.08662879 0.03343302 0.05073487 0.08664894 0.03404426 0.05018842 0.08599996 0.03476715 0.05032008 0.08667367 0.03463214 0.05005812 0.0865904 0.03502899 0.04966413 0.08667469 0.03584671 0.04947501 0.08599996 0.03626102 0.04941189 0.08660328 0.03647989 0.04921346 0.08661061 0.0371868 0.04900413 0.08599996 0.03819984 0.04907482 0.08665019 0.03799718 0.0490067 0.08659988 0.03878146 0.04902386 0.08657443 0.03960603 0.04909992 0.08599996 0.04033553 0.04912412 0.08658432 0.04039287 0.04958701 0.08599996 0.04205971 0.0494278 0.08663308 0.04155415 0.0497809 0.08660286 0.04244762 0.0505712 0.08599996 0.04379421 0.05039107 0.08661174 0.04350543 0.05112969 0.08662468 0.04442745 0.05180656 0.08599996 0.04510104 0.0515713 0.08657157 0.0448752 0.05218237 0.08663314 0.04537588 0.05295348 0.08599996 0.04590851 0.05284357 0.08658313 0.0458334 0.05369198 0.08660614 0.04628443 0.05425882 0.08599996 0.04653096 0.05486756 0.08661037 0.04670959 0.0558061 0.08599996 0.04692065 0.05583226 0.08664077 0.04690414 0.05657327 0.08660089 0.04698485 0.05734282 0.08599996 0.04700475 0.05757999 0.08660215 0.04697912 0.0587818 0.08599996 0.04680716 0.05856114 0.08660036 0.04684227 0.0595625 0.08659672 0.04657942 0.06016415 0.08599996 0.04636085 0.06047999 0.0866298 0.04619413 0.06135177 0.08658111 0.0457158 0.06167984 0.08599996 0.04550933 0.06211853 0.08659952 0.04514366 0.06300902 0.08599996 0.04430294 0.06271344 0.08660191 0.04459398 0.06323122 0.08661144 0.04400831 0.06384062 0.08660423 0.04314821 0.06393694 0.08599996 0.04300516 0.06429326 0.08660465 0.04227703 0.06471157 0.08599996 0.04123413 0.06456232 0.08663076 0.04158473 0.06484615 0.08659505 0.04056656 0.06496816 0.08662521 0.03962159 0.06501084 0.08099997 0.03914308 0.06500136 0.08040809 0.03898245 0.06481331 0.08099997 0.03715294 0.06478393 0.0803194 0.03723514 0.06430256 0.08040916 0.0357396 0.06410378 0.08099997 0.03529447 0.0635873 0.08039361 0.03446131 0.06322878 0.08099997 0.03396046 0.06298649 0.08040946 0.03369712 0.06228268 0.08039945 0.03299182 0.06179809 0.08099997 0.03256273 0.06150561 0.0803194 0.03241181 0.06068378 0.08037072 0.0319032 0.05987387 0.08099997 0.03151303 0.0600146 0.08034062 0.03160673 0.05860102 0.08040523 0.03116494 0.05813813 0.08099997 0.03106909 0.05700826 0.0804255 0.03100091 0.05613881 0.08099997 0.0310176 0.05503499 0.08040219 0.03124862 0.05420649 0.08099997 0.03149056 0.05410277 0.08038836 0.03154426 0.05317872 0.0804122 0.03197419 0.05295348 0.08099997 0.03209143 0.05235368 0.0804066 0.0324859 0.0518065 0.08099997 0.0328989 0.05155456 0.08040821 0.03314304 0.05088347 0.08040195 0.0338422 0.0505712 0.08099997 0.03420573 0.05038011 0.08034616 0.03452748 0.04989457 0.08043509 0.03532427 0.04976493 0.08099997 0.03557127 0.04956084 0.08039045 0.03607094 0.04927211 0.08099997 0.03688454 0.04923778 0.08042466 0.03705114 0.04900622 0.08099997 0.03845757 0.04902768 0.08039581 0.03961414 0.04907912 0.08099997 0.04025459 0.04916608 0.08041232 0.04062938 0.04940778 0.08042085 0.04151713 0.04949373 0.08099997 0.04178529 0.04970306 0.08039534 0.04226893 0.05008971 0.08099997 0.04305493 0.05049681 0.08040821 0.04365491 0.05089884 0.08099997 0.04418438 0.05115467 0.08037459 0.04445648 0.05200141 0.08099997 0.04526787 0.05270361 0.08041566 0.04575115 0.05347281 0.08099997 0.04619395 0.05349868 0.08037436 0.04618453 0.05425667 0.08041387 0.04651272 0.05502241 0.08099997 0.04676645 0.05665713 0.08099997 0.04700475 0.056804 0.08039474 0.0469973 0.05819386 0.08099997 0.04692065 0.05859756 0.08043074 0.04683834 0.05987393 0.08099997 0.04648691 0.05934 0.08042985 0.04664957 0.06010198 0.08040094 0.04636996 0.06084704 0.08042335 0.04601299 0.06168293 0.08099997 0.04551368 0.0615276 0.0804004 0.04559123 0.06216245 0.08039969 0.04510617 0.0628736 0.08040624 0.04443299 0.06300592 0.08099997 0.04430013 0.0634942 0.08041697 0.04366898 0.06394052 0.08099997 0.04300725 0.06430315 0.08038759 0.04225218 0.06474518 0.08099997 0.04111468 0.064583 0.08040559 0.04153889 0.06478106 0.08037585 0.0408284 0.06493902 0.08041042 0.03996646 0.06489133 0.08018243 0.0394116 0.06463927 0.08003592 0.04002684 0.06447249 0.08000248 0.04047346 0.06481224 0.08022379 0.0403639 0.0645321 0.08019715 0.04141372 0.06450414 0.08007937 0.04104292 0.06413692 0.0800423 0.04194283 0.06416887 0.08019262 0.04232633 0.06392252 0.08037865 0.04299634 0.06323766 0.08000409 0.04340922 0.06382435 0.08015424 0.04292148 0.06343352 0.08004313 0.04327082 0.06342834 0.08020097 0.04361116 0.06295168 0.08022385 0.04422789 0.06262731 0.08009129 0.04441022 0.06222951 0.08024501 0.04497665 0.06186246 0.08004325 0.04500263 0.06126374 0.08018952 0.04565966 0.06109732 0.08000421 0.0454182 0.06045305 0.08011847 0.0460385 0.06049257 0.08025676 0.04613572 0.05991208 0.08000487 0.04604363 0.05951523 0.08022642 0.0465216 0.05890476 0.08005803 0.04651427 0.05893808 0.08022123 0.04668539 0.05826359 0.08021867 0.0468223 0.05791485 0.0800116 0.04657459 0.05781769 0.08036565 0.04694932 0.05763739 0.08012014 0.04681277 0.05667328 0.08016687 0.04688346 0.05694657 0.08007603 0.04677802 0.05637037 0.08000326 0.0465691 0.05578422 0.0803247 0.0468896 0.05568104 0.0800721 0.04665744 0.05501884 0.08036679 0.04674184 0.05505168 0.08014619 0.04661655 0.05485045 0.08000391 0.0462864 0.05410492 0.08021837 0.04637664 0.05429482 0.08007162 0.04628992 0.05334931 0.08001077 0.04572218 0.0531966 0.08018535 0.04591983 0.052796 0.08005666 0.04550874 0.05241668 0.0802139 0.04546332 0.05199259 0.080352 0.04522699 0.05182296 0.08000558 0.0445761 0.05137246 0.08018636 0.044555 0.05171185 0.08007884 0.04471373 0.05066853 0.08023881 0.04378348 0.0507732 0.08008778 0.04369312 0.05068534 0.08000677 0.04327261 0.05007237 0.08034741 0.04297637 0.0502268 0.08013582 0.04296648 0.04996657 0.08005231 0.04224699 0.04966557 0.08025586 0.04206138 0.04968243 0.08000242 0.0410366 0.04953986 0.08010387 0.04133313 0.04936784 0.08023864 0.04115849 0.04914337 0.08025783 0.04020214 0.04935234 0.08007955 0.04046654 0.04942178 0.08000254 0.039397 0.04915833 0.08012568 0.03938817 0.04901444 0.08035367 0.03876864 0.04921495 0.08008682 0.03853547 0.04909092 0.0803346 0.03789263 0.04943376 0.08000677 0.03800117 0.04927992 0.08012622 0.03763103 0.04940313 0.0802477 0.03667998 0.04951369 0.08005326 0.03700405 0.04993283 0.08006376 0.03577291 0.05025368 0.08000272 0.03546893 0.0499351 0.08023715 0.03537571 0.05057954 0.08009546 0.03455138 0.05112296 0.08019268 0.03370392 0.05137288 0.08001613 0.0338096 0.05183297 0.08009767 0.03314405 0.05204784 0.08022928 0.03280192 0.05262243 0.08000344 0.0327847 0.05258613 0.08018916 0.03244906 0.05274796 0.08005982 0.03252434 0.05333387 0.08018362 0.03199911 0.05373817 0.08003497 0.03202581 0.05413538 0.08016765 0.03165137 0.05487817 0.08001154 0.03163385 0.05535233 0.08018177 0.03127187 0.05555462 0.08002394 0.03145909 0.05600398 0.0803644 0.03106749 0.0565046 0.08007442 0.03123903 0.05700099 0.08020323 0.03108137 0.05737721 0.0800023 0.03141623 0.05752032 0.08005905 0.03127181 0.05781394 0.08036065 0.03105133 0.05830848 0.08013343 0.03125929 0.0587024 0.08018231 0.03128433 0.05859965 0.08003401 0.03147047 0.05939519 0.080343 0.03138089 0.05964547 0.08006078 0.03171056 0.05993121 0.08014947 0.03170037 0.06021827 0.08000516 0.03208428 0.06089019 0.080132 0.03218179 0.06154215 0.08005189 0.03273189 0.0622493 0.08020365 0.03307658 0.06233865 0.0800032 0.03356415 0.0625239 0.08010196 0.0334708 0.06298947 0.08022791 0.03380745 0.06309676 0.0800414 0.03426271 0.06350547 0.08016371 0.03455007 0.06392836 0.08035767 0.03502362 0.06367659 0.08001005 0.03528648 0.06410825 0.08017861 0.03555428 0.06420844 0.08004456 0.03622835 0.06458431 0.080352 0.03649091 0.06443929 0.0801419 0.03647369 0.06459534 0.08008819 0.03725695 0.06444746 0.08000189 0.03751873 0.064933 0.08037227 0.03802889 0.06488877 0.08022308 0.03822731 0.06473231 0.08005666 0.03839117 0.064839 0.08684718 0.03825831 0.06476551 0.08692777 0.03934103 0.0645622 0.08699333 0.03799527 0.06467914 0.08688026 0.03740912 0.06444269 0.08692473 0.03675156 0.06434094 0.08683121 0.03610205 0.06413865 0.08699595 0.0364198 0.06380915 0.08696806 0.03540885 0.06410187 0.08664178 0.03534209 0.06385231 0.08684676 0.03512281 0.06296485 0.08699727 0.03430169 0.06316322 0.08681756 0.03405231 0.06317824 0.08692282 0.03427457 0.06238687 0.08692568 0.03338891 0.06236416 0.08675479 0.0331518 0.06177616 0.08699434 0.03308272 0.06169277 0.08686619 0.03269517 0.06102806 0.08684521 0.0322389 0.06084138 0.08699369 0.03241991 0.06024456 0.08677566 0.03176432 0.06009685 0.08692264 0.03186237 0.05951511 0.08699649 0.03181821 0.05915135 0.08679819 0.03138148 0.05854761 0.08693003 0.03138351 0.0581879 0.08678352 0.0311672 0.05763536 0.08698111 0.03136515 0.05716001 0.08677732 0.03107523 0.05706924 0.08692598 0.03121602 0.05571395 0.08699792 0.03149515 0.05585521 0.08683574 0.03119802 0.05549341 0.08696508 0.0314446 0.05498045 0.08673876 0.03131419 0.05462843 0.08682775 0.03147375 0.05392801 0.08695286 0.0319032 0.05396211 0.0868178 0.03171139 0.05307823 0.08677208 0.03210264 0.05311465 0.08699339 0.0324493 0.0527684 0.08691859 0.03246718 0.0520451 0.08677744 0.0328111 0.05175721 0.08684384 0.03312247 0.05176115 0.08696049 0.0333392 0.05134266 0.0869956 0.03387361 0.05111527 0.08685302 0.0337857 0.05067223 0.08690273 0.03442364 0.05018609 0.08699411 0.03558963 0.05018168 0.08691745 0.03523021 0.04992699 0.0867576 0.03540396 0.04963898 0.086919 0.03644537 0.04954546 0.08699482 0.03740084 0.04931974 0.08680957 0.03712439 0.04920077 0.0868926 0.03834056 0.04939728 0.0869922 0.03849333 0.0490657 0.08676427 0.03904324 0.0492683 0.08694672 0.03942358 0.04917752 0.08681941 0.04011249 0.04947441 0.08699494 0.04021078 0.04924649 0.08667135 0.04089343 0.04950368 0.08686542 0.04134243 0.04975974 0.08699196 0.04142141 0.04994541 0.08678203 0.04261785 0.05006021 0.08689588 0.04260444 0.05014312 0.08696848 0.04248666 0.05073016 0.08689641 0.0436784 0.05101728 0.08699715 0.04367375 0.05079722 0.08673346 0.04396915 0.0514881 0.08676409 0.0447086 0.05138462 0.08692628 0.04437375 0.0520972 0.08698332 0.04487389 0.05215859 0.08687305 0.04517531 0.05301636 0.08678382 0.0458498 0.0528835 0.08690494 0.04563498 0.05339348 0.08699637 0.04569011 0.05385118 0.08689981 0.0461502 0.05386841 0.08672159 0.04631245 0.05468404 0.08678913 0.04657173 0.05470877 0.08698695 0.0463069 0.05558025 0.08682328 0.04676187 0.05569279 0.08694553 0.04663145 0.05654054 0.08699405 0.04660302 0.056629 0.08677518 0.04691857 0.05692648 0.08685618 0.04686397 0.05820655 0.08672273 0.0468716 0.05811327 0.08699262 0.0465542 0.05757397 0.08688193 0.04681414 0.05860167 0.08691054 0.04663676 0.05935841 0.08676826 0.04657047 0.05969721 0.08695155 0.04625266 0.06005781 0.08678126 0.04630434 0.06064862 0.08689016 0.04592746 0.06118851 0.08682078 0.04570072 0.06119138 0.08699649 0.04536503 0.0619654 0.08676904 0.04518675 0.06230568 0.08691704 0.04470664 0.06251341 0.08698594 0.04428416 0.06269282 0.08677929 0.04450774 0.06306356 0.08687955 0.04397124 0.06364965 0.08676004 0.04334062 0.06344199 0.08689785 0.04342424 0.06357294 0.08699214 0.04288911 0.06404721 0.08684176 0.04251855 0.06416314 0.08697861 0.04172164 0.06429201 0.08685839 0.04193603 0.06459689 0.08683371 0.04111957 0.06441771 0.08699381 0.04075103 0.06481224 0.08675444 0.04039788 0.0646857 0.0868991 0.04038411 0.06457567 0.08699727 0.03945893 0.06487733 0.08681011 0.03957605 0.06596636 0.08136105 0.03966242 0.06598931 0.08139204 0.03856343 0.06589174 0.08118218 0.03878796 0.06580764 0.08112758 0.03982448 0.06565147 0.08101028 0.03908407 0.06582617 0.08141857 0.0407769 0.06553614 0.08100956 0.04027926 0.06578671 0.0812208 0.04054671 0.06554496 0.08107739 0.0409975 0.06560432 0.08123433 0.04139465 0.06554001 0.08142054 0.0418365 0.06534969 0.08112889 0.04191589 0.06520587 0.08100849 0.04165583 0.06525897 0.08133363 0.04254454 0.06495773 0.08106648 0.04268741 0.06496518 0.08124202 0.04305559 0.06479156 0.08140218 0.04349827 0.06437563 0.08109813 0.04382985 0.06437504 0.08100503 0.04344815 0.06436645 0.08125865 0.04407984 0.06431996 0.08141201 0.04423302 0.06372052 0.08135294 0.04496967 0.06336408 0.08100771 0.04484617 0.0636816 0.08114248 0.04481399 0.0631147 0.08138918 0.04559689 0.06303894 0.0811339 0.04548001 0.06244015 0.08136022 0.04615795 0.06232124 0.08114999 0.04608905 0.0620718 0.08102637 0.04605078 0.06168729 0.08140081 0.0466789 0.06165552 0.08119064 0.04658788 0.0606907 0.08139878 0.04720985 0.0604906 0.0810123 0.04692023 0.06096887 0.08114433 0.04693347 0.05986863 0.08117866 0.04741925 0.05964082 0.08136683 0.04759502 0.0591641 0.08105623 0.04747742 0.0588414 0.08100128 0.04737246 0.058748 0.0813868 0.04782325 0.05878704 0.08118504 0.04771554 0.05790394 0.08138471 0.04794889 0.0577827 0.08113217 0.04782128 0.05745899 0.08102226 0.04765212 0.05702787 0.08141124 0.04799789 0.05698585 0.08124649 0.04793918 0.05637115 0.08100467 0.04759472 0.05656749 0.0811311 0.04783606 0.05610901 0.08136063 0.04794621 0.05567467 0.0811612 0.04777592 0.05505001 0.08134382 0.04777485 0.05552417 0.08104074 0.0475862 0.05445182 0.08111476 0.04746234 0.0543769 0.08142447 0.04760873 0.05396825 0.08127492 0.04742449 0.05373287 0.08102101 0.04703938 0.05227988 0.08100187 0.04619109 0.05349266 0.08140766 0.04728573 0.05316728 0.08117341 0.04702109 0.05250638 0.0813933 0.04679852 0.05216777 0.08124619 0.04652416 0.05240064 0.08109652 0.04650777 0.05136042 0.08138167 0.04601198 0.05140638 0.08115535 0.04588848 0.05135285 0.08106464 0.04570323 0.05052548 0.08138829 0.04524421 0.05089622 0.08100479 0.04506266 0.05069017 0.08122581 0.0453127 0.05031913 0.08108496 0.04472017 0.04999506 0.08135497 0.04463386 0.04973077 0.08119547 0.04414492 0.04943251 0.08140522 0.04386651 0.04972958 0.08102911 0.04376256 0.04928719 0.08119684 0.04345303 0.04898649 0.0813964 0.04308831 0.04898083 0.08106595 0.04255312 0.04876631 0.08121967 0.04244381 0.04862606 0.08140695 0.0422911 0.04931217 0.08100086 0.04279649 0.04828923 0.08139282 0.04126411 0.04863959 0.08101212 0.04124021 0.0484721 0.08114957 0.04142355 0.04823452 0.08124703 0.04076439 0.04831492 0.08110082 0.04047 0.04804438 0.08140826 0.03991401 0.04809242 0.08123087 0.03961664 0.04826366 0.08105385 0.03943181 0.04801017 0.08139258 0.03856748 0.0481233 0.08116191 0.03883999 0.04827308 0.08107161 0.03813391 0.04817485 0.08121359 0.03768205 0.04813909 0.08138662 0.03745406 0.04841589 0.0810011 0.0385496 0.04853546 0.08108103 0.03661841 0.04833781 0.08139646 0.03657156 0.04864436 0.08101743 0.03673833 0.04850125 0.0812245 0.03625851 0.04863888 0.08140975 0.03567558 0.04895412 0.08120787 0.03514593 0.04912382 0.08139121 0.03464508 0.04951643 0.08100974 0.03466403 0.04907602 0.08109575 0.03515642 0.04953193 0.08120542 0.034132 0.04971408 0.08140915 0.03372043 0.0498228 0.08108812 0.03392273 0.05008226 0.08121192 0.03336876 0.05034607 0.08100718 0.0335015 0.05027276 0.08141976 0.03302305 0.05076915 0.08123391 0.03259569 0.0507189 0.08108514 0.03285127 0.05086928 0.08139812 0.03241598 0.05142408 0.08100396 0.03245979 0.05151778 0.08107352 0.03214591 0.05156481 0.08139526 0.0318315 0.05165833 0.08121013 0.03186416 0.05229145 0.08133935 0.03134602 0.05279695 0.08112204 0.03121513 0.05267643 0.08100879 0.03153473 0.05307328 0.0813893 0.03090715 0.05356574 0.08125007 0.03074681 0.05416166 0.08137905 0.03046149 0.05398869 0.0810092 0.03091055 0.05396115 0.0810886 0.03074997 0.05469197 0.08119177 0.03039836 0.05547988 0.08139002 0.03012949 0.05534833 0.08107751 0.03037261 0.05553454 0.08100461 0.03052133 0.0556358 0.08121168 0.03019052 0.05681496 0.08140379 0.02999973 0.05653315 0.0812841 0.03005456 0.05659818 0.08113354 0.03015977 0.05686664 0.08103817 0.03029084 0.05745345 0.08119094 0.03010904 0.0578801 0.08140963 0.03004539 0.05797785 0.08100408 0.03045421 0.0583108 0.0810588 0.03034365 0.0582838 0.08122986 0.03016448 0.05876731 0.08140957 0.03017753 0.05908906 0.08120566 0.03033417 0.05988442 0.08138179 0.03047597 0.05989629 0.08106529 0.03072178 0.0596174 0.08101004 0.03077566 0.06001281 0.08121222 0.03060829 0.06091111 0.08139038 0.03089946 0.06086438 0.08117222 0.03099685 0.06115031 0.08100855 0.03142392 0.06170529 0.08137089 0.03133696 0.06160128 0.0811668 0.03140544 0.06242936 0.08108282 0.03207796 0.06241703 0.0814349 0.03181254 0.0625022 0.0812329 0.03195881 0.06308746 0.08100819 0.03286337 0.06313192 0.08139413 0.03241789 0.06334882 0.08116245 0.03278946 0.06390535 0.08139395 0.03322732 0.06391644 0.0811547 0.03343671 0.06408023 0.0810061 0.03407847 0.06454527 0.08137506 0.03410691 0.06446599 0.0811429 0.03422433 0.06501823 0.0813446 0.03494042 0.0648995 0.08102154 0.03541791 0.06482452 0.08112239 0.03488928 0.06529068 0.08139044 0.03551721 0.06532418 0.08116233 0.03590071 0.06551891 0.08134925 0.03613328 0.06534749 0.08100306 0.03691172 0.06581944 0.08139568 0.03720217 0.06551766 0.08105903 0.03699225 0.06570273 0.0812112 0.03705465 0.06587094 0.08125752 0.03787589 0.06575602 0.08109462 0.03804308 0.06598341 0.08566397 0.03879112 0.0659278 0.08562344 0.03791636 0.06565815 0.08559775 0.03655463 0.06529808 0.0856167 0.03551751 0.06441426 0.0855956 0.03389519 0.0637263 0.08559131 0.03302389 0.06292247 0.08560937 0.03222346 0.06203949 0.08560174 0.03154766 0.06128865 0.08565688 0.03110218 0.0604875 0.08557444 0.03070384 0.05938673 0.08560806 0.03032225 0.05833435 0.08564621 0.03011029 0.05722016 0.08559668 0.03000098 0.05586463 0.08560663 0.03007149 0.05476278 0.08560276 0.03028637 0.05399918 0.08568167 0.0305376 0.05351221 0.08556807 0.0307033 0.05272227 0.08559119 0.03108423 0.05175554 0.08562165 0.03168851 0.05075418 0.08565038 0.03253293 0.0500887 0.08560866 0.03323554 0.04933315 0.08561319 0.03428685 0.04879939 0.08558142 0.03529495 0.04845941 0.08561176 0.03617727 0.04823583 0.0856024 0.0369696 0.0480737 0.08564549 0.03793036 0.04800343 0.08557647 0.03878015 0.04802995 0.08560806 0.03967684 0.04814308 0.08559316 0.04058408 0.04836708 0.08566784 0.04148936 0.04862105 0.08561336 0.04227101 0.04900294 0.08565688 0.04310065 0.04946827 0.08563297 0.04391139 0.05013239 0.0856139 0.04481601 0.05086231 0.08561062 0.04557585 0.0517174 0.08560752 0.0462867 0.05268263 0.08558994 0.04689431 0.05351436 0.08560955 0.04729253 0.05436241 0.08562844 0.04759663 0.05541676 0.08558917 0.04786247 0.05656993 0.08561456 0.0479843 0.05740904 0.08563739 0.04798185 0.05859571 0.08559113 0.04785966 0.05962568 0.08562326 0.04760134 0.06065386 0.08565855 0.04721248 0.06148386 0.08563631 0.04679596 0.06206214 0.08557158 0.04644072 0.06281858 0.08564496 0.04585278 0.06335902 0.0856598 0.04534667 0.06375795 0.08559089 0.04494035 0.06445264 0.08560204 0.04404675 0.06500351 0.08566105 0.04308658 0.06536865 0.08559507 0.0423032 0.06566238 0.08561319 0.04142326 0.06586682 0.08559823 0.04052317 0.06595963 0.08567953 0.03962916 0.06580096 0.08589863 0.03837734 0.06554228 0.08599829 0.03813916 0.06559419 0.08594769 0.03740394 0.0658279 0.08568704 0.03736859 0.06554508 0.08584982 0.03659963 0.06503188 0.08599066 0.03579396 0.065198 0.08581727 0.03553342 0.06496316 0.0856685 0.03484225 0.0645188 0.08599364 0.03477942 0.06461369 0.0858286 0.03440558 0.06424379 0.08579224 0.03380501 0.064085 0.08595663 0.03391861 0.06359124 0.0857467 0.03295224 0.06358826 0.08590829 0.03316968 0.06294208 0.08587044 0.03244036 0.06312781 0.0859965 0.03295028 0.06217187 0.08579498 0.03173953 0.06211054 0.0859512 0.03190559 0.06143379 0.08589631 0.0313813 0.06080651 0.0857923 0.03093731 0.06066834 0.08599644 0.03121441 0.06008291 0.08594554 0.03081744 0.06004285 0.08578103 0.03061079 0.05908554 0.08584904 0.03037613 0.0584405 0.08588463 0.03028589 0.05857777 0.08599436 0.03053194 0.05747789 0.08596163 0.03029906 0.0574631 0.08577817 0.03008955 0.0566945 0.08585739 0.03013503 0.05585324 0.08599561 0.0304681 0.05580067 0.08586901 0.03022539 0.05482321 0.08580493 0.0303657 0.05476182 0.08598774 0.03063219 0.05384778 0.08591198 0.03078693 0.05321592 0.08577203 0.03091228 0.05287194 0.08596676 0.03134411 0.05233758 0.08586412 0.03146451 0.05237352 0.08576852 0.0313608 0.05142378 0.08599638 0.03242009 0.05186355 0.08595192 0.0319435 0.05123049 0.085725 0.03215342 0.05112886 0.08588582 0.03240334 0.05021947 0.08599698 0.03372013 0.05030846 0.08590298 0.03325861 0.04969507 0.08581733 0.03391873 0.04957348 0.08594685 0.03440058 0.04913908 0.08575516 0.03473967 0.04907751 0.08599561 0.03557783 0.04905194 0.08588463 0.03515177 0.04868334 0.08575874 0.03573441 0.0486744 0.08595991 0.03638899 0.04839986 0.08583778 0.03678518 0.04818296 0.08579403 0.0376476 0.0483455 0.08595532 0.03790938 0.04837638 0.08599305 0.03881448 0.04810321 0.08582276 0.03879153 0.04811507 0.08579683 0.03964895 0.04827141 0.08591091 0.04012811 0.04850393 0.08599221 0.04047125 0.04820704 0.08577656 0.04052066 0.04852598 0.0858944 0.04145884 0.04903501 0.08599418 0.04230386 0.04871088 0.08580136 0.04225701 0.04905295 0.08588117 0.04286092 0.04968851 0.08594405 0.04380482 0.04950147 0.08581161 0.04378819 0.05036616 0.08599281 0.04453128 0.05016291 0.08581227 0.04470747 0.05095183 0.08578479 0.0455535 0.05124413 0.08595579 0.04556822 0.05168145 0.08583533 0.04611176 0.05211007 0.08599793 0.04606598 0.05251258 0.0857678 0.04672664 0.05239534 0.08592569 0.0464642 0.05321186 0.08582627 0.04703861 0.05352973 0.0859645 0.04698836 0.05342882 0.08599913 0.04679763 0.05408984 0.08584022 0.04738992 0.05503249 0.08594471 0.04752862 0.0552808 0.08576172 0.04776573 0.05608594 0.08578521 0.0478726 0.05597263 0.08599591 0.04753762 0.05621111 0.08593761 0.04772305 0.05691057 0.08584773 0.04786747 0.05778831 0.08599901 0.04755169 0.0578134 0.08594357 0.04771202 0.05787366 0.08576977 0.04788708 0.05872195 0.08575469 0.04776889 0.05922615 0.08589005 0.04754674 0.05994248 0.08596533 0.04720216 0.06023144 0.08579635 0.04730868 0.06091612 0.08599627 0.04665631 0.06132453 0.08589434 0.04669421 0.06221747 0.08579325 0.04623419 0.0621823 0.08599621 0.0458576 0.06230092 0.08593666 0.04596525 0.06298416 0.08590638 0.04545956 0.06388914 0.08582335 0.04462897 0.06348979 0.08597576 0.04476898 0.06402349 0.08599227 0.04401248 0.06451994 0.085855 0.04370439 0.0646702 0.08599346 0.04292184 0.06501746 0.08589237 0.04266828 0.06537216 0.08578574 0.04208207 0.06532222 0.08592218 0.04182201 0.06530994 0.08599275 0.04127013 0.06573235 0.08579456 0.04079949 0.06573271 0.08591502 0.04008138 0.06559813 0.08599263 0.03966867 -0.03683018 0.07316797 -0.02224254 -0.03696751 0.07305401 -0.02215039 -0.03646719 0.07311737 -0.02225083 -0.03720182 0.073004 -0.02205079 -0.03624945 0.07318502 -0.02231818 -0.03621363 0.07300996 -0.02215903 -0.03578698 0.07318174 -0.02244019 -0.03578621 0.07309448 -0.02239096 -0.0355544 0.07302433 -0.0223838 -0.03534573 0.07315164 -0.02261698 -0.03485631 0.07305234 -0.02279949 -0.0348702 0.07316172 -0.02289664 -0.03478956 0.07300364 -0.02271717 -0.03461366 0.0731799 -0.02309679 -0.03429263 0.07316464 -0.0233879 -0.03418624 0.07304781 -0.02336442 -0.03399574 0.07300704 -0.02345079 -0.03394335 0.07315099 -0.023799 -0.03367149 0.073152 -0.02423655 -0.0335747 0.07305473 -0.02424633 -0.03336101 0.07300406 -0.02442252 -0.03343755 0.07317572 -0.02479749 -0.03326302 0.07306712 -0.0251379 -0.03332811 0.07317161 -0.02518987 -0.03308069 0.07300758 -0.02557647 -0.03324425 0.0731917 -0.02581781 -0.03319907 0.07309603 -0.0259028 -0.03313076 0.07304048 -0.0260998 -0.03327953 0.07317376 -0.02656561 -0.03331273 0.0730983 -0.02693796 -0.03315955 0.07301104 -0.02678292 -0.03343719 0.07319349 -0.02719295 -0.0333985 0.07300889 -0.02755457 -0.0335282 0.07308971 -0.02756428 -0.03369575 0.07318174 -0.02779793 -0.033822 0.07306146 -0.02814906 -0.0337485 0.07300895 -0.02819812 -0.03411567 0.07317614 -0.02841639 -0.03432458 0.07306575 -0.02873963 -0.03439295 0.07300412 -0.0289821 -0.03465878 0.07318836 -0.02894288 -0.03480118 0.07306957 -0.02912807 -0.0351994 0.07315385 -0.02930682 -0.03521364 0.07300841 -0.02951061 -0.03543168 0.07306003 -0.02950024 -0.03579455 0.07317233 -0.02956533 -0.03626388 0.07301241 -0.02984517 -0.03653705 0.07320147 -0.02973026 -0.03644573 0.07310581 -0.02975451 -0.03714144 0.07308989 -0.02981108 -0.03709262 0.07318472 -0.02975529 -0.03717279 0.07300931 -0.02992093 -0.03756308 0.0731697 -0.02971875 -0.03787285 0.07305341 -0.02974706 -0.0380088 0.07316422 -0.02962273 -0.03834307 0.07300233 -0.02973765 -0.03845196 0.07317489 -0.02946829 -0.03858786 0.07307451 -0.02947318 -0.03895998 0.0731886 -0.02920609 -0.0395593 0.07300221 -0.02907246 -0.03923279 0.07304698 -0.0291332 -0.03934127 0.07318538 -0.02893739 -0.0395438 0.07306224 -0.02887058 -0.03966546 0.07316684 -0.02865338 -0.03994542 0.07317364 -0.02833771 -0.04010426 0.07307434 -0.02823519 -0.0402534 0.07320189 -0.02787685 -0.04033988 0.07300937 -0.02805566 -0.04044669 0.07314395 -0.02752155 -0.04070305 0.07301068 -0.02728748 -0.04062116 0.07317793 -0.02701115 -0.04075157 0.0730614 -0.02679139 -0.04072278 0.07314497 -0.02656698 -0.0409677 0.0730046 -0.02601748 -0.04076039 0.07316774 -0.02610099 -0.04084557 0.07305657 -0.02591347 -0.04073792 0.07318502 -0.02562814 -0.0406751 0.07316684 -0.02520054 -0.04077672 0.07303059 -0.02513951 -0.04048091 0.07322019 -0.02458423 -0.04061764 0.07306873 -0.0247606 -0.04047614 0.07311391 -0.02449578 -0.04042506 0.07300364 -0.02398073 -0.04024004 0.07306659 -0.02395832 -0.04012763 0.07314807 -0.0238986 -0.0397982 0.07317852 -0.02349066 -0.03973221 0.07307285 -0.02333301 -0.03948634 0.07300418 -0.02291655 -0.03934824 0.07317614 -0.0230599 -0.03917825 0.07304441 -0.02281528 -0.03888118 0.07316851 -0.02274489 -0.03855401 0.07314497 -0.02256989 -0.03824901 0.07300806 -0.02226257 -0.03810858 0.07317388 -0.02240663 -0.0379616 0.07305926 -0.02227979 -0.0376563 0.07316815 -0.02229803 -0.03728443 0.07314437 -0.02224487 -0.03673559 0.09380769 -0.02975034 -0.03581053 0.09383559 -0.02956748 -0.03531903 0.0938372 -0.02936828 -0.03463017 0.09381926 -0.02892059 -0.03425168 0.09382688 -0.02856415 -0.03394383 0.09382355 -0.02819031 -0.03370147 0.0938152 -0.0277974 -0.03347545 0.09380728 -0.02730572 -0.03333556 0.0938434 -0.02686417 -0.03325939 0.09382569 -0.02636593 -0.03324478 0.09380137 -0.02590727 -0.03340786 0.09380519 -0.02488988 -0.0336551 0.09380871 -0.02428817 -0.03389507 0.0938149 -0.02388566 -0.03411048 0.09385573 -0.02358293 -0.03475797 0.09385883 -0.02297228 -0.03519934 0.09384614 -0.02269315 -0.03566688 0.09383416 -0.02248334 -0.03613442 0.09382587 -0.0223394 -0.0366432 0.09383541 -0.022255 -0.03728348 0.09380966 -0.02225035 -0.03792107 0.09383267 -0.02235263 -0.03837037 0.0938149 -0.02250248 -0.03878688 0.09384465 -0.02268612 -0.03933852 0.09381175 -0.02305513 -0.03970909 0.09382921 -0.02339202 -0.03997313 0.09382671 -0.0236997 -0.0402534 0.0937981 -0.02412307 -0.04046058 0.0938149 -0.02453887 -0.04064255 0.09379762 -0.02507275 -0.04075878 0.09382867 -0.02580732 -0.04073792 0.0938149 -0.02637183 -0.04067373 0.09385496 -0.02683597 -0.04053157 0.09381061 -0.02727812 -0.04035031 0.09383428 -0.02771151 -0.04010725 0.09383136 -0.0281164 -0.039756 0.09382694 -0.0285626 -0.03926789 0.09382897 -0.02900028 -0.03888118 0.09383141 -0.02925503 -0.03851538 0.0938552 -0.02944809 -0.03814589 0.09382712 -0.02958083 -0.03771233 0.09384673 -0.02969664 -0.03728103 0.0938028 -0.02974402 -0.03663498 0.09389609 -0.02977919 -0.03715646 0.09392446 -0.02981442 -0.03664952 0.09399062 -0.02990752 -0.03623729 0.09380978 -0.02967882 -0.0359674 0.09393715 -0.02969193 -0.03562247 0.09399652 -0.02971267 -0.03512179 0.09397298 -0.02940428 -0.03494596 0.09388339 -0.02917921 -0.03446877 0.09393453 -0.02887642 -0.03405421 0.09399604 -0.02865087 -0.03416597 0.09395098 -0.02861195 -0.03384107 0.0939241 -0.02814304 -0.03345775 0.09399604 -0.02776795 -0.03353941 0.09393823 -0.02765172 -0.03313881 0.09399133 -0.02677732 -0.03316706 0.0939508 -0.02644968 -0.03319942 0.09390336 -0.02609598 -0.03309547 0.09399062 -0.02564328 -0.03326678 0.09385478 -0.02548629 -0.03325194 0.09399133 -0.02480792 -0.03339582 0.09390282 -0.02479243 -0.03354972 0.0939278 -0.02436327 -0.03371173 0.09399163 -0.02384173 -0.03387224 0.09394967 -0.02375322 -0.03442907 0.09385365 -0.02324485 -0.03440219 0.09399157 -0.02305006 -0.03463965 0.09396094 -0.02293246 -0.03551054 0.09396445 -0.02242404 -0.03562021 0.09399557 -0.02226054 -0.03644382 0.09396243 -0.02216851 -0.03723949 0.09393692 -0.02217459 -0.03740942 0.09399521 -0.02206873 -0.03773736 0.09392738 -0.02224671 -0.03852713 0.09398931 -0.02238053 -0.03857314 0.09393686 -0.02250313 -0.03935426 0.09399211 -0.02285766 -0.03930127 0.09391057 -0.02296578 -0.03991919 0.09394663 -0.02348673 -0.04022252 0.0939967 -0.02368313 -0.04031741 0.09392553 -0.02411466 -0.04059523 0.09393334 -0.02468365 -0.04080337 0.0939911 -0.02497708 -0.04075157 0.09389191 -0.02541983 -0.04087316 0.09396821 -0.02593207 -0.04085099 0.09399104 -0.02682793 -0.04079747 0.09393757 -0.02652192 -0.04052543 0.09393942 -0.02751243 -0.04036176 0.09397715 -0.02795934 -0.04003024 0.09398686 -0.02845597 -0.03953766 0.09394019 -0.0288794 -0.03940439 0.09399634 -0.02914398 -0.03876668 0.09396791 -0.02945792 -0.03789854 0.0939961 -0.02987331 -0.03776657 0.09395247 -0.02978354 -0.04145389 0.07475 -0.02682203 -0.04150426 0.078 -0.0258876 -0.0414105 0.078 -0.02697092 -0.04097771 0.078 -0.02812767 -0.04094541 0.07475 -0.02818697 -0.04032963 0.078 -0.02904343 -0.04028367 0.07475 -0.02909296 -0.03929185 0.078 -0.0298984 -0.03923016 0.07475 -0.02993398 -0.03782027 0.078 -0.03044712 -0.03775012 0.07475 -0.03045952 -0.03624987 0.078 -0.03045952 -0.03617966 0.07475 -0.03044712 -0.03507333 0.078 -0.03007423 -0.03480947 0.07475 -0.0299493 -0.03421396 0.078 -0.02954787 -0.03374272 0.07475 -0.02912819 -0.0332151 0.078 -0.0284875 -0.03302228 0.07475 -0.02812767 -0.03260499 0.078 -0.02703899 -0.03254199 0.07475 -0.02678602 -0.032494 0.078 -0.02569729 -0.03258192 0.07475 -0.02499157 -0.03274953 0.078 -0.02448892 -0.03316849 0.07475 -0.02361905 -0.03345698 0.078 -0.02317452 -0.03377455 0.07475 -0.02285385 -0.03473782 0.07475 -0.02208173 -0.03467494 0.078 -0.02212834 -0.03559231 0.078 -0.02172201 -0.03613936 0.07475 -0.02156656 -0.03666216 0.078 -0.02149248 -0.03771072 0.07475 -0.02152693 -0.03797084 0.078 -0.02159464 -0.0389266 0.078 -0.02192568 -0.03919047 0.07475 -0.02205061 -0.03987604 0.078 -0.02251803 -0.04041963 0.07475 -0.02303028 -0.04084002 0.078 -0.0236116 -0.04115545 0.07475 -0.0242483 -0.04137301 0.078 -0.02488642 -0.04146218 0.07475 -0.02532744 -0.03254604 0.08899998 -0.02517789 -0.03250813 0.09224998 -0.02558445 -0.03274953 0.09224998 -0.02448892 -0.03310644 0.08899998 -0.02371174 -0.03337377 0.09224998 -0.02329796 -0.03371787 0.08899998 -0.02291619 -0.03425353 0.09224998 -0.02242666 -0.03457653 0.08899998 -0.02218198 -0.03541702 0.09224998 -0.02175641 -0.0360285 0.08899998 -0.02158337 -0.03696501 0.09224998 -0.02148395 -0.03759765 0.08899998 -0.02151745 -0.03818917 0.09224998 -0.02164852 -0.03888595 0.08899998 -0.02190214 -0.03932499 0.09224998 -0.02212828 -0.04007899 0.08899998 -0.02268159 -0.04020392 0.09224998 -0.02283036 -0.04085052 0.09224998 -0.02364695 -0.04105871 0.08899998 -0.02400583 -0.04130923 0.09224998 -0.02467077 -0.04148292 0.08899998 -0.02543812 -0.04150694 0.09224998 -0.02577507 -0.04143047 0.08899998 -0.02689564 -0.041395 0.09224998 -0.02703893 -0.04097771 0.08899998 -0.02812767 -0.04080259 0.09224998 -0.02845597 -0.04038006 0.08899998 -0.02898287 -0.03989779 0.09224998 -0.02945327 -0.03936034 0.08899998 -0.02986264 -0.03882735 0.09224998 -0.03013652 -0.03782027 0.08899998 -0.03044712 -0.03733777 0.09224998 -0.03050744 -0.03632658 0.08899998 -0.03046751 -0.03569954 0.09224998 -0.03033846 -0.03514528 0.08899998 -0.03011047 -0.03427201 0.09224998 -0.02960145 -0.03421396 0.08899998 -0.02954781 -0.03349632 0.08899998 -0.0288347 -0.03345662 0.09224998 -0.02878499 -0.03289794 0.08899998 -0.02788919 -0.03283482 0.09224998 -0.02775573 -0.03253781 0.08899998 -0.02667254 -0.03253215 0.09224998 -0.02659195 -0.02950686 0.0936014 -0.02621072 -0.02962964 0.09383702 -0.02638345 -0.02958333 0.09361326 -0.02710312 -0.02982836 0.09396213 -0.02682065 -0.02972447 0.09378975 -0.02744948 -0.02982473 0.09360122 -0.02818274 -0.02995932 0.09394156 -0.0277304 -0.03026455 0.09399145 -0.02838057 -0.02996701 0.09377866 -0.02838093 -0.03023707 0.09357368 -0.02924913 -0.0302186 0.09374302 -0.02906912 -0.03040695 0.09394329 -0.02902841 -0.03054434 0.09378862 -0.02965801 -0.03080427 0.09358757 -0.03022927 -0.03095346 0.09399056 -0.02980375 -0.03095823 0.0937677 -0.0303263 -0.03117054 0.09391295 -0.03038144 -0.03138047 0.09360957 -0.03095918 -0.03142958 0.09378802 -0.03089183 -0.03199303 0.09396952 -0.03116899 -0.03198367 0.09388267 -0.0313546 -0.03194135 0.09365773 -0.03151875 -0.03266924 0.093997 -0.03161478 -0.03264153 0.09359073 -0.03210508 -0.03259766 0.09374636 -0.03200292 -0.03291094 0.09390175 -0.03206235 -0.03341352 0.0935744 -0.03258568 -0.03358268 0.09376889 -0.03259956 -0.03359454 0.09395122 -0.0323891 -0.03455531 0.09399718 -0.03266423 -0.03423547 0.09360408 -0.03297197 -0.03438979 0.09389758 -0.03283464 -0.03442531 0.09371423 -0.03299933 -0.03538256 0.09360027 -0.03332346 -0.03513091 0.09372091 -0.03321707 -0.03552764 0.09388476 -0.03318458 -0.03560554 0.09398788 -0.033019 -0.03611528 0.09375298 -0.03338712 -0.03646779 0.09360367 -0.03348064 -0.0366311 0.09389662 -0.03330349 -0.03708982 0.09381335 -0.03339934 -0.03758925 0.09360229 -0.03347641 -0.03725695 0.09399247 -0.0331211 -0.03769433 0.09385091 -0.03333657 -0.0384891 0.09363186 -0.03334188 -0.03833007 0.09397125 -0.03306221 -0.03845995 0.09384638 -0.03322201 -0.03918576 0.09359192 -0.03317141 -0.0392313 0.09380275 -0.03306722 -0.03976637 0.09399813 -0.03252428 -0.03965032 0.09395378 -0.03272914 -0.03990703 0.09361547 -0.03290712 -0.03988748 0.09381568 -0.03280735 -0.04056769 0.09363532 -0.03258651 -0.04075801 0.09388744 -0.03229945 -0.04125529 0.09360074 -0.03217101 -0.04115712 0.09377467 -0.03215223 -0.04099655 0.09399771 -0.03185957 -0.04183954 0.09361398 -0.03172194 -0.04168295 0.09397119 -0.03144824 -0.04169005 0.09384745 -0.03168827 -0.04235386 0.09367483 -0.0312274 -0.04232472 0.09392815 -0.03095811 -0.04285776 0.0936048 -0.03067642 -0.04279965 0.09378188 -0.03062504 -0.04268139 0.09399884 -0.03022509 -0.04295623 0.09392905 -0.03017038 -0.0432887 0.09360194 -0.03007918 -0.04337918 0.09376645 -0.02982139 -0.04368776 0.09356796 -0.02939337 -0.043392 0.09394997 -0.02939528 -0.04374086 0.09377682 -0.02912074 -0.04399269 0.09359073 -0.02870362 -0.04386496 0.09390163 -0.02850675 -0.04364097 0.09399604 -0.02850878 -0.0441724 0.09377276 -0.02795612 -0.04421305 0.09358084 -0.02804833 -0.04400199 0.09396928 -0.02764016 -0.04438412 0.09356784 -0.02731019 -0.0442968 0.09386777 -0.02692562 -0.04440563 0.09374606 -0.02677708 -0.04447793 0.09357589 -0.02655631 -0.04410898 0.09399551 -0.0256592 -0.04419809 0.09395837 -0.02644598 -0.04448199 0.09367072 -0.02584719 -0.04433238 0.0938732 -0.02560234 -0.0444405 0.093593 -0.02508002 -0.04433006 0.09383481 -0.02507489 -0.04430705 0.09366875 -0.02438324 -0.04396343 0.09399354 -0.02448618 -0.0441519 0.09386932 -0.02432507 -0.04410493 0.09362715 -0.02362203 -0.04395169 0.09387975 -0.02364277 -0.04376107 0.0936076 -0.0227558 -0.04349702 0.09397268 -0.0229128 -0.04368716 0.0938059 -0.02281373 -0.04332846 0.09377098 -0.02210807 -0.04328292 0.0935921 -0.02190971 -0.04284298 0.09399193 -0.0218988 -0.04295921 0.09389275 -0.02174013 -0.04284715 0.09360462 -0.02131026 -0.04281824 0.09380054 -0.02141696 -0.04237753 0.09355932 -0.02077174 -0.04236996 0.09378182 -0.02087551 -0.04206985 0.09393817 -0.02081501 -0.0419209 0.09364652 -0.02035248 -0.04132139 0.09399342 -0.02032947 -0.04154384 0.09387552 -0.02023261 -0.04139018 0.09365981 -0.01993817 -0.04073172 0.09359848 -0.01949441 -0.04084491 0.09384965 -0.01971524 -0.0401414 0.0939933 -0.01959973 -0.04025787 0.09375762 -0.01931852 -0.03988617 0.09391081 -0.01929283 -0.03993409 0.09358787 -0.01910036 -0.03941857 0.09376901 -0.01897108 -0.03901308 0.09360462 -0.01877582 -0.03880077 0.09397387 -0.01905345 -0.03860723 0.09384024 -0.01879811 -0.03812533 0.09360587 -0.01858979 -0.03798574 0.09399753 -0.01897096 -0.03788053 0.09391701 -0.01876544 -0.03752684 0.09376817 -0.01858663 -0.0373618 0.09357786 -0.01850992 -0.03710365 0.09396141 -0.0187866 -0.03664088 0.09359008 -0.01851129 -0.03661322 0.09380608 -0.01860332 -0.03587877 0.0936107 -0.01858979 -0.03586834 0.09392678 -0.01880896 -0.03572964 0.0937972 -0.01869839 -0.03495073 0.0939958 -0.01917618 -0.03510862 0.09365731 -0.01875609 -0.03482246 0.09390139 -0.01902443 -0.03440225 0.09361004 -0.01896983 -0.0342803 0.09375578 -0.01907539 -0.03411418 0.09393382 -0.01932984 -0.03373998 0.09359776 -0.01924949 -0.03298902 0.09366083 -0.01967847 -0.0334903 0.09381335 -0.01948767 -0.03307849 0.09393829 -0.01989299 -0.03275692 0.09399598 -0.0203045 -0.03247177 0.093571 -0.02002197 -0.03236293 0.0937938 -0.0202108 -0.03175044 0.09361493 -0.02064692 -0.03188461 0.09394288 -0.02085238 -0.03168654 0.0938192 -0.02084875 -0.03113734 0.09360843 -0.02133011 -0.03126269 0.09399205 -0.02178305 -0.03095006 0.09375369 -0.02167278 -0.03058296 0.09358161 -0.02211391 -0.03091263 0.09393417 -0.02201968 -0.0305953 0.09381347 -0.02229261 -0.03045159 0.09399485 -0.0231924 -0.03017693 0.09360229 -0.0228967 -0.03022271 0.09377336 -0.02296787 -0.03020972 0.09390896 -0.02331471 -0.02990198 0.09360188 -0.02359026 -0.02991074 0.09379196 -0.02382487 -0.0296939 0.09360367 -0.02432399 -0.02999442 0.09396684 -0.02439266 -0.02975761 0.093845 -0.02460002 -0.02993422 0.09399849 -0.02540802 -0.02953881 0.09360992 -0.02525281 -0.02979129 0.09395277 -0.02547806 -0.02960097 0.09380406 -0.02558028 -0.02950787 0.09266221 -0.02637004 -0.02961021 0.09265923 -0.02726453 -0.02979105 0.09261006 -0.02803242 -0.03024733 0.09264081 -0.02926027 -0.03068494 0.09263879 -0.03003591 -0.03116744 0.09259074 -0.03069287 -0.03161191 0.0926482 -0.03121113 -0.03218328 0.09266877 -0.03174662 -0.03276574 0.09259742 -0.0321753 -0.03356635 0.09263479 -0.03266555 -0.03459823 0.09262222 -0.03310072 -0.03548437 0.09265917 -0.03334236 -0.03794515 0.09265685 -0.03344118 -0.03958404 0.09264683 -0.03303617 -0.04027223 0.09265857 -0.0327453 -0.04104274 0.09266233 -0.03231871 -0.04152542 0.09259623 -0.03196275 -0.04210865 0.09266805 -0.03148853 -0.04262 0.0926218 -0.03095424 -0.04306912 0.09265959 -0.03040158 -0.04389828 0.09266316 -0.02894693 -0.04416728 0.09257626 -0.02815574 -0.04449152 0.09267097 -0.02640122 -0.04446691 0.09266108 -0.02528339 -0.04429858 0.09262919 -0.02430278 -0.04405885 0.09266263 -0.02346235 -0.0436902 0.09265077 -0.02261829 -0.0428493 0.09264904 -0.02131223 -0.04237306 0.09266394 -0.02077054 -0.04125672 0.09259396 -0.01984125 -0.04069578 0.09257596 -0.01949214 -0.03903877 0.09265953 -0.01878106 -0.03813356 0.09264647 -0.01859033 -0.03712594 0.09260904 -0.01850754 -0.03624123 0.0926218 -0.0185467 -0.0353564 0.09264743 -0.01868265 -0.03444397 0.09265214 -0.01895278 -0.03375416 0.09266388 -0.01924115 -0.03307491 0.09264922 -0.0196135 -0.03246784 0.09259593 -0.02004057 -0.03180068 0.09260964 -0.02060323 -0.03114318 0.09263926 -0.02132391 -0.03069901 0.09266883 -0.02193522 -0.0303446 0.09265869 -0.02254843 -0.02996826 0.09263831 -0.02339631 -0.0297746 0.09261155 -0.02403348 -0.02962976 0.09259742 -0.02468121 -0.02952843 0.09261447 -0.02546131 -0.02957737 0.09247577 -0.02619099 -0.02969884 0.09236884 -0.02524602 -0.02976322 0.09230071 -0.02612894 -0.02995741 0.09225898 -0.02479922 -0.02993696 0.09237951 -0.0239495 -0.0303744 0.09225767 -0.02337211 -0.03029251 0.09243553 -0.02286601 -0.03067445 0.0924704 -0.02210986 -0.03075373 0.09228587 -0.02239531 -0.03129768 0.09234458 -0.02142858 -0.03134196 0.09247773 -0.02118611 -0.03179717 0.09225475 -0.02113115 -0.03200191 0.09237617 -0.02062416 -0.03269243 0.09235262 -0.02008426 -0.03277695 0.09225279 -0.02030479 -0.03317302 0.09246677 -0.01964467 -0.03363019 0.09227883 -0.01964163 -0.03377681 0.09245711 -0.01932281 -0.03434014 0.09231883 -0.01924031 -0.03463655 0.09243953 -0.01898127 -0.03509336 0.09226 -0.0191164 -0.03547292 0.09242326 -0.01876825 -0.03626954 0.0922932 -0.0188173 -0.03640508 0.09239614 -0.01865911 -0.03705513 0.09225243 -0.01891171 -0.03753334 0.09247207 -0.0185939 -0.0373702 0.0923348 -0.01872432 -0.03811073 0.09228467 -0.01888102 -0.03849065 0.09239441 -0.01878219 -0.03901803 0.09249061 -0.01884067 -0.03941726 0.09225165 -0.01934117 -0.03952902 0.09231317 -0.01919311 -0.03993099 0.09262228 -0.01910501 -0.03985446 0.09243547 -0.01917964 -0.04066216 0.09239023 -0.01961797 -0.0406816 0.09225851 -0.01988244 -0.04123294 0.09233033 -0.02007138 -0.04182624 0.09262192 -0.02026927 -0.04171812 0.09239578 -0.02034807 -0.04211783 0.09227997 -0.02094006 -0.04229885 0.09246128 -0.02081042 -0.04297715 0.09245026 -0.02161359 -0.04279685 0.09231078 -0.02163279 -0.04327785 0.09262573 -0.02190953 -0.04332923 0.09231829 -0.02241939 -0.04352515 0.09249597 -0.02242141 -0.04288166 0.09224998 -0.02207046 -0.04367554 0.09229224 -0.0232284 -0.04397761 0.09249436 -0.02341753 -0.04400336 0.09225136 -0.02491575 -0.04406213 0.09231084 -0.02430272 -0.04423546 0.09246516 -0.02437442 -0.0443648 0.09244579 -0.02518004 -0.04418462 0.09228605 -0.02549648 -0.04444187 0.09250652 -0.02589786 -0.04431134 0.09235364 -0.02620899 -0.04439294 0.09247618 -0.02671843 -0.04418885 0.09230482 -0.02691406 -0.04401308 0.09225225 -0.02694386 -0.04437947 0.09264039 -0.02730989 -0.04423063 0.09247732 -0.02769184 -0.04403495 0.09233945 -0.02794259 -0.04373389 0.09225648 -0.02829498 -0.04378116 0.09242451 -0.02894258 -0.04349178 0.09232324 -0.02929037 -0.04346293 0.09257793 -0.02977234 -0.04283994 0.0922532 -0.03004181 -0.04312831 0.09232121 -0.02991008 -0.04304426 0.09247267 -0.03031057 -0.04248601 0.09236162 -0.030869 -0.04190337 0.09247034 -0.03157567 -0.0418955 0.09226197 -0.03119778 -0.04144442 0.09233707 -0.03178757 -0.04077982 0.09239453 -0.03232634 -0.04086267 0.09226399 -0.03199678 -0.04004627 0.09247577 -0.03277361 -0.03937494 0.09225296 -0.03270637 -0.03994375 0.09232199 -0.03264933 -0.03892713 0.09258157 -0.03323274 -0.03918844 0.09237307 -0.03300338 -0.03812336 0.09235191 -0.03323388 -0.03788632 0.09250712 -0.03339272 -0.0380764 0.09225237 -0.03301328 -0.03707563 0.09232616 -0.03327822 -0.03699362 0.09257054 -0.03348159 -0.0361554 0.0922569 -0.03308629 -0.03615963 0.09257769 -0.03343683 -0.03628867 0.092372 -0.03329819 -0.03544557 0.09240293 -0.0332067 -0.03442835 0.09242129 -0.03293263 -0.03484755 0.09230601 -0.0329172 -0.03427571 0.09225833 -0.0325942 -0.03339672 0.09241682 -0.03244936 -0.03337341 0.09228497 -0.03221642 -0.0329222 0.09225523 -0.0318439 -0.0324409 0.09236913 -0.03174781 -0.03193873 0.0924763 -0.03144299 -0.03195285 0.09227013 -0.03108012 -0.03152453 0.09237414 -0.03089302 -0.03119969 0.09226304 -0.03018879 -0.03087592 0.09242486 -0.03014075 -0.03049653 0.09242951 -0.02952051 -0.03056061 0.09225791 -0.02908051 -0.03000783 0.09260708 -0.02867823 -0.03012132 0.09236818 -0.02855914 -0.02996265 0.09230417 -0.0277028 -0.02974367 0.0924769 -0.02758979 -0.02992814 0.09225851 -0.0269218 -0.02966243 0.09242546 -0.02690398 -0.02950578 0.07339674 -0.02584302 -0.02957063 0.07323503 -0.02579027 -0.02966797 0.07311362 -0.02622306 -0.02955806 0.07341027 -0.0250895 -0.0298689 0.07300686 -0.02584457 -0.02963298 0.0732249 -0.02505826 -0.02979475 0.07308506 -0.02490562 -0.02969425 0.07337075 -0.02434158 -0.02987653 0.07312256 -0.02421361 -0.03013765 0.07300746 -0.02410131 -0.02989047 0.07333475 -0.02366322 -0.03002345 0.0734139 -0.0232532 -0.03023386 0.07309037 -0.02325856 -0.03024184 0.07320857 -0.0229507 -0.03042644 0.07335579 -0.02240449 -0.03069424 0.07300585 -0.02272433 -0.03064656 0.07308989 -0.02241468 -0.03090816 0.07321053 -0.02176421 -0.03089886 0.07339996 -0.02164477 -0.03120213 0.07303911 -0.02170932 -0.03186547 0.07300674 -0.02104628 -0.03137379 0.07332724 -0.02106642 -0.03175735 0.07311141 -0.02087712 -0.03192257 0.07333743 -0.02049946 -0.03264075 0.07340449 -0.01989632 -0.03250765 0.0732578 -0.02006399 -0.03274232 0.07300883 -0.02028691 -0.0328986 0.07312488 -0.01990258 -0.0331344 0.07325571 -0.01963764 -0.0337612 0.07343995 -0.019225 -0.03363591 0.07305365 -0.01958459 -0.03377044 0.07321578 -0.01932126 -0.03444123 0.07324415 -0.01901727 -0.03480631 0.07311654 -0.01899766 -0.03476226 0.07340091 -0.01884549 -0.03517425 0.0732575 -0.01878356 -0.03466206 0.07300543 -0.01926386 -0.03567856 0.07334166 -0.01862907 -0.03628796 0.07300823 -0.01890534 -0.03590959 0.0731033 -0.0187658 -0.03642296 0.07334512 -0.01853334 -0.03676033 0.07313156 -0.01865559 -0.03714865 0.07342094 -0.01849913 -0.03740745 0.0732696 -0.01855993 -0.03759461 0.07309937 -0.01871496 -0.03759127 0.07300639 -0.01890778 -0.03833323 0.07339507 -0.01861953 -0.03826862 0.07321643 -0.01868176 -0.03878396 0.07305788 -0.01897412 -0.03875988 0.07300406 -0.01912653 -0.03920167 0.07339626 -0.01883476 -0.03925728 0.07317227 -0.0189644 -0.03989881 0.07340985 -0.01908576 -0.04005503 0.07321035 -0.01923948 -0.04020959 0.07305049 -0.01950436 -0.04059964 0.07339423 -0.01942557 -0.04082715 0.07300263 -0.02003353 -0.04106283 0.07322126 -0.01978492 -0.04139125 0.07340937 -0.01991856 -0.04126936 0.07309025 -0.02007317 -0.04194551 0.07316362 -0.02051186 -0.04218494 0.07335168 -0.02059578 -0.04211533 0.0730099 -0.02100837 -0.04262542 0.07342708 -0.02104085 -0.04269981 0.07319623 -0.02126556 -0.04308915 0.07340371 -0.02162724 -0.04305452 0.07305866 -0.02199745 -0.04324615 0.07323014 -0.02198463 -0.04358243 0.07340234 -0.02240437 -0.04368233 0.07325309 -0.02272003 -0.04342174 0.07300323 -0.0229637 -0.04367244 0.07310259 -0.02298927 -0.04404407 0.07339382 -0.02342796 -0.04409915 0.07317262 -0.02393501 -0.04399925 0.07304245 -0.0242359 -0.04426264 0.07339179 -0.02415674 -0.04442131 0.07341581 -0.02490663 -0.04436826 0.07327413 -0.02486097 -0.04409283 0.07300388 -0.02543216 -0.04433888 0.07314276 -0.02535802 -0.04449439 0.07341057 -0.02578967 -0.04447859 0.0733329 -0.02624905 -0.04430407 0.07309544 -0.02619421 -0.04439622 0.07343739 -0.02729541 -0.0443691 0.07326924 -0.02712273 -0.04427051 0.07312834 -0.02704292 -0.04405581 0.0730074 -0.0270214 -0.04411965 0.07320612 -0.02809232 -0.04392695 0.07303833 -0.02800577 -0.04410582 0.07342553 -0.02839601 -0.04387748 0.07333832 -0.02895963 -0.04327732 0.073004 -0.02931362 -0.04361748 0.07308262 -0.0290659 -0.04353773 0.07320541 -0.02950072 -0.04349845 0.07342839 -0.02974259 -0.04314923 0.07306617 -0.02986156 -0.04325222 0.07324403 -0.03002685 -0.04296958 0.07338881 -0.03053843 -0.04274755 0.07329159 -0.03076303 -0.04271483 0.0731011 -0.03056269 -0.04239225 0.07300245 -0.03060495 -0.04234588 0.07340824 -0.03125619 -0.04202908 0.07315069 -0.03139728 -0.0421893 0.07306087 -0.03106689 -0.0416547 0.0734182 -0.03188323 -0.04167431 0.07329058 -0.03181797 -0.04130983 0.07301175 -0.03169977 -0.04109174 0.07317268 -0.03215056 -0.04091256 0.07340687 -0.032395 -0.04044061 0.07303702 -0.03233635 -0.04048985 0.07317268 -0.03251647 -0.04024875 0.07340073 -0.03275567 -0.0392571 0.07300341 -0.03275573 -0.0397005 0.07322919 -0.03292256 -0.03941059 0.07338947 -0.03310054 -0.03928136 0.07310074 -0.03294813 -0.03862166 0.07333916 -0.03330969 -0.03824615 0.07310199 -0.0332145 -0.0375427 0.0733909 -0.03347945 -0.03755688 0.07318854 -0.03338605 -0.03719609 0.07301038 -0.0331391 -0.03663051 0.07338351 -0.03348469 -0.03664338 0.07315319 -0.03336268 -0.03577423 0.07333588 -0.03338521 -0.03600978 0.07309591 -0.03324115 -0.0356875 0.07300657 -0.03298532 -0.03514599 0.07341229 -0.03326475 -0.03496146 0.07317954 -0.03311067 -0.0345956 0.07306939 -0.03286832 -0.03445696 0.07341086 -0.03305292 -0.03412473 0.07324087 -0.03285747 -0.03431069 0.07300561 -0.0325821 -0.03374969 0.07343006 -0.03275835 -0.03349822 0.07321196 -0.03254234 -0.03292477 0.07339006 -0.03229427 -0.03345012 0.07304549 -0.03228801 -0.03289598 0.07313704 -0.03210097 -0.03264349 0.07300895 -0.03165113 -0.03232604 0.07327359 -0.03180855 -0.03198671 0.07339346 -0.03157681 -0.03225767 0.07309824 -0.03155809 -0.03165555 0.07321894 -0.03114652 -0.03136557 0.07340627 -0.03094536 -0.03164386 0.0730707 -0.03091931 -0.0310654 0.07325762 -0.0304991 -0.03141188 0.07300162 -0.03034323 -0.03089308 0.07343119 -0.03035283 -0.03085935 0.0730918 -0.02996587 -0.03052806 0.0733298 -0.02975767 -0.03051257 0.07303935 -0.02915453 -0.03016829 0.07337737 -0.02907758 -0.03026372 0.07317781 -0.02903509 -0.03022152 0.07300204 -0.02812457 -0.02989268 0.07339042 -0.02837884 -0.02988243 0.07324516 -0.02817195 -0.02963966 0.07340276 -0.02744174 -0.03005397 0.07309627 -0.02826315 -0.02990257 0.0730583 -0.02745652 -0.02974146 0.07317769 -0.02740514 -0.02953386 0.07333791 -0.02653944 -0.02951365 0.07438015 -0.0256378 -0.02952319 0.07431995 -0.02658051 -0.02964943 0.07436043 -0.02748131 -0.02988743 0.07432913 -0.02837467 -0.03016614 0.07435482 -0.02907919 -0.03051763 0.07434368 -0.02976596 -0.03101515 0.07432931 -0.03052395 -0.03179436 0.07439112 -0.03139001 -0.03246951 0.07437962 -0.03196668 -0.03309726 0.07433605 -0.03240191 -0.03381502 0.07440334 -0.03277695 -0.03464555 0.07435429 -0.03312051 -0.03574329 0.07434493 -0.03339439 -0.03666597 0.07435077 -0.03348851 -0.03752428 0.07441145 -0.03346878 -0.03833997 0.07436031 -0.03337782 -0.03922939 0.07435446 -0.03315627 -0.03991919 0.07435953 -0.03290295 -0.04078704 0.07439589 -0.03246504 -0.04167276 0.07435411 -0.03186571 -0.04215413 0.07442551 -0.03142189 -0.04262137 0.07436996 -0.03095471 -0.04310715 0.07433897 -0.03034901 -0.0435996 0.07434123 -0.02956539 -0.04397672 0.07438313 -0.02872806 -0.04421973 0.07433605 -0.02802282 -0.04440355 0.07439017 -0.02715867 -0.04449659 0.07436925 -0.02600145 -0.04441106 0.07434368 -0.02484285 -0.04421198 0.0743913 -0.02398025 -0.04392337 0.07441663 -0.02315241 -0.04367983 0.07434219 -0.02259618 -0.04329729 0.07432246 -0.02192801 -0.04284948 0.07435572 -0.02131342 -0.04237139 0.07431966 -0.02076655 -0.0418173 0.07442516 -0.02027469 -0.04122978 0.07440215 -0.01982128 -0.04057788 0.07434779 -0.01941251 -0.03990888 0.07433438 -0.01908928 -0.03918379 0.07437658 -0.01883327 -0.03831321 0.07438242 -0.0186212 -0.0371679 0.07431739 -0.01849848 -0.03626126 0.07431781 -0.01853674 -0.03533571 0.07438272 -0.01869231 -0.03444939 0.07434052 -0.01894992 -0.0337696 0.07433861 -0.01923418 -0.03292721 0.07434266 -0.01970088 -0.03217762 0.07433736 -0.0202592 -0.0316478 0.07436716 -0.02075493 -0.03114235 0.07432949 -0.02131837 -0.03074711 0.07441574 -0.02188456 -0.03034514 0.07442504 -0.02257907 -0.03002321 0.07438313 -0.02327185 -0.02977722 0.07435297 -0.02399623 -0.02961564 0.07431828 -0.02468979 -0.0295763 0.07451951 -0.02636921 -0.02977341 0.07469773 -0.02648842 -0.02989631 0.07474374 -0.02595275 -0.02969324 0.07458025 -0.0270819 -0.03013747 0.07474917 -0.02779603 -0.02993988 0.07466745 -0.02779471 -0.02987772 0.0744794 -0.02819937 -0.03005075 0.07467263 -0.02821439 -0.03027385 0.07457768 -0.0290566 -0.03061825 0.07472652 -0.02926611 -0.03054767 0.07452052 -0.02967649 -0.03077065 0.07466143 -0.02979624 -0.03097397 0.07453078 -0.03033417 -0.03132033 0.07474696 -0.03024482 -0.03138703 0.07466787 -0.03064489 -0.0314365 0.07452309 -0.03091949 -0.03212285 0.07472956 -0.03125244 -0.03202867 0.0746141 -0.03141313 -0.03267604 0.07463872 -0.03192239 -0.0333231 0.07474696 -0.03206044 -0.0331912 0.07455974 -0.03235024 -0.0339418 0.07470434 -0.03255778 -0.03427267 0.07457536 -0.03286582 -0.03546005 0.07474714 -0.03292655 -0.0351293 0.07447803 -0.03322213 -0.03499841 0.07467144 -0.03299921 -0.03571176 0.07464903 -0.03319954 -0.03627383 0.07452523 -0.03338909 -0.03674137 0.07474416 -0.03310859 -0.03682577 0.07461822 -0.0333516 -0.03778439 0.07467508 -0.03324252 -0.03878802 0.07452958 -0.03321188 -0.03851318 0.07474714 -0.03291654 -0.03924524 0.07471132 -0.03286796 -0.03973615 0.07460975 -0.03283709 -0.04029154 0.07457911 -0.03261595 -0.04046362 0.07474422 -0.03222715 -0.04094511 0.07464432 -0.03216618 -0.04142981 0.07472133 -0.03165352 -0.04158169 0.07458758 -0.03178906 -0.04246777 0.07465505 -0.03086161 -0.04217433 0.07474303 -0.03089231 -0.04285228 0.07453346 -0.03056579 -0.0434429 0.07452595 -0.02970683 -0.04329371 0.07463455 -0.02976089 -0.04309314 0.07474613 -0.02966564 -0.04380524 0.07460731 -0.0288037 -0.04363667 0.07471185 -0.02880901 -0.0441147 0.07456737 -0.02803194 -0.04390788 0.07474076 -0.02780038 -0.04421287 0.07465827 -0.0271722 -0.04440104 0.07453238 -0.02655392 -0.04421323 0.0747075 -0.02630263 -0.044402 0.07455092 -0.02553325 -0.04405945 0.07474803 -0.02549606 -0.044227 0.07467341 -0.02507603 -0.04430288 0.07454377 -0.02474051 -0.04384106 0.07474595 -0.02403211 -0.04407376 0.07461136 -0.02398967 -0.04370802 0.07464522 -0.02306038 -0.04338002 0.07472318 -0.02270823 -0.04334807 0.07450133 -0.02211481 -0.04304587 0.07466238 -0.02191936 -0.04280221 0.07454937 -0.02139592 -0.04235947 0.07474666 -0.02132344 -0.0421788 0.07466894 -0.0208683 -0.0423184 0.07451403 -0.02080619 -0.04126536 0.07463479 -0.02003574 -0.0411002 0.07470822 -0.02005833 -0.04038488 0.07457309 -0.01942211 -0.04042923 0.074741 -0.01975029 -0.03954678 0.07465624 -0.01915085 -0.03919297 0.07449752 -0.01887917 -0.0388832 0.07474267 -0.01912003 -0.03752213 0.07474702 -0.01891618 -0.03807991 0.07464909 -0.01876264 -0.03768056 0.07448726 -0.01858353 -0.03701376 0.07449734 -0.01855927 -0.03698879 0.07466185 -0.01870572 -0.03627693 0.07451081 -0.01860004 -0.03586441 0.07461845 -0.01873385 -0.03612893 0.07474362 -0.01893621 -0.03514289 0.07470339 -0.01901423 -0.03485268 0.07454067 -0.0189011 -0.03414636 0.07450771 -0.01913505 -0.03422212 0.07474619 -0.01946723 -0.03378421 0.07465708 -0.01943498 -0.03328186 0.07447713 -0.0195375 -0.03269314 0.07474637 -0.02034443 -0.03261703 0.07465434 -0.02014356 -0.03233879 0.07450366 -0.0202015 -0.0315389 0.07453399 -0.02097445 -0.0315777 0.07469183 -0.02117913 -0.03093129 0.07460045 -0.02182245 -0.03094553 0.07474201 -0.02222818 -0.03036266 0.07465499 -0.02294218 -0.03031086 0.07474875 -0.02365446 -0.03000497 0.07452905 -0.02351003 -0.03001993 0.0746842 -0.02398002 -0.02967637 0.07453131 -0.0247516 -0.0299037 0.0747146 -0.02476435 -0.02970069 0.07464671 -0.02553921 -0.03100794 0.08861541 -0.0261414 -0.03099066 0.08799999 -0.02625477 -0.03106385 0.08867532 -0.02674013 -0.03127735 0.08799999 -0.02787363 -0.03118741 0.08860063 -0.02748161 -0.03154182 0.0885986 -0.0284993 -0.03216505 0.08799999 -0.02960264 -0.0319674 0.08859777 -0.0292595 -0.03231573 0.0886082 -0.02974063 -0.03270465 0.08859306 -0.03018426 -0.03345245 0.08799999 -0.03085714 -0.03326588 0.08860176 -0.0306943 -0.03385514 0.0885992 -0.03110474 -0.03503471 0.08799999 -0.03170031 -0.03509569 0.08865994 -0.03167837 -0.03710281 0.08799999 -0.03202867 -0.03615415 0.08865439 -0.03192579 -0.03673171 0.08864629 -0.03198224 -0.03731751 0.08865249 -0.0319786 -0.0380336 0.08862608 -0.03190517 -0.03887283 0.08799999 -0.03171563 -0.03877443 0.08860951 -0.0317257 -0.03930181 0.08861416 -0.03153413 -0.04035347 0.08799999 -0.03100126 -0.03985428 0.08863317 -0.0312649 -0.0403012 0.08859622 -0.03100889 -0.0408554 0.08865684 -0.03057926 -0.04147738 0.08799999 -0.03000777 -0.04130226 0.08865159 -0.03016376 -0.04179763 0.08860057 -0.02960079 -0.04241168 0.08799999 -0.0286588 -0.04227823 0.08858156 -0.02885484 -0.04258137 0.08862131 -0.02818161 -0.04285943 0.08857059 -0.02731937 -0.04294061 0.08799999 -0.02694094 -0.042993 0.08859246 -0.02628219 -0.04298037 0.08799999 -0.02529752 -0.04297518 0.08861726 -0.02553552 -0.04286646 0.08864241 -0.02478015 -0.04260909 0.08799999 -0.02384418 -0.04264301 0.08862984 -0.02397817 -0.04234254 0.08860129 -0.02327924 -0.04183489 0.08799999 -0.02239727 -0.04185229 0.08859318 -0.02246445 -0.04130256 0.08862662 -0.02183002 -0.04054749 0.08799999 -0.02114284 -0.04073792 0.08859741 -0.0213077 -0.03999394 0.08856832 -0.02079802 -0.03937315 0.08799999 -0.02047938 -0.03917872 0.08861064 -0.02041244 -0.03794348 0.08799999 -0.02005285 -0.0383284 0.08857899 -0.02014756 -0.03741109 0.08857506 -0.02001273 -0.03610211 0.08799999 -0.02004325 -0.03652524 0.08857953 -0.02001774 -0.03580892 0.08868163 -0.02013915 -0.03506559 0.0885927 -0.02032065 -0.034527 0.08799999 -0.02051931 -0.03414934 0.08856457 -0.02071321 -0.03300833 0.08799999 -0.02147692 -0.03338813 0.08859366 -0.02121311 -0.03292304 0.08864378 -0.02161318 -0.03231275 0.08859843 -0.0222494 -0.03186935 0.08799999 -0.02286469 -0.03146582 0.08859741 -0.02368456 -0.03116875 0.08799999 -0.02446609 -0.03117787 0.08857864 -0.02454537 -0.03102684 0.08858603 -0.02543169 -0.03101098 0.07899999 -0.0264914 -0.03099852 0.07840502 -0.02583485 -0.0310558 0.07837235 -0.02675241 -0.03126597 0.07899999 -0.02781587 -0.03147113 0.07838827 -0.02832263 -0.03204506 0.07899999 -0.02943575 -0.03180867 0.0784077 -0.02900159 -0.03290611 0.07833015 -0.03036355 -0.03316998 0.07899999 -0.03063035 -0.03346437 0.07835549 -0.03083729 -0.03456348 0.07899999 -0.03151535 -0.03401684 0.07832294 -0.03118664 -0.03481125 0.07840675 -0.03158605 -0.03659671 0.07899999 -0.03201603 -0.03622984 0.07840561 -0.03195011 -0.03711777 0.0784071 -0.03199869 -0.03790849 0.07831674 -0.03191071 -0.0382322 0.07899999 -0.03188139 -0.03937315 0.07899999 -0.0315206 -0.04054749 0.07899999 -0.03085708 -0.04086476 0.07839637 -0.03059202 -0.04153347 0.07899999 -0.02994418 -0.04160046 0.07840174 -0.0298497 -0.04206347 0.07833904 -0.02919518 -0.04222506 0.07899999 -0.02896779 -0.04247301 0.07841175 -0.0284698 -0.04285466 0.07899999 -0.02744179 -0.04294389 0.07835251 -0.02672529 -0.04298859 0.07836681 -0.02615815 -0.04300528 0.07899999 -0.02570033 -0.04296982 0.07833355 -0.02560269 -0.04292362 0.07841855 -0.02501696 -0.0427494 0.07899999 -0.02422642 -0.04271507 0.07836455 -0.02420127 -0.04235225 0.07843244 -0.02327406 -0.04213064 0.07899999 -0.02286475 -0.04187625 0.07841795 -0.0225076 -0.04120111 0.07899999 -0.02169281 -0.04130548 0.07840472 -0.02181631 -0.0405206 0.07839816 -0.02114361 -0.04009705 0.07899999 -0.02085047 -0.0399909 0.07835662 -0.02080994 -0.03922617 0.07842266 -0.02042698 -0.03891491 0.07899999 -0.02030026 -0.03730034 0.07899999 -0.01998347 -0.03775882 0.07837951 -0.02005368 -0.0365175 0.0783807 -0.02002322 -0.03580963 0.07899999 -0.02011144 -0.03583484 0.07840722 -0.02011793 -0.03505647 0.07841348 -0.02032297 -0.03442931 0.07899999 -0.02055478 -0.03346723 0.07841145 -0.02115052 -0.03316998 0.07899999 -0.02136957 -0.03292381 0.07832545 -0.02162098 -0.03210884 0.07899999 -0.02248346 -0.0325067 0.07837861 -0.02203482 -0.03195339 0.07840543 -0.02274817 -0.03146457 0.07843005 -0.02367961 -0.03140765 0.07899999 -0.02380514 -0.03114169 0.07842367 -0.02467745 -0.03105038 0.07899999 -0.02510327 -0.03111159 0.07818865 -0.02560722 -0.03126055 0.07805228 -0.02585154 -0.03140121 0.07800358 -0.02544498 -0.03115487 0.07824176 -0.02498185 -0.03133833 0.07808619 -0.0247628 -0.031327 0.07823479 -0.02425706 -0.03185164 0.07801097 -0.02368354 -0.03167116 0.07811421 -0.02363538 -0.03162908 0.07825863 -0.02344316 -0.03201901 0.07822775 -0.02279323 -0.03221201 0.07809531 -0.02271819 -0.03244 0.07823556 -0.02220547 -0.03278702 0.07801026 -0.02224802 -0.03285187 0.07810747 -0.02191364 -0.03378289 0.07800233 -0.02141886 -0.03351664 0.07820683 -0.02122163 -0.03373634 0.07808268 -0.02121794 -0.03388363 0.07836872 -0.02088522 -0.03417605 0.07819998 -0.02081221 -0.03441029 0.07838362 -0.02059495 -0.03453218 0.07804208 -0.02084165 -0.03483301 0.0781753 -0.02052336 -0.03541982 0.07820618 -0.02029341 -0.03529566 0.07801157 -0.02060806 -0.036363 0.07815569 -0.02015447 -0.03670442 0.07801461 -0.02034628 -0.03723567 0.07832908 -0.02002018 -0.03760588 0.07814812 -0.0201618 -0.03834491 0.07836812 -0.02016031 -0.03804069 0.07804673 -0.0203678 -0.03852462 0.07813858 -0.02034658 -0.03893136 0.07827615 -0.02036708 -0.03836572 0.07800054 -0.02059888 -0.03929078 0.07803207 -0.02078229 -0.03946048 0.0781666 -0.02065163 -0.04016649 0.07810693 -0.0211063 -0.04074507 0.07820588 -0.02142328 -0.04032123 0.07800537 -0.02148145 -0.04118061 0.07808369 -0.02199226 -0.04122769 0.07822394 -0.02185434 -0.0411064 0.07800537 -0.02219182 -0.04172968 0.07823848 -0.02241611 -0.04171383 0.07811725 -0.02256822 -0.04183006 0.07803356 -0.02298003 -0.04212325 0.07800215 -0.02373373 -0.0421769 0.07820194 -0.02313452 -0.04253959 0.07826155 -0.02384179 -0.04235255 0.0780816 -0.02379912 -0.04278278 0.07821094 -0.02471673 -0.04258054 0.07803809 -0.02475607 -0.0427649 0.07812386 -0.02506452 -0.04277783 0.07807099 -0.02600002 -0.04287111 0.07815682 -0.02605623 -0.04258656 0.07800245 -0.02642709 -0.04277372 0.07812041 -0.02685898 -0.04281252 0.07834589 -0.02744626 -0.0424183 0.07801419 -0.02764165 -0.04261642 0.0781846 -0.02780377 -0.04228806 0.07808893 -0.02837932 -0.04241108 0.0782485 -0.02844423 -0.0420798 0.07812184 -0.02888154 -0.04173523 0.07800585 -0.02902644 -0.04186165 0.0782541 -0.02941882 -0.04144144 0.07810688 -0.0297569 -0.04124927 0.0780223 -0.02975934 -0.04137468 0.0782563 -0.03002578 -0.04088765 0.07810497 -0.03033709 -0.04044836 0.07818782 -0.0307852 -0.04034554 0.07836139 -0.03096634 -0.03992754 0.07800447 -0.03079092 -0.0400753 0.07812422 -0.03096908 -0.03975051 0.07833439 -0.03131622 -0.03941893 0.07808947 -0.03127151 -0.03920292 0.07839763 -0.03157925 -0.03874975 0.07818609 -0.03163909 -0.03873789 0.07806998 -0.03150802 -0.0384556 0.07837492 -0.03181248 -0.03785765 0.07800465 -0.03155177 -0.03747808 0.07808351 -0.03177529 -0.03716439 0.07823044 -0.03193151 -0.03626841 0.07825523 -0.03189975 -0.03607922 0.07800662 -0.03156471 -0.03610289 0.07807201 -0.0317133 -0.03565382 0.07814878 -0.0317083 -0.03551721 0.07836806 -0.0318045 -0.0349726 0.07818204 -0.0315364 -0.03412377 0.07800459 -0.03080594 -0.03477269 0.07804471 -0.03127181 -0.03444373 0.07819467 -0.03132456 -0.03360033 0.07811057 -0.03074222 -0.03321081 0.07804316 -0.0302971 -0.03275281 0.07800638 -0.02969837 -0.03249806 0.07838422 -0.02995657 -0.03259879 0.0781446 -0.02987706 -0.03211593 0.07832479 -0.02945494 -0.03205341 0.07811176 -0.02907991 -0.03210383 0.07800567 -0.02876406 -0.03167849 0.07821959 -0.02859979 -0.0315988 0.07809251 -0.02811676 -0.03177642 0.07800227 -0.02800798 -0.03138595 0.0782271 -0.0278927 -0.03118956 0.078404 -0.02749317 -0.03138619 0.07804012 -0.02709907 -0.03123533 0.07817912 -0.02724158 -0.03109592 0.07820278 -0.02639418 -0.03108513 0.08879178 -0.02599984 -0.03129142 0.08894503 -0.02669602 -0.03124046 0.08873903 -0.02748537 -0.03139358 0.08890622 -0.027516 -0.03162127 0.0889979 -0.02752864 -0.03154277 0.08880603 -0.02826899 -0.03189742 0.08899044 -0.0283975 -0.03180158 0.08877176 -0.02884715 -0.03210729 0.08891165 -0.02910584 -0.03220087 0.08880287 -0.02943986 -0.03255015 0.08896946 -0.02954411 -0.03265118 0.08879047 -0.03000771 -0.0328471 0.08891844 -0.03003394 -0.03348022 0.08899706 -0.03037446 -0.03307038 0.08877503 -0.03043556 -0.03356033 0.08883219 -0.03077924 -0.03417921 0.08890402 -0.03107798 -0.03430658 0.08867001 -0.03134387 -0.03469204 0.08898341 -0.03115898 -0.03485548 0.08887434 -0.0314328 -0.03569626 0.08862918 -0.0318492 -0.03549301 0.08895581 -0.03151226 -0.03579956 0.08884239 -0.03175419 -0.03628033 0.08899962 -0.03152728 -0.03649908 0.08895117 -0.03171098 -0.03680509 0.08883357 -0.03187692 -0.0375052 0.08886981 -0.03182548 -0.03732985 0.08897495 -0.03165876 -0.03812688 0.08892571 -0.03166681 -0.0384714 0.08881139 -0.03171771 -0.03857159 0.08899784 -0.03136634 -0.03908681 0.08894997 -0.03134876 -0.03944611 0.0887717 -0.03139913 -0.03997021 0.08890718 -0.0309953 -0.04016745 0.08899843 -0.03060477 -0.04047 0.08883821 -0.03075098 -0.04108959 0.08898413 -0.02991789 -0.04108774 0.08887058 -0.03017646 -0.04160821 0.08892315 -0.02949661 -0.0418238 0.0887494 -0.02947723 -0.04222053 0.08881467 -0.02875125 -0.04211783 0.0889979 -0.02826923 -0.04223954 0.08894163 -0.02836078 -0.04247444 0.08883059 -0.02815115 -0.04280275 0.08873891 -0.02732735 -0.0425592 0.08894002 -0.0275129 -0.04277944 0.08890444 -0.02656859 -0.04292815 0.08877313 -0.02618354 -0.04259949 0.08899492 -0.02628016 -0.0427764 0.08892089 -0.02575767 -0.04282051 0.08883213 -0.02513366 -0.04225194 0.08899778 -0.02404195 -0.04253649 0.08896887 -0.02463334 -0.04255926 0.08884263 -0.02408075 -0.04204779 0.08895647 -0.0233038 -0.04215949 0.08881086 -0.02312296 -0.04172748 0.08877491 -0.02242571 -0.04159116 0.08889919 -0.02242881 -0.04130858 0.08899682 -0.02241879 -0.04108989 0.0888586 -0.02180093 -0.04077559 0.08879131 -0.02144604 -0.04059404 0.08897262 -0.02160036 -0.0402643 0.08890777 -0.02120196 -0.03928256 0.08899801 -0.02088767 -0.04031562 0.08873951 -0.02106636 -0.0397014 0.08877348 -0.02072221 -0.03967553 0.0889399 -0.02090924 -0.03900724 0.08879613 -0.02044433 -0.03891676 0.08894491 -0.02058416 -0.03816515 0.08871507 -0.02015095 -0.03820163 0.08890295 -0.02031254 -0.03766077 0.08899199 -0.02041792 -0.03735959 0.08880841 -0.02010452 -0.0370866 0.08899319 -0.02035027 -0.03660786 0.08872872 -0.02006065 -0.03643465 0.08890235 -0.02021306 -0.03558593 0.08889663 -0.0203588 -0.03539645 0.0889815 -0.02057468 -0.03496575 0.08875334 -0.02041357 -0.03466981 0.088903 -0.02068263 -0.03399306 0.08871883 -0.02085655 -0.03430014 0.08899509 -0.0210812 -0.03399074 0.08888739 -0.02100694 -0.03343307 0.08879345 -0.02128475 -0.03329229 0.0889486 -0.02162009 -0.03290975 0.08885335 -0.02180111 -0.03247278 0.08880972 -0.0222122 -0.0330438 0.08899509 -0.02204531 -0.03245985 0.08895868 -0.0225231 -0.03187984 0.08865356 -0.02289319 -0.03204566 0.08886593 -0.02289271 -0.03181344 0.08899575 -0.02381283 -0.03165137 0.08871936 -0.02337694 -0.03177887 0.08891308 -0.02347034 -0.03128474 0.08875763 -0.02437877 -0.03138291 0.08889514 -0.02446812 -0.03144347 0.08899521 -0.02519494 -0.03110837 0.0887531 -0.0252546 -0.03121912 0.08892136 -0.02567857 -0.02997589 0.08700001 -0.02612084 -0.03002113 0.08758145 -0.02651906 -0.03014236 0.08763688 -0.02736341 -0.03027927 0.08700001 -0.02801805 -0.03027987 0.08763659 -0.02792924 -0.03049629 0.0876019 -0.02857708 -0.03098505 0.08700001 -0.02961403 -0.03085184 0.08758801 -0.02934879 -0.03130584 0.08761411 -0.03006118 -0.03206288 0.08700001 -0.03098654 -0.03175753 0.08757436 -0.03063672 -0.03214633 0.08764082 -0.03103226 -0.03359258 0.08700001 -0.03214341 -0.03332614 0.08764863 -0.03194475 -0.03389102 0.08767223 -0.03225392 -0.03477662 0.08763772 -0.03263068 -0.03538727 0.08700001 -0.03282928 -0.03559976 0.08760195 -0.03285413 -0.03628808 0.08761215 -0.03295797 -0.03695046 0.08700001 -0.03301042 -0.03699612 0.08766353 -0.03298503 -0.03767019 0.08762294 -0.03296041 -0.03834068 0.08700001 -0.0328812 -0.03836631 0.08759188 -0.03286224 -0.03983801 0.08700001 -0.03241759 -0.0397253 0.08758604 -0.03244507 -0.04033899 0.0876038 -0.03214716 -0.04119348 0.08700001 -0.03161811 -0.04107373 0.0876522 -0.03167879 -0.04160678 0.08763158 -0.03126138 -0.0425738 0.08700001 -0.03029149 -0.04202961 0.08759075 -0.03086429 -0.04254412 0.0876674 -0.03025013 -0.04289132 0.08759021 -0.02977544 -0.04329878 0.08759963 -0.02905279 -0.04352778 0.08700001 -0.02856189 -0.04362291 0.08759099 -0.02825713 -0.04394638 0.08700001 -0.02699387 -0.04394263 0.08760535 -0.02685773 -0.0439794 0.08767944 -0.02616775 -0.04396784 0.08700001 -0.02512681 -0.04397892 0.08755856 -0.0254569 -0.04388028 0.08762472 -0.02475309 -0.04368984 0.08764195 -0.02396327 -0.04354393 0.08700001 -0.02348494 -0.04327833 0.08764177 -0.02292054 -0.04291582 0.08700001 -0.02223807 -0.04284495 0.08767223 -0.022179 -0.04246062 0.08759105 -0.0216251 -0.04169601 0.08700001 -0.02076244 -0.04186868 0.08759349 -0.0209698 -0.04122799 0.0875923 -0.02042496 -0.0404576 0.08763563 -0.0199204 -0.0399338 0.08700001 -0.0196256 -0.03971314 0.08760815 -0.0195527 -0.03891074 0.08759576 -0.01926547 -0.03792971 0.08700001 -0.01902717 -0.03806304 0.08759188 -0.01908427 -0.03736752 0.08760279 -0.01901406 -0.03635632 0.08763867 -0.01903367 -0.03578102 0.08700001 -0.01908707 -0.03546017 0.087628 -0.01917797 -0.03480029 0.08765262 -0.0193659 -0.0342313 0.08700001 -0.0195592 -0.03425365 0.08756792 -0.019562 -0.03347045 0.08760279 -0.01995563 -0.03275984 0.08700001 -0.02040219 -0.03277182 0.08758735 -0.0204246 -0.03209787 0.08763682 -0.02101153 -0.03121912 0.08700001 -0.02199167 -0.03154104 0.0876398 -0.02163481 -0.03103113 0.08758431 -0.02234047 -0.03055864 0.08760267 -0.02326136 -0.03025233 0.08700001 -0.02404505 -0.03023296 0.08764255 -0.02424299 -0.03010487 0.08758163 -0.02480381 -0.03001379 0.08763092 -0.02565544 -0.03002649 0.07999998 -0.02687388 -0.02999716 0.07943165 -0.02599167 -0.03005802 0.0794022 -0.02686995 -0.03017926 0.07941699 -0.02756482 -0.0303623 0.07940888 -0.0282135 -0.03043192 0.07999998 -0.02843695 -0.03061485 0.07941734 -0.02886378 -0.03103983 0.07999998 -0.02970367 -0.03111112 0.07942795 -0.02979844 -0.03173649 0.07940787 -0.03060996 -0.0321381 0.07999998 -0.03105986 -0.03278452 0.07937282 -0.0315783 -0.033688 0.07999998 -0.03219538 -0.03334742 0.07942372 -0.03196984 -0.03395748 0.0793904 -0.03229832 -0.03464448 0.07934367 -0.03257745 -0.03548967 0.07999998 -0.03285264 -0.03525257 0.07933551 -0.03276276 -0.03591758 0.07938992 -0.03291034 -0.03648942 0.07936429 -0.03297406 -0.0375809 0.07999998 -0.03301048 -0.03718614 0.07936465 -0.03298985 -0.03805047 0.07941997 -0.03291893 -0.03869777 0.07935291 -0.03277903 -0.03961241 0.07999998 -0.03251266 -0.03957921 0.07941412 -0.03250879 -0.04142916 0.07999998 -0.03146505 -0.04159229 0.0794261 -0.03128588 -0.04225939 0.07938814 -0.03061074 -0.04293054 0.07999998 -0.02976566 -0.04266202 0.07939821 -0.03010863 -0.04297721 0.07934743 -0.02962189 -0.04336577 0.07940024 -0.02890169 -0.04372066 0.07999998 -0.02801799 -0.04362779 0.07939046 -0.02823561 -0.04386091 0.07941269 -0.02739262 -0.04401081 0.07999998 -0.02629715 -0.0439732 0.07939791 -0.02655988 -0.04399675 0.07942557 -0.02583324 -0.04394519 0.079427 -0.02513355 -0.04383665 0.07999998 -0.02438378 -0.04382306 0.07939338 -0.02445906 -0.04362797 0.079355 -0.02378338 -0.04338556 0.07940626 -0.02314019 -0.04321575 0.07999998 -0.02275753 -0.04305952 0.0794304 -0.02249699 -0.04234147 0.07999998 -0.02144926 -0.04259335 0.07939934 -0.02179199 -0.04137426 0.07941889 -0.02053278 -0.04095584 0.07999998 -0.0201978 -0.0406388 0.07940918 -0.02002334 -0.03907155 0.07999998 -0.01928418 -0.03938597 0.07940804 -0.01942241 -0.03876715 0.07938778 -0.01923257 -0.03817367 0.07932102 -0.01911598 -0.03712242 0.07999998 -0.0189839 -0.0364685 0.07939177 -0.01902192 -0.03543901 0.07999998 -0.01916098 -0.03558319 0.07933866 -0.01915961 -0.03493368 0.07941234 -0.01931458 -0.0341587 0.07999998 -0.01959645 -0.03411638 0.07941222 -0.01962023 -0.03290235 0.07999998 -0.0203005 -0.03319728 0.07942485 -0.02011972 -0.03188014 0.07941842 -0.0212239 -0.03174483 0.07999998 -0.02136224 -0.03092694 0.07999998 -0.02249372 -0.03040206 0.07999998 -0.0236451 -0.03006339 0.07999998 -0.02495449 -0.03007441 0.07931935 -0.02512061 -0.03004616 0.07926636 -0.02615457 -0.03017401 0.07911777 -0.02569067 -0.03040564 0.0790081 -0.02525836 -0.03029221 0.07913261 -0.02461665 -0.03021472 0.07936328 -0.02430528 -0.03044146 0.07934039 -0.0235877 -0.03069728 0.07900404 -0.02404415 -0.03054964 0.0790916 -0.02383559 -0.03067398 0.07933998 -0.0230416 -0.03109449 0.07901287 -0.02294617 -0.03074133 0.07914489 -0.02319353 -0.03094321 0.07933592 -0.02252072 -0.03128159 0.07910031 -0.02228438 -0.03132981 0.07934403 -0.02191758 -0.03188121 0.07924312 -0.02131551 -0.03212118 0.07900643 -0.02151155 -0.03215163 0.0791018 -0.02120542 -0.03252381 0.07932287 -0.02064186 -0.03304082 0.07902932 -0.02061116 -0.0331611 0.07911533 -0.02034586 -0.03335982 0.07927584 -0.02006757 -0.03452086 0.07900214 -0.01987743 -0.03415274 0.07908433 -0.01982706 -0.03426182 0.07926809 -0.0196138 -0.0349425 0.07921308 -0.01939558 -0.03503501 0.07907444 -0.01952123 -0.03589832 0.07909935 -0.01927447 -0.03608697 0.07902318 -0.01939523 -0.03628844 0.07921677 -0.01911795 -0.03721135 0.07932913 -0.01901793 -0.03698235 0.07909315 -0.01919853 -0.03744679 0.0790047 -0.01939928 -0.03775203 0.07917416 -0.01914358 -0.03869473 0.07900375 -0.01962423 -0.03864449 0.07906872 -0.01943296 -0.03924041 0.07921952 -0.01944899 -0.03968971 0.07912278 -0.01970559 -0.04005652 0.07935053 -0.0197162 -0.04031509 0.07904428 -0.0201354 -0.04068154 0.07900142 -0.02053296 -0.04060894 0.07919526 -0.02011191 -0.04116457 0.07921075 -0.0204764 -0.04152041 0.07908183 -0.02093249 -0.0419088 0.07933241 -0.02102965 -0.04217672 0.07919865 -0.02141845 -0.04190087 0.07900768 -0.02153724 -0.04234004 0.07905 -0.02190333 -0.04275846 0.07917982 -0.02219885 -0.04323899 0.07925146 -0.02295231 -0.0428065 0.07900893 -0.02279573 -0.04313355 0.0790916 -0.02306121 -0.04351073 0.07916384 -0.02379399 -0.04352152 0.0790528 -0.02426791 -0.04356521 0.0790022 -0.02521294 -0.04379975 0.07923519 -0.02464044 -0.04377424 0.07908976 -0.0253973 -0.0439189 0.07924878 -0.02547597 -0.04390156 0.07918816 -0.02626901 -0.04371368 0.07907402 -0.02694177 -0.0438112 0.07926142 -0.02738052 -0.04351395 0.07900327 -0.02706581 -0.04327613 0.07900542 -0.02806794 -0.0434525 0.07908403 -0.02813518 -0.04350161 0.07922953 -0.02839684 -0.04310607 0.07917332 -0.02919369 -0.04283946 0.07903385 -0.02927953 -0.04273277 0.07912296 -0.02972567 -0.04230898 0.07913529 -0.03034132 -0.04197895 0.07900273 -0.03035253 -0.04182511 0.07926738 -0.03100681 -0.04158067 0.07916474 -0.03113627 -0.04135328 0.07905328 -0.03114628 -0.04103094 0.07932627 -0.03170412 -0.04070568 0.07912957 -0.03175407 -0.04044455 0.07933813 -0.03207874 -0.04045516 0.0790084 -0.03166264 -0.04001981 0.07922518 -0.03223067 -0.03981411 0.07907861 -0.03216809 -0.03923821 0.07920604 -0.03254562 -0.03921896 0.07900351 -0.03221458 -0.03868889 0.07903629 -0.03249347 -0.03799468 0.0791887 -0.03283625 -0.03721588 0.0790596 -0.03275406 -0.03669786 0.07900202 -0.03260821 -0.03680467 0.07915699 -0.0328713 -0.0358203 0.07914936 -0.03276515 -0.0355913 0.0790373 -0.03256422 -0.03476661 0.07907652 -0.03240746 -0.03430885 0.07917451 -0.03233981 -0.03429448 0.07900243 -0.03200107 -0.03339773 0.07919478 -0.03189933 -0.03352671 0.0790469 -0.0317713 -0.03255575 0.07912617 -0.03121185 -0.03223055 0.07938528 -0.03111541 -0.03223735 0.07900309 -0.03059989 -0.03192532 0.07921004 -0.03070098 -0.03176546 0.07906061 -0.03026962 -0.03128594 0.07922059 -0.02991682 -0.03118413 0.07909023 -0.02951407 -0.03082889 0.0792216 -0.0291416 -0.03107678 0.07900822 -0.02896881 -0.03076809 0.0790764 -0.02865356 -0.03056615 0.07920706 -0.0285322 -0.03047895 0.07906639 -0.02780282 -0.03024798 0.07922703 -0.02756953 -0.03058922 0.07900255 -0.02750915 -0.03033691 0.07902669 -0.02653598 -0.03020805 0.07911741 -0.02675247 -0.03006243 0.08775103 -0.02614563 -0.03019618 0.08790516 -0.02586299 -0.03014695 0.0878176 -0.02683246 -0.03039842 0.08799856 -0.02590888 -0.03042775 0.08798617 -0.02709239 -0.0304479 0.08780419 -0.02820473 -0.03056025 0.08790981 -0.02818417 -0.03085613 0.08799767 -0.02839356 -0.0310235 0.08796072 -0.02905118 -0.03091913 0.08782941 -0.02924114 -0.03124213 0.08785653 -0.02974754 -0.03168815 0.08780711 -0.03041756 -0.03200757 0.08799183 -0.03037893 -0.03228926 0.08789545 -0.03093564 -0.03271365 0.08765572 -0.03151869 -0.03313004 0.08786308 -0.03166294 -0.03328669 0.08797097 -0.03156727 -0.03426814 0.08788323 -0.0322687 -0.03423202 0.08799767 -0.03198122 -0.03499215 0.08791667 -0.03248959 -0.03553807 0.08778977 -0.03276038 -0.03614121 0.08799535 -0.03256982 -0.03582561 0.08792108 -0.03267598 -0.03631579 0.08779269 -0.03287696 -0.03675734 0.08791077 -0.0327928 -0.03775393 0.08782994 -0.03285074 -0.03778415 0.0879938 -0.03258097 -0.03857165 0.08789485 -0.03263801 -0.03894299 0.0876494 -0.03271383 -0.03965222 0.08778274 -0.03239881 -0.03938013 0.08798295 -0.03221046 -0.0394839 0.08790415 -0.03233444 -0.04027956 0.0879895 -0.03177607 -0.04049199 0.08784294 -0.03192532 -0.04131472 0.08788812 -0.0312981 -0.04136699 0.08799558 -0.03096121 -0.04211997 0.08779627 -0.03064811 -0.04213619 0.08795732 -0.03033632 -0.04283332 0.08785295 -0.02963268 -0.04270857 0.08799177 -0.0293644 -0.04341161 0.08780384 -0.02858465 -0.04319804 0.08795475 -0.02861005 -0.04378217 0.08766901 -0.02766925 -0.04359954 0.08791524 -0.02759504 -0.04350966 0.08799505 -0.0272383 -0.0438379 0.08779513 -0.02701282 -0.0437982 0.08789819 -0.02650976 -0.0435931 0.08799546 -0.02577525 -0.04392248 0.08775168 -0.02548241 -0.04375815 0.0879293 -0.025635 -0.04372769 0.08783197 -0.02451604 -0.0434041 0.08799207 -0.02424645 -0.04360431 0.08796048 -0.02479672 -0.04339289 0.08783012 -0.02342408 -0.04311513 0.08795171 -0.02319264 -0.04284483 0.08788907 -0.02247625 -0.04245758 0.08799439 -0.02224981 -0.04236733 0.0879383 -0.02191025 -0.04240918 0.08780753 -0.02170908 -0.04197001 0.08775365 -0.02115809 -0.04168623 0.0879454 -0.0211448 -0.04131537 0.08781629 -0.02061408 -0.04101043 0.0879997 -0.02078455 -0.04095315 0.08793097 -0.02051156 -0.04068356 0.08779525 -0.02015262 -0.04009747 0.08798927 -0.0201261 -0.04011005 0.08789509 -0.01993256 -0.03967314 0.08779519 -0.01962912 -0.03908193 0.08794885 -0.01959103 -0.03882253 0.08780711 -0.01933336 -0.03786563 0.08778613 -0.01913392 -0.03803741 0.08799761 -0.01948678 -0.03782027 0.08794552 -0.01930487 -0.03711915 0.08785712 -0.01914 -0.03682285 0.08775442 -0.01906037 -0.03637373 0.08799761 -0.01942992 -0.03641021 0.08790361 -0.01921486 -0.03545391 0.08780401 -0.01926881 -0.03570622 0.08793455 -0.01936465 -0.03476077 0.08799183 -0.01977503 -0.03468388 0.08789962 -0.01958954 -0.03390187 0.08778178 -0.01980751 -0.03377306 0.08795243 -0.0200929 -0.03326302 0.08778274 -0.02016776 -0.03324705 0.0879954 -0.02056556 -0.03257918 0.08794498 -0.02090144 -0.0325694 0.08779036 -0.0206899 -0.0318523 0.08799558 -0.02184474 -0.03182351 0.0878759 -0.02151668 -0.03107869 0.0877512 -0.02237677 -0.0310688 0.0878843 -0.02260416 -0.03111743 0.08799254 -0.02293455 -0.0306006 0.08775746 -0.02332407 -0.03070014 0.08794552 -0.02358913 -0.03041362 0.08777981 -0.02386158 -0.03031259 0.08786147 -0.02449971 -0.03012955 0.08777415 -0.02513313 -0.03035151 0.08795583 -0.02495509 -0.02899974 0.08660328 -0.02599197 -0.02902281 0.08599996 -0.02679818 -0.02906048 0.08656764 -0.02697962 -0.02924311 0.08657002 -0.0279718 -0.02944368 0.08599996 -0.02868634 -0.02962553 0.08659267 -0.02910459 -0.03023904 0.08599996 -0.0302993 -0.03007775 0.08658605 -0.03000617 -0.03051102 0.08658605 -0.03067541 -0.03109687 0.08599996 -0.03140878 -0.0310527 0.08666741 -0.03132742 -0.0315566 0.0865814 -0.03186041 -0.03242599 0.08599996 -0.03259837 -0.03214889 0.08656525 -0.03236126 -0.03318905 0.08657145 -0.03303325 -0.03420644 0.08599996 -0.03350937 -0.03403413 0.08667486 -0.03341341 -0.03468549 0.08660954 -0.0336526 -0.03556048 0.08599996 -0.03387588 -0.03538626 0.0865994 -0.03383189 -0.03639441 0.08660274 -0.03397709 -0.03713983 0.08599996 -0.03401833 -0.03757059 0.08661228 -0.03397834 -0.03930711 0.08599996 -0.03369003 -0.03879767 0.08663219 -0.0337904 -0.0397433 0.08658611 -0.03351271 -0.04063683 0.08658868 -0.03312742 -0.04130047 0.08599996 -0.03276896 -0.04147255 0.08666741 -0.03261417 -0.04214805 0.08657443 -0.03212231 -0.04288077 0.08599996 -0.03145658 -0.04271692 0.08663994 -0.03158187 -0.04323124 0.08664906 -0.03099805 -0.04372662 0.08656996 -0.0303297 -0.04393696 0.08599996 -0.03000509 -0.0441209 0.08658611 -0.02964127 -0.0445767 0.08599996 -0.02860534 -0.04450446 0.08663141 -0.02875834 -0.04478818 0.08657932 -0.02782315 -0.04490935 0.08599996 -0.0272426 -0.04493713 0.08658975 -0.02698218 -0.04501086 0.08599996 -0.02585679 -0.04499137 0.08661663 -0.02620327 -0.04495948 0.08658033 -0.02517163 -0.04485732 0.08599996 -0.02446252 -0.0447694 0.08667111 -0.02415978 -0.04441297 0.08599996 -0.02294027 -0.0445652 0.08660209 -0.02341091 -0.04427546 0.08662897 -0.0226925 -0.04390299 0.08662253 -0.02197051 -0.04342871 0.08599996 -0.02120572 -0.0434978 0.08659493 -0.02133852 -0.0430085 0.08659261 -0.02072244 -0.04219341 0.08599996 -0.01989889 -0.04243016 0.08662134 -0.02013438 -0.04166603 0.08661109 -0.01950299 -0.04053926 0.08599996 -0.01879352 -0.04078322 0.08660078 -0.0189554 -0.0400542 0.08666872 -0.01862305 -0.03933405 0.08659267 -0.01835119 -0.038643 0.08599996 -0.01815807 -0.03857171 0.08661448 -0.01816153 -0.03782498 0.08660042 -0.01804637 -0.0368601 0.08599996 -0.01798158 -0.03702372 0.08660036 -0.01800382 -0.03619521 0.08657443 -0.01804149 -0.03521806 0.08599996 -0.01819276 -0.03538733 0.08660286 -0.01816838 -0.03441804 0.08663684 -0.01843386 -0.03383576 0.08599996 -0.01863908 -0.03354763 0.08659178 -0.01878648 -0.03283566 0.0865674 -0.01916939 -0.03215408 0.08599996 -0.01960253 -0.03218042 0.08661663 -0.0196225 -0.03157716 0.08661103 -0.02012521 -0.03086555 0.08599996 -0.0208525 -0.03102833 0.0866236 -0.02068698 -0.03049314 0.08661562 -0.02135634 -0.0299285 0.08599996 -0.02221739 -0.03009045 0.08658891 -0.02197265 -0.02970451 0.0866248 -0.02273511 -0.02942836 0.08658707 -0.02342355 -0.02935063 0.08599996 -0.02364057 -0.02920389 0.0865978 -0.02422058 -0.02904784 0.08599996 -0.02500349 -0.02907049 0.08663415 -0.02501094 -0.02900803 0.08099997 -0.02659898 -0.02900892 0.08039689 -0.02560693 -0.02902615 0.08041143 -0.02661645 -0.02917343 0.08036017 -0.02762818 -0.02930277 0.08099997 -0.02822434 -0.0294888 0.08043909 -0.02876591 -0.03007811 0.08099997 -0.03006792 -0.02987802 0.08042556 -0.02964186 -0.03036844 0.08039683 -0.03047502 -0.03102004 0.08039909 -0.03130835 -0.03158473 0.08099997 -0.03192746 -0.03153783 0.08038675 -0.03183746 -0.03204661 0.08033424 -0.032265 -0.03284585 0.08040738 -0.03283357 -0.03303998 0.08099997 -0.03295844 -0.03354644 0.08037507 -0.03320801 -0.03431284 0.08099997 -0.03354805 -0.03441452 0.08039939 -0.033571 -0.03540575 0.08044868 -0.03384041 -0.03586184 0.08099997 -0.03393089 -0.03618681 0.08040577 -0.03395551 -0.03696656 0.08038675 -0.03399437 -0.0378611 0.08099997 -0.03398233 -0.03800874 0.08041006 -0.03393775 -0.03898167 0.08042079 -0.03374922 -0.03979349 0.08099997 -0.03350937 -0.0397433 0.08041679 -0.033513 -0.04043978 0.08042353 -0.03322148 -0.0410465 0.08099997 -0.03290849 -0.04099625 0.08036547 -0.03292268 -0.04151552 0.08036392 -0.0325905 -0.04250621 0.08099997 -0.03184306 -0.04211235 0.08041292 -0.03215038 -0.04273277 0.08037501 -0.0315693 -0.04335981 0.08038693 -0.03085076 -0.04387414 0.08099997 -0.03013032 -0.0439015 0.08039915 -0.03003823 -0.04429346 0.08037334 -0.02926844 -0.0445404 0.08099997 -0.02869141 -0.04458045 0.08038467 -0.02853828 -0.04479742 0.08038657 -0.02776384 -0.04493874 0.08099997 -0.02713584 -0.04493474 0.08041387 -0.02700275 -0.04500073 0.08040434 -0.02603816 -0.04495841 0.08099997 -0.02494007 -0.04491937 0.08032029 -0.02500236 -0.04480338 0.0804398 -0.02423709 -0.04458516 0.08042556 -0.02346026 -0.0444374 0.08099997 -0.0230202 -0.04429239 0.08040213 -0.02271884 -0.04383337 0.08039057 -0.02184134 -0.04348236 0.08099997 -0.02126306 -0.04327607 0.0803864 -0.02104723 -0.04270035 0.0803979 -0.02039283 -0.04169082 0.08099997 -0.01947546 -0.04212605 0.08040732 -0.01986175 -0.0414921 0.08032029 -0.01940208 -0.04078173 0.08033096 -0.01896828 -0.03979349 0.08099997 -0.01849061 -0.04008048 0.08039897 -0.01862108 -0.03933364 0.08039808 -0.01835209 -0.03779971 0.08099997 -0.01800787 -0.03860098 0.08039414 -0.0181666 -0.03780037 0.08039158 -0.01804476 -0.03618365 0.08040064 -0.01804524 -0.03580611 0.08099997 -0.01807928 -0.0353921 0.08040958 -0.01816588 -0.03412604 0.08099997 -0.01851302 -0.0338633 0.08038598 -0.01864689 -0.03315865 0.08032739 -0.01900154 -0.03269821 0.08099997 -0.01924741 -0.0323289 0.08039414 -0.01950448 -0.03154897 0.08099997 -0.02012497 -0.03154671 0.0803402 -0.02016556 -0.03061968 0.08040177 -0.02117288 -0.03022217 0.08099997 -0.02169626 -0.03007745 0.08041715 -0.02199363 -0.02971106 0.08040213 -0.02271109 -0.0294069 0.08099997 -0.02344882 -0.02936047 0.08039951 -0.02362453 -0.0290572 0.08099997 -0.02494764 -0.02913063 0.08040893 -0.024576 -0.02905422 0.08026415 -0.02578538 -0.02918106 0.08011537 -0.02556264 -0.02920949 0.08009004 -0.02633702 -0.02912282 0.08024758 -0.02501052 -0.02937805 0.08000963 -0.02624791 -0.02939242 0.08003515 -0.02482658 -0.02927577 0.08017206 -0.02437812 -0.02978068 0.08000081 -0.0236417 -0.02961236 0.0800656 -0.02362418 -0.02955847 0.08020263 -0.02331006 -0.02988398 0.08009231 -0.02281123 -0.02996343 0.08023202 -0.02234536 -0.030384 0.08002871 -0.02209192 -0.03116101 0.08000063 -0.02116936 -0.03044313 0.08010685 -0.02173238 -0.03042036 0.08022296 -0.02158039 -0.03133887 0.08002889 -0.02078396 -0.03106886 0.08034825 -0.02065265 -0.03108429 0.08015745 -0.02080887 -0.03179758 0.08012866 -0.0201295 -0.03236865 0.08022356 -0.01956391 -0.03267413 0.08007234 -0.01953506 -0.03308302 0.08000451 -0.0194751 -0.03369235 0.08008712 -0.01893931 -0.03416043 0.08018219 -0.01863014 -0.0348671 0.08000069 -0.01872223 -0.03465676 0.08037185 -0.018359 -0.03490257 0.08004105 -0.01857399 -0.03501302 0.08015358 -0.01838773 -0.03563046 0.08023786 -0.01818484 -0.0361135 0.08006584 -0.01827871 -0.03687649 0.08033108 -0.01801562 -0.03703081 0.08000594 -0.01837795 -0.03698348 0.08011353 -0.01817357 -0.03795772 0.08018308 -0.01815825 -0.03822749 0.08008301 -0.0183025 -0.0390073 0.08001589 -0.01859974 -0.03897035 0.08020353 -0.01834112 -0.03993856 0.08022981 -0.01863235 -0.03977769 0.08011126 -0.01868468 -0.04025471 0.08000516 -0.01910442 -0.04086911 0.0800811 -0.01923674 -0.04263132 0.08000349 -0.02087515 -0.04187208 0.08005416 -0.01996809 -0.04210591 0.08022558 -0.01993834 -0.0426312 0.08018827 -0.02046275 -0.04307925 0.08024543 -0.02088785 -0.04297268 0.08007133 -0.02102822 -0.04364508 0.08018743 -0.02172237 -0.04364967 0.08004385 -0.02207428 -0.04412674 0.08020502 -0.02255821 -0.04411113 0.08009529 -0.02278542 -0.04420864 0.08000361 -0.02352398 -0.04443579 0.0801711 -0.02335435 -0.04470407 0.08025091 -0.02405518 -0.04464399 0.08008921 -0.02446377 -0.04469311 0.08004671 -0.02517521 -0.04493224 0.0802319 -0.02593559 -0.04454094 0.08000087 -0.02683615 -0.04475718 0.08006429 -0.02633178 -0.04487264 0.08023452 -0.02695131 -0.0447126 0.08012181 -0.02740931 -0.0443415 0.08002877 -0.02830016 -0.04454874 0.08016425 -0.02828317 -0.04386949 0.08000928 -0.0293166 -0.04413264 0.08024173 -0.02948766 -0.04401946 0.08010804 -0.02944654 -0.04351437 0.08020067 -0.03048974 -0.04337716 0.0800935 -0.03050434 -0.04304367 0.08000493 -0.03064513 -0.04291152 0.08017122 -0.03121501 -0.04222011 0.08022719 -0.0319693 -0.04237806 0.08006924 -0.0316053 -0.04075151 0.08000338 -0.03261709 -0.04161709 0.08004081 -0.0321871 -0.04146009 0.08017838 -0.03250849 -0.04075837 0.08013331 -0.03289252 -0.04006713 0.08019924 -0.03329092 -0.04002279 0.0800454 -0.0331031 -0.03914576 0.08024585 -0.03364628 -0.03909295 0.08010804 -0.03353434 -0.03915935 0.0800091 -0.03332453 -0.03797352 0.08025234 -0.03388404 -0.03791105 0.08001446 -0.03358823 -0.03785169 0.08009928 -0.0337693 -0.0367999 0.08023136 -0.03393012 -0.03673583 0.08007764 -0.03377658 -0.03600704 0.08000409 -0.03354746 -0.03604143 0.08007913 -0.03372663 -0.03571557 0.08025646 -0.03384011 -0.03511625 0.08022379 -0.03370249 -0.03495675 0.08004122 -0.03344023 -0.03433817 0.08023989 -0.03347325 -0.03394019 0.08011275 -0.03321111 -0.03408521 0.08001041 -0.03306227 -0.03285372 0.08021599 -0.03275579 -0.03309625 0.08004939 -0.03267335 -0.03260642 0.08000296 -0.03219991 -0.03210842 0.08008253 -0.03206729 -0.03134256 0.08019703 -0.03151875 -0.03141188 0.08006751 -0.0313856 -0.03106021 0.08000588 -0.03076809 -0.03088557 0.08018881 -0.03100758 -0.03057563 0.0800808 -0.03041094 -0.03051823 0.08027017 -0.03060281 -0.0300529 0.08018547 -0.02976799 -0.0301752 0.08000802 -0.02941983 -0.02975112 0.08025276 -0.02924156 -0.02959328 0.0800898 -0.02846926 -0.02944874 0.08026987 -0.02849566 -0.0295971 0.08000433 -0.02778732 -0.02930718 0.0800935 -0.02734827 -0.02909833 0.08023452 -0.02672535 -0.02909666 0.08681017 -0.02596187 -0.0291239 0.08679378 -0.0267961 -0.02926921 0.08695155 -0.02598977 -0.02933293 0.08692187 -0.02734065 -0.02916955 0.08673232 -0.02737492 -0.02955603 0.08699554 -0.02764534 -0.02941662 0.086793 -0.0282793 -0.02969932 0.08692538 -0.02866554 -0.02970522 0.08677774 -0.02910023 -0.0301693 0.08699524 -0.02933514 -0.0301541 0.08693623 -0.02965438 -0.03014498 0.08679395 -0.02995461 -0.03067314 0.08679676 -0.03075462 -0.0305885 0.08689886 -0.03046149 -0.03100228 0.08696752 -0.0308218 -0.03142058 0.08690422 -0.03145545 -0.0317704 0.08676773 -0.03196644 -0.03177559 0.08699786 -0.03152114 -0.03227412 0.0869289 -0.03217124 -0.03266334 0.08667218 -0.03270065 -0.03273361 0.08684378 -0.03261637 -0.03351241 0.08699309 -0.0327816 -0.03366357 0.08691567 -0.0330435 -0.03355407 0.08675247 -0.0331515 -0.03481841 0.08697378 -0.03337275 -0.03471535 0.08684891 -0.03352755 -0.03559368 0.08680444 -0.03378504 -0.03626668 0.0869233 -0.03374862 -0.03632408 0.08699518 -0.03357803 -0.03661686 0.08677607 -0.03391325 -0.03743773 0.08681952 -0.03388309 -0.03749465 0.08699345 -0.03361737 -0.03831821 0.08680635 -0.03379726 -0.0382725 0.0869463 -0.03363478 -0.03937828 0.08683574 -0.03351747 -0.03934544 0.08699357 -0.03325152 -0.04001349 0.08679133 -0.03331822 -0.04021263 0.08694165 -0.03305613 -0.04079771 0.08682048 -0.0329262 -0.04114472 0.08699065 -0.03241288 -0.04171204 0.08689981 -0.0322377 -0.04212236 0.08676594 -0.03205573 -0.04209977 0.08699738 -0.03161644 -0.0426045 0.08689028 -0.03146386 -0.04324114 0.08696526 -0.03052884 -0.04314893 0.08685666 -0.03089231 -0.04372942 0.08677691 -0.03019505 -0.04392313 0.08700054 -0.0291481 -0.04411798 0.08682197 -0.02941268 -0.04402607 0.08695048 -0.02923762 -0.04456585 0.08682847 -0.0282467 -0.04455101 0.08695745 -0.02762341 -0.04480582 0.08676093 -0.02744692 -0.04489052 0.08682662 -0.02629101 -0.04477608 0.08691477 -0.02650141 -0.04460912 0.08699792 -0.0258212 -0.04491674 0.08673411 -0.02525073 -0.04472148 0.08691954 -0.02495712 -0.04440981 0.08695679 -0.02382075 -0.04452395 0.08682012 -0.0236122 -0.04394304 0.08699661 -0.02291333 -0.04409867 0.08689206 -0.02269649 -0.04377424 0.08677238 -0.02187716 -0.04344773 0.08690935 -0.02161478 -0.04328042 0.08699363 -0.02170574 -0.04306858 0.08676701 -0.02088844 -0.04293769 0.08692705 -0.02098006 -0.0420171 0.08699429 -0.02027422 -0.04225438 0.08689063 -0.02019071 -0.04161155 0.08681458 -0.01958566 -0.04121601 0.0869314 -0.01948189 -0.04088056 0.08677661 -0.01908886 -0.04056328 0.08699387 -0.01926976 -0.04021298 0.08689123 -0.01886773 -0.03959494 0.08696311 -0.01874577 -0.03941369 0.08678573 -0.01845788 -0.0379287 0.08699935 -0.01845306 -0.03866779 0.08688157 -0.01833462 -0.03815752 0.08693647 -0.01832813 -0.03772312 0.08676916 -0.01810312 -0.03725552 0.08694541 -0.01826179 -0.03678816 0.08678597 -0.01807975 -0.03598475 0.08682072 -0.01816517 -0.03619778 0.0869947 -0.01841896 -0.03526532 0.08692878 -0.01842761 -0.03485023 0.0868023 -0.01838737 -0.03422123 0.08699095 -0.01886719 -0.03389096 0.08681148 -0.0187388 -0.03301078 0.08673089 -0.01911938 -0.03309595 0.08686017 -0.01918172 -0.03359508 0.08696424 -0.01908677 -0.03234922 0.08688288 -0.0196852 -0.03194814 0.08698546 -0.02025002 -0.03151583 0.08685505 -0.02035719 -0.03108763 0.08699923 -0.02125686 -0.03093081 0.08680558 -0.02092891 -0.03075081 0.08693951 -0.02140325 -0.03012406 0.08680146 -0.02207869 -0.0302695 0.08696216 -0.02224922 -0.0298348 0.08694618 -0.02305668 -0.0299369 0.08699959 -0.0232805 -0.02959281 0.08683186 -0.02329581 -0.02932167 0.0867685 -0.02400207 -0.02949833 0.08699429 -0.02461898 -0.02926081 0.08688741 -0.02477723 -0.02803856 0.08140558 -0.02514523 -0.02807533 0.08122974 -0.02581763 -0.02825129 0.08107894 -0.02523446 -0.02836674 0.0810092 -0.02599102 -0.02813029 0.08124756 -0.02488613 -0.02831631 0.08114641 -0.02421104 -0.02823823 0.08137196 -0.02397596 -0.02870148 0.08100104 -0.02369254 -0.02857273 0.08106052 -0.02363103 -0.02847486 0.08138924 -0.02313089 -0.02864271 0.0811479 -0.02302515 -0.02878916 0.08133244 -0.02235203 -0.02927821 0.08103001 -0.0220136 -0.02919912 0.08117514 -0.02172666 -0.02920842 0.08140218 -0.0215016 -0.0295757 0.08113586 -0.02118003 -0.02973479 0.08133304 -0.02071326 -0.03001964 0.08107131 -0.02068984 -0.03001761 0.08100253 -0.02101773 -0.03026664 0.08135497 -0.02004408 -0.03037619 0.08114159 -0.02012181 -0.03074622 0.08104115 -0.01992839 -0.03088325 0.08141243 -0.01940095 -0.03093081 0.08121639 -0.01946264 -0.03156161 0.08100867 -0.01929485 -0.03155505 0.08110165 -0.01906955 -0.03156322 0.08132523 -0.01884853 -0.03232127 0.08131849 -0.01833355 -0.03263503 0.08100348 -0.01859772 -0.03241968 0.08108389 -0.0185002 -0.03306478 0.08138877 -0.01791119 -0.03338515 0.08120769 -0.01784652 -0.03334504 0.08105361 -0.01805907 -0.03415393 0.08141922 -0.01745826 -0.03428161 0.08116453 -0.01753759 -0.03460061 0.08100789 -0.01771098 -0.0352022 0.08132851 -0.01719778 -0.03546112 0.08110147 -0.0173211 -0.03607785 0.08138936 -0.01705223 -0.03592699 0.08100616 -0.01745611 -0.03614008 0.08122205 -0.01711958 -0.03681969 0.08108478 -0.01720273 -0.03713572 0.08134204 -0.01701271 -0.03794425 0.08138692 -0.01705491 -0.03810602 0.08100521 -0.01745855 -0.03789299 0.08112263 -0.01720231 -0.03877407 0.08140558 -0.01717954 -0.03874492 0.081169 -0.01728367 -0.03963071 0.08138906 -0.01739794 -0.03942 0.08106762 -0.01757609 -0.03964704 0.08120453 -0.01749265 -0.04001098 0.08100759 -0.01791644 -0.04068559 0.08138096 -0.01779037 -0.04066765 0.0811811 -0.01788967 -0.04110729 0.08103877 -0.01831191 -0.04192203 0.08138221 -0.01846683 -0.04157394 0.08121746 -0.01834279 -0.04181504 0.08100724 -0.0188362 -0.04216474 0.08111965 -0.01882892 -0.04281032 0.08138978 -0.01913315 -0.04282844 0.08116966 -0.01928669 -0.04344683 0.08140218 -0.01972454 -0.04282498 0.08101987 -0.01959007 -0.04358273 0.08125913 -0.019939 -0.04363393 0.08110868 -0.02018767 -0.04420834 0.08138114 -0.0206139 -0.04368579 0.08100563 -0.02056568 -0.0442202 0.08111155 -0.02091032 -0.04477578 0.08135294 -0.02148997 -0.04469603 0.08114016 -0.02162021 -0.04484879 0.08100897 -0.02238237 -0.04521346 0.0814079 -0.02232652 -0.04506474 0.08117252 -0.02225303 -0.04538989 0.08133244 -0.022789 -0.045349 0.08109772 -0.02318638 -0.04564821 0.08135294 -0.02354812 -0.04549813 0.08100116 -0.02474987 -0.04562389 0.08114367 -0.02397805 -0.04586315 0.08139532 -0.02445995 -0.04556214 0.0810467 -0.02431768 -0.0458309 0.08121705 -0.02471297 -0.04597377 0.08140641 -0.02534949 -0.04584473 0.08112627 -0.02562111 -0.04598295 0.08134371 -0.02620315 -0.0456627 0.08102232 -0.02620655 -0.04596757 0.0813989 -0.02671951 -0.04579687 0.08112013 -0.02689749 -0.04549384 0.08100503 -0.02737063 -0.04585969 0.08141893 -0.02757567 -0.04574853 0.08121162 -0.0277518 -0.04547601 0.08105063 -0.02810424 -0.04561376 0.08141487 -0.02861803 -0.04547756 0.08126729 -0.0288698 -0.04528182 0.08109772 -0.02900701 -0.04494416 0.08100461 -0.02929925 -0.04518187 0.0813784 -0.02973347 -0.045116 0.08118468 -0.02964293 -0.04479628 0.08140569 -0.03049093 -0.04457402 0.08107256 -0.0304405 -0.04472458 0.0812053 -0.03044599 -0.04429823 0.08139044 -0.0312584 -0.04404503 0.08100372 -0.03093498 -0.04412043 0.08114045 -0.03128039 -0.04374164 0.08142554 -0.03196144 -0.0436846 0.0812202 -0.03191316 -0.04318714 0.0810554 -0.03218346 -0.04312413 0.08138269 -0.03258705 -0.04279398 0.08100384 -0.03236114 -0.04286855 0.08116489 -0.032669 -0.04228848 0.08138215 -0.03328055 -0.04198259 0.08106619 -0.03321009 -0.04202073 0.08122581 -0.03337997 -0.04119628 0.08100324 -0.03350049 -0.04131966 0.08138471 -0.03388923 -0.04123282 0.08119404 -0.03383213 -0.04079771 0.08103674 -0.03384649 -0.04049944 0.08141857 -0.03429037 -0.04044419 0.08117985 -0.03420621 -0.03966724 0.08140957 -0.03459328 -0.0396018 0.08124089 -0.03454691 -0.03901904 0.08100253 -0.03434586 -0.03941392 0.08107239 -0.03443771 -0.03879839 0.08140963 -0.03481614 -0.03874933 0.08123439 -0.03475773 -0.03818112 0.08108371 -0.03470981 -0.03768706 0.08139812 -0.03497469 -0.03787654 0.08120179 -0.03486418 -0.03751188 0.08100503 -0.03458845 -0.03701859 0.08124291 -0.03493458 -0.03686571 0.08106893 -0.03477293 -0.03630691 0.08140438 -0.03497511 -0.03595143 0.08123564 -0.03487426 -0.0356999 0.0811181 -0.03473418 -0.03522133 0.08140695 -0.03481984 -0.03550511 0.08100432 -0.03448641 -0.03479391 0.08120518 -0.03463786 -0.03436356 0.08143347 -0.03460526 -0.03445708 0.08103781 -0.03433513 -0.03387171 0.08120435 -0.03435379 -0.03345596 0.08135312 -0.03426134 -0.0332129 0.08106505 -0.03389143 -0.03248721 0.08137369 -0.03378391 -0.03264665 0.08100885 -0.03345817 -0.0327233 0.08118534 -0.03380179 -0.03214603 0.08110362 -0.03336143 -0.03173559 0.08120828 -0.03319847 -0.03137069 0.08140677 -0.03302478 -0.03145778 0.08100867 -0.03262686 -0.03104537 0.08115112 -0.03258216 -0.03056192 0.08140754 -0.03228545 -0.0304656 0.0810399 -0.03177666 -0.0301997 0.08122014 -0.03178232 -0.02998983 0.08137559 -0.03163409 -0.02955257 0.08136492 -0.03104215 -0.02979063 0.0811218 -0.03111213 -0.02942788 0.08105427 -0.0303747 -0.02921539 0.08118605 -0.03032016 -0.02980446 0.08100235 -0.03067409 -0.02902621 0.08135682 -0.03014814 -0.02868998 0.0813834 -0.02945256 -0.02897822 0.08100467 -0.02912425 -0.02876025 0.08113127 -0.02923101 -0.02834326 0.08136552 -0.02843028 -0.02844917 0.08111959 -0.02824288 -0.02866476 0.08103853 -0.02853077 -0.02813887 0.08138561 -0.02754384 -0.02826565 0.08112466 -0.02743303 -0.0285263 0.0810061 -0.02751135 -0.02801513 0.08138012 -0.0264886 -0.02815437 0.08113551 -0.02647161 -0.02800196 0.08562195 -0.0260154 -0.02810829 0.08561182 -0.0273903 -0.02840322 0.08558219 -0.02867484 -0.02879184 0.08558988 -0.02968597 -0.02921849 0.0856058 -0.03051364 -0.02970445 0.08564621 -0.03125184 -0.03027659 0.0856142 -0.03197485 -0.03087043 0.08564734 -0.03257495 -0.03158712 0.08566302 -0.03317254 -0.03252887 0.08559763 -0.03381317 -0.03372985 0.08560836 -0.0343852 -0.03475397 0.08562159 -0.03470849 -0.03566354 0.08559614 -0.0348972 -0.03656929 0.08558285 -0.03498822 -0.03745722 0.08558601 -0.03498661 -0.0387777 0.08562815 -0.03481495 -0.03968065 0.08558791 -0.03458935 -0.04052215 0.08558887 -0.03427982 -0.04129534 0.08559501 -0.03390562 -0.04204207 0.08562272 -0.03344684 -0.04281628 0.08557534 -0.03286707 -0.04343515 0.08559101 -0.03228861 -0.04401689 0.08564811 -0.03161799 -0.04468148 0.08561199 -0.03068953 -0.04519164 0.08560395 -0.02971822 -0.04553359 0.08557438 -0.02885776 -0.04577016 0.08562129 -0.02799201 -0.045933 0.08555996 -0.0271005 -0.04599153 0.08561247 -0.02624392 -0.04596728 0.08564734 -0.02536964 -0.04581165 0.08561128 -0.02417069 -0.04546111 0.08558285 -0.02292329 -0.04497873 0.08565962 -0.02186518 -0.04453378 0.08560115 -0.02108293 -0.04401218 0.08560174 -0.02036416 -0.04327362 0.08557075 -0.0195409 -0.04228174 0.08564054 -0.01872235 -0.04146963 0.08561307 -0.01818931 -0.04065817 0.08566772 -0.01779055 -0.03923422 0.08567148 -0.01729834 -0.03831928 0.08558136 -0.01709848 -0.03746449 0.08557891 -0.01701301 -0.03611356 0.08565068 -0.01705545 -0.03522878 0.0856772 -0.01719373 -0.03432649 0.08567529 -0.01742398 -0.0335865 0.08566242 -0.01769059 -0.03306639 0.08557796 -0.01790636 -0.0323264 0.08560055 -0.01831245 -0.03157114 0.08563548 -0.01883298 -0.03071725 0.08559823 -0.01955348 -0.02998286 0.085626 -0.02037626 -0.02945178 0.08559429 -0.02110344 -0.02901118 0.0856471 -0.0218786 -0.0286228 0.08557397 -0.02271223 -0.028351 0.08560901 -0.02352678 -0.02810335 0.08562397 -0.02465093 -0.02814948 0.08585953 -0.02642929 -0.02838754 0.08599442 -0.02593922 -0.02813583 0.08575546 -0.02714025 -0.02836555 0.08596616 -0.02702456 -0.0283004 0.08586025 -0.02766191 -0.02863383 0.08599555 -0.02806085 -0.02845174 0.08575916 -0.02861511 -0.02864724 0.08593595 -0.02867621 -0.02890735 0.08580976 -0.02971595 -0.02934825 0.0859906 -0.02999883 -0.02928978 0.08580279 -0.03045594 -0.02964639 0.08589947 -0.03087526 -0.03114026 0.08599931 -0.03228199 -0.03034579 0.08596962 -0.03158307 -0.03032171 0.08583581 -0.03185564 -0.03113961 0.08585482 -0.03264796 -0.03132355 0.08594369 -0.0326581 -0.03203547 0.08588534 -0.03329682 -0.03231853 0.08572083 -0.03363454 -0.03270268 0.08598017 -0.03351926 -0.03280717 0.08584004 -0.03382605 -0.03356415 0.08579146 -0.03422772 -0.03363353 0.08596056 -0.03403472 -0.03459441 0.08583676 -0.03455448 -0.0346921 0.08599531 -0.03431868 -0.03578758 0.08598411 -0.03456646 -0.03564596 0.08584302 -0.03477537 -0.03676265 0.08573979 -0.03494536 -0.03678464 0.08599138 -0.03463131 -0.0369451 0.08587241 -0.03485101 -0.03802621 0.0856837 -0.0349195 -0.03817379 0.08596247 -0.03464269 -0.03906047 0.08578294 -0.0346837 -0.03963476 0.08599567 -0.03419375 -0.03927034 0.08594405 -0.0344479 -0.04005014 0.08578169 -0.03438431 -0.04036045 0.08590692 -0.03413212 -0.04087793 0.08580982 -0.03401249 -0.04099988 0.08598989 -0.03365808 -0.04182022 0.08577001 -0.03352117 -0.04182255 0.08588087 -0.03340554 -0.04207193 0.08599406 -0.03296899 -0.0428673 0.0857321 -0.03276413 -0.04284703 0.08592063 -0.03256434 -0.04353356 0.08578205 -0.03207087 -0.04357111 0.08599793 -0.03153049 -0.0438466 0.0859059 -0.03154665 -0.04450589 0.08577501 -0.03082984 -0.04431802 0.08595693 -0.03074544 -0.04484677 0.08586102 -0.03012013 -0.04468905 0.08599448 -0.02986484 -0.04540425 0.08576709 -0.02903652 -0.04525679 0.0858587 -0.02920305 -0.04519271 0.08596354 -0.02893954 -0.0456112 0.085855 -0.02810657 -0.04547166 0.08599871 -0.02738964 -0.04567527 0.0859431 -0.02719455 -0.0458613 0.0857672 -0.02714264 -0.04588061 0.0858404 -0.02600091 -0.04565322 0.08598107 -0.02567344 -0.04586243 0.08576577 -0.02488934 -0.04571557 0.08591461 -0.02488476 -0.0454356 0.08599245 -0.02421212 -0.04566198 0.08584135 -0.02406847 -0.04532521 0.08593362 -0.02324473 -0.04545557 0.08580517 -0.02320408 -0.04522597 0.08579146 -0.02255576 -0.04488629 0.08599895 -0.02260971 -0.04468381 0.08593821 -0.0217936 -0.04452347 0.08578133 -0.02120417 -0.04410195 0.08594113 -0.02089375 -0.04400783 0.08578491 -0.0204845 -0.04371744 0.08599746 -0.02065861 -0.04343605 0.08591389 -0.02000457 -0.04339641 0.08574157 -0.01974761 -0.04266184 0.0859791 -0.01942771 -0.04275548 0.08575803 -0.01916438 -0.04244327 0.08586758 -0.0190218 -0.04164844 0.08588349 -0.01848626 -0.04136669 0.08599787 -0.01861011 -0.04086959 0.08591884 -0.01810693 -0.03999608 0.08566761 -0.01753169 -0.04003113 0.08587187 -0.01769453 -0.03996884 0.08598476 -0.01787853 -0.03906917 0.08592468 -0.01746547 -0.03813177 0.0857594 -0.01713275 -0.038459 0.08599805 -0.01754182 -0.03828227 0.08587658 -0.01725816 -0.03739273 0.08596807 -0.01731264 -0.03703558 0.08591496 -0.01719951 -0.03691893 0.08566796 -0.01701807 -0.03592252 0.08599519 -0.01745826 -0.03590732 0.08588278 -0.01723343 -0.03465974 0.08589565 -0.01749873 -0.03439491 0.08599293 -0.01777178 -0.03355389 0.0858711 -0.0178554 -0.03317981 0.08597892 -0.01821929 -0.03280711 0.08581131 -0.01814723 -0.03215163 0.085801 -0.01852422 -0.03223997 0.08593803 -0.018655 -0.03183025 0.08599883 -0.01915436 -0.03111451 0.08581888 -0.01932758 -0.03115868 0.08596616 -0.01954144 -0.03046363 0.08583205 -0.01998114 -0.02987587 0.0859217 -0.0208525 -0.02983015 0.08599507 -0.02121806 -0.02957993 0.08578234 -0.02104318 -0.02898669 0.08589541 -0.02229875 -0.02891433 0.08599561 -0.02303385 -0.02867549 0.08575826 -0.02275085 -0.02839773 0.08577859 -0.02362793 -0.02852976 0.08593606 -0.02377295 -0.02820718 0.08578902 -0.0244975 -0.02831971 0.08597266 -0.02542507 -0.02815306 0.08583891 -0.02518445 -0.03693014 0.07318705 -0.06724023 -0.03680646 0.07310986 -0.06720602 -0.03680324 0.07302075 -0.06710153 -0.03603893 0.07318377 -0.06736075 -0.03609281 0.07306611 -0.06728368 -0.03602391 0.07300394 -0.06717175 -0.03561478 0.07307618 -0.06743866 -0.03528791 0.07317179 -0.06764853 -0.03530478 0.07300728 -0.06745058 -0.03478509 0.07307624 -0.06788402 -0.03467369 0.07318049 -0.06804442 -0.03438776 0.07300442 -0.06802588 -0.03435713 0.07311671 -0.06829041 -0.0341053 0.07319611 -0.06860172 -0.03398245 0.07307934 -0.06866544 -0.03369539 0.07305347 -0.06902557 -0.033683 0.07316464 -0.06922072 -0.03367453 0.07300442 -0.06885516 -0.03342264 0.07304394 -0.06958776 -0.03340572 0.07318514 -0.06989246 -0.0331459 0.07300627 -0.07016766 -0.03325134 0.07306259 -0.07019835 -0.0332731 0.07320266 -0.07053375 -0.03321951 0.07308274 -0.07052654 -0.03323221 0.07314831 -0.07101422 -0.03305608 0.07300579 -0.07119625 -0.0331974 0.07307076 -0.07138019 -0.03331309 0.0731883 -0.07174068 -0.03330349 0.07310718 -0.0718559 -0.0333026 0.07303243 -0.07214635 -0.03347092 0.07317245 -0.07229411 -0.03355705 0.07300257 -0.07298797 -0.03367471 0.07315278 -0.07276844 -0.0336669 0.0730313 -0.0730049 -0.03394871 0.07318812 -0.07319343 -0.03414309 0.07314252 -0.07346028 -0.03452974 0.07300639 -0.07410162 -0.03457051 0.07314848 -0.07387852 -0.0346564 0.07301986 -0.07412064 -0.03496575 0.07315105 -0.07416701 -0.0353347 0.07303959 -0.07449156 -0.03527528 0.07316422 -0.07434177 -0.03580456 0.07316946 -0.07456928 -0.03601545 0.07300674 -0.07482922 -0.03610748 0.07306402 -0.07472676 -0.036439 0.07315385 -0.07472324 -0.03685265 0.07306522 -0.07482856 -0.03699195 0.07317924 -0.07475918 -0.03746163 0.07300341 -0.07494646 -0.03747999 0.0730704 -0.07479035 -0.03755962 0.07320386 -0.07471382 -0.03819882 0.07314562 -0.07457655 -0.0383991 0.07302713 -0.07463419 -0.03854882 0.07320231 -0.07442474 -0.03901618 0.07300388 -0.07440525 -0.03887659 0.07307553 -0.07432734 -0.03903174 0.07316422 -0.0741645 -0.03934335 0.07314497 -0.07394772 -0.03975892 0.07316553 -0.07356178 -0.03980332 0.07300543 -0.07378047 -0.0398271 0.07304871 -0.07362008 -0.04021251 0.07317447 -0.0729596 -0.04027056 0.07305997 -0.07300877 -0.04054844 0.0730037 -0.07277923 -0.04046303 0.07316815 -0.07246363 -0.04060769 0.07305186 -0.07233494 -0.04064583 0.07317364 -0.07193261 -0.04080915 0.07306009 -0.07148551 -0.04093527 0.07300394 -0.07142812 -0.04075586 0.07318872 -0.07118576 -0.04080557 0.07307243 -0.07061576 -0.04074484 0.07316905 -0.07066279 -0.04089432 0.07300359 -0.07021236 -0.04065257 0.07319164 -0.07011651 -0.04068487 0.07306271 -0.06995207 -0.04049789 0.07318717 -0.06962674 -0.04045224 0.07307446 -0.06936949 -0.04026091 0.07316982 -0.06912583 -0.04040718 0.07300829 -0.06904888 -0.03999012 0.07313781 -0.0687015 -0.0398032 0.07317405 -0.06849443 -0.03986912 0.0730108 -0.06832545 -0.03947156 0.07305425 -0.06805211 -0.03934305 0.07317376 -0.06805521 -0.0391252 0.07302665 -0.0677483 -0.03873759 0.07300072 -0.06739515 -0.03888124 0.07316857 -0.06774491 -0.03846377 0.07314795 -0.06752932 -0.03838872 0.07302027 -0.06735384 -0.03802567 0.07309043 -0.06732988 -0.03802353 0.07318902 -0.06738632 -0.03754836 0.07314729 -0.06727361 -0.03742957 0.07300841 -0.06708937 -0.03662419 0.09379589 -0.07473689 -0.03607839 0.09381246 -0.07464313 -0.03544622 0.09380453 -0.07442325 -0.03480446 0.09380728 -0.07405227 -0.03437477 0.09383183 -0.07369136 -0.03405714 0.09383368 -0.07334363 -0.03369832 0.09381109 -0.07279998 -0.03333824 0.09379637 -0.07183516 -0.03325617 0.09380918 -0.07132786 -0.03324967 0.09383106 -0.07071286 -0.03331953 0.0938031 -0.07025718 -0.03343355 0.09383314 -0.06980299 -0.03369212 0.09383046 -0.06920391 -0.03406465 0.09380799 -0.06865453 -0.03458571 0.09379184 -0.06811505 -0.03545504 0.09381538 -0.06757587 -0.03598314 0.09380698 -0.0673803 -0.03653192 0.0938152 -0.06727278 -0.03700089 0.09381395 -0.06724178 -0.03765594 0.09380346 -0.06729823 -0.03837466 0.09381091 -0.06749981 -0.03897231 0.0938434 -0.06779289 -0.03943669 0.09385359 -0.06812655 -0.03975319 0.09382063 -0.06843626 -0.04016923 0.09383267 -0.0689758 -0.04039108 0.09380668 -0.06937652 -0.04064244 0.09379893 -0.07007205 -0.0407586 0.09382539 -0.0708177 -0.04073262 0.09383434 -0.07147085 -0.04059791 0.09383302 -0.07210779 -0.04034608 0.09381157 -0.07271003 -0.0401414 0.09382826 -0.07306653 -0.03982192 0.0938121 -0.07348155 -0.03951478 0.09382897 -0.07379561 -0.03904592 0.09380602 -0.07415425 -0.03837794 0.09382653 -0.07450187 -0.03773885 0.09384483 -0.07469201 -0.03721994 0.09382945 -0.07475757 -0.03649318 0.09396016 -0.0748375 -0.03635871 0.09388965 -0.07474094 -0.03685545 0.09399569 -0.07495778 -0.03558707 0.09392291 -0.07454591 -0.03502047 0.09392744 -0.07427096 -0.03523528 0.09399503 -0.07454246 -0.03419262 0.0939902 -0.07375723 -0.034433 0.09394329 -0.07385569 -0.033876 0.09392601 -0.07320946 -0.03361058 0.09398311 -0.07294708 -0.03350734 0.09385746 -0.07241982 -0.03328013 0.09399092 -0.07225143 -0.03330552 0.09392225 -0.07194137 -0.03318673 0.09394508 -0.07144027 -0.03303396 0.09399747 -0.07120561 -0.03318482 0.09392482 -0.07084792 -0.03319102 0.09399795 -0.06984096 -0.03327393 0.09393078 -0.07014417 -0.03338903 0.09394824 -0.06966513 -0.03378123 0.09390288 -0.06897354 -0.03383362 0.09398978 -0.0686782 -0.03419965 0.09392982 -0.0683937 -0.03464806 0.09389138 -0.06802779 -0.03472864 0.09399086 -0.0677942 -0.03508192 0.09383279 -0.06776529 -0.03524506 0.09394061 -0.06758588 -0.03573375 0.09399676 -0.06724411 -0.0358718 0.09392929 -0.0673511 -0.0363872 0.09392732 -0.06722891 -0.03684371 0.09399747 -0.06703412 -0.03709107 0.09390789 -0.06719088 -0.0371899 0.09397614 -0.06710648 -0.03793805 0.09391212 -0.06730091 -0.03807806 0.09399157 -0.06722593 -0.03879404 0.09395951 -0.0675829 -0.0392431 0.09399163 -0.06778031 -0.03993004 0.0939939 -0.06835663 -0.03995013 0.0939213 -0.06858634 -0.04036337 0.09393334 -0.06917065 -0.04056674 0.09399616 -0.06927692 -0.04061466 0.09392857 -0.06976509 -0.04088842 0.0939967 -0.07025909 -0.04075318 0.09393113 -0.07028073 -0.04083627 0.09393846 -0.07088643 -0.04094392 0.09399539 -0.07144403 -0.04077565 0.09394949 -0.07176178 -0.04060143 0.09397196 -0.07244306 -0.04035872 0.09393918 -0.07285284 -0.04040151 0.09399563 -0.07301372 -0.04006016 0.09393316 -0.07329249 -0.03970795 0.09399533 -0.07389259 -0.0396614 0.09394323 -0.07377451 -0.03910422 0.09392797 -0.07418817 -0.03887623 0.09399586 -0.07448101 -0.03850078 0.09393668 -0.07452827 -0.03803724 0.09398859 -0.07477355 -0.03731489 0.09394669 -0.07483464 -0.04148507 0.07475 -0.07148277 -0.04150956 0.078 -0.07099997 -0.04135668 0.078 -0.0721895 -0.04119104 0.07475 -0.07268238 -0.04075634 0.078 -0.07351785 -0.04044115 0.07475 -0.07393407 -0.03983891 0.078 -0.07450568 -0.03941893 0.07475 -0.07480758 -0.03878647 0.078 -0.07514774 -0.03819042 0.07475 -0.07536268 -0.0378099 0.078 -0.07543015 -0.03669768 0.078 -0.07551205 -0.03662657 0.07475 -0.07550674 -0.03538334 0.078 -0.0752114 -0.03500229 0.07475 -0.07506477 -0.03430098 0.078 -0.0746209 -0.03374272 0.07475 -0.07412821 -0.03328377 0.078 -0.07357674 -0.03308111 0.07475 -0.07322573 -0.0326994 0.078 -0.07236182 -0.03264331 0.07475 -0.0721895 -0.03249639 0.078 -0.07125854 -0.03248625 0.07475 -0.07085251 -0.03263044 0.078 -0.06980812 -0.03269946 0.07475 -0.06963807 -0.03316843 0.07475 -0.06861913 -0.03337377 0.078 -0.06829798 -0.03377449 0.07475 -0.06785392 -0.03454536 0.078 -0.06719934 -0.03473782 0.07475 -0.06708168 -0.03581082 0.078 -0.06664848 -0.03599643 0.07475 -0.06660348 -0.03711259 0.078 -0.06648129 -0.03730231 0.07475 -0.0664879 -0.03819251 0.078 -0.06665718 -0.03882747 0.07475 -0.06686347 -0.0392301 0.078 -0.06706589 -0.03998583 0.07475 -0.06761652 -0.04054296 0.078 -0.06817448 -0.04072594 0.07475 -0.06845963 -0.04118359 0.07475 -0.06932389 -0.04133164 0.078 -0.06970119 -0.04146218 0.07475 -0.07032746 -0.03252333 0.08899998 -0.07040381 -0.03248584 0.09224998 -0.07066172 -0.0327931 0.09224998 -0.0693832 -0.03294116 0.08899998 -0.06900584 -0.0332539 0.09224998 -0.0684868 -0.03364193 0.08899998 -0.06799417 -0.0339899 0.09224998 -0.06764012 -0.03448492 0.08899998 -0.067249 -0.03510755 0.09224998 -0.0668928 -0.03591746 0.08899998 -0.06660205 -0.03651553 0.09224998 -0.0665099 -0.03759765 0.08899998 -0.06651747 -0.03808248 0.09224998 -0.06660205 -0.03899085 0.08899998 -0.06694632 -0.03951501 0.09224998 -0.067249 -0.0402674 0.08899998 -0.06786352 -0.04067945 0.09224998 -0.06835466 -0.04100942 0.08899998 -0.06894433 -0.04138028 0.09224998 -0.06988459 -0.04137301 0.08899998 -0.06988644 -0.04151087 0.08899998 -0.07103377 -0.04150611 0.09224998 -0.0710805 -0.04134911 0.09224998 -0.0722236 -0.04131931 0.08899998 -0.07233226 -0.0407347 0.09224998 -0.07354623 -0.04056346 0.08899998 -0.07379555 -0.03989768 0.09224998 -0.07445335 -0.03956502 0.08899998 -0.07470566 -0.03895872 0.09224998 -0.07506728 -0.03867948 0.08899998 -0.07518666 -0.03748685 0.09224998 -0.07550293 -0.03733801 0.08899998 -0.07551169 -0.03569954 0.09224998 -0.07533842 -0.03563046 0.08899998 -0.07531714 -0.03427195 0.09224998 -0.07460141 -0.03427416 0.08899998 -0.07459849 -0.03349632 0.08899998 -0.07383477 -0.03324359 0.09224998 -0.07351785 -0.03289794 0.08899998 -0.0728892 -0.03264331 0.09224998 -0.0721895 -0.03253781 0.08899998 -0.07167249 -0.02950698 0.09359735 -0.07133448 -0.02958208 0.09375238 -0.07155817 -0.02960461 0.0938121 -0.07081317 -0.02977144 0.09394538 -0.07149481 -0.02995502 0.09399849 -0.07162064 -0.02970016 0.09383261 -0.07213902 -0.02961891 0.09359776 -0.07230991 -0.02986454 0.09389913 -0.07260227 -0.02979081 0.09365063 -0.07302391 -0.02998584 0.09378403 -0.07342869 -0.03008347 0.09367334 -0.07386136 -0.0301603 0.09397387 -0.07321196 -0.03081738 0.09399569 -0.07453 -0.03050273 0.09389787 -0.07437092 -0.03040593 0.09367865 -0.07453978 -0.03072673 0.09361183 -0.07510042 -0.03110939 0.09378385 -0.07551646 -0.03112924 0.09359008 -0.07566303 -0.03120291 0.09391415 -0.0754202 -0.03177738 0.09359651 -0.0763846 -0.03179192 0.09373021 -0.0763325 -0.03202813 0.09399366 -0.07611554 -0.03185641 0.09387648 -0.07623547 -0.03252166 0.09366589 -0.07699704 -0.03249651 0.09387135 -0.07680052 -0.03312391 0.09360241 -0.07741582 -0.03321003 0.09398591 -0.07707232 -0.03309506 0.09379893 -0.07729905 -0.03375357 0.09357446 -0.0777598 -0.03375959 0.09377115 -0.07768476 -0.03396308 0.09394878 -0.07756888 -0.03453117 0.09366887 -0.07806611 -0.03490948 0.09385055 -0.07807147 -0.03503632 0.09399443 -0.07784157 -0.03537732 0.09360915 -0.07832092 -0.03574395 0.09388875 -0.07822173 -0.03622502 0.09364557 -0.07844859 -0.03694784 0.09382748 -0.07839441 -0.036996 0.09359306 -0.07849693 -0.0366109 0.09397888 -0.07815593 -0.038064 0.09399849 -0.0780192 -0.03771275 0.09366673 -0.07844972 -0.03752928 0.0939415 -0.07822442 -0.03812557 0.09360957 -0.07840985 -0.03812605 0.09383392 -0.07829391 -0.03885775 0.09359782 -0.0782625 -0.03855764 0.09393674 -0.07808494 -0.0388208 0.09382337 -0.07816469 -0.039716 0.09360378 -0.07799029 -0.03953063 0.09380096 -0.07795882 -0.03956949 0.09395211 -0.077762 -0.04021662 0.0937913 -0.07768607 -0.04061186 0.09359174 -0.07756966 -0.04093456 0.09395825 -0.0770604 -0.04081296 0.09380334 -0.07734745 -0.041229 0.09360957 -0.07718771 -0.04152387 0.09382748 -0.07684957 -0.04067665 0.09399914 -0.07705241 -0.04182165 0.09359925 -0.07673972 -0.04234313 0.09362316 -0.07625281 -0.04213869 0.09395796 -0.0760743 -0.04246121 0.09378618 -0.0760259 -0.04274928 0.09399378 -0.07521021 -0.04287254 0.09357917 -0.07566255 -0.04291033 0.09383106 -0.0754345 -0.04328453 0.09360092 -0.07508587 -0.04352575 0.09376645 -0.07456564 -0.04367566 0.09356504 -0.07441782 -0.04332637 0.09394335 -0.07452756 -0.04343509 0.09399586 -0.07399874 -0.04375708 0.09390282 -0.07379078 -0.04397594 0.09360396 -0.07374227 -0.0439825 0.09378594 -0.07350993 -0.04424774 0.09366542 -0.07287472 -0.04414933 0.09389799 -0.07257157 -0.04391878 0.09398031 -0.07281088 -0.04440146 0.09364831 -0.0721479 -0.04447996 0.09357082 -0.07153439 -0.04434108 0.09384995 -0.07157665 -0.04412221 0.09399521 -0.07144433 -0.04441845 0.09379321 -0.07100611 -0.04449319 0.09359854 -0.07078647 -0.04419642 0.09396708 -0.0708549 -0.04443925 0.09362196 -0.07010281 -0.04433137 0.09379529 -0.06989663 -0.04417538 0.09391504 -0.06967741 -0.04431337 0.09359037 -0.06935071 -0.04410463 0.09379017 -0.0688591 -0.04410755 0.09363549 -0.06863433 -0.04382723 0.09397923 -0.06876081 -0.04350042 0.09399479 -0.06812065 -0.04376727 0.09359163 -0.06776446 -0.04374939 0.09379529 -0.06793344 -0.04335314 0.0939151 -0.06740373 -0.04334402 0.09366869 -0.06702768 -0.04269742 0.09399247 -0.06671744 -0.04308283 0.09382593 -0.06680268 -0.04282116 0.09365618 -0.06629204 -0.04248052 0.09391802 -0.0661906 -0.04224711 0.0936228 -0.06564575 -0.04210597 0.09384822 -0.06568104 -0.04150933 0.09365117 -0.06502228 -0.04155254 0.09399497 -0.06553006 -0.04142284 0.09388101 -0.06515091 -0.04094094 0.09396761 -0.06497848 -0.04087471 0.09360074 -0.06458312 -0.04093742 0.09378576 -0.0647124 -0.04006814 0.09359604 -0.06415581 -0.04033869 0.09390372 -0.06450128 -0.0400508 0.09377491 -0.0642277 -0.03964269 0.09399425 -0.06438511 -0.03920549 0.09359896 -0.06383574 -0.03917849 0.09386259 -0.06396442 -0.03852099 0.0936582 -0.06366962 -0.03870689 0.09393495 -0.06393879 -0.0380088 0.09382683 -0.06367862 -0.03753477 0.09360808 -0.06352025 -0.03731018 0.0939961 -0.06389135 -0.03743976 0.09388196 -0.06367063 -0.03664094 0.09359014 -0.06351131 -0.03658866 0.09394502 -0.06376832 -0.03661328 0.09380608 -0.06360334 -0.03591227 0.09360158 -0.06358361 -0.03571903 0.09381926 -0.06371206 -0.03495508 0.09359562 -0.06378316 -0.03514528 0.09397023 -0.06403917 -0.03486639 0.09377616 -0.06388169 -0.03407716 0.09399509 -0.06449252 -0.03411602 0.09361177 -0.0640828 -0.0339809 0.09387105 -0.06430453 -0.03357905 0.09374922 -0.06439018 -0.03343224 0.09359371 -0.06440645 -0.03314572 0.09394007 -0.0648539 -0.03280186 0.09363716 -0.06479632 -0.03280019 0.09382164 -0.06492203 -0.03203296 0.09364712 -0.06539088 -0.03215545 0.09383362 -0.06543052 -0.03244298 0.09397482 -0.06545108 -0.0318157 0.09399843 -0.06618487 -0.03140079 0.09359925 -0.06601542 -0.03176885 0.09394431 -0.06598538 -0.03131842 0.09377539 -0.06621599 -0.03090524 0.09361463 -0.06663924 -0.03108155 0.09392982 -0.06677067 -0.03076899 0.09379601 -0.06699389 -0.03043168 0.09359711 -0.06737881 -0.03055012 0.09399247 -0.06794744 -0.03036791 0.09372252 -0.06759697 -0.03039121 0.09387201 -0.06779646 -0.03001087 0.093602 -0.06829077 -0.03009837 0.09378272 -0.06827777 -0.02978569 0.09359359 -0.06896167 -0.03005194 0.09392762 -0.06885564 -0.02982598 0.09380698 -0.0691592 -0.02962976 0.09363639 -0.06965965 -0.02998274 0.09399622 -0.06993776 -0.02954757 0.09366494 -0.07029044 -0.02977329 0.09393388 -0.07018154 -0.02951192 0.09261757 -0.07131814 -0.02964472 0.09265238 -0.07246899 -0.02988368 0.09265863 -0.07335895 -0.03026384 0.09261691 -0.07428616 -0.03069931 0.09266561 -0.07506459 -0.0316196 0.09264534 -0.0762186 -0.03232735 0.09264504 -0.07686573 -0.03375148 0.09264522 -0.07775497 -0.03443968 0.09265702 -0.07804626 -0.03517025 0.09263586 -0.07826733 -0.03586864 0.09257513 -0.07839667 -0.03723633 0.09265571 -0.07849675 -0.0380972 0.09265697 -0.07841622 -0.03883975 0.09256827 -0.0782513 -0.03958737 0.09263837 -0.07803368 -0.04025989 0.09265506 -0.07775086 -0.04090887 0.09265214 -0.07739663 -0.04151993 0.09259313 -0.07696819 -0.04224354 0.09267657 -0.07636636 -0.04285091 0.09261685 -0.07567799 -0.04329794 0.09257918 -0.07504212 -0.04365223 0.09264922 -0.07445496 -0.04391026 0.09259057 -0.07388448 -0.04420942 0.0926578 -0.07305651 -0.04442447 0.09266376 -0.07207196 -0.04449439 0.09266185 -0.07121396 -0.04447793 0.09264773 -0.07048261 -0.04434722 0.09263849 -0.06950199 -0.04411011 0.09265685 -0.0686236 -0.04382908 0.09264707 -0.06790971 -0.04348444 0.09261006 -0.0672515 -0.04308325 0.09266692 -0.06661647 -0.04263025 0.09263473 -0.06605392 -0.04208743 0.0926091 -0.06550353 -0.04138433 0.09265208 -0.06491464 -0.04041194 0.09265661 -0.06431984 -0.03958135 0.09263873 -0.063964 -0.03866153 0.09265595 -0.06368583 -0.03777784 0.0926482 -0.06354463 -0.03679597 0.09263658 -0.06350439 -0.03567451 0.09265184 -0.06361782 -0.03459948 0.09265661 -0.06389373 -0.03357148 0.09264719 -0.06432962 -0.03280371 0.09262412 -0.06479322 -0.0321747 0.09261018 -0.06527113 -0.03150916 0.09264636 -0.06589221 -0.03092217 0.09260624 -0.06662398 -0.03062522 0.09258127 -0.06708341 -0.02982109 0.09264272 -0.06883257 -0.02962738 0.09260916 -0.0696814 -0.02952224 0.09265029 -0.07047146 -0.02959007 0.09248471 -0.07042312 -0.02965569 0.09238445 -0.07133865 -0.02979797 0.0922926 -0.07048118 -0.02972131 0.09239339 -0.0699054 -0.03002434 0.09228438 -0.06918704 -0.02998697 0.09241735 -0.06866782 -0.03045088 0.09225338 -0.06827753 -0.03007256 0.09260576 -0.06815892 -0.03044486 0.09236204 -0.06771212 -0.03032934 0.09262031 -0.06758987 -0.03116148 0.09225648 -0.0669049 -0.03084373 0.09237605 -0.06700372 -0.03135037 0.09240812 -0.06625115 -0.03172075 0.09233891 -0.06596636 -0.03205734 0.09246289 -0.0654664 -0.03223937 0.09228926 -0.0655688 -0.03297221 0.09225523 -0.06513994 -0.03291928 0.09238302 -0.06488054 -0.03347802 0.09246784 -0.06447118 -0.03404593 0.09228169 -0.06443589 -0.03403586 0.0924021 -0.06424623 -0.03482532 0.09225273 -0.06425362 -0.0347144 0.09233939 -0.06407284 -0.03482913 0.0924642 -0.06390589 -0.03559994 0.09228223 -0.06394398 -0.03574037 0.09243202 -0.0637058 -0.0372529 0.09225487 -0.0638808 -0.03638446 0.09232246 -0.06375241 -0.03684902 0.09243911 -0.0635972 -0.03756034 0.09246712 -0.06359958 -0.03805136 0.09230667 -0.06382507 -0.03862434 0.09244287 -0.06377136 -0.03878486 0.09225362 -0.06413292 -0.03933984 0.09240448 -0.06400543 -0.03950369 0.09229922 -0.06421852 -0.04054516 0.09245532 -0.06448251 -0.0402891 0.09235429 -0.06446027 -0.04079347 0.09225755 -0.0649529 -0.04134374 0.09242528 -0.06501764 -0.04192191 0.0923537 -0.06557923 -0.04253816 0.09225487 -0.06648766 -0.04250669 0.0924313 -0.06606835 -0.04262942 0.09230375 -0.06644213 -0.04305022 0.09244763 -0.06672167 -0.04352259 0.09243983 -0.0675016 -0.04337269 0.09230446 -0.06755691 -0.04390656 0.09245836 -0.06830346 -0.04379993 0.09225279 -0.06894767 -0.04385936 0.09231096 -0.06863939 -0.0441268 0.09244936 -0.06898176 -0.04424017 0.0923779 -0.06975203 -0.04420071 0.09229457 -0.07036644 -0.04439121 0.09251433 -0.07008892 -0.04440879 0.09243774 -0.07118499 -0.04409223 0.09225368 -0.07129675 -0.04430288 0.09234559 -0.07129776 -0.04430586 0.09252262 -0.07248663 -0.04421007 0.09238308 -0.07242721 -0.04398685 0.09225797 -0.07244294 -0.04403084 0.0924738 -0.07339072 -0.04389512 0.09233319 -0.0733447 -0.04359269 0.0922687 -0.07380044 -0.04361873 0.09240603 -0.07425397 -0.0430001 0.09231221 -0.07510191 -0.04265522 0.0922504 -0.07524693 -0.04276603 0.09240156 -0.07558399 -0.04216557 0.09247076 -0.07633924 -0.04206907 0.09229499 -0.07614928 -0.04140287 0.09234434 -0.07683008 -0.0411458 0.09225189 -0.07673966 -0.04087692 0.09246331 -0.07732182 -0.04069519 0.09230506 -0.07723265 -0.04020696 0.0924564 -0.07768315 -0.03996616 0.09227639 -0.07755297 -0.03936445 0.09239518 -0.07798111 -0.03763431 0.09225052 -0.07808208 -0.03856396 0.09230911 -0.07808107 -0.038118 0.09245836 -0.0783295 -0.0373314 0.0923044 -0.07824313 -0.0370084 0.09246438 -0.078426 -0.03660511 0.09261667 -0.07847905 -0.03596293 0.09235072 -0.07824045 -0.03591704 0.09227931 -0.07810652 -0.03481179 0.09246623 -0.07809603 -0.03449887 0.09234607 -0.07786989 -0.03481179 0.09225463 -0.0777592 -0.0336461 0.09225857 -0.07730793 -0.03351074 0.09243011 -0.07752484 -0.03307497 0.09260916 -0.07737892 -0.03278696 0.09230279 -0.07689154 -0.03234696 0.09245204 -0.07677006 -0.03206241 0.09227865 -0.07623249 -0.03171664 0.09245729 -0.07619774 -0.03136593 0.09232026 -0.07560551 -0.03108733 0.0925768 -0.0755881 -0.03083413 0.09225684 -0.07459676 -0.0307452 0.09241831 -0.07493078 -0.03043806 0.09239751 -0.07433688 -0.03006654 0.09249782 -0.07369184 -0.03001731 0.09238988 -0.0733323 -0.03032618 0.09225642 -0.07352435 -0.02977806 0.09250009 -0.07280111 -0.02986735 0.09231388 -0.07237833 -0.02961194 0.09250456 -0.07189428 -0.02988088 0.09225589 -0.07143825 -0.02952539 0.0734108 -0.07041335 -0.02950632 0.07339566 -0.07116049 -0.02956813 0.07322919 -0.07097232 -0.02969336 0.07311618 -0.0704199 -0.02978092 0.07304537 -0.07120549 -0.02967214 0.07320755 -0.06983804 -0.02997183 0.07300251 -0.07003259 -0.02962046 0.07341933 -0.06967175 -0.02988743 0.07304143 -0.06976896 -0.02977836 0.07342123 -0.06898039 -0.02991777 0.07316404 -0.06890392 -0.03001964 0.07333046 -0.06829965 -0.03025472 0.07303166 -0.06851541 -0.03038859 0.07316172 -0.06770765 -0.03039318 0.07341676 -0.06744658 -0.0308749 0.07300752 -0.06733137 -0.03072667 0.07312774 -0.06717997 -0.03084206 0.07332003 -0.06675475 -0.03114193 0.07340097 -0.06632298 -0.03138679 0.07308971 -0.06633174 -0.03161215 0.07319194 -0.06591606 -0.03162455 0.07340687 -0.06577414 -0.03181612 0.07301187 -0.06611406 -0.03219097 0.07339823 -0.0652498 -0.03223848 0.07308673 -0.06547349 -0.03235912 0.07317876 -0.0652408 -0.03278285 0.07300209 -0.06529235 -0.03275632 0.07337296 -0.06482577 -0.033149 0.07323247 -0.06464874 -0.03308755 0.0730825 -0.06485188 -0.03342139 0.0734089 -0.06441199 -0.03388571 0.07303106 -0.06452006 -0.03374147 0.07316499 -0.06437551 -0.03405821 0.07338911 -0.06410658 -0.03461754 0.07324123 -0.06395173 -0.03494322 0.07300317 -0.06421625 -0.03487604 0.07310986 -0.06398189 -0.03481942 0.07343208 -0.06382453 -0.03567343 0.07336866 -0.06362307 -0.03557926 0.07303971 -0.06392532 -0.03591281 0.0731936 -0.06367951 -0.03666108 0.07336252 -0.06351727 -0.03647255 0.07311147 -0.06368654 -0.03695684 0.07300359 -0.06390106 -0.03741443 0.07334023 -0.06352573 -0.03736329 0.07310128 -0.06368917 -0.03809887 0.07343471 -0.06358104 -0.03830784 0.07321017 -0.06369274 -0.03831702 0.07300776 -0.06398487 -0.03899437 0.07333403 -0.06378412 -0.03918713 0.07309412 -0.06403082 -0.03953582 0.07340824 -0.06394475 -0.03985738 0.0732336 -0.06414151 -0.04003089 0.07311272 -0.06432944 -0.04022735 0.07333427 -0.06424921 -0.04007458 0.07300609 -0.06456977 -0.0407896 0.07341647 -0.06452584 -0.04105383 0.07323533 -0.06476849 -0.04078722 0.07309979 -0.06474846 -0.04164445 0.0733506 -0.06512439 -0.04164218 0.07313394 -0.06529986 -0.04133147 0.07300615 -0.06534701 -0.04211986 0.07336431 -0.06553137 -0.04217481 0.07304292 -0.06596153 -0.042589 0.07319122 -0.06613475 -0.04260122 0.07341045 -0.06601601 -0.04309111 0.07337284 -0.06663757 -0.04281908 0.07300508 -0.06692177 -0.04316419 0.07307446 -0.06712162 -0.04345017 0.07317322 -0.06737774 -0.04358279 0.07339137 -0.06740856 -0.04396092 0.07337403 -0.06822931 -0.04353076 0.07301086 -0.06811678 -0.04382598 0.07312995 -0.06828761 -0.04412382 0.07323777 -0.06886887 -0.04420864 0.07340168 -0.06894266 -0.044052 0.07305562 -0.06930977 -0.04437935 0.07336056 -0.06971734 -0.04435145 0.07322269 -0.06992644 -0.04398673 0.07300323 -0.06978142 -0.04447752 0.07339757 -0.07047766 -0.04437375 0.07315319 -0.07081419 -0.04425656 0.07305735 -0.07110476 -0.04448771 0.07337903 -0.07136768 -0.04402971 0.07300168 -0.07204031 -0.04436475 0.07322227 -0.07192867 -0.04437941 0.07340627 -0.07232165 -0.04420846 0.07314836 -0.07256537 -0.04421252 0.07340812 -0.0730459 -0.04402798 0.07315909 -0.07325613 -0.04375869 0.07300794 -0.07328933 -0.04398161 0.07340568 -0.07373118 -0.0436263 0.07309508 -0.07408046 -0.04373425 0.07333999 -0.07427543 -0.04344701 0.07324981 -0.07471352 -0.04324674 0.07313328 -0.07487809 -0.04330092 0.07341909 -0.07506477 -0.0429278 0.07302206 -0.07503724 -0.04295802 0.07318753 -0.07539892 -0.04283136 0.07337683 -0.07570487 -0.04236364 0.07340371 -0.07623732 -0.04218012 0.07308602 -0.07614088 -0.042288 0.07319194 -0.07618069 -0.0417872 0.07300215 -0.07624572 -0.04168963 0.07338923 -0.07685106 -0.04173457 0.07321912 -0.07671135 -0.04131096 0.07307374 -0.07685798 -0.04105752 0.07316237 -0.07716763 -0.04072916 0.07335495 -0.07749855 -0.04029297 0.0730071 -0.077322 -0.04000484 0.0731607 -0.07774353 -0.03977042 0.07341355 -0.0779711 -0.03890573 0.0730865 -0.07805025 -0.0392974 0.07324421 -0.07807469 -0.03887432 0.07340794 -0.07825905 -0.03858125 0.07300633 -0.07794362 -0.03831595 0.07327181 -0.07833838 -0.03813493 0.07339882 -0.07840949 -0.03737759 0.07339525 -0.07848596 -0.03757858 0.07306081 -0.07822585 -0.03731459 0.07316297 -0.07837826 -0.03642392 0.07300353 -0.07810282 -0.03663051 0.07337146 -0.0784828 -0.03639119 0.07304507 -0.07819974 -0.03609013 0.07319623 -0.07835042 -0.03572016 0.07336604 -0.07838475 -0.0347706 0.07340699 -0.07815784 -0.03535276 0.07311272 -0.07814431 -0.03480678 0.07321846 -0.07808864 -0.0346418 0.0730105 -0.07773387 -0.03393751 0.07340234 -0.07784646 -0.03420716 0.07313752 -0.07781338 -0.03341287 0.0733546 -0.07757318 -0.03315323 0.0731287 -0.07726627 -0.03348743 0.07300686 -0.07719802 -0.03287315 0.07334131 -0.07724761 -0.03258663 0.07300591 -0.07660144 -0.03218501 0.07339513 -0.07674443 -0.03224742 0.07316702 -0.07665169 -0.03163474 0.07333123 -0.07621783 -0.03174418 0.07307636 -0.07604444 -0.03102821 0.07342213 -0.07554143 -0.03116708 0.07323855 -0.07560765 -0.03123265 0.07301098 -0.07519793 -0.03094184 0.07311552 -0.0751239 -0.03066515 0.07325315 -0.07491141 -0.03050035 0.07339423 -0.07473295 -0.030173 0.07338201 -0.0740897 -0.03057742 0.0730741 -0.07442075 -0.03060925 0.07300376 -0.07408344 -0.03007477 0.07320934 -0.0736677 -0.03017842 0.07308971 -0.0736047 -0.02988696 0.07340699 -0.07336837 -0.0296911 0.07339042 -0.07265937 -0.02978157 0.0732035 -0.07266569 -0.02998459 0.07300144 -0.07197684 -0.02997541 0.07303756 -0.07266652 -0.02957302 0.07335442 -0.07196038 -0.02967464 0.07314229 -0.07171368 -0.02950853 0.07435655 -0.07065337 -0.02954262 0.07439273 -0.0717082 -0.02964931 0.07439178 -0.07244426 -0.029841 0.07434898 -0.07323604 -0.03017759 0.07434171 -0.0741083 -0.03051769 0.07434296 -0.07476621 -0.03101444 0.07435548 -0.07551854 -0.03163063 0.07442146 -0.07621264 -0.03218442 0.07434624 -0.07674539 -0.03279286 0.0743314 -0.07720673 -0.03360438 0.07435232 -0.07768684 -0.03443312 0.07442498 -0.07802855 -0.03511857 0.0743876 -0.07825052 -0.03591191 0.07433038 -0.07841897 -0.03664904 0.07437771 -0.07848381 -0.03740489 0.07439625 -0.07847774 -0.03808528 0.07437658 -0.0784136 -0.03909218 0.07438993 -0.07819569 -0.04007798 0.07435512 -0.07783865 -0.0408774 0.07438951 -0.07740581 -0.04138225 0.0743891 -0.07707697 -0.04184675 0.07433003 -0.07672137 -0.04239255 0.07436323 -0.07620424 -0.04285722 0.07433342 -0.07568114 -0.04329544 0.07434231 -0.07507103 -0.04362529 0.07440572 -0.07448899 -0.04395747 0.07442295 -0.0737549 -0.04420953 0.07434958 -0.07305294 -0.04436028 0.07442688 -0.07234448 -0.04447495 0.07435691 -0.07154738 -0.04449081 0.07433921 -0.07060104 -0.04438245 0.07435399 -0.0697025 -0.04420208 0.07439804 -0.06895017 -0.04397833 0.07434803 -0.0682612 -0.04366701 0.07434779 -0.06757265 -0.04329621 0.07433438 -0.06692856 -0.04285091 0.07434415 -0.06631284 -0.0423637 0.07434624 -0.06576263 -0.0418114 0.07435518 -0.0652529 -0.04114198 0.07440471 -0.06476157 -0.04041296 0.0743854 -0.06432819 -0.03959584 0.0743165 -0.06396389 -0.03887385 0.07439875 -0.06374973 -0.03811091 0.07440775 -0.06359666 -0.03741234 0.07441598 -0.06352645 -0.03649282 0.07436627 -0.06351959 -0.03550642 0.07434779 -0.06365388 -0.03482133 0.07439726 -0.06383496 -0.03408712 0.07432401 -0.06409001 -0.03340679 0.07433277 -0.06441891 -0.03278559 0.07432878 -0.06479763 -0.03218853 0.07435595 -0.06525307 -0.03162676 0.07433319 -0.06577032 -0.03115838 0.07435947 -0.06630408 -0.03069931 0.07433438 -0.06693536 -0.03024715 0.07436066 -0.06773948 -0.02982389 0.07437002 -0.06882971 -0.02962356 0.07437646 -0.06968641 -0.02956867 0.07452541 -0.0708149 -0.02971804 0.0746411 -0.07181447 -0.03008002 0.0747444 -0.07267314 -0.02984088 0.07462185 -0.07264161 -0.02995985 0.07452452 -0.07335233 -0.03010606 0.07467812 -0.07332265 -0.03023815 0.07454514 -0.07403928 -0.03057962 0.07467722 -0.07442992 -0.03089189 0.07474303 -0.07466048 -0.0306431 0.07452118 -0.07484483 -0.03107941 0.07465869 -0.07526421 -0.03118419 0.07451564 -0.07562702 -0.03183054 0.0746867 -0.07611095 -0.03184705 0.07474893 -0.07584536 -0.0323596 0.07458275 -0.07674878 -0.03260189 0.07472091 -0.07668179 -0.03281468 0.07452172 -0.07713603 -0.03376334 0.07474541 -0.07732826 -0.03350436 0.07466655 -0.07739806 -0.03359401 0.07453745 -0.07759177 -0.03451102 0.07466077 -0.07785779 -0.03542715 0.07474958 -0.07789194 -0.03547179 0.0747174 -0.07803714 -0.0353195 0.07461118 -0.07816153 -0.03553187 0.07450085 -0.07829415 -0.03617912 0.07456749 -0.0783506 -0.03704977 0.07474505 -0.07811439 -0.03687256 0.07462579 -0.07834315 -0.03761297 0.07462942 -0.07831269 -0.038365 0.07471251 -0.07808345 -0.0384711 0.07454168 -0.07827323 -0.03925091 0.07462507 -0.07798856 -0.03980112 0.07474589 -0.07754778 -0.04021447 0.07455301 -0.07768034 -0.04037553 0.07469117 -0.07742083 -0.04126375 0.07460135 -0.07700759 -0.04128754 0.07471179 -0.07679581 -0.04215556 0.07455891 -0.07631856 -0.04209834 0.07474857 -0.07591408 -0.04201519 0.07467299 -0.07628303 -0.04292315 0.07452088 -0.07548618 -0.042741 0.07473278 -0.07527083 -0.04281586 0.07464975 -0.07542765 -0.04336065 0.07463043 -0.07465821 -0.04361236 0.07474577 -0.07363206 -0.04375129 0.07466387 -0.07377821 -0.04416006 0.07451617 -0.07298344 -0.04406827 0.07469761 -0.07261008 -0.04434502 0.07460635 -0.07159775 -0.04413455 0.07474178 -0.07098376 -0.0444259 0.07451552 -0.07065105 -0.04422891 0.07469308 -0.07042169 -0.04396998 0.0747472 -0.06974786 -0.04428237 0.07456952 -0.06972122 -0.04406642 0.07465821 -0.06913805 -0.04387515 0.07458996 -0.06831616 -0.04356282 0.07474619 -0.06825715 -0.04353702 0.07460075 -0.0675891 -0.04301506 0.0747171 -0.06704688 -0.04320561 0.07455301 -0.0669533 -0.04276233 0.07460016 -0.06639766 -0.04230952 0.07456541 -0.06584829 -0.04215228 0.0747376 -0.06603801 -0.04168957 0.07460653 -0.06531786 -0.04121768 0.07474398 -0.0652638 -0.04082512 0.07463318 -0.06473451 -0.03970825 0.07468014 -0.06424933 -0.04009926 0.07473927 -0.06458938 -0.03962731 0.07449948 -0.06403255 -0.038347 0.07474851 -0.06402623 -0.03879547 0.0746079 -0.06386607 -0.03805989 0.07465863 -0.06377172 -0.03706663 0.0747137 -0.06379723 -0.03685325 0.0746259 -0.06365907 -0.03621757 0.07448637 -0.06359279 -0.0352801 0.07474434 -0.06407982 -0.03581619 0.07466781 -0.06380891 -0.03540319 0.07456213 -0.06377267 -0.03425437 0.07449251 -0.06407779 -0.03463625 0.07464212 -0.06407129 -0.03384619 0.07467395 -0.06443703 -0.03345412 0.07452595 -0.06447643 -0.03350865 0.07474726 -0.06482601 -0.03279751 0.07452678 -0.06487858 -0.03284192 0.0747177 -0.0651161 -0.03223299 0.07453387 -0.06531792 -0.03221619 0.07467216 -0.06551271 -0.03168803 0.07455044 -0.06583249 -0.03151363 0.07474416 -0.06642973 -0.03126502 0.0745992 -0.06637722 -0.03085458 0.07451236 -0.06681483 -0.03110903 0.07471281 -0.06684589 -0.03060656 0.07466435 -0.06748211 -0.03033983 0.0744937 -0.06767803 -0.03043937 0.07474613 -0.06828737 -0.03007811 0.07454067 -0.06833666 -0.03001648 0.07463592 -0.0687415 -0.02999305 0.07471001 -0.0692982 -0.02972829 0.07458335 -0.06974238 -0.02989292 0.07474678 -0.07091069 -0.0297237 0.07466864 -0.07049268 -0.03099066 0.08799999 -0.07125478 -0.03102213 0.08859044 -0.07147604 -0.03111106 0.08859437 -0.07214564 -0.03120416 0.08799999 -0.07258671 -0.03135496 0.08863228 -0.07301515 -0.03176206 0.08799999 -0.07397031 -0.03167498 0.08859252 -0.07375741 -0.03191792 0.08867186 -0.07415956 -0.03231573 0.0886082 -0.07474064 -0.03297477 0.08799999 -0.07548928 -0.03272897 0.08866214 -0.0751928 -0.03314155 0.08861792 -0.07558584 -0.03375977 0.08860546 -0.07604748 -0.03475302 0.08799999 -0.07659524 -0.03439593 0.08866262 -0.07638871 -0.03522747 0.08858388 -0.07673746 -0.03665339 0.08799999 -0.07701152 -0.03609925 0.08861541 -0.07692545 -0.03668808 0.08859056 -0.07698863 -0.03742492 0.08866864 -0.07696926 -0.03858721 0.08799999 -0.07681691 -0.03808242 0.08861172 -0.07689851 -0.03874725 0.0886715 -0.07672208 -0.03932589 0.08859312 -0.07652699 -0.04009699 0.08799999 -0.07614952 -0.03987395 0.08860951 -0.0762605 -0.040488 0.08859169 -0.0758816 -0.04127794 0.08799999 -0.07523763 -0.04117912 0.08860057 -0.07530331 -0.04179239 0.0885939 -0.07460927 -0.04218262 0.08799999 -0.07404124 -0.04218536 0.08860194 -0.07400941 -0.04245746 0.08860385 -0.07348138 -0.04278361 0.08799999 -0.0726757 -0.0426833 0.08861082 -0.07290524 -0.04284787 0.08858448 -0.07233095 -0.04294097 0.08866977 -0.07171112 -0.04302424 0.08799999 -0.07074689 -0.04299217 0.08861434 -0.07113325 -0.04296731 0.08859133 -0.0703774 -0.042849 0.08861035 -0.06968855 -0.04266721 0.08799999 -0.06898516 -0.04257184 0.08859658 -0.06876546 -0.04183495 0.08799999 -0.06739729 -0.04211485 0.08863961 -0.06787782 -0.04151028 0.08859157 -0.06703692 -0.0406621 0.08799999 -0.06623572 -0.0408582 0.08861541 -0.06641346 -0.04025042 0.08861297 -0.06596046 -0.03938174 0.08799999 -0.06546956 -0.03959983 0.08866411 -0.06560957 -0.03886985 0.08860754 -0.06530129 -0.03789573 0.08799999 -0.06505638 -0.03789174 0.08859938 -0.06506365 -0.03684723 0.08859664 -0.06500256 -0.03620314 0.08799999 -0.0650233 -0.03607463 0.08866989 -0.06508892 -0.035546 0.08857864 -0.06518077 -0.03494888 0.08866786 -0.06537842 -0.034527 0.08799999 -0.06551933 -0.03425967 0.08863139 -0.06566894 -0.03300833 0.08799999 -0.06647694 -0.03349721 0.08864879 -0.06613981 -0.03293079 0.08856713 -0.06659191 -0.03241813 0.08860141 -0.06712859 -0.03186935 0.08799999 -0.06786471 -0.03180211 0.08864086 -0.06802439 -0.03141677 0.08859103 -0.06879174 -0.03116875 0.08799999 -0.06946611 -0.03112083 0.08859431 -0.06980454 -0.03100693 0.08857911 -0.07068866 -0.03101098 0.07899999 -0.07149147 -0.03100764 0.07839864 -0.07127243 -0.03111875 0.07841336 -0.07219129 -0.03126597 0.07899999 -0.07281589 -0.03204506 0.07899999 -0.07443577 -0.03256797 0.07839345 -0.07504129 -0.03317004 0.07899999 -0.07563042 -0.03364282 0.07840675 -0.07597661 -0.03429621 0.07899999 -0.07637268 -0.03464215 0.07843434 -0.07652443 -0.0357055 0.07899999 -0.07687371 -0.03551673 0.07840085 -0.0768094 -0.03599661 0.07833343 -0.07690054 -0.03700464 0.07840502 -0.07700371 -0.03704237 0.07899999 -0.07700896 -0.03817951 0.07843255 -0.07688921 -0.0386787 0.07899999 -0.07679116 -0.03915721 0.0784052 -0.07659798 -0.03998833 0.07840853 -0.07620263 -0.04016941 0.07899999 -0.07610529 -0.04072999 0.07840764 -0.07569926 -0.04134297 0.07899999 -0.07517099 -0.04141914 0.07837605 -0.07505214 -0.04186701 0.07839041 -0.07449918 -0.04245293 0.07899999 -0.07357323 -0.04226529 0.07840216 -0.07387489 -0.04256337 0.07837682 -0.07322621 -0.04277753 0.07842218 -0.07261157 -0.04295402 0.07899999 -0.07185184 -0.04289835 0.07837247 -0.07205313 -0.04299116 0.07840108 -0.07130515 -0.0429908 0.07899999 -0.07055109 -0.04292923 0.07840716 -0.07008427 -0.0427494 0.07899999 -0.06922638 -0.04273575 0.07842206 -0.06923466 -0.04246979 0.07838523 -0.06854951 -0.04213064 0.07899999 -0.06786471 -0.04179495 0.07840538 -0.06739449 -0.04099166 0.07899999 -0.06647694 -0.04129981 0.07843714 -0.06681609 -0.04076462 0.07841742 -0.06632679 -0.03920179 0.07899999 -0.06538975 -0.03960865 0.07841384 -0.06559973 -0.03916108 0.07835882 -0.06541275 -0.03834706 0.07838708 -0.06515645 -0.0374943 0.07899999 -0.0650056 -0.03730839 0.0784052 -0.06500393 -0.03580635 0.07899999 -0.06509542 -0.03611952 0.07839965 -0.06506222 -0.03510683 0.07835292 -0.06531578 -0.03439331 0.07899999 -0.06558734 -0.03437334 0.07842129 -0.0656076 -0.03328514 0.07899999 -0.06626957 -0.03291451 0.07842344 -0.06659865 -0.03210884 0.07899999 -0.06748348 -0.03210067 0.0783959 -0.06753236 -0.03140765 0.07899999 -0.06880515 -0.03136634 0.07840776 -0.06893581 -0.03105038 0.07899999 -0.07010328 -0.0311219 0.0783863 -0.0698142 -0.03101998 0.0784139 -0.07054448 -0.03106117 0.0782417 -0.07116365 -0.0311352 0.07817935 -0.07039159 -0.03131455 0.07802766 -0.07088166 -0.0314036 0.07807785 -0.0695194 -0.03150558 0.07800233 -0.06998568 -0.03126579 0.07821732 -0.06952315 -0.03145474 0.0782476 -0.06888002 -0.03199315 0.07800632 -0.06841641 -0.03183722 0.0781179 -0.06826746 -0.03168886 0.07833969 -0.06823992 -0.03215658 0.07821553 -0.06759399 -0.03259754 0.07805407 -0.06730121 -0.03253012 0.07826089 -0.06707751 -0.03309828 0.07823413 -0.06652909 -0.03345364 0.07809364 -0.06639552 -0.03342795 0.078004 -0.06668376 -0.03371435 0.0783717 -0.06598633 -0.03404414 0.07823997 -0.06585431 -0.03448277 0.07810318 -0.0657553 -0.03449368 0.07800757 -0.06595695 -0.03464037 0.0782476 -0.06554853 -0.03544163 0.07809442 -0.06540292 -0.03611671 0.07825583 -0.065117 -0.03653204 0.078009 -0.06537443 -0.0361123 0.07808887 -0.06527352 -0.03694635 0.07817912 -0.06510138 -0.03772449 0.07822293 -0.06511902 -0.03785508 0.07809406 -0.06525802 -0.03806006 0.07800608 -0.06547874 -0.03865993 0.07819908 -0.06532675 -0.03881984 0.0780121 -0.06563937 -0.03950446 0.07813912 -0.06570285 -0.04002243 0.07834035 -0.06583106 -0.04006618 0.07805162 -0.06614661 -0.04045718 0.07825523 -0.06615972 -0.0405361 0.07800519 -0.06664091 -0.0408045 0.07812887 -0.06656157 -0.04127383 0.07826417 -0.06685703 -0.04130393 0.07809424 -0.0671032 -0.04173374 0.07801848 -0.06787574 -0.04184961 0.07813167 -0.06771713 -0.04214358 0.07832258 -0.0679453 -0.04253488 0.07823485 -0.06884753 -0.04234898 0.07808303 -0.06879174 -0.04221373 0.07800108 -0.06896841 -0.04265022 0.07808053 -0.06972801 -0.04279649 0.07821118 -0.06980133 -0.04255223 0.0780031 -0.07030725 -0.04297429 0.07835733 -0.07060772 -0.04284608 0.07814735 -0.07056617 -0.04293388 0.07824635 -0.07116276 -0.04268211 0.07802838 -0.07119005 -0.04279267 0.0780974 -0.07145524 -0.04286158 0.07822185 -0.07184839 -0.0424571 0.07800787 -0.07237631 -0.04259473 0.07808452 -0.07249683 -0.04267472 0.0782386 -0.07273852 -0.0423299 0.07816356 -0.07349717 -0.04198813 0.0780394 -0.07379847 -0.04171502 0.07800114 -0.07397496 -0.04190242 0.07818394 -0.07428008 -0.04155832 0.07803905 -0.07444322 -0.04147064 0.07813751 -0.07477831 -0.0412262 0.07827013 -0.07518905 -0.04092967 0.07803577 -0.07513833 -0.04083687 0.07812011 -0.075401 -0.04069596 0.07824933 -0.07565069 -0.04019403 0.07800734 -0.07564777 -0.04005521 0.07819348 -0.07605898 -0.03958618 0.07810902 -0.07621788 -0.03899407 0.07827776 -0.07662034 -0.03897351 0.0780552 -0.07640486 -0.03800076 0.07826697 -0.07686513 -0.03820276 0.07800447 -0.07647722 -0.03791779 0.0781008 -0.0767439 -0.03709441 0.07815617 -0.07687872 -0.03705555 0.07800489 -0.07661682 -0.03659814 0.07819396 -0.0768941 -0.03617995 0.07804059 -0.07665401 -0.03560322 0.07816755 -0.07671695 -0.03540152 0.0780102 -0.07641613 -0.03485882 0.07827347 -0.07655614 -0.03483277 0.07812267 -0.07641994 -0.03418475 0.07822179 -0.07621186 -0.03380686 0.07800424 -0.07560914 -0.0344066 0.07803815 -0.07609951 -0.03354305 0.0781601 -0.07575577 -0.03312391 0.07838779 -0.07557046 -0.0331614 0.07807844 -0.07531911 -0.03284144 0.07825094 -0.07524746 -0.03270721 0.07800406 -0.07462018 -0.03248053 0.07812601 -0.07471293 -0.03197073 0.07840251 -0.07427811 -0.0322538 0.07804036 -0.07418256 -0.03192037 0.07821154 -0.07404005 -0.03153163 0.07837098 -0.07344824 -0.03182214 0.07803797 -0.07341176 -0.03154015 0.07815897 -0.07318013 -0.03132796 0.07833755 -0.07291001 -0.03151321 0.07800823 -0.07231324 -0.03117412 0.07826197 -0.07220333 -0.03125149 0.07813739 -0.07211285 -0.03121286 0.07808995 -0.07141691 -0.03107482 0.08878517 -0.0709834 -0.0312547 0.08892685 -0.07160341 -0.03113377 0.08879083 -0.07173591 -0.03144508 0.08899527 -0.07187438 -0.03121066 0.0887444 -0.07235711 -0.03145134 0.08889412 -0.07276785 -0.0316236 0.08879214 -0.07347232 -0.03184342 0.0889635 -0.0734598 -0.03217291 0.08890473 -0.0742231 -0.03230094 0.0888065 -0.07457667 -0.03261077 0.08899366 -0.07453453 -0.03289532 0.08888059 -0.07514381 -0.03334319 0.088952 -0.07541364 -0.03333175 0.08879095 -0.07563936 -0.03354263 0.08899819 -0.07539409 -0.03390884 0.08884942 -0.07599067 -0.03423678 0.0889641 -0.07598423 -0.03520339 0.08899849 -0.07629555 -0.03466379 0.08890587 -0.07631635 -0.03498327 0.08879864 -0.07655572 -0.03551608 0.08876866 -0.07674229 -0.0356428 0.08894664 -0.07657575 -0.03616428 0.08883756 -0.07681864 -0.03679025 0.0887919 -0.07691204 -0.03669905 0.08897191 -0.07668429 -0.03749215 0.08892482 -0.07676106 -0.03838062 0.08899581 -0.07644712 -0.03823727 0.08886039 -0.07672673 -0.03931862 0.08881705 -0.07642614 -0.03937375 0.08893924 -0.07624274 -0.04015976 0.08884614 -0.07595288 -0.04019194 0.08899408 -0.07562595 -0.04068154 0.08879113 -0.07563167 -0.04095232 0.08893495 -0.07519155 -0.04123568 0.08879357 -0.07512509 -0.04153281 0.08899366 -0.07432866 -0.04174143 0.08875751 -0.07457244 -0.04159188 0.08888369 -0.07459849 -0.04229795 0.08876693 -0.07367479 -0.04203331 0.08889514 -0.07391285 -0.04229122 0.08894526 -0.07324659 -0.04256051 0.08884894 -0.07288146 -0.04234236 0.08899962 -0.07259547 -0.04276686 0.08878803 -0.07232433 -0.0426827 0.08893376 -0.07198935 -0.04285794 0.08885937 -0.07122904 -0.04259395 0.08899718 -0.07114064 -0.04278659 0.08891522 -0.07081341 -0.04291176 0.08875387 -0.07043242 -0.04280644 0.08883357 -0.07005989 -0.04263973 0.08896172 -0.07010489 -0.04263538 0.0887534 -0.06911587 -0.0425682 0.08890038 -0.06932353 -0.04218757 0.0889979 -0.0688948 -0.04212242 0.08895766 -0.06846427 -0.04230558 0.08882969 -0.06845533 -0.04190582 0.08890849 -0.06790214 -0.04169267 0.08883154 -0.06744843 -0.04111057 0.08897137 -0.06705021 -0.04121375 0.08880144 -0.0668525 -0.04063832 0.08899927 -0.0667603 -0.04046803 0.08884572 -0.06625699 -0.03967076 0.08896106 -0.06593805 -0.03993356 0.08884847 -0.06591415 -0.03901112 0.08881503 -0.06545066 -0.03806996 0.08899909 -0.06551617 -0.03844636 0.08897078 -0.06549769 -0.03808349 0.0888344 -0.06521195 -0.03704369 0.08880233 -0.06508767 -0.03699529 0.08896112 -0.06528061 -0.03627389 0.08887594 -0.06520611 -0.03601396 0.0889948 -0.06547594 -0.03550183 0.08875864 -0.06525492 -0.0351479 0.0889092 -0.06549942 -0.03495967 0.08898502 -0.06573885 -0.03432232 0.08881604 -0.0657491 -0.03403532 0.08890324 -0.06600344 -0.03392082 0.08899885 -0.06633543 -0.03346842 0.08887279 -0.06634783 -0.03316354 0.08895534 -0.06674498 -0.03286129 0.08877903 -0.06675523 -0.0323804 0.08885413 -0.06738251 -0.03209692 0.08861315 -0.06755459 -0.03227096 0.08898973 -0.06791228 -0.03210139 0.08884465 -0.06776237 -0.03169715 0.08884406 -0.06846755 -0.03183746 0.08899664 -0.06884455 -0.03160828 0.08893316 -0.06897741 -0.03138399 0.08878231 -0.06912392 -0.03127032 0.08882451 -0.06962031 -0.03133738 0.08895391 -0.07011979 -0.03147232 0.08899277 -0.07000893 -0.03113836 0.08882629 -0.0703808 -0.03000551 0.08758902 -0.07120454 -0.0300107 0.08700001 -0.07152378 -0.03005999 0.08762496 -0.07185417 -0.03027927 0.08700001 -0.07301813 -0.03021216 0.08758902 -0.07271409 -0.03049749 0.08759969 -0.07358086 -0.03090399 0.08700001 -0.07446235 -0.03086841 0.08758908 -0.07437866 -0.03143072 0.0875926 -0.07524144 -0.03193318 0.08700001 -0.07586616 -0.03213346 0.08756619 -0.07603573 -0.03279405 0.08761632 -0.07658767 -0.03344607 0.08700001 -0.07705062 -0.0333743 0.08759123 -0.07698434 -0.03397083 0.08758604 -0.07730799 -0.03538066 0.08700001 -0.07784557 -0.03458648 0.0875892 -0.07756781 -0.03527009 0.0876047 -0.07777804 -0.03596419 0.08765792 -0.07790905 -0.03680461 0.08761799 -0.07799422 -0.03747189 0.08700001 -0.07800126 -0.03762781 0.08767521 -0.07795476 -0.0384081 0.08766442 -0.07784146 -0.03901904 0.08700001 -0.07771354 -0.03908127 0.08758163 -0.07768136 -0.03971832 0.08757442 -0.07744926 -0.04046291 0.08700001 -0.07710313 -0.04052042 0.0876044 -0.07704925 -0.04122245 0.08762133 -0.0765742 -0.04186183 0.08700001 -0.07605993 -0.04175132 0.08763992 -0.07612651 -0.04223358 0.08762335 -0.07563543 -0.04260629 0.08757585 -0.07519495 -0.04286211 0.08700001 -0.07484501 -0.04306495 0.08757436 -0.07449269 -0.04352778 0.08700001 -0.07356184 -0.0433222 0.08765035 -0.07398092 -0.04385608 0.08759957 -0.07241082 -0.04394638 0.08700001 -0.07199388 -0.04398971 0.08759552 -0.07138001 -0.0439893 0.08700001 -0.07047635 -0.04397857 0.08759254 -0.07049459 -0.04389244 0.08758145 -0.06978857 -0.04372066 0.08700001 -0.06898194 -0.04369097 0.08758437 -0.06893843 -0.04337126 0.08760398 -0.06811159 -0.04284328 0.08700001 -0.06708329 -0.04305011 0.08765685 -0.06750619 -0.04267269 0.0875827 -0.06690216 -0.04210591 0.08760082 -0.06621235 -0.0414161 0.08700001 -0.06554675 -0.04146021 0.08768153 -0.06562972 -0.04083627 0.08765876 -0.06516033 -0.0402348 0.08700001 -0.06478601 -0.04031658 0.08757925 -0.06483745 -0.03968101 0.08761328 -0.06454014 -0.03895103 0.08700001 -0.06425952 -0.03891611 0.08760249 -0.06426787 -0.03837388 0.08763384 -0.06414598 -0.03739869 0.08700001 -0.06400072 -0.03771042 0.08757919 -0.06403779 -0.03688806 0.08767139 -0.06401675 -0.0354886 0.08700001 -0.06412971 -0.03627717 0.08759218 -0.06404054 -0.0356279 0.08760195 -0.06414014 -0.03495365 0.08762496 -0.06431376 -0.03429335 0.08765649 -0.06456136 -0.03369069 0.08700001 -0.06481957 -0.03377944 0.08758908 -0.0647841 -0.03302896 0.08766829 -0.06525516 -0.03253161 0.08700001 -0.06559789 -0.03249961 0.08759665 -0.06564289 -0.0317251 0.08757722 -0.06638848 -0.0316323 0.08700001 -0.06649607 -0.03105461 0.0876699 -0.0673325 -0.03072398 0.08700001 -0.06784343 -0.03077286 0.08758634 -0.06780761 -0.03043901 0.08760696 -0.06856375 -0.03007233 0.08700001 -0.06983363 -0.03013688 0.08762878 -0.06964713 -0.03002339 0.08760398 -0.07048934 -0.03002649 0.07999998 -0.07187384 -0.03001374 0.07935023 -0.07084703 -0.03002309 0.07940894 -0.07153058 -0.0301094 0.0794329 -0.0722295 -0.030299 0.07942545 -0.07303184 -0.03049218 0.07999998 -0.0736072 -0.0309357 0.07932883 -0.07446289 -0.03132784 0.07999998 -0.07514476 -0.0313251 0.07931941 -0.07506603 -0.03172975 0.07937663 -0.07559573 -0.03237807 0.07939738 -0.07625615 -0.03280162 0.07999998 -0.07663255 -0.03306102 0.07941854 -0.07678425 -0.03364741 0.0793904 -0.0771389 -0.03448534 0.07999998 -0.07755106 -0.03429424 0.0794208 -0.07745409 -0.0348286 0.07932931 -0.07763844 -0.0363546 0.07999998 -0.07799535 -0.03630733 0.07939529 -0.07796096 -0.03696334 0.07942068 -0.07799822 -0.03768098 0.07940888 -0.07796382 -0.03861933 0.07999998 -0.07784557 -0.03853976 0.07940697 -0.07782894 -0.04002171 0.07940894 -0.07731091 -0.04055386 0.07999998 -0.07705062 -0.04060649 0.07937705 -0.07699084 -0.04133224 0.07939469 -0.07649809 -0.04206675 0.07999998 -0.07586616 -0.04164934 0.0793327 -0.07621228 -0.04222768 0.07937192 -0.07564294 -0.04277807 0.07938867 -0.07494819 -0.04336172 0.07999998 -0.07400214 -0.04331511 0.07939034 -0.07401573 -0.04363387 0.07939732 -0.07322043 -0.04381912 0.07935392 -0.07252937 -0.04397714 0.07999998 -0.0718196 -0.04394346 0.07942557 -0.07187789 -0.04399567 0.07942068 -0.07118993 -0.04396867 0.07941126 -0.0703271 -0.04394984 0.07999998 -0.07007902 -0.04382306 0.07939338 -0.06945908 -0.04357576 0.07999998 -0.0685507 -0.04363679 0.07942557 -0.06877833 -0.04303348 0.07934218 -0.06747794 -0.04288762 0.07999998 -0.06719738 -0.04261893 0.07932943 -0.06685096 -0.04201996 0.07999998 -0.06610351 -0.04225283 0.07939314 -0.06638091 -0.04175436 0.07942062 -0.06586462 -0.04123777 0.07941699 -0.06543117 -0.04061663 0.07999998 -0.06497734 -0.04062956 0.07940006 -0.06501907 -0.03937196 0.0793994 -0.06441849 -0.03901904 0.07999998 -0.06428641 -0.03853547 0.07941359 -0.06416928 -0.03747177 0.07999998 -0.06399869 -0.03767919 0.07943373 -0.06403332 -0.03678858 0.07941317 -0.06400233 -0.0353806 0.07999998 -0.06415438 -0.03512465 0.07938581 -0.06425845 -0.03409463 0.07939952 -0.06463199 -0.0333383 0.07999998 -0.06500786 -0.03332173 0.0793991 -0.06504911 -0.03279441 0.07935106 -0.06542015 -0.03236442 0.07941168 -0.06575334 -0.03197997 0.07999998 -0.06610351 -0.03175365 0.07941102 -0.06637006 -0.03118717 0.07999998 -0.06708985 -0.03122764 0.07936728 -0.06705033 -0.03076308 0.07939732 -0.06783145 -0.03051358 0.07999998 -0.06832283 -0.03047806 0.0793991 -0.06846845 -0.03021329 0.07940089 -0.06928622 -0.03006339 0.07999998 -0.06995451 -0.03006064 0.0793904 -0.07012188 -0.03015625 0.07914763 -0.07037627 -0.03029716 0.07904338 -0.07037252 -0.03024053 0.07926493 -0.06939852 -0.03038161 0.07909411 -0.0694164 -0.03048318 0.0792154 -0.06866377 -0.03084319 0.07900649 -0.06855851 -0.03080397 0.07908803 -0.06819975 -0.03100866 0.07919245 -0.06755858 -0.03150242 0.07908004 -0.06702011 -0.03180044 0.07900488 -0.06690132 -0.03159558 0.07922387 -0.06667292 -0.03217238 0.07926023 -0.0660026 -0.03214514 0.07909774 -0.06622737 -0.03288251 0.07915186 -0.06549382 -0.03305631 0.07900434 -0.06567502 -0.03350216 0.07909893 -0.0651496 -0.03378695 0.07927495 -0.06483089 -0.03404682 0.07903456 -0.06498229 -0.03456479 0.0791893 -0.06453359 -0.03523904 0.0791257 -0.06438159 -0.03562378 0.07900917 -0.06450146 -0.03594505 0.07933831 -0.06409436 -0.0363118 0.07909476 -0.06422388 -0.03667962 0.07923984 -0.06407433 -0.03748214 0.07928693 -0.06405407 -0.03768765 0.07912474 -0.0641905 -0.03756147 0.07900416 -0.06439709 -0.03827738 0.07922661 -0.06419086 -0.03848886 0.07902741 -0.06447929 -0.03918075 0.07909816 -0.06453877 -0.03901731 0.07924419 -0.06436288 -0.03992986 0.07932454 -0.06466037 -0.04007005 0.0790044 -0.06513524 -0.04028028 0.07922542 -0.06490087 -0.04039663 0.07910037 -0.06509763 -0.04091942 0.07924753 -0.06527596 -0.04106891 0.07905822 -0.06560939 -0.04146295 0.07920283 -0.0657221 -0.04192495 0.07920908 -0.06614464 -0.04207456 0.07900518 -0.06674814 -0.04183787 0.07906067 -0.06629759 -0.04241853 0.07912486 -0.06682538 -0.04281717 0.07906466 -0.06754904 -0.04319995 0.07918053 -0.06798821 -0.04338717 0.07937526 -0.06815439 -0.04297381 0.07900613 -0.06818377 -0.04342561 0.07906949 -0.06884449 -0.04361283 0.07923632 -0.06891185 -0.04385089 0.07921868 -0.06999129 -0.04359495 0.07904022 -0.06973302 -0.04356914 0.0790047 -0.07020711 -0.04377037 0.07907092 -0.07072913 -0.04392659 0.07922965 -0.07088869 -0.04356771 0.07900363 -0.07180559 -0.04390382 0.07924407 -0.07170027 -0.04376453 0.07908743 -0.07165938 -0.0436865 0.07911145 -0.07236605 -0.04359638 0.0792188 -0.07309538 -0.04334098 0.0790475 -0.0732817 -0.04323416 0.07923191 -0.07402712 -0.04304802 0.07909911 -0.07414227 -0.04278212 0.07923346 -0.07481819 -0.04269355 0.07900375 -0.07435464 -0.04235833 0.07913672 -0.07528543 -0.0419647 0.07900518 -0.07537746 -0.04161167 0.07908928 -0.07600152 -0.04091334 0.07917195 -0.0766716 -0.04071807 0.07902663 -0.07654863 -0.03999239 0.07920187 -0.07723283 -0.03996169 0.07910466 -0.0771417 -0.03961199 0.07900738 -0.07709604 -0.03927916 0.07934123 -0.07760477 -0.03872805 0.07911026 -0.07760703 -0.03821837 0.07923173 -0.07782381 -0.03801727 0.07900524 -0.07755064 -0.03761398 0.07908004 -0.07775431 -0.03711372 0.07920259 -0.07791709 -0.03615641 0.07917529 -0.07783967 -0.03638499 0.07904368 -0.07769644 -0.03557872 0.0793274 -0.07783687 -0.03508931 0.07900136 -0.07732826 -0.03496408 0.07909578 -0.07750189 -0.03386235 0.07923406 -0.07718461 -0.03383183 0.07907634 -0.07699918 -0.03307658 0.07921582 -0.07670104 -0.03318983 0.07900655 -0.076406 -0.03250545 0.07906317 -0.07605999 -0.03228282 0.07921737 -0.07607209 -0.03177422 0.07908999 -0.07535821 -0.0320003 0.07900208 -0.07527267 -0.03127127 0.07909309 -0.07466667 -0.03113687 0.07902437 -0.07418811 -0.03074043 0.07912057 -0.07375949 -0.03063696 0.07933515 -0.07388085 -0.03079712 0.07900446 -0.07329976 -0.03042757 0.07924473 -0.07322543 -0.0304113 0.07907491 -0.07258558 -0.03022867 0.07919466 -0.07237505 -0.03007954 0.07927638 -0.07171481 -0.03039056 0.07900255 -0.07130014 -0.03022688 0.07908439 -0.0714963 -0.03006547 0.08775609 -0.07115924 -0.03028225 0.08794671 -0.07156175 -0.03029298 0.08795976 -0.07079821 -0.03017908 0.08783012 -0.07192397 -0.03044766 0.08799737 -0.07191157 -0.03029185 0.0877816 -0.07271832 -0.03049945 0.08795505 -0.07273781 -0.03052181 0.08782219 -0.07336139 -0.03099507 0.08791017 -0.07421022 -0.03089195 0.08777201 -0.07427632 -0.03113794 0.08799248 -0.07410258 -0.03145492 0.08781844 -0.07510501 -0.03203296 0.08796542 -0.07550948 -0.03180491 0.08773338 -0.07561552 -0.03269279 0.08799886 -0.07598525 -0.03217923 0.08779358 -0.07596427 -0.03260904 0.08788138 -0.07623445 -0.03301578 0.08776068 -0.07667756 -0.03326791 0.08795708 -0.07660084 -0.0337103 0.08779782 -0.07707697 -0.03442406 0.08791679 -0.07728648 -0.03447055 0.08775228 -0.07746517 -0.03475022 0.08799773 -0.07718843 -0.03546321 0.08796548 -0.07752662 -0.03531885 0.08782696 -0.07768034 -0.03630876 0.08787566 -0.07781052 -0.03681367 0.0879954 -0.07760965 -0.03706955 0.08789348 -0.07782709 -0.03791004 0.08798527 -0.07758092 -0.03814542 0.08789581 -0.0777207 -0.0388754 0.08792537 -0.07750618 -0.03915846 0.08778131 -0.07758146 -0.03946161 0.0879901 -0.07716536 -0.039779 0.08786004 -0.07726716 -0.04016858 0.08772087 -0.0771932 -0.04039484 0.08798187 -0.0767439 -0.04061806 0.08781671 -0.07686722 -0.04123789 0.08786469 -0.07638996 -0.04183053 0.08799701 -0.07550674 -0.04168331 0.08794724 -0.07585263 -0.04208129 0.08781117 -0.07566851 -0.04275315 0.08774149 -0.07489246 -0.04255849 0.08790755 -0.07492947 -0.04281508 0.0879842 -0.07421505 -0.04305696 0.08788114 -0.07416689 -0.04334002 0.08799976 -0.07278847 -0.04357117 0.0876705 -0.07336705 -0.04333823 0.08792978 -0.07338953 -0.04368317 0.08781176 -0.07271826 -0.04368913 0.08792006 -0.0721811 -0.04388165 0.08775079 -0.07188135 -0.04392188 0.0877822 -0.07114368 -0.04358869 0.08799761 -0.07109349 -0.04374969 0.08794158 -0.07068425 -0.04390889 0.08776676 -0.07046747 -0.04376608 0.0877788 -0.06950134 -0.04364627 0.08791297 -0.06959813 -0.04335933 0.08799612 -0.0692175 -0.04328811 0.08792811 -0.0684598 -0.04340904 0.0877611 -0.06834894 -0.04274398 0.08796876 -0.06756204 -0.04277461 0.08786004 -0.06729698 -0.04255372 0.08777183 -0.06685662 -0.04210525 0.08775383 -0.06629979 -0.04210484 0.08799749 -0.06682801 -0.04203724 0.08791202 -0.06643426 -0.04126745 0.08799254 -0.06593501 -0.04114198 0.087879 -0.06555402 -0.04028093 0.08797907 -0.0651887 -0.04013276 0.08780354 -0.06484162 -0.03977638 0.08790338 -0.06478351 -0.0390191 0.08778965 -0.0643801 -0.0385254 0.08800011 -0.06460827 -0.03910565 0.08795928 -0.06462574 -0.03833687 0.08791589 -0.06433963 -0.03769409 0.08778399 -0.06410962 -0.0376721 0.08795678 -0.06431186 -0.03678804 0.08791166 -0.06421035 -0.03627359 0.08799159 -0.06441003 -0.03609097 0.08781987 -0.06416577 -0.03551572 0.08784145 -0.06428182 -0.0347703 0.08799022 -0.06474864 -0.03508758 0.08793866 -0.06452018 -0.03452402 0.0878297 -0.06457376 -0.03392738 0.08793133 -0.06497561 -0.03355121 0.08782833 -0.06503456 -0.03361225 0.08799743 -0.06535094 -0.03288972 0.08794462 -0.06564593 -0.03255057 0.08778721 -0.06570601 -0.03204077 0.08775305 -0.06614416 -0.03191995 0.08798843 -0.06671106 -0.03191995 0.08788645 -0.06642204 -0.03139495 0.08780634 -0.06696343 -0.03122794 0.08796441 -0.06759262 -0.03083902 0.08784717 -0.06794095 -0.03092604 0.08799958 -0.06844717 -0.0304104 0.08773118 -0.06878936 -0.03057247 0.08793234 -0.06886053 -0.03030055 0.08782964 -0.06939917 -0.03042215 0.08797663 -0.06988316 -0.03014248 0.08784323 -0.07044577 -0.02899813 0.08658921 -0.07102566 -0.02907556 0.08662337 -0.07204484 -0.02914261 0.08599996 -0.07253742 -0.02920246 0.08659303 -0.07277554 -0.02958703 0.08599996 -0.07405972 -0.02942085 0.08664971 -0.07352346 -0.02972996 0.08661317 -0.07432526 -0.03008049 0.08660954 -0.07500511 -0.03057122 0.08599996 -0.07579427 -0.03049886 0.08660191 -0.07565528 -0.03100115 0.08659303 -0.07628846 -0.03180658 0.08599996 -0.07710111 -0.03154796 0.08664816 -0.07684004 -0.03238278 0.08664244 -0.07752531 -0.03295356 0.08599996 -0.07790857 -0.03326535 0.08666115 -0.07806026 -0.03420644 0.08599996 -0.07850939 -0.03408473 0.08666282 -0.07843768 -0.03484839 0.08660221 -0.07870537 -0.03594326 0.08599996 -0.07894963 -0.03580445 0.08661639 -0.07890409 -0.03660756 0.086658 -0.07897692 -0.03754854 0.08599996 -0.07898753 -0.03739047 0.08660352 -0.07898628 -0.03842788 0.08661139 -0.07887029 -0.03892213 0.08599996 -0.07877814 -0.03938782 0.08660173 -0.0786311 -0.04042518 0.08599996 -0.07824307 -0.04028058 0.08659553 -0.07829755 -0.04137128 0.08663254 -0.07769465 -0.04195302 0.08599996 -0.07730722 -0.04231852 0.08661705 -0.07697314 -0.04335629 0.08599996 -0.07588988 -0.04297965 0.08660042 -0.07630866 -0.04348677 0.08662843 -0.07566857 -0.0438534 0.08665728 -0.07509613 -0.04427969 0.08599996 -0.07434672 -0.04413604 0.08662331 -0.07460057 -0.04444611 0.08664077 -0.07389724 -0.04484844 0.08599996 -0.0726478 -0.04474902 0.08659207 -0.07299268 -0.04493713 0.08658975 -0.07198214 -0.04501086 0.08599996 -0.0708568 -0.04499155 0.08661264 -0.07121813 -0.04496556 0.08663374 -0.07035571 -0.04485732 0.08599996 -0.06946253 -0.04486614 0.0866124 -0.06957304 -0.0446974 0.08663815 -0.06885623 -0.04434347 0.08599996 -0.06775456 -0.04437673 0.08658444 -0.06789839 -0.04390722 0.08662408 -0.06697827 -0.04329931 0.08599996 -0.06604892 -0.04355287 0.086681 -0.06644845 -0.04323929 0.08659356 -0.06599766 -0.04271572 0.08662134 -0.06541228 -0.04189711 0.08599996 -0.06463772 -0.04216408 0.08663219 -0.06490123 -0.04149645 0.08660954 -0.06438928 -0.04080009 0.08656489 -0.06396037 -0.03993088 0.08599996 -0.06353217 -0.04008096 0.08657646 -0.0636183 -0.03934943 0.08658206 -0.06335473 -0.0385974 0.0865699 -0.06316143 -0.03819376 0.08599996 -0.06307929 -0.03778803 0.08658611 -0.06304097 -0.03665703 0.08599996 -0.06299519 -0.03702372 0.08660042 -0.06300383 -0.03602784 0.08660328 -0.06305944 -0.03488582 0.08599996 -0.06326407 -0.0350703 0.08662337 -0.06324338 -0.03414684 0.08665943 -0.06353855 -0.03298872 0.08599996 -0.06405246 -0.03349804 0.08660203 -0.06381183 -0.03264445 0.08660757 -0.06429046 -0.03168052 0.08658736 -0.06502199 -0.03155171 0.08599996 -0.06512808 -0.03099685 0.08657443 -0.0657134 -0.03028959 0.08599996 -0.06659197 -0.03058946 0.08667117 -0.06624674 -0.03027582 0.08657157 -0.06666696 -0.02978742 0.08659952 -0.06753849 -0.02928841 0.08599996 -0.06876575 -0.02941936 0.08662772 -0.06846761 -0.02920109 0.08660572 -0.06923776 -0.02907049 0.08663415 -0.07001096 -0.02898061 0.08599996 -0.07093995 -0.02900803 0.08099997 -0.07159894 -0.02900779 0.08038902 -0.07079625 -0.02906042 0.08041101 -0.07196164 -0.02920204 0.08040219 -0.07277107 -0.02930277 0.08099997 -0.07322436 -0.02941054 0.08037608 -0.07350713 -0.02980017 0.08039373 -0.07448804 -0.03007811 0.08099997 -0.07506793 -0.03029918 0.08039939 -0.07536345 -0.03073543 0.08039534 -0.07596844 -0.031304 0.08099997 -0.07663476 -0.0314216 0.08038681 -0.07673203 -0.03230047 0.08039194 -0.07747322 -0.0325334 0.08099997 -0.07765161 -0.03302305 0.08036547 -0.07793349 -0.03375273 0.08099997 -0.07831829 -0.03385639 0.08039927 -0.07835227 -0.03527402 0.08099997 -0.07883167 -0.03541558 0.08040219 -0.07883799 -0.03618252 0.08039534 -0.07895374 -0.03705662 0.08099997 -0.07901191 -0.03717255 0.0803892 -0.07899707 -0.03884297 0.08099997 -0.07880491 -0.03918099 0.08039873 -0.0786972 -0.04009735 0.08039039 -0.07837063 -0.04033827 0.08099997 -0.07827717 -0.04080498 0.08039534 -0.07803219 -0.04172992 0.08099997 -0.0774762 -0.0415216 0.08041971 -0.07759779 -0.04215222 0.08040994 -0.07711666 -0.04246729 0.08033424 -0.07681769 -0.04290294 0.08099997 -0.07640898 -0.04315125 0.08039915 -0.07611572 -0.04387414 0.08099997 -0.07513034 -0.04371267 0.08040219 -0.07534569 -0.04422217 0.08041363 -0.07444542 -0.0445404 0.08099997 -0.07369142 -0.04479438 0.08038336 -0.07277494 -0.04493874 0.08099997 -0.07213586 -0.04493564 0.08040761 -0.07199019 -0.04497879 0.0803281 -0.07130622 -0.04495841 0.08099997 -0.06994009 -0.0449745 0.08038777 -0.07043093 -0.04488372 0.08033871 -0.06972074 -0.04470372 0.0804063 -0.06885409 -0.0444374 0.08099997 -0.06802022 -0.04445058 0.08039456 -0.06809866 -0.04411292 0.08040821 -0.06734448 -0.04348242 0.08099997 -0.06626313 -0.04363471 0.08039641 -0.06652879 -0.04298913 0.08039402 -0.06570327 -0.04244929 0.08037 -0.06515407 -0.04210668 0.08099997 -0.06482613 -0.04164427 0.08037531 -0.06448936 -0.04065734 0.08099997 -0.06386578 -0.04080277 0.08039808 -0.06396615 -0.03995448 0.08041203 -0.06356394 -0.03916883 0.08099997 -0.06329131 -0.0391615 0.08035671 -0.06330621 -0.03823083 0.08040934 -0.06309789 -0.03733819 0.08099997 -0.06297838 -0.0372166 0.08038979 -0.06300342 -0.03634148 0.08032572 -0.06304186 -0.03541278 0.08099997 -0.06314861 -0.03479135 0.08042764 -0.06330758 -0.03393995 0.08099997 -0.06359517 -0.03370791 0.08043873 -0.06370401 -0.03269803 0.08099997 -0.06424754 -0.03201127 0.08042055 -0.06474292 -0.03154885 0.08099997 -0.06512504 -0.03129446 0.08037102 -0.06540358 -0.03074324 0.08039641 -0.06602108 -0.03022223 0.08099997 -0.06669622 -0.0302723 0.08039796 -0.06667894 -0.02988433 0.08037006 -0.06736171 -0.02956032 0.08034974 -0.06809043 -0.02940696 0.08099997 -0.06844884 -0.02936655 0.08037722 -0.06863874 -0.02921289 0.08033686 -0.06923109 -0.0290572 0.08099997 -0.06994765 -0.02906316 0.08041852 -0.07000946 -0.02913159 0.08014702 -0.07091373 -0.0293346 0.0800203 -0.0710051 -0.02914237 0.08020955 -0.07002961 -0.02947384 0.08000665 -0.06980609 -0.02933287 0.08009248 -0.06952399 -0.02986758 0.08000463 -0.06831336 -0.02953988 0.08012425 -0.06857484 -0.02976793 0.08014696 -0.06791019 -0.0303983 0.08018034 -0.06665748 -0.03020477 0.08007001 -0.06722241 -0.03080713 0.08000528 -0.06657689 -0.03108757 0.0800631 -0.0659781 -0.03106504 0.08019679 -0.06577908 -0.03178489 0.08016574 -0.06507933 -0.0322445 0.08000832 -0.06502318 -0.03245794 0.08010947 -0.06462824 -0.03268402 0.08034175 -0.06427735 -0.03335297 0.08027178 -0.06393092 -0.03325915 0.08011889 -0.0641179 -0.03386288 0.08002996 -0.06397491 -0.03451663 0.08000111 -0.06384229 -0.03411442 0.08012497 -0.06370866 -0.03444445 0.08025097 -0.06347769 -0.03525465 0.08006852 -0.06342244 -0.03542995 0.0803523 -0.06316912 -0.03582352 0.08018535 -0.06318634 -0.03701633 0.08000683 -0.06336677 -0.03651487 0.08007615 -0.06323158 -0.03759104 0.08026409 -0.06306844 -0.0376054 0.08011883 -0.06318932 -0.03828513 0.08000475 -0.06349152 -0.03860336 0.0802409 -0.06322824 -0.03902602 0.08011567 -0.06342887 -0.03953856 0.08001697 -0.06378227 -0.04006201 0.08022183 -0.06369459 -0.04019731 0.080087 -0.06389313 -0.04093414 0.08014953 -0.0641781 -0.04092574 0.08000397 -0.06448727 -0.04184311 0.08017498 -0.064763 -0.04201561 0.08003979 -0.06513971 -0.04280978 0.08017796 -0.06565457 -0.04284685 0.08000957 -0.06607937 -0.04321575 0.08010536 -0.0662598 -0.04345107 0.08029723 -0.06633162 -0.04377043 0.08018064 -0.06693559 -0.04393333 0.08005994 -0.06751722 -0.04393309 0.08000296 -0.06789433 -0.04429197 0.08022522 -0.0678907 -0.04446011 0.08006381 -0.06884014 -0.04461282 0.08022034 -0.06881129 -0.04457592 0.08000594 -0.07010638 -0.04475337 0.08014965 -0.06969177 -0.04482108 0.08011132 -0.07058781 -0.04486596 0.08019375 -0.07182633 -0.04468256 0.08003962 -0.07173842 -0.04429256 0.08000195 -0.07311552 -0.04468029 0.08016073 -0.07274973 -0.04441303 0.0800445 -0.07318401 -0.04458689 0.08036535 -0.07350903 -0.04447329 0.08018511 -0.07354968 -0.04420351 0.08020323 -0.07427453 -0.04395943 0.0800395 -0.07432389 -0.0438857 0.08020627 -0.07490748 -0.04342645 0.08000379 -0.07504284 -0.0434432 0.08022201 -0.07560604 -0.04319572 0.08005917 -0.07567417 -0.04293417 0.08021146 -0.07625114 -0.04212212 0.08016395 -0.0769999 -0.04218477 0.08000576 -0.07659065 -0.0412811 0.08021372 -0.07766789 -0.04114562 0.08010691 -0.0776413 -0.04105633 0.08001548 -0.07748448 -0.04042243 0.08019042 -0.07811969 -0.03989565 0.08000296 -0.07801812 -0.03986668 0.08005803 -0.07819509 -0.03969097 0.08018225 -0.07842117 -0.03896647 0.0801897 -0.07865542 -0.0388785 0.08003473 -0.07846486 -0.03817999 0.08034312 -0.07889914 -0.03755176 0.08000278 -0.07858914 -0.03819298 0.08010727 -0.07872831 -0.03728818 0.08015149 -0.07887184 -0.03637337 0.08017957 -0.07887089 -0.03620433 0.08003288 -0.07865786 -0.03542399 0.08017665 -0.07873368 -0.03468358 0.08033126 -0.07864075 -0.03509747 0.08000981 -0.07839465 -0.03439515 0.08007991 -0.07834428 -0.0337466 0.08026331 -0.07825571 -0.03318589 0.08012175 -0.07785731 -0.03291207 0.08000683 -0.07745188 -0.03207063 0.08022743 -0.07721 -0.03206723 0.08006978 -0.07701164 -0.03163415 0.0801326 -0.07672685 -0.03108286 0.08021706 -0.07626307 -0.03131878 0.08000439 -0.0760433 -0.03109902 0.08006286 -0.07603341 -0.03053492 0.08015757 -0.07550102 -0.03035014 0.08001279 -0.07479083 -0.03005194 0.08025187 -0.07485318 -0.02983635 0.08018755 -0.07435941 -0.02943634 0.08022028 -0.07336777 -0.02955067 0.0800029 -0.07253384 -0.02966803 0.08004653 -0.07345873 -0.02928167 0.08011144 -0.07234197 -0.02917444 0.08025467 -0.07235527 -0.0290355 0.08031833 -0.07148039 -0.02907079 0.08677524 -0.07098889 -0.02919816 0.0869078 -0.07094913 -0.0291379 0.08678489 -0.07195395 -0.02929997 0.08694911 -0.07178294 -0.02967846 0.08699327 -0.0731759 -0.02929174 0.08679783 -0.07277774 -0.02946811 0.08695399 -0.07270556 -0.02956312 0.08685421 -0.07354342 -0.0298317 0.08678764 -0.07436835 -0.02999371 0.08691012 -0.07442098 -0.03032374 0.08699363 -0.07465994 -0.03035354 0.08678787 -0.07529544 -0.03063172 0.08694052 -0.07542979 -0.03092199 0.08680081 -0.07606768 -0.03150844 0.08699798 -0.07623714 -0.03149414 0.08692073 -0.07650977 -0.0318585 0.08677041 -0.0770393 -0.03252887 0.08686423 -0.07746404 -0.03262692 0.08696311 -0.0773468 -0.03384119 0.08699852 -0.07792609 -0.03372067 0.08682161 -0.07817798 -0.03355669 0.08696347 -0.07789069 -0.0342797 0.08692044 -0.07829684 -0.03503441 0.08682572 -0.07864147 -0.03554898 0.08696913 -0.07855409 -0.03582417 0.08684796 -0.07878226 -0.03672778 0.08699333 -0.07862162 -0.03661423 0.08689063 -0.07881224 -0.03752386 0.08684247 -0.07886171 -0.03769648 0.08699291 -0.07859492 -0.03820091 0.08677673 -0.0788322 -0.03863078 0.08695489 -0.07855194 -0.03897786 0.08678501 -0.07866638 -0.03961491 0.08684545 -0.07842957 -0.03966587 0.08699125 -0.07814455 -0.04043614 0.08676135 -0.07815057 -0.04036211 0.08691674 -0.07802224 -0.04084461 0.08699643 -0.07754868 -0.04108017 0.08681732 -0.07775664 -0.04138785 0.08692866 -0.07741576 -0.04182702 0.08679145 -0.07727116 -0.04195451 0.08698141 -0.07684242 -0.04250931 0.08683043 -0.076644 -0.04260206 0.0869928 -0.07617282 -0.04292935 0.08693218 -0.07603198 -0.04329562 0.08678793 -0.0758084 -0.0435552 0.0869956 -0.07486981 -0.04391086 0.08687072 -0.07472389 -0.04421406 0.08696681 -0.07370573 -0.04432058 0.08684772 -0.07387787 -0.04463011 0.08683162 -0.07301408 -0.04452049 0.08699607 -0.07211911 -0.04486596 0.08676832 -0.0720573 -0.0447216 0.08694171 -0.07176703 -0.04493778 0.08674788 -0.07077592 -0.04479843 0.08690297 -0.07066303 -0.04455977 0.0869975 -0.07031232 -0.04477918 0.08682727 -0.06965965 -0.04467272 0.08692979 -0.06977856 -0.04445379 0.08695775 -0.06899458 -0.04440599 0.08683586 -0.06829476 -0.04410469 0.08699172 -0.06822609 -0.04424226 0.08672702 -0.06772041 -0.04397851 0.08691191 -0.06752455 -0.04327815 0.08698892 -0.06662899 -0.04377031 0.08686369 -0.06700849 -0.04311954 0.08683913 -0.06603842 -0.04264956 0.0868209 -0.06549274 -0.0422827 0.08693593 -0.06531369 -0.04210764 0.08699673 -0.06537467 -0.04191768 0.0868082 -0.06481218 -0.04126882 0.08688116 -0.06443154 -0.04098182 0.08699262 -0.06448584 -0.04110562 0.08674925 -0.06420105 -0.04043328 0.08676826 -0.06384968 -0.0403611 0.08692318 -0.06399136 -0.03968584 0.08676421 -0.06353706 -0.03952181 0.08690416 -0.06361263 -0.03903156 0.08698987 -0.06363445 -0.03894144 0.08675426 -0.06330412 -0.03841704 0.08691489 -0.06333935 -0.03820043 0.08677637 -0.06316506 -0.03751188 0.086995 -0.06341022 -0.0374177 0.0867927 -0.06309801 -0.03701812 0.08690142 -0.06318432 -0.03620278 0.08674222 -0.06308668 -0.03617125 0.08699148 -0.06340157 -0.03544574 0.08689528 -0.06332945 -0.03463524 0.08674037 -0.06341487 -0.03432339 0.08698928 -0.0638408 -0.03416818 0.08690869 -0.06373232 -0.03342837 0.08684229 -0.06398081 -0.03305381 0.08695602 -0.06436586 -0.03273385 0.08678704 -0.06432616 -0.03232687 0.08699637 -0.06500893 -0.03194671 0.08691668 -0.0650621 -0.03189736 0.08674216 -0.0649113 -0.03115242 0.08675682 -0.06563031 -0.03101497 0.08689576 -0.0659675 -0.03124022 0.08699142 -0.06599509 -0.03020668 0.08678948 -0.06692457 -0.03046965 0.08697497 -0.06695073 -0.02993053 0.08690667 -0.06769347 -0.0297631 0.08676445 -0.06775909 -0.02991718 0.08699673 -0.06825459 -0.0295701 0.08686769 -0.06846261 -0.02950304 0.08696919 -0.06926393 -0.02930206 0.08680826 -0.06921851 -0.02918463 0.08683675 -0.07002598 -0.0293951 0.08699005 -0.0701701 -0.02803927 0.0814045 -0.07013911 -0.02800673 0.08139407 -0.07120645 -0.02813005 0.08115291 -0.07077044 -0.02841359 0.08100682 -0.07026588 -0.02813136 0.08124929 -0.06987899 -0.02828031 0.08108019 -0.06996476 -0.0282703 0.08139896 -0.0688076 -0.02830094 0.08117276 -0.06917017 -0.02861028 0.08100938 -0.06894534 -0.02865201 0.08109247 -0.06818681 -0.02850991 0.08121603 -0.06826376 -0.02869212 0.08139967 -0.06753563 -0.02887171 0.08123093 -0.06730175 -0.02930802 0.08100241 -0.06718671 -0.02929037 0.08105272 -0.06687182 -0.02920728 0.08141392 -0.0665009 -0.0292651 0.08122074 -0.06655186 -0.02968955 0.08134096 -0.06577301 -0.02986896 0.08109861 -0.06582403 -0.03022813 0.08100426 -0.06569778 -0.03025919 0.08141392 -0.06503927 -0.03041702 0.08123022 -0.06496423 -0.03040814 0.08110857 -0.06514024 -0.03105711 0.08138036 -0.06424325 -0.03095829 0.08102637 -0.06477093 -0.03112536 0.08116942 -0.06432855 -0.03191792 0.0813412 -0.06358802 -0.03219246 0.0810011 -0.063874 -0.03195559 0.08109533 -0.06377696 -0.03271722 0.08136171 -0.06309485 -0.03259217 0.08107864 -0.06339269 -0.03342354 0.08111757 -0.06291484 -0.03352487 0.08137083 -0.06270629 -0.03436988 0.08139532 -0.06239706 -0.03436172 0.08116638 -0.06251621 -0.03424501 0.08100801 -0.06281507 -0.03542351 0.08139508 -0.06213831 -0.03543585 0.08121466 -0.06221491 -0.03568726 0.08108204 -0.06230509 -0.03647494 0.0810104 -0.06236797 -0.03659188 0.08139044 -0.06201398 -0.03652626 0.08118534 -0.06211352 -0.0374661 0.08141714 -0.0620135 -0.03738546 0.08118832 -0.06210374 -0.03825825 0.08104526 -0.06235837 -0.03835922 0.08137083 -0.06211102 -0.03849494 0.08115768 -0.06225079 -0.03937667 0.08100026 -0.06274336 -0.03948378 0.08138269 -0.06235086 -0.03918403 0.08122497 -0.06234741 -0.03968739 0.08105021 -0.0626825 -0.04031926 0.08122307 -0.06271386 -0.04047971 0.08139806 -0.06270384 -0.04039621 0.08109229 -0.06288236 -0.04129594 0.08136004 -0.06310242 -0.0410422 0.08101254 -0.06337308 -0.04121959 0.08112788 -0.06322658 -0.04229521 0.08139014 -0.06372278 -0.04185843 0.08107304 -0.06369131 -0.0420196 0.08124619 -0.06360512 -0.04236245 0.08101022 -0.06422299 -0.04290229 0.08119297 -0.0643258 -0.04313671 0.08141827 -0.06441849 -0.04310584 0.08107775 -0.06469285 -0.04377132 0.08143216 -0.06507146 -0.04365861 0.08122682 -0.0650475 -0.04442101 0.08136653 -0.06591516 -0.04408466 0.08112651 -0.06570333 -0.04376643 0.08100682 -0.06564855 -0.04470294 0.08120858 -0.0665028 -0.04502004 0.08141064 -0.06692087 -0.04484182 0.08105516 -0.06711822 -0.04453164 0.08100521 -0.06685006 -0.04514104 0.08123421 -0.06733226 -0.04545778 0.08139342 -0.06792354 -0.04542791 0.08118391 -0.068134 -0.04526776 0.08100682 -0.06850898 -0.04582536 0.08138889 -0.06923466 -0.04573464 0.08126384 -0.06906342 -0.04557961 0.08109438 -0.06902289 -0.04578495 0.0811572 -0.06975024 -0.04597449 0.0814079 -0.0703572 -0.04568129 0.0810374 -0.07028657 -0.04589068 0.08119302 -0.07043403 -0.04598438 0.08134436 -0.07122975 -0.0458042 0.08110278 -0.0714364 -0.0459215 0.08138281 -0.07214093 -0.04554009 0.08100128 -0.07209408 -0.04582643 0.08122307 -0.07233512 -0.04564195 0.08105355 -0.07228928 -0.04576134 0.0813868 -0.07303559 -0.04557955 0.08113956 -0.07321071 -0.04552543 0.0813716 -0.0738601 -0.0452156 0.08102756 -0.07383197 -0.04520511 0.0811845 -0.07444667 -0.04520195 0.08138471 -0.07469159 -0.04483479 0.08111274 -0.07508766 -0.04479789 0.0813868 -0.07548314 -0.04453814 0.08100861 -0.07523047 -0.04440581 0.08134114 -0.07609492 -0.04407405 0.08115708 -0.0763691 -0.04371893 0.08137524 -0.07697737 -0.04266297 0.08100634 -0.07751727 -0.04354846 0.08103656 -0.07674014 -0.04321569 0.08113443 -0.0773071 -0.04310208 0.08137106 -0.077605 -0.04265236 0.08116984 -0.07785356 -0.04244476 0.08139818 -0.07816159 -0.04208225 0.08121734 -0.07832962 -0.04155439 0.08109515 -0.07854157 -0.04169869 0.08132916 -0.07865464 -0.04127746 0.08141928 -0.07891708 -0.04098993 0.08100646 -0.07865321 -0.04051017 0.08142101 -0.07928615 -0.04087096 0.08123606 -0.07904827 -0.040192 0.08108711 -0.07919651 -0.03991079 0.08126646 -0.07946747 -0.03902053 0.08100759 -0.07939821 -0.03947693 0.08141553 -0.07965546 -0.03906714 0.08113974 -0.07961344 -0.03874903 0.08133149 -0.07980996 -0.03806102 0.08119589 -0.07984781 -0.03760975 0.08139264 -0.0799793 -0.03786361 0.08104145 -0.07966697 -0.03682816 0.08112198 -0.07984519 -0.03653365 0.08138453 -0.07998234 -0.03693974 0.08100795 -0.07962769 -0.03607082 0.08124166 -0.07989019 -0.03537267 0.08139491 -0.07985198 -0.035465 0.08119457 -0.07977336 -0.03561794 0.08104103 -0.07960516 -0.03420466 0.0810045 -0.07915693 -0.03454077 0.08112907 -0.07950139 -0.03433108 0.08137089 -0.0795871 -0.03370183 0.08133125 -0.07935434 -0.03310304 0.08136105 -0.07910209 -0.03353089 0.08111643 -0.07912093 -0.03270441 0.08117544 -0.078781 -0.03245776 0.08105546 -0.07847875 -0.03230166 0.08139038 -0.07867079 -0.03214442 0.08100193 -0.0780887 -0.03181976 0.08119857 -0.07825171 -0.03134888 0.08138042 -0.07800251 -0.03129041 0.08115148 -0.07778185 -0.03119403 0.08103859 -0.07749336 -0.03056299 0.08139526 -0.07728427 -0.03061842 0.08118236 -0.07719731 -0.02996665 0.08136814 -0.07660228 -0.03016114 0.08100491 -0.07624423 -0.03023546 0.08110749 -0.07666665 -0.02975565 0.08110076 -0.07603883 -0.02934354 0.08139026 -0.07573068 -0.02914649 0.08121556 -0.07524502 -0.02878189 0.08139938 -0.07466042 -0.02904027 0.08105373 -0.07461935 -0.02902787 0.08100557 -0.07423806 -0.02866804 0.08120536 -0.07416933 -0.02846044 0.08140838 -0.07383424 -0.0284605 0.08114993 -0.0734117 -0.02852278 0.08099997 -0.07226574 -0.0282275 0.08140385 -0.07299762 -0.02847951 0.08103531 -0.07280111 -0.02822947 0.08119684 -0.07254922 -0.02807146 0.08137631 -0.07207608 -0.02810442 0.08121722 -0.0716331 -0.02827835 0.08104854 -0.07154363 -0.02801096 0.08563339 -0.07122415 -0.02807885 0.08560067 -0.07216185 -0.02828645 0.0856074 -0.07325661 -0.02862107 0.08561336 -0.07427096 -0.02900052 0.08558285 -0.07512098 -0.02944767 0.08561992 -0.07588368 -0.03006666 0.08559465 -0.07674103 -0.03156179 0.08563488 -0.07815867 -0.03210127 0.08563721 -0.07854193 -0.03269171 0.08556908 -0.0789017 -0.03349035 0.08559036 -0.07928502 -0.03418576 0.08566647 -0.0795356 -0.03503584 0.08563637 -0.07977652 -0.03611284 0.08558607 -0.07995438 -0.03718858 0.08560866 -0.07999807 -0.03835862 0.08560645 -0.07989251 -0.03942644 0.08559364 -0.07966881 -0.04048788 0.08556127 -0.07929724 -0.04128831 0.08565735 -0.07889574 -0.04191225 0.08557415 -0.07854586 -0.04279851 0.08557164 -0.07788258 -0.04345476 0.08561629 -0.07726365 -0.04403889 0.0855723 -0.0766077 -0.04455608 0.08563178 -0.0758742 -0.04510033 0.08559107 -0.07492786 -0.04561239 0.0856046 -0.07361412 -0.04585242 0.08565682 -0.07254993 -0.04597324 0.08558142 -0.07167673 -0.04599559 0.08558845 -0.07079583 -0.04589092 0.08563494 -0.06963145 -0.04565817 0.08559775 -0.06855469 -0.04536586 0.08560532 -0.06769281 -0.04501718 0.08561146 -0.06692147 -0.04444164 0.08566045 -0.06595814 -0.04401218 0.08560174 -0.06536418 -0.04326885 0.0856322 -0.06454658 -0.04224097 0.08559447 -0.06368106 -0.04129558 0.08563446 -0.06310105 -0.04029256 0.08558082 -0.06262022 -0.03896313 0.08560401 -0.06221574 -0.03787416 0.08558177 -0.0620439 -0.03699076 0.08560949 -0.06200462 -0.03611356 0.08565068 -0.06205546 -0.03524267 0.08561199 -0.06217837 -0.03430491 0.08564776 -0.06242334 -0.03349745 0.08560955 -0.06271457 -0.03271621 0.08561134 -0.0630905 -0.03192186 0.08566439 -0.0635873 -0.03130263 0.08565962 -0.06405365 -0.03067398 0.08559387 -0.06459552 -0.02998715 0.08560138 -0.06536513 -0.02934134 0.08561325 -0.06627321 -0.02879655 0.08560585 -0.06730824 -0.0284624 0.08558696 -0.06815749 -0.02817499 0.08557355 -0.06921339 -0.02803146 0.08560138 -0.07029473 -0.02816897 0.08587974 -0.0713256 -0.0280888 0.08579218 -0.07070726 -0.0281406 0.08577781 -0.0720703 -0.0283423 0.08596122 -0.07202452 -0.02827453 0.08572357 -0.0730108 -0.02842819 0.08591365 -0.07297188 -0.02866238 0.0859974 -0.07307392 -0.02864843 0.08581024 -0.07409077 -0.02873438 0.08592766 -0.07393723 -0.02917498 0.08599865 -0.07453787 -0.02904295 0.08575838 -0.07506382 -0.02920877 0.08594381 -0.07498431 -0.02955281 0.08586913 -0.07578527 -0.03003531 0.08597278 -0.07619208 -0.03004133 0.08578521 -0.07657998 -0.03061026 0.08588194 -0.0771054 -0.03075164 0.08564102 -0.07746732 -0.03142178 0.0859943 -0.07759433 -0.0313068 0.0858311 -0.0778225 -0.03162389 0.08595496 -0.07786941 -0.03202569 0.08584415 -0.07834362 -0.03267908 0.08590781 -0.07867676 -0.0331034 0.08578068 -0.0790286 -0.03346586 0.08599638 -0.07884305 -0.03383761 0.08592361 -0.07919615 -0.03489691 0.08598649 -0.07940459 -0.03498321 0.08584797 -0.07963776 -0.03582209 0.08571642 -0.0798825 -0.03588795 0.08592385 -0.07971113 -0.03671962 0.08589369 -0.07982468 -0.03748947 0.08599811 -0.07959538 -0.03745937 0.08578824 -0.07990688 -0.03814816 0.08592951 -0.07969498 -0.038589 0.08580422 -0.07976675 -0.03927481 0.08595407 -0.07942509 -0.03964889 0.08578467 -0.07951742 -0.04025554 0.08590281 -0.07918328 -0.04047316 0.08599078 -0.07890588 -0.04064077 0.0857411 -0.07917505 -0.04135251 0.08590567 -0.07865494 -0.0420224 0.08579176 -0.07836651 -0.04217487 0.08598804 -0.07793903 -0.04269003 0.0857743 -0.07788145 -0.04326224 0.08599895 -0.07685869 -0.04322743 0.0858311 -0.0773403 -0.04310411 0.08593517 -0.07728451 -0.04398959 0.08580374 -0.07652783 -0.04392147 0.0859515 -0.07632106 -0.04444897 0.08583241 -0.07583355 -0.04465341 0.08599412 -0.07495832 -0.04474717 0.08591634 -0.07515597 -0.04496133 0.08575659 -0.07506 -0.04532778 0.08570897 -0.07430297 -0.04523223 0.08587276 -0.07423251 -0.04538601 0.08593851 -0.07351291 -0.0454306 0.08599197 -0.07286441 -0.04557919 0.08580237 -0.07338249 -0.04572862 0.08588343 -0.07235163 -0.04592376 0.08576244 -0.07147175 -0.04563003 0.08598875 -0.07144695 -0.04581022 0.08590686 -0.07085084 -0.04591089 0.08575677 -0.07031977 -0.04567968 0.08592182 -0.06963789 -0.04564887 0.08582019 -0.06892758 -0.04545438 0.08599388 -0.06926542 -0.04540938 0.08585852 -0.06818825 -0.04490846 0.08599507 -0.06759315 -0.04511868 0.08580756 -0.06735312 -0.04490685 0.08593732 -0.06723958 -0.04463648 0.08581542 -0.06642073 -0.04410439 0.08599251 -0.06608766 -0.04371571 0.08587908 -0.06524217 -0.04313665 0.08582109 -0.06455808 -0.04285073 0.08598947 -0.06464606 -0.04238963 0.08578574 -0.06389516 -0.04232227 0.08593827 -0.06405121 -0.04144519 0.08599239 -0.06361162 -0.04149979 0.08581024 -0.06331616 -0.04100281 0.08592349 -0.06317561 -0.04045414 0.08578962 -0.06277948 -0.03941148 0.08599048 -0.06269413 -0.03943979 0.08573853 -0.06238806 -0.03934425 0.08587288 -0.06247103 -0.03799879 0.08599346 -0.06243634 -0.03806692 0.08576577 -0.06213015 -0.03831243 0.08588051 -0.06226623 -0.03714889 0.08585357 -0.06213194 -0.03678929 0.08596485 -0.0623067 -0.03585833 0.08599334 -0.06245207 -0.03609472 0.08587521 -0.06220674 -0.03492558 0.08577525 -0.06231141 -0.03470963 0.08592289 -0.06251215 -0.03412759 0.08599263 -0.06286883 -0.03356617 0.08580601 -0.06278657 -0.03340953 0.0859363 -0.06301319 -0.03272604 0.08582168 -0.06320184 -0.03199481 0.08599686 -0.06397658 -0.03194051 0.08591264 -0.06379449 -0.03077179 0.08582091 -0.06464648 -0.03079628 0.08596479 -0.06488955 -0.03000324 0.08581817 -0.0654999 -0.029738 0.08599644 -0.06638425 -0.02974855 0.08594202 -0.06610697 -0.02936875 0.08577287 -0.06635946 -0.02916747 0.08589667 -0.0669561 -0.02874416 0.08574682 -0.06755459 -0.02885305 0.08599203 -0.0681383 -0.02872532 0.08589684 -0.06796199 -0.02840441 0.085774 -0.06859314 -0.0284022 0.08589679 -0.06906831 -0.02817183 0.08578127 -0.0696845 -0.02839821 0.08599555 -0.07070332 -0.02832752 0.08595567 -0.07002031 -0.03681582 0.07319229 0.04275274 -0.0367099 0.07307064 0.04281407 -0.03625231 0.0731697 0.0426861 -0.03694933 0.07300835 0.04294097 -0.03582394 0.07300359 0.04278916 -0.03597098 0.07305914 0.0426985 -0.03581398 0.07317316 0.04256671 -0.03537267 0.07317352 0.04239016 -0.03532648 0.0730592 0.04245281 -0.03477358 0.07306027 0.04213047 -0.03496378 0.07318502 0.04215663 -0.03468942 0.07300376 0.04221707 -0.03458815 0.07317519 0.04188454 -0.03423416 0.07305991 0.0416581 -0.03422135 0.0731731 0.04153615 -0.03389924 0.07301247 0.04138636 -0.03389501 0.07318884 0.04111313 -0.03375715 0.07309788 0.040986 -0.03365254 0.07318741 0.0407077 -0.03350377 0.07302403 0.04070502 -0.03348308 0.07316565 0.04033303 -0.03325027 0.07306104 0.03983408 -0.03331094 0.07317543 0.03974175 -0.03308939 0.07300567 0.03968298 -0.03324145 0.07315087 0.03920567 -0.03307354 0.07300806 0.0386939 -0.03325396 0.07319676 0.03871864 -0.03319221 0.07307261 0.03869014 -0.03335535 0.07319122 0.03807473 -0.03329604 0.07310473 0.0381686 -0.03325051 0.07302206 0.0379467 -0.0334987 0.0731399 0.03760373 -0.03350609 0.07300817 0.03720206 -0.03374058 0.07317876 0.03712683 -0.03387439 0.07314234 0.03689259 -0.03400361 0.0730611 0.03660929 -0.03431338 0.0731855 0.03636729 -0.03405398 0.07300442 0.03636074 -0.03439319 0.0730623 0.0361917 -0.03475826 0.07316762 0.03598028 -0.03479349 0.073004 0.03571575 -0.03500479 0.07306188 0.03572058 -0.03512197 0.07318502 0.03574669 -0.0355404 0.07318508 0.03553664 -0.03589862 0.07300382 0.03518456 -0.03577798 0.07305985 0.03536176 -0.03598004 0.07316774 0.03538119 -0.03653436 0.073197 0.03526967 -0.03652584 0.07309621 0.03522342 -0.03660857 0.07302838 0.03512901 -0.03718012 0.07316714 0.03524243 -0.03767734 0.07300394 0.03508597 -0.03739064 0.07306212 0.03518223 -0.03783529 0.07318854 0.03533339 -0.03813052 0.07305717 0.03533124 -0.03829234 0.07316792 0.03546935 -0.03870558 0.07300859 0.03546237 -0.03873986 0.07320082 0.0356698 -0.03876912 0.07305759 0.03559648 -0.03932064 0.07307195 0.03595972 -0.03926378 0.0731877 0.03600049 -0.03969156 0.07319205 0.03637844 -0.03992176 0.07300615 0.03634214 -0.03992837 0.0730682 0.03653603 -0.04016232 0.07320976 0.03696334 -0.04033428 0.073107 0.03718274 -0.0404219 0.07301795 0.0371201 -0.04050981 0.07317435 0.03765249 -0.04068154 0.07306551 0.03792762 -0.04063969 0.07318502 0.03807097 -0.04073601 0.07315367 0.03853166 -0.04084867 0.07300496 0.03804033 -0.04082369 0.07307165 0.03897368 -0.04075533 0.07319688 0.0390945 -0.04092645 0.07300382 0.03960865 -0.04068523 0.07319039 0.03974759 -0.04078739 0.07306212 0.03956884 -0.04067146 0.07307147 0.0400542 -0.04050177 0.07317417 0.04037022 -0.04040896 0.07307171 0.04073315 -0.04047966 0.07300299 0.04089772 -0.04025709 0.07316631 0.04088228 -0.03999418 0.07318502 0.04126828 -0.0400061 0.07306236 0.04137551 -0.03970462 0.07314902 0.04162144 -0.03968942 0.07301032 0.04185944 -0.03930681 0.07313764 0.04198139 -0.03896504 0.07318711 0.04220324 -0.03891879 0.07303994 0.0423448 -0.03850376 0.07318603 0.04244518 -0.0382781 0.07300394 0.04275006 -0.03827583 0.07306414 0.04261487 -0.0378406 0.0731734 0.04266816 -0.03755956 0.07304215 0.04282319 -0.03727775 0.07317173 0.04274863 -0.03697615 0.09379976 0.03524428 -0.03643923 0.09380304 0.03528547 -0.03591388 0.0938518 0.03539311 -0.03544569 0.09379959 0.03557753 -0.03488743 0.09385126 0.03588151 -0.03451603 0.0938149 0.03618204 -0.03411245 0.09381341 0.03659063 -0.03379285 0.09383141 0.03703814 -0.03354179 0.09383744 0.03751122 -0.03325277 0.09384083 0.03861737 -0.03324288 0.09385854 0.03929787 -0.03334945 0.09382939 0.0399152 -0.03357768 0.09383773 0.04056513 -0.03389227 0.09381175 0.04111754 -0.0343163 0.09381514 0.04163104 -0.03473097 0.09381335 0.04199576 -0.03512024 0.09383183 0.04225599 -0.0355345 0.09382504 0.0424627 -0.03618329 0.09380775 0.04266977 -0.03681099 0.09380251 0.04275172 -0.03739362 0.09383231 0.04274058 -0.03783315 0.09383183 0.04266613 -0.03839045 0.09381568 0.04249393 -0.03913009 0.09381026 0.04210287 -0.03969156 0.09380793 0.0416215 -0.03997159 0.0938639 0.04131931 -0.04027003 0.09381973 0.04085516 -0.04047966 0.09382754 0.04042255 -0.0406292 0.09385317 0.040008 -0.04072767 0.09380739 0.03947001 -0.04075479 0.09380495 0.03881114 -0.04065066 0.09384077 0.03807371 -0.04046046 0.09385097 0.03751105 -0.04027509 0.09382957 0.03715431 -0.03999489 0.09381002 0.03672617 -0.03960448 0.09382861 0.03628873 -0.03926718 0.09379726 0.03600555 -0.03889071 0.09382641 0.03575152 -0.03834676 0.09381943 0.03548824 -0.0376383 0.09383487 0.03529024 -0.03648686 0.09389704 0.03523206 -0.03707689 0.09399139 0.03506803 -0.03622835 0.09397935 0.03517413 -0.03528475 0.09399628 0.03541541 -0.03543019 0.0939368 0.03551191 -0.03491955 0.09395289 0.03575205 -0.03434282 0.09389644 0.03628337 -0.03439402 0.09398102 0.03609734 -0.03387063 0.09399038 0.03663074 -0.0338236 0.09393829 0.0368489 -0.03339266 0.0939849 0.03751218 -0.03337347 0.09383481 0.03799957 -0.03314602 0.09399026 0.0382722 -0.03321373 0.09394496 0.03836637 -0.03306788 0.09399348 0.03935635 -0.03318578 0.09395587 0.03959065 -0.0333957 0.09390425 0.04021072 -0.03336966 0.09399348 0.04053658 -0.03363913 0.09395903 0.04091697 -0.03396368 0.09390765 0.04130101 -0.0338574 0.09399628 0.04139912 -0.03421926 0.09393787 0.04163914 -0.03465056 0.09399628 0.04220658 -0.03470343 0.09394401 0.04207283 -0.03529888 0.09394747 0.04245555 -0.03586083 0.09398955 0.0427609 -0.03571122 0.09388947 0.0425657 -0.03632891 0.09392756 0.04276329 -0.03716671 0.09399676 0.0429666 -0.03695613 0.09392642 0.04281675 -0.03766882 0.09394925 0.04279291 -0.03847086 0.09390044 0.04251062 -0.03846597 0.09398859 0.04263901 -0.03938746 0.09399509 0.04215693 -0.03901767 0.09392505 0.04223829 -0.03952282 0.0939275 0.04187071 -0.04002481 0.09399074 0.04149901 -0.04028892 0.09395867 0.04100126 -0.04057145 0.09394651 0.04043835 -0.04074007 0.09399563 0.04029363 -0.04085576 0.09398037 0.03960216 -0.04077827 0.0939098 0.0394715 -0.04094618 0.09399485 0.03902763 -0.04081845 0.09392797 0.03881263 -0.04083561 0.09398204 0.03827738 -0.0406416 0.09393882 0.03779035 -0.0406816 0.0939967 0.03754705 -0.04032748 0.09397453 0.03699731 -0.03999704 0.09393018 0.03662687 -0.0400331 0.09399652 0.03646111 -0.03947818 0.09396803 0.03601807 -0.03904539 0.09393066 0.03576904 -0.03893429 0.09399557 0.03554856 -0.03844308 0.09392476 0.03546768 -0.03803402 0.09389692 0.03534775 -0.03807169 0.09399056 0.0352289 -0.03749316 0.09395271 0.03517538 -0.03718113 0.09388136 0.03521883 -0.04052412 0.09399551 0.04518723 -0.0414766 0.07475 0.03840374 -0.04150426 0.078 0.03911232 -0.0414105 0.078 0.03802907 -0.04105877 0.07475 0.03700584 -0.04097771 0.078 0.03687226 -0.04032969 0.078 0.03595656 -0.04028373 0.07475 0.03590703 -0.03919774 0.078 0.03503978 -0.0392301 0.07475 0.03506594 -0.03786057 0.07475 0.03456658 -0.03759765 0.078 0.03451746 -0.03640228 0.07475 0.03451746 -0.03624993 0.078 0.03455173 -0.0351755 0.078 0.03487437 -0.03480219 0.07475 0.03503978 -0.03421396 0.078 0.03545212 -0.03367024 0.07475 0.03595656 -0.0332151 0.078 0.03651243 -0.03302228 0.07475 0.03687226 -0.03260499 0.078 0.037961 -0.03254199 0.07475 0.0382139 -0.032494 0.078 0.03930264 -0.03258192 0.07475 0.04000836 -0.03274953 0.078 0.04051101 -0.03316849 0.07475 0.04138094 -0.03337377 0.078 0.04170203 -0.03377455 0.07475 0.04214608 -0.0345453 0.078 0.0428006 -0.03461533 0.07475 0.04283523 -0.03585177 0.07475 0.04336774 -0.03559231 0.078 0.04327791 -0.03666222 0.078 0.04350745 -0.03707873 0.07475 0.04351031 -0.03797084 0.078 0.04340529 -0.0381124 0.07475 0.04336863 -0.0389266 0.078 0.04307425 -0.03919047 0.07475 0.04294931 -0.03987604 0.078 0.04248189 -0.04041963 0.07475 0.04196965 -0.04084002 0.078 0.04138833 -0.04115545 0.07475 0.04075163 -0.04137301 0.078 0.0401135 -0.04146218 0.07475 0.03967255 -0.03251487 0.08899998 0.03948271 -0.03249567 0.09224998 0.03888761 -0.03258943 0.09224998 0.03997087 -0.03277266 0.08899998 0.04057449 -0.03302228 0.09224998 0.04112768 -0.03341686 0.08899998 0.04175883 -0.03374272 0.09224998 0.0421282 -0.03457653 0.08899998 0.04281795 -0.03490519 0.09224998 0.04300773 -0.03613799 0.08899998 0.04344636 -0.03629237 0.09224998 0.04346036 -0.03786194 0.09224998 0.04344636 -0.03770756 0.08899998 0.04346036 -0.03888595 0.08899998 0.04309785 -0.03922623 0.09224998 0.04292339 -0.04007899 0.08899998 0.04231834 -0.04037183 0.09224998 0.04202389 -0.04102045 0.08899998 0.04106116 -0.04115819 0.09224998 0.04075282 -0.04140079 0.08899998 0.03997182 -0.0414372 0.09224998 0.03978246 -0.04151087 0.08899998 0.03896617 -0.04150694 0.09224998 0.03877508 -0.04131931 0.08899998 0.03766769 -0.04132962 0.09224998 0.03774875 -0.04080259 0.09224998 0.03654396 -0.04074609 0.08899998 0.03648674 -0.03984725 0.08899998 0.03548669 -0.03989779 0.09224998 0.03554666 -0.03895866 0.09224998 0.03493267 -0.03854519 0.08899998 0.03475439 -0.03767335 0.09224998 0.03453242 -0.03744858 0.08899998 0.03451663 -0.03632658 0.08899998 0.03453242 -0.03632718 0.09224998 0.034536 -0.03527867 0.09224998 0.0348348 -0.03480219 0.08899998 0.03503978 -0.03427201 0.09224998 0.03539848 -0.03353738 0.08899998 0.03609448 -0.03324359 0.09224998 0.03648209 -0.0328564 0.08899998 0.03721666 -0.03264331 0.09224998 0.03781044 -0.03253781 0.08899998 0.03832739 -0.02952849 0.09362131 0.0384311 -0.02950668 0.09360057 0.03920239 -0.02960264 0.09381383 0.03916889 -0.02962732 0.09381711 0.03846144 -0.02981197 0.09394305 0.03801161 -0.02985596 0.09399038 0.03907561 -0.02964222 0.09359818 0.0375452 -0.02969473 0.093764 0.03763949 -0.02988386 0.09375947 0.03682285 -0.03029149 0.09399914 0.03676551 -0.02996236 0.09359169 0.03640353 -0.03013139 0.09395885 0.03677028 -0.03024321 0.09384036 0.03602916 -0.030317 0.09359198 0.03560215 -0.03056186 0.09379929 0.03531861 -0.03086322 0.09397083 0.03524768 -0.03081685 0.09359806 0.03475534 -0.03100347 0.09380525 0.0346558 -0.03172314 0.09399759 0.03425383 -0.03137552 0.09361737 0.03404808 -0.03151011 0.09388393 0.03412693 -0.03189659 0.09367048 0.03352636 -0.03233265 0.09393155 0.0334227 -0.03260499 0.09360498 0.03292363 -0.03252124 0.09382575 0.03312522 -0.03315186 0.09399753 0.03305613 -0.03313404 0.09375828 0.03264743 -0.0334447 0.09358847 0.03239911 -0.03330284 0.09393978 0.03275996 -0.03389698 0.09386008 0.03231942 -0.03413558 0.09364515 0.03208047 -0.03459674 0.09399223 0.03228741 -0.03479486 0.09360814 0.03183668 -0.03509455 0.09382754 0.03185606 -0.03553354 0.0936287 0.03165298 -0.03542011 0.09398603 0.03201961 -0.0362901 0.09364914 0.03154551 -0.03601014 0.09387665 0.03172826 -0.0367527 0.09390676 0.03169888 -0.03699171 0.09365069 0.03151208 -0.03689157 0.09399729 0.03190582 -0.0377596 0.09383445 0.03165227 -0.03756588 0.09362316 0.03153091 -0.03829729 0.09361314 0.03161495 -0.03801131 0.0939241 0.03179073 -0.03805834 0.09398752 0.03194439 -0.03890973 0.09385651 0.03188252 -0.03920966 0.09359776 0.03183662 -0.03973436 0.09379798 0.03210681 -0.03945684 0.09399467 0.0323252 -0.04009252 0.09358787 0.03216564 -0.04026186 0.09391975 0.03247982 -0.04055976 0.09375292 0.03247004 -0.04094928 0.09363526 0.03263461 -0.04072326 0.09396016 0.03282338 -0.04138052 0.09383165 0.03304994 -0.04185688 0.09399521 0.03378289 -0.04151421 0.0936017 0.03301584 -0.04210901 0.09362643 0.03351986 -0.04188722 0.09388136 0.03352361 -0.04260361 0.09364813 0.03403258 -0.04272663 0.0938884 0.03441739 -0.04311877 0.09366708 0.03468853 -0.0430271 0.09399574 0.03523063 -0.04349696 0.09356492 0.03525352 -0.04344272 0.09377741 0.03530734 -0.04356598 0.09392112 0.03582906 -0.04384768 0.09360128 0.03595072 -0.04387742 0.09372818 0.03612178 -0.0441187 0.09359079 0.03664809 -0.04389524 0.0939899 0.03715789 -0.04408341 0.09385186 0.03695559 -0.04430949 0.09359627 0.03733581 -0.04438239 0.09376829 0.03810769 -0.04422277 0.09389787 0.03783881 -0.04444324 0.09359127 0.03810274 -0.04449135 0.0936231 0.03885585 -0.04408192 0.09399622 0.03841537 -0.04422265 0.09396004 0.03902226 -0.04435735 0.09385466 0.03934347 -0.04447525 0.09360355 0.03955239 -0.04433459 0.09378916 0.04011517 -0.04395604 0.09399491 0.04049628 -0.04438251 0.09359776 0.04030168 -0.04421263 0.09389668 0.04020667 -0.0442143 0.09363615 0.04100894 -0.04404509 0.09387552 0.04108476 -0.04403501 0.09358501 0.04160487 -0.04392939 0.09376877 0.04167717 -0.04355585 0.09399223 0.04179698 -0.04357564 0.09357917 0.04261183 -0.04356223 0.09393459 0.04211568 -0.04356288 0.09373712 0.04252415 -0.04329293 0.09385508 0.04282337 -0.04307967 0.09363186 0.04337692 -0.04291021 0.0939368 0.04321444 -0.04262626 0.09399676 0.04330855 -0.04272735 0.09380078 0.04370611 -0.04260492 0.09358191 0.04398041 -0.04230898 0.09376829 0.04419684 -0.04195398 0.09360975 0.04462873 -0.04221785 0.0939098 0.04409468 -0.04180771 0.09398871 0.0442804 -0.04154694 0.09386801 0.04478424 -0.04121756 0.0936203 0.04519385 -0.04065924 0.09385132 0.04540097 -0.04043686 0.09359443 0.04566657 -0.0399366 0.09379506 0.0458064 -0.03954154 0.09364628 0.04604423 -0.03959947 0.0939666 0.04571849 -0.039182 0.09389084 0.04598826 -0.03885668 0.09366154 0.04625195 -0.03807729 0.09384137 0.04630351 -0.03791368 0.09361612 0.04644185 -0.03828746 0.09397363 0.04606133 -0.03691911 0.09399998 0.04607844 -0.0370323 0.09364706 0.04648822 -0.03727179 0.09394896 0.04622715 -0.03665995 0.09386432 0.04634916 -0.0362972 0.09365367 0.04645437 -0.03581547 0.09395509 0.04612666 -0.03568148 0.09381014 0.04628318 -0.03553074 0.093625 0.04634529 -0.03492575 0.09356844 0.04621094 -0.03484469 0.09381848 0.04607969 -0.03479814 0.09399002 0.0457893 -0.03408604 0.09363412 0.04590076 -0.03415894 0.09385442 0.04579073 -0.03342628 0.09360468 0.04558873 -0.0336489 0.09389054 0.04552185 -0.03365844 0.09399545 0.045264 -0.03292924 0.09376847 0.04521673 -0.03278338 0.09359103 0.04519927 -0.03295028 0.09392118 0.04505181 -0.03217226 0.09364175 0.04472571 -0.03216654 0.09399461 0.04421687 -0.03232049 0.0938887 0.04464 -0.03162777 0.09362804 0.04422199 -0.03177398 0.09387987 0.04415464 -0.03116708 0.09367203 0.04368835 -0.03125154 0.09388339 0.04354435 -0.0310198 0.09396564 0.04301756 -0.03069943 0.09360957 0.04305905 -0.0306015 0.09381943 0.04272198 -0.03083938 0.09399688 0.0425328 -0.0303204 0.09360462 0.04240083 -0.03047019 0.09391623 0.04223668 -0.02994763 0.09359931 0.04155266 -0.03008234 0.09377413 0.04170525 -0.03018969 0.09394079 0.04148268 -0.02969598 0.09360074 0.0406866 -0.02982765 0.09381008 0.04084587 -0.03009879 0.09399759 0.04062753 -0.02986234 0.09394437 0.040259 -0.02971321 0.09384626 0.0400927 -0.02957099 0.09365797 0.03992533 -0.02950716 0.0926482 0.03879314 -0.02955943 0.0926252 0.0381146 -0.029688 0.09267747 0.03733515 -0.02990162 0.09264951 0.03659081 -0.03017735 0.09266066 0.03589135 -0.03049254 0.09261751 0.03528898 -0.03092706 0.09264951 0.03460562 -0.03138947 0.09268486 0.03402322 -0.03192055 0.09261184 0.03349512 -0.03247857 0.09267014 0.03301805 -0.03394436 0.09265178 0.03215038 -0.03478294 0.09261685 0.03184443 -0.03571534 0.09263616 0.03161275 -0.03739148 0.0926488 0.03151428 -0.03811311 0.09265071 0.03158688 -0.03901344 0.09264504 0.03177595 -0.03990411 0.0926038 0.03209722 -0.04055756 0.09264713 0.03240227 -0.0415427 0.09269696 0.03301984 -0.04237854 0.09264886 0.03377884 -0.04294556 0.09262543 0.03443306 -0.04339134 0.092628 0.03508484 -0.04381752 0.09263676 0.03588789 -0.04404485 0.09259164 0.03646171 -0.04430228 0.09265863 0.03730207 -0.04446285 0.09264647 0.03825318 -0.04449439 0.09265768 0.03919917 -0.04444217 0.09267693 0.03992021 -0.04426401 0.09264165 0.04086434 -0.04398173 0.092601 0.04170644 -0.04284244 0.09264016 0.04369437 -0.04226964 0.09267461 0.04434019 -0.04164397 0.09260076 0.04487597 -0.04070776 0.09264355 0.04551827 -0.03990554 0.09266984 0.0459125 -0.03920298 0.09268164 0.0461688 -0.03851175 0.09266936 0.0463441 -0.03774142 0.09257405 0.04644554 -0.03681707 0.09261792 0.04649293 -0.03589665 0.09262192 0.0464105 -0.03518617 0.09263616 0.0462715 -0.03452879 0.09257709 0.04606395 -0.03356021 0.09267443 0.04566794 -0.03277999 0.09266257 0.04519701 -0.03217893 0.09264153 0.04473894 -0.03162384 0.09266853 0.04422694 -0.03112387 0.09262555 0.0436483 -0.03006809 0.09265476 0.04186451 -0.02978324 0.09266519 0.04103463 -0.02962595 0.09260404 0.04030501 -0.0295208 0.09267234 0.03954201 -0.0295751 0.09248274 0.03938293 -0.02978217 0.09228837 0.03908872 -0.02978157 0.09235554 0.0402379 -0.02994525 0.09225875 0.0400086 -0.02986365 0.09244263 0.04097878 -0.03035503 0.09225332 0.04152983 -0.03016489 0.09233987 0.04155719 -0.03009432 0.09247577 0.0417245 -0.03045105 0.09258407 0.04262721 -0.03050643 0.09234273 0.04235225 -0.03074371 0.09257596 0.04310208 -0.03094875 0.09239828 0.04319787 -0.03123563 0.09228253 0.04331409 -0.0315479 0.0924983 0.04406416 -0.03165727 0.09225296 0.04366397 -0.03174358 0.09230989 0.04401308 -0.03200685 0.09241682 0.04443514 -0.03271687 0.09247976 0.04507046 -0.03263753 0.09235036 0.04486864 -0.03320991 0.09225434 0.04501873 -0.03361904 0.09251952 0.04564166 -0.0334143 0.0923385 0.04535651 -0.03451174 0.0924009 0.04594475 -0.03450125 0.09225779 0.0456838 -0.03546804 0.09237748 0.04618746 -0.03585463 0.0922538 0.04601228 -0.03626346 0.09235662 0.04628849 -0.03705346 0.09237033 0.04633945 -0.03735125 0.0922653 0.0461319 -0.03813147 0.09231173 0.04617261 -0.03839862 0.09247702 0.0462957 -0.03906738 0.09250569 0.04615318 -0.03944998 0.09233069 0.04586482 -0.03913044 0.0922507 0.04575413 -0.03987723 0.09248077 0.0458495 -0.04023426 0.0922808 0.04542106 -0.04057717 0.09241139 0.04545873 -0.04089486 0.09251797 0.04535108 -0.04129862 0.09230387 0.04482877 -0.0415945 0.09242892 0.04479658 -0.04142266 0.09225445 0.04455226 -0.04282921 0.09225058 0.04301273 -0.04228353 0.09242993 0.04417765 -0.04243433 0.0922901 0.04374742 -0.04289305 0.09243249 0.04347169 -0.04330438 0.09261018 0.04304403 -0.0433247 0.09233558 0.0426532 -0.04368644 0.09258252 0.04236233 -0.04353129 0.09228485 0.04203218 -0.04384416 0.09239977 0.04171562 -0.04387462 0.09225052 0.04069441 -0.04403167 0.09229701 0.04071033 -0.04415506 0.09245955 0.0409581 -0.04433262 0.09250432 0.04026859 -0.04423081 0.09233635 0.0399968 -0.04443222 0.09250289 0.03942155 -0.04410016 0.09225332 0.03913652 -0.04432219 0.09235578 0.03903889 -0.04442161 0.09250849 0.03842073 -0.04426777 0.09237736 0.0379548 -0.04406964 0.09226733 0.03789061 -0.04425114 0.09249007 0.03733187 -0.04392832 0.09228599 0.03700113 -0.0438885 0.0923646 0.03648722 -0.04339605 0.09225678 0.03584843 -0.04343813 0.0923649 0.03549879 -0.04360997 0.09253025 0.03554713 -0.04311382 0.09249037 0.03476226 -0.04286885 0.09228843 0.03480845 -0.04198223 0.09225064 0.0339663 -0.04266506 0.0923748 0.03433233 -0.04229527 0.09246653 0.03380393 -0.04210162 0.09229969 0.0338692 -0.04165947 0.0924592 0.03322154 -0.04126447 0.09231507 0.03311568 -0.0407828 0.09247595 0.03260308 -0.04047572 0.09225344 0.0328148 -0.04020196 0.09229642 0.03251796 -0.03984087 0.09238737 0.0322197 -0.039191 0.09245902 0.03191655 -0.03891652 0.09229552 0.03202736 -0.03823739 0.09242987 0.03170686 -0.03798079 0.0922572 0.03193467 -0.03719294 0.09244304 0.03159612 -0.0371595 0.09232062 0.03173089 -0.03657573 0.09259569 0.03152489 -0.03627794 0.0922563 0.03192567 -0.03590553 0.09235036 0.03176343 -0.03567522 0.09247332 0.031695 -0.03489977 0.0922935 0.03208452 -0.03459966 0.09244608 0.03199374 -0.03426498 0.09225016 0.03247898 -0.03400707 0.09234774 0.03233319 -0.03379237 0.09248566 0.03229701 -0.03318899 0.09262561 0.03254729 -0.03341317 0.09225898 0.03283065 -0.03314638 0.09240782 0.0327121 -0.03254729 0.09231841 0.03325551 -0.03252381 0.09247058 0.03307783 -0.03187286 0.09236699 0.03375077 -0.03168034 0.09225392 0.03427726 -0.03130614 0.09250265 0.03420382 -0.03110384 0.0923354 0.03470426 -0.03077661 0.09247237 0.03495365 -0.03065931 0.09227973 0.03560328 -0.03041654 0.0923767 0.03574794 -0.03018009 0.0925036 0.03601884 -0.02990239 0.09246653 0.03682208 -0.02996426 0.09233713 0.03706145 -0.03025144 0.09225445 0.0367729 -0.02966558 0.09249311 0.03775721 -0.02997535 0.09225255 0.03801196 -0.02968174 0.09236878 0.03839969 -0.02952069 0.07343167 0.03955245 -0.02952033 0.07333177 0.03883177 -0.02959424 0.07319974 0.03925418 -0.0298323 0.07302522 0.03958308 -0.02961409 0.07324266 0.03986328 -0.02962058 0.07339596 0.04031378 -0.02978146 0.07309585 0.04012215 -0.02982926 0.07316285 0.04074871 -0.02980172 0.07335364 0.04106616 -0.03016442 0.07303601 0.04127967 -0.0303424 0.07299995 0.04135537 -0.0300765 0.07342576 0.04189079 -0.03012305 0.07318592 0.04174154 -0.03035277 0.07324802 0.04234623 -0.0305044 0.07336479 0.0427308 -0.0306698 0.07304465 0.04249894 -0.0308755 0.0732001 0.04317712 -0.03092038 0.0734325 0.04339098 -0.03129148 0.0732184 0.04374849 -0.03139442 0.07340735 0.04397797 -0.03138893 0.07301306 0.04344367 -0.03205335 0.07340121 0.04463797 -0.0320121 0.07311654 0.04437702 -0.03196239 0.07325929 0.04447931 -0.03255122 0.07300627 0.04457938 -0.03268754 0.0731945 0.04502284 -0.03279054 0.07340568 0.0452032 -0.03349447 0.07308763 0.04540479 -0.03361982 0.07343089 0.04569876 -0.03341758 0.07325702 0.0455293 -0.03424245 0.07317608 0.04586476 -0.03399181 0.07300627 0.04544341 -0.03460001 0.07335245 0.04609549 -0.03493702 0.07304078 0.04591363 -0.03519034 0.07338684 0.04627233 -0.03547209 0.07310485 0.04616677 -0.03635883 0.07300299 0.0460847 -0.03586316 0.07340061 0.04640966 -0.03610074 0.07320106 0.04635602 -0.03679281 0.07338595 0.04649561 -0.03695476 0.07305598 0.04624545 -0.03691214 0.07321792 0.0464226 -0.03742486 0.07334524 0.04647344 -0.03773903 0.07314264 0.04632043 -0.03812098 0.07336783 0.04640716 -0.0387175 0.07306015 0.04605442 -0.03830671 0.07300126 0.04597824 -0.03861862 0.07316601 0.04620182 -0.03883409 0.07334882 0.04625946 -0.03957146 0.07339423 0.04604041 -0.03966587 0.0731821 0.045901 -0.04011726 0.07333993 0.04580873 -0.03984427 0.07303398 0.04561132 -0.04073959 0.0732479 0.04543524 -0.04069846 0.07300251 0.04504203 -0.04057973 0.07309007 0.04536223 -0.04104357 0.07340812 0.04531747 -0.04141551 0.07310098 0.04483491 -0.04171335 0.07333099 0.04481512 -0.04172772 0.07300722 0.04433524 -0.04207539 0.07324737 0.04443621 -0.04238539 0.07341039 0.04421603 -0.04230034 0.07304227 0.04389083 -0.04241693 0.07315039 0.04399907 -0.04294645 0.07337975 0.04356569 -0.04307121 0.07326489 0.04331594 -0.04318714 0.07313978 0.04298675 -0.04285705 0.07300931 0.04308021 -0.04347193 0.0733298 0.04275768 -0.04344636 0.07305318 0.04229491 -0.04383206 0.07336682 0.04207247 -0.0437256 0.0731638 0.0420286 -0.04364144 0.07300436 0.04151272 -0.04415994 0.07340168 0.04123312 -0.04392373 0.07312208 0.04144704 -0.04418492 0.07319891 0.04081851 -0.04438799 0.07334601 0.04022026 -0.04406428 0.07304686 0.04051345 -0.04437327 0.07317227 0.03955394 -0.04410314 0.07300323 0.03919655 -0.04447752 0.07339757 0.03952229 -0.04423075 0.07305061 0.03936403 -0.0444929 0.07340323 0.03866624 -0.04443264 0.07328099 0.03841769 -0.04426568 0.07308399 0.03835147 -0.04435461 0.07339441 0.03753066 -0.04425257 0.07324582 0.03730928 -0.04419952 0.07314062 0.03748357 -0.04389077 0.07300263 0.0373432 -0.04390871 0.07303816 0.03692996 -0.04404312 0.07336485 0.03644305 -0.04383575 0.07315063 0.03623163 -0.04381573 0.07339698 0.03588032 -0.04349523 0.07339638 0.03525888 -0.04325133 0.0730099 0.03553408 -0.04339301 0.07318413 0.03527945 -0.04300272 0.07338249 0.03450781 -0.04294335 0.07314908 0.03464245 -0.04248952 0.07300347 0.03446924 -0.04259967 0.07335591 0.03402894 -0.04252409 0.07317709 0.03409326 -0.04219275 0.07306313 0.03392964 -0.04211866 0.07336407 0.03353112 -0.04186266 0.07317811 0.03343313 -0.04152792 0.07338333 0.03302884 -0.04141616 0.0730403 0.0332911 -0.04117751 0.07320839 0.0328775 -0.04089385 0.07339346 0.03259557 -0.04054772 0.07308745 0.03262209 -0.04045742 0.07300448 0.03279685 -0.04036736 0.07320016 0.03239977 -0.04025506 0.07338356 0.03224998 -0.03953641 0.07341951 0.03194367 -0.0395776 0.07322937 0.03203147 -0.03942847 0.07303541 0.03221064 -0.0388835 0.07334256 0.03175413 -0.03869789 0.07308369 0.03190952 -0.0382384 0.07300633 0.03198182 -0.0382896 0.07323396 0.03167778 -0.03808516 0.07342344 0.0315802 -0.03777772 0.0730974 0.03173428 -0.03741693 0.07333368 0.03152692 -0.03683912 0.07324159 0.03156316 -0.03658521 0.07340925 0.0315141 -0.03675645 0.0730642 0.03173756 -0.0362752 0.07300275 0.03194922 -0.03570473 0.07337158 0.03161692 -0.0359162 0.07315528 0.03171086 -0.0347706 0.07340699 0.03184217 -0.03528213 0.0730412 0.03199082 -0.03494679 0.07317435 0.03189688 -0.03389966 0.07342678 0.03216755 -0.03412514 0.07327461 0.03212475 -0.03384584 0.07311069 0.03238326 -0.03400272 0.07300859 0.03252238 -0.03343147 0.07324957 0.03247272 -0.0330829 0.07342553 0.0326054 -0.03246766 0.07339042 0.0330308 -0.03269553 0.07322818 0.03294336 -0.03232306 0.07300305 0.03363555 -0.03271096 0.0730524 0.03315746 -0.03188574 0.07340705 0.03351825 -0.03175693 0.07327234 0.03370082 -0.03179574 0.07311671 0.03382754 -0.03122544 0.07340276 0.03421378 -0.03120934 0.07322478 0.03435522 -0.03130102 0.07303202 0.03461647 -0.03069281 0.07332772 0.03497272 -0.03085392 0.07308506 0.03506392 -0.03080445 0.07300287 0.03555172 -0.03025645 0.07340347 0.03571665 -0.03027951 0.07322013 0.03583896 -0.03036326 0.07303094 0.03622043 -0.03007507 0.07314193 0.03650814 -0.02989542 0.07337999 0.03661775 -0.02983129 0.07318532 0.03717267 -0.02968996 0.07338529 0.0373491 -0.03000432 0.07303726 0.03728467 -0.02954304 0.07338833 0.03821367 -0.02970564 0.07314378 0.03798872 -0.02996814 0.07300019 0.0381574 -0.02974772 0.0730732 0.03840005 -0.0295155 0.07438105 0.03859382 -0.02962201 0.07435464 0.03767776 -0.02979135 0.07438313 0.03696203 -0.03008753 0.07435882 0.03609251 -0.0306245 0.07434892 0.03504973 -0.03116148 0.07434886 0.03429836 -0.03164637 0.07433134 0.03374999 -0.03218561 0.0743581 0.03325563 -0.03279322 0.07436734 0.03279846 -0.0335443 0.07439273 0.03235101 -0.03447008 0.07434839 0.0319435 -0.03515738 0.07432436 0.03173094 -0.0360434 0.07438057 0.0315659 -0.03683596 0.07438474 0.03150832 -0.03796154 0.07435071 0.03156203 -0.03902906 0.07436609 0.03178215 -0.04011195 0.07433259 0.03217405 -0.0409221 0.07437902 0.03261679 -0.04153662 0.07434231 0.03303134 -0.04211944 0.07433807 0.03352242 -0.04262703 0.07433605 0.03404492 -0.04306828 0.07439738 0.03461211 -0.04358249 0.07431471 0.03539788 -0.04398345 0.07435572 0.03627753 -0.04419922 0.07439565 0.03693747 -0.04438412 0.07431787 0.03768974 -0.04447388 0.07437473 0.03847503 -0.04449123 0.07436609 0.03919947 -0.04443907 0.0743466 0.03992801 -0.04430913 0.07437473 0.04064661 -0.04411411 0.0743038 0.04137694 -0.04383659 0.07441049 0.04204607 -0.04358023 0.07434183 0.04260069 -0.04309886 0.07436174 0.04335552 -0.04247456 0.0743376 0.04412841 -0.04184502 0.07435429 0.04471904 -0.0412327 0.0743553 0.0451861 -0.04046827 0.07441467 0.04563492 -0.03989225 0.07435464 0.045915 -0.03906571 0.07440471 0.04619777 -0.03850477 0.07431524 0.04634732 -0.03698325 0.07435584 0.04649513 -0.03625482 0.07441896 0.04644709 -0.03549849 0.07436561 0.04634195 -0.03481149 0.07442015 0.04615658 -0.03409969 0.07435476 0.04591143 -0.03343224 0.07437747 0.04558807 -0.03279304 0.07435071 0.04520434 -0.03217184 0.07439082 0.04472559 -0.03151106 0.07436543 0.04410809 -0.03089684 0.07433849 0.04335469 -0.03051382 0.07440799 0.04273849 -0.03017568 0.07435309 0.04210031 -0.02990865 0.07443058 0.04138392 -0.02968895 0.0743348 0.04066449 -0.02954131 0.07435208 0.03978329 -0.02961349 0.07457083 0.03869384 -0.02979993 0.07471412 0.03874492 -0.02997457 0.07474899 0.04004585 -0.02973043 0.07461082 0.03782284 -0.0300039 0.07471573 0.03728562 -0.03041177 0.07474935 0.03632754 -0.02990144 0.07458537 0.03699326 -0.03010636 0.07452774 0.03624594 -0.03024643 0.07468658 0.03634887 -0.03055548 0.07451671 0.03528863 -0.03064119 0.07465195 0.03538429 -0.03118997 0.07471597 0.03474485 -0.03118377 0.0745545 0.03441208 -0.03167039 0.07452815 0.03383159 -0.03184354 0.07474565 0.03412306 -0.03212362 0.07470917 0.03366488 -0.0322563 0.0745809 0.03334021 -0.03282761 0.07459521 0.03292202 -0.0333687 0.07474368 0.03287398 -0.03363239 0.07463383 0.03248578 -0.0341109 0.07448989 0.0321381 -0.03441834 0.07466882 0.03218525 -0.03503471 0.07451176 0.03182852 -0.03514748 0.07474243 0.03211277 -0.03554022 0.07460737 0.0317797 -0.03614211 0.07472902 0.03188687 -0.03660297 0.0746091 0.03165364 -0.03735679 0.07446444 0.03154981 -0.03728735 0.07470715 0.03178966 -0.03771293 0.07456636 0.03162997 -0.03826779 0.0747497 0.03201651 -0.03856718 0.07462769 0.03182268 -0.03940838 0.07469397 0.03217226 -0.03958475 0.07453435 0.0320428 -0.04031354 0.07458281 0.03239607 -0.04007244 0.07474553 0.0325827 -0.04101264 0.0746864 0.03294992 -0.04123121 0.074539 0.03291112 -0.04142826 0.07474857 0.03347045 -0.04176533 0.07456344 0.03333544 -0.04206192 0.07468646 0.03379654 -0.04245537 0.07452356 0.03395831 -0.0426079 0.07474201 0.03459721 -0.04300123 0.07462584 0.03476113 -0.04357576 0.07445865 0.03546983 -0.04345089 0.07466119 0.03558123 -0.0435847 0.07473278 0.03620308 -0.04386794 0.07458537 0.03629237 -0.04403364 0.07464075 0.03697288 -0.04385513 0.07474309 0.03707313 -0.04424357 0.0745306 0.03738194 -0.04421818 0.07465904 0.03792315 -0.04437786 0.07450479 0.03806072 -0.04411602 0.07474297 0.03863668 -0.04436933 0.07459723 0.03886246 -0.04434674 0.07458817 0.03974246 -0.0440877 0.07474219 0.03970938 -0.04414594 0.07468408 0.0402655 -0.0441026 0.07462042 0.04091089 -0.04405075 0.07449603 0.04138976 -0.04362636 0.07474547 0.04162085 -0.04355192 0.07466465 0.04222297 -0.04341542 0.07454401 0.04271107 -0.04262101 0.07474446 0.04338806 -0.04296916 0.07457917 0.04335373 -0.04259639 0.07447612 0.04392063 -0.0422765 0.07464081 0.04408329 -0.04191863 0.07448458 0.04459798 -0.04145461 0.07471293 0.04467284 -0.04143607 0.07458359 0.04489821 -0.04084306 0.0745626 0.04532736 -0.04037666 0.0747435 0.04526585 -0.04025232 0.0746423 0.04556113 -0.0395953 0.07469582 0.04576015 -0.03952324 0.07455056 0.04596376 -0.03861743 0.07460814 0.04617971 -0.0389046 0.07474273 0.04587388 -0.03788232 0.07439875 0.04643756 -0.03791958 0.07465487 0.046247 -0.03719073 0.0745427 0.04641199 -0.03736722 0.07474106 0.04612195 -0.03657257 0.07465976 0.04629099 -0.03571462 0.07470816 0.04610592 -0.03554683 0.07455474 0.04625809 -0.034814 0.07474851 0.04576271 -0.03452587 0.07466387 0.0458675 -0.03409123 0.07452893 0.04582619 -0.03338021 0.07460767 0.04540944 -0.03337061 0.07471531 0.04521322 -0.03268909 0.07458174 0.04500061 -0.03256577 0.07474166 0.0445826 -0.03170478 0.07457762 0.04415994 -0.03193026 0.07468765 0.0441873 -0.03130656 0.07465332 0.04358559 -0.03115552 0.07474732 0.04304665 -0.03097742 0.07451242 0.0433551 -0.03065764 0.07468116 0.04257005 -0.03021508 0.07454222 0.04198658 -0.03036856 0.07471346 0.04181504 -0.03005236 0.07468909 0.04110825 -0.02976161 0.07456827 0.04053676 -0.02958178 0.07448828 0.03967392 -0.02976447 0.07468849 0.03960955 -0.03099066 0.08799999 0.03874516 -0.03103321 0.08860409 0.03838622 -0.03127735 0.08799999 0.0371263 -0.03116029 0.0885998 0.03764128 -0.03132408 0.08863312 0.03708362 -0.03159767 0.08860278 0.03639185 -0.03192925 0.08799999 0.03577554 -0.0319674 0.08859777 0.03574049 -0.03242087 0.08858895 0.03512287 -0.03287029 0.08799999 0.03461772 -0.03295862 0.08867132 0.03458815 -0.03348022 0.08864825 0.03415197 -0.03434544 0.08799999 0.03359514 -0.03467714 0.08858603 0.03347074 -0.03540706 0.08858978 0.03321528 -0.03620302 0.08799999 0.03302329 -0.03609919 0.08859199 0.03307139 -0.03698837 0.08859091 0.03299582 -0.0380001 0.08799999 0.03306901 -0.03792953 0.08861511 0.03307855 -0.03862959 0.08862483 0.0332309 -0.03957062 0.08799999 0.03355473 -0.03950786 0.08858585 0.03354895 -0.04013919 0.08861726 0.03389465 -0.04117596 0.08799999 0.03465056 -0.04074275 0.08859926 0.03431195 -0.0415191 0.08857399 0.03504431 -0.04241168 0.08799999 0.03634113 -0.04203975 0.08860951 0.03575444 -0.04234784 0.08860296 0.03629016 -0.04261982 0.08862853 0.03691393 -0.04294061 0.08799999 0.03805899 -0.04290175 0.0886293 0.03793519 -0.04299664 0.08855581 0.03872734 -0.04298037 0.08799999 0.03970247 -0.04297709 0.08861082 0.03945195 -0.04288095 0.08860146 0.04018104 -0.04260909 0.08799999 0.04115575 -0.04263198 0.08859252 0.04106789 -0.04233646 0.08860492 0.04173165 -0.04183495 0.08799999 0.04260265 -0.04204928 0.08865815 0.04221481 -0.04169291 0.08861702 0.04272764 -0.04114848 0.08864039 0.04332411 -0.04043042 0.08799999 0.04394876 -0.04061746 0.08859634 0.04378193 -0.04012316 0.08859914 0.0441181 -0.03959995 0.08866405 0.04439032 -0.03891628 0.08799999 0.04470342 -0.03905338 0.08861666 0.04463058 -0.03845012 0.08860343 0.04481697 -0.03774607 0.08857607 0.04495483 -0.03740453 0.08799999 0.04500102 -0.03627145 0.08859413 0.04495543 -0.03621608 0.08799999 0.04495334 -0.03578519 0.08862638 0.04487353 -0.03508502 0.08799999 0.04469966 -0.034922 0.08859002 0.04462546 -0.03428882 0.08859634 0.04435151 -0.03399688 0.08799999 0.04420119 -0.03339785 0.0885899 0.04380339 -0.03287029 0.08799999 0.04338228 -0.03258991 0.08859175 0.04306787 -0.03194975 0.08859384 0.04224723 -0.03186935 0.08799999 0.04213523 -0.03159779 0.08865898 0.04158079 -0.03116875 0.08799999 0.04053384 -0.03132134 0.08858871 0.04092836 -0.03101545 0.0885955 0.03947782 -0.03104501 0.07899999 0.03805434 -0.03100806 0.07838296 0.03887063 -0.03105181 0.0783962 0.03825056 -0.0312168 0.07842367 0.03738003 -0.031663 0.07899999 0.03621155 -0.03196054 0.07845652 0.03572899 -0.03262168 0.07899999 0.03487604 -0.03269433 0.07840371 0.03481626 -0.03360921 0.07841694 0.03404319 -0.03352534 0.07899999 0.03410261 -0.03470396 0.07899999 0.03343337 -0.03427588 0.07836407 0.03366327 -0.03597211 0.07841169 0.03308874 -0.03614634 0.07899999 0.03305178 -0.03682875 0.07840812 0.03300237 -0.03779691 0.07899999 0.03302329 -0.03777879 0.07840114 0.03305196 -0.03879982 0.07841229 0.03327155 -0.03965449 0.07899999 0.03359514 -0.03960585 0.07834798 0.03360962 -0.0405215 0.07842528 0.03414028 -0.04124391 0.07899999 0.0347169 -0.04116976 0.07836389 0.03469544 -0.04187148 0.07841968 0.03548783 -0.04222506 0.07899999 0.03603214 -0.04233777 0.07840681 0.03626757 -0.04258579 0.07839792 0.03682214 -0.04285466 0.07899999 0.03755813 -0.04280972 0.07842063 0.03749686 -0.04295015 0.07841247 0.03825068 -0.04299867 0.07840049 0.038966 -0.04300528 0.07899999 0.0392996 -0.04295551 0.07843327 0.03972315 -0.0427103 0.07899999 0.04091852 -0.04285579 0.07834142 0.04024291 -0.04269236 0.07840871 0.04088598 -0.0421983 0.07845103 0.04199707 -0.04186177 0.07899999 0.04255264 -0.04191327 0.07835233 0.04242473 -0.04150092 0.07840651 0.04296189 -0.04087406 0.07841652 0.0435878 -0.04083001 0.07899999 0.04363036 -0.04016077 0.0783872 0.04409289 -0.039743 0.07899999 0.04435062 -0.03930014 0.07839387 0.04454445 -0.0382387 0.07899999 0.04489272 -0.03819721 0.07842081 0.04488474 -0.03718876 0.07841557 0.04499763 -0.0365954 0.07899999 0.04500102 -0.0364229 0.07840943 0.0449689 -0.03566008 0.07843643 0.04485106 -0.03508371 0.07899999 0.04470342 -0.03429275 0.07842516 0.04435604 -0.03369897 0.07899999 0.04402786 -0.0331397 0.07840794 0.04358905 -0.03278046 0.07899999 0.04327231 -0.03260725 0.07841634 0.04308807 -0.03200513 0.07899999 0.04235082 -0.03166496 0.0783832 0.04173088 -0.03140765 0.07899999 0.04119479 -0.03143197 0.07837694 0.04121488 -0.03105038 0.07899999 0.03989666 -0.03109395 0.07840692 0.04003775 -0.0310266 0.07835388 0.03942209 -0.03121685 0.07808798 0.03941053 -0.03119832 0.07816594 0.03999304 -0.03144395 0.07800269 0.03959912 -0.0312094 0.07833397 0.04051429 -0.0314846 0.07805556 0.04060351 -0.03169226 0.07800471 0.04081749 -0.03145158 0.07818782 0.04099917 -0.03183794 0.07805627 0.0415377 -0.03181016 0.07819044 0.04180634 -0.03202694 0.07837486 0.04234784 -0.03214925 0.07805448 0.04207682 -0.0323103 0.07813662 0.04250383 -0.03260213 0.07800096 0.04240864 -0.03234428 0.0782755 0.04270911 -0.03293275 0.07827192 0.04335367 -0.03281807 0.07803988 0.0428906 -0.03290528 0.07813018 0.04316985 -0.03344655 0.07801103 0.04338037 -0.03358703 0.07815295 0.04377508 -0.033724 0.07836139 0.0440157 -0.03399866 0.07804036 0.04385817 -0.03463184 0.07809424 0.04430532 -0.03431206 0.07822549 0.04428225 -0.03493869 0.07838326 0.04462772 -0.03527057 0.07826167 0.0446965 -0.0354405 0.07800644 0.04441535 -0.03569763 0.07813906 0.0447095 -0.03609561 0.07823216 0.04486221 -0.03665971 0.07807552 0.04476994 -0.03687793 0.07823574 0.04493415 -0.03654897 0.07800728 0.04460984 -0.03740149 0.07810842 0.04480409 -0.03771811 0.07823544 0.04488831 -0.03790527 0.07802706 0.04460895 -0.03841388 0.07810014 0.04464322 -0.03892022 0.07800239 0.04425966 -0.03861707 0.07823389 0.04470616 -0.03928315 0.07824319 0.04448127 -0.0393967 0.0780524 0.04422229 -0.03983336 0.07826197 0.04422903 -0.04029166 0.07813358 0.04383701 -0.04015421 0.07801884 0.04370641 -0.04060518 0.07823503 0.04371684 -0.04087454 0.07805401 0.04324156 -0.04131501 0.07820701 0.0430473 -0.0414527 0.07800209 0.04239374 -0.04163014 0.07811427 0.04255223 -0.04195851 0.07800424 0.04167479 -0.04207593 0.07815062 0.04193812 -0.0424171 0.07835882 0.04155737 -0.04235702 0.07811671 0.04131519 -0.04264557 0.07821464 0.04078739 -0.04257929 0.07808059 0.04051488 -0.0425198 0.07801228 0.04014289 -0.04278391 0.07810658 0.03972339 -0.0429393 0.07825642 0.03926706 -0.04290771 0.07819122 0.03883624 -0.0427193 0.07804572 0.03853929 -0.04279196 0.07820504 0.03778338 -0.04253464 0.07800555 0.0379613 -0.04260164 0.07817864 0.03716641 -0.04238694 0.07804286 0.03704887 -0.04190957 0.07800322 0.03628569 -0.04239523 0.07820767 0.03657966 -0.04207611 0.07823044 0.03593337 -0.04183918 0.07806664 0.03585141 -0.04160076 0.07825946 0.03522956 -0.04127979 0.0781334 0.03501546 -0.04107207 0.07804483 0.03497707 -0.04050844 0.07800221 0.03465372 -0.04064643 0.07819586 0.03434944 -0.04017436 0.07804113 0.03424215 -0.04005801 0.07836657 0.03385066 -0.03983497 0.07814979 0.03385645 -0.03898334 0.07805472 0.03360342 -0.03873109 0.07800108 0.03369563 -0.03901606 0.07821708 0.03343349 -0.03846991 0.07826125 0.03323614 -0.03808838 0.07806581 0.03334009 -0.03755325 0.07823407 0.03308802 -0.03724819 0.07800865 0.03338098 -0.03710824 0.07811468 0.03317344 -0.03659331 0.0782718 0.03306001 -0.03636497 0.07806158 0.03327244 -0.03586155 0.07815551 0.03323841 -0.03521859 0.07837706 0.03327304 -0.03560191 0.07801181 0.0335288 -0.03494709 0.07824957 0.03342056 -0.03494715 0.07808208 0.03357857 -0.03419548 0.07814973 0.03385013 -0.03410041 0.07800954 0.03415751 -0.03341537 0.07826346 0.03424763 -0.03346383 0.07808566 0.03440046 -0.03286999 0.07800161 0.03521746 -0.03283464 0.07817983 0.03482961 -0.03241688 0.07804316 0.03555619 -0.0321834 0.07824331 0.03551918 -0.03195255 0.07813173 0.03604042 -0.03159725 0.0783419 0.03642028 -0.0317409 0.0780943 0.03652769 -0.03164279 0.0780034 0.03730678 -0.03140735 0.07821673 0.03704506 -0.03136169 0.07807868 0.03772538 -0.03122299 0.07823199 0.03766286 -0.0311008 0.07820671 0.03854954 -0.03128534 0.07804954 0.03841704 -0.03112435 0.08883702 0.03866487 -0.03136587 0.08898061 0.03836154 -0.03123188 0.08883285 0.0378192 -0.03154414 0.08896106 0.03731137 -0.03148603 0.0888561 0.03701394 -0.03171849 0.08878266 0.03630888 -0.0319612 0.08899289 0.03647148 -0.03222697 0.0889061 0.03569692 -0.03234988 0.0887528 0.03530132 -0.03269076 0.08899468 0.03540986 -0.03274655 0.08890378 0.035043 -0.03343248 0.08894026 0.03447496 -0.03425073 0.08899539 0.03410238 -0.03383713 0.08889418 0.03411471 -0.0340619 0.08867007 0.03378671 -0.03446918 0.08887976 0.03374475 -0.03497713 0.08873158 0.03339874 -0.03515642 0.08887344 0.0334562 -0.03540098 0.08899003 0.03359144 -0.03596025 0.08876693 0.03316062 -0.03614771 0.08888155 0.03322738 -0.03657156 0.08898854 0.0333653 -0.03685766 0.08877247 0.03307402 -0.03715044 0.08891659 0.03321629 -0.03762161 0.08876067 0.03309595 -0.03811341 0.0888459 0.03323215 -0.03827911 0.08899152 0.03350585 -0.03872156 0.08887332 0.03341966 -0.03921133 0.08877462 0.03349739 -0.03940927 0.08897072 0.03383827 -0.03990477 0.08882212 0.03387188 -0.04045605 0.08890515 0.03433579 -0.04056912 0.08878195 0.03427773 -0.04042935 0.08899527 0.03455841 -0.04112643 0.0887624 0.03473478 -0.04116612 0.0889008 0.03494411 -0.0416404 0.08876985 0.03531122 -0.04144966 0.08899044 0.03554272 -0.04188019 0.08885061 0.03573715 -0.04223459 0.08883082 0.03630179 -0.04213541 0.08893531 0.03639781 -0.04205369 0.08899652 0.03660786 -0.04265755 0.08878523 0.03725284 -0.0424304 0.08897352 0.03730165 -0.04269015 0.08890193 0.03782278 -0.04286915 0.08874887 0.03807085 -0.04271405 0.08895039 0.03848087 -0.0425831 0.08899837 0.03914099 -0.04292184 0.08878612 0.03893887 -0.04275798 0.08892619 0.03945136 -0.0428344 0.08877468 0.04007083 -0.04252767 0.08894628 0.0406239 -0.04257559 0.08875983 0.04103296 -0.04232829 0.08899062 0.04086315 -0.04219931 0.08886897 0.04169619 -0.04184544 0.08884048 0.04232352 -0.04152989 0.08899372 0.04235172 -0.04139536 0.08885627 0.04288822 -0.04086577 0.08899611 0.04308712 -0.04064673 0.08890968 0.04351514 -0.04035109 0.08876264 0.04390007 -0.03990852 0.0888822 0.04405289 -0.03947895 0.08899629 0.04403781 -0.03927695 0.08895003 0.04426413 -0.03912293 0.08884716 0.04447042 -0.03859984 0.08879494 0.04469311 -0.03817766 0.0889523 0.04461008 -0.03792762 0.08880573 0.04483443 -0.0371468 0.0889967 0.04461562 -0.03711473 0.08866703 0.0449838 -0.03724062 0.08890998 0.04479426 -0.0365113 0.08885729 0.04484558 -0.03556531 0.08886367 0.04468023 -0.03586119 0.08895838 0.0446043 -0.03499114 0.08875453 0.04459297 -0.03450024 0.08889657 0.04425418 -0.03389883 0.08878183 0.04405176 -0.03469485 0.08898985 0.04414582 -0.03351712 0.08895027 0.04356026 -0.03323537 0.08899831 0.04312849 -0.03309023 0.08876925 0.04346275 -0.0326687 0.08884036 0.04297733 -0.03249931 0.08894658 0.04255813 -0.0321232 0.08879125 0.04235315 -0.03224819 0.08899623 0.04195475 -0.03187274 0.0889132 0.04170614 -0.0315544 0.08882987 0.04123973 -0.03165853 0.0889936 0.04073691 -0.03142738 0.08889925 0.04068744 -0.03117245 0.08866304 0.04036521 -0.03133606 0.0889101 0.04023808 -0.03107488 0.08876329 0.03940224 -0.03141623 0.08899694 0.03933453 -0.03123998 0.0889188 0.03955262 -0.03000545 0.08759659 0.03917038 -0.03004455 0.08763784 0.03826975 -0.03016948 0.08700001 0.03731793 -0.03018254 0.08760952 0.03743535 -0.03036683 0.08766156 0.03681445 -0.03055965 0.08756577 0.03624951 -0.03106939 0.08700001 0.03523427 -0.03094655 0.08760952 0.0354954 -0.03141742 0.08759272 0.03477603 -0.03219532 0.08700001 0.03389465 -0.0320121 0.08764082 0.03410339 -0.03246593 0.08762651 0.0336796 -0.03295272 0.08757907 0.03328627 -0.03359258 0.08700001 0.03285652 -0.0336346 0.08765751 0.03287768 -0.03429418 0.08764493 0.03255617 -0.03538727 0.08700001 0.03217065 -0.03496062 0.08766484 0.03231954 -0.03561007 0.08761548 0.03214561 -0.0365051 0.08763772 0.03202396 -0.03747022 0.08700001 0.03198117 -0.03753006 0.08760958 0.03202176 -0.03840661 0.08762902 0.03215122 -0.03951466 0.08700001 0.03244888 -0.03922277 0.08765733 0.03237283 -0.03957778 0.08758944 0.03249102 -0.04036062 0.0875827 0.03286176 -0.04076397 0.08700001 0.03309148 -0.04093068 0.087632 0.03322035 -0.04140806 0.08758586 0.03356093 -0.0420311 0.08700001 0.03409272 -0.04200983 0.08764499 0.03412705 -0.0424472 0.08766072 0.03462696 -0.04286271 0.08759975 0.03518223 -0.04316055 0.08700001 0.035645 -0.04323047 0.08756494 0.03581011 -0.04358309 0.08758091 0.0366159 -0.04383665 0.08700001 0.03738379 -0.04381608 0.087677 0.03748756 -0.04394209 0.08759808 0.03813004 -0.04400539 0.08700001 0.03895628 -0.04399687 0.08757251 0.03882932 -0.04397523 0.08762383 0.0394932 -0.04383045 0.08700001 0.04068207 -0.04385071 0.08759349 0.04043853 -0.04362648 0.08765202 0.04121673 -0.04337376 0.08759778 0.04188477 -0.04293054 0.08700001 0.04276567 -0.04304653 0.08756792 0.04252552 -0.04267919 0.08760952 0.04308313 -0.04224878 0.0875923 0.04362672 -0.04142916 0.08700001 0.04446506 -0.04147785 0.08756607 0.04439073 -0.04037606 0.08757275 0.04514056 -0.03929281 0.08700001 0.04565036 -0.03938591 0.08758604 0.0455783 -0.03874909 0.08761066 0.04577225 -0.03801369 0.08757913 0.04592442 -0.03739887 0.08700001 0.04599922 -0.03737425 0.08767229 0.045973 -0.03646004 0.08758777 0.04598045 -0.03600406 0.08700001 0.0459395 -0.03559297 0.08762806 0.04584878 -0.03443545 0.08700001 0.04553431 -0.0349186 0.08759295 0.04568004 -0.03427529 0.08760952 0.04544216 -0.03366756 0.08756679 0.04515522 -0.03275984 0.08700001 0.04459774 -0.03305566 0.08759897 0.04477798 -0.03239673 0.0875985 0.04427373 -0.03121912 0.08700001 0.04300826 -0.03174078 0.08759295 0.04361474 -0.03130626 0.0876258 0.04305827 -0.03095102 0.08767485 0.04248791 -0.0306304 0.08761638 0.04188799 -0.03037035 0.08700001 0.04127961 -0.03035926 0.08759057 0.04120516 -0.03018432 0.08762812 0.0405597 -0.02999877 0.08700001 0.03957915 -0.03006392 0.08762949 0.03987783 -0.03000169 0.07999998 0.03865069 -0.03000837 0.07938283 0.03884255 -0.03005802 0.0794022 0.03812998 -0.03021299 0.07999998 0.03721755 -0.03041636 0.07940942 0.03661954 -0.03094339 0.07999998 0.03544044 -0.03119027 0.07940328 0.03509551 -0.03186404 0.07939612 0.03424417 -0.0321381 0.07999998 0.03394007 -0.03250646 0.07939517 0.03363871 -0.03302145 0.07937645 0.03324943 -0.03323596 0.07999998 0.03309148 -0.03365582 0.07944244 0.03285032 -0.03464841 0.07999998 0.0323801 -0.03417396 0.0793783 0.03260213 -0.0357905 0.07940304 0.03210556 -0.03635138 0.07999998 0.03201943 -0.03792464 0.07999998 0.03204399 -0.03805047 0.07941997 0.03208106 -0.0388922 0.07938832 0.03226256 -0.03961241 0.07999998 0.03248727 -0.03989815 0.07941001 0.03262728 -0.04061299 0.07938802 0.03301113 -0.04142916 0.07999998 0.03353494 -0.04123139 0.07941973 0.03342592 -0.04188632 0.07939076 0.0339899 -0.04257875 0.07941222 0.03476989 -0.04303115 0.07999998 0.03537929 -0.04304522 0.07940024 0.03547883 -0.04344147 0.07940018 0.03626114 -0.04376184 0.07999998 0.03714895 -0.04376935 0.07938975 0.037225 -0.04401081 0.07999998 0.03870284 -0.04399675 0.07942557 0.03916668 -0.04394239 0.07941782 0.03988158 -0.04383665 0.07999998 0.04061621 -0.04382306 0.07939338 0.04054093 -0.04363971 0.079418 0.04121041 -0.04321569 0.07999998 0.0422424 -0.04313796 0.07943773 0.04237222 -0.04258602 0.07936644 0.04320931 -0.04234147 0.07999998 0.04355067 -0.04188364 0.07941132 0.0440163 -0.04095578 0.07999998 0.04480212 -0.04123783 0.07941699 0.04456883 -0.0406295 0.07940012 0.044981 -0.03907155 0.07999998 0.04571574 -0.03937619 0.07939898 0.04557985 -0.03873038 0.07941234 0.04578006 -0.03787028 0.07940161 0.04594588 -0.03712236 0.07999998 0.04601603 -0.03681445 0.07941436 0.04599857 -0.03575849 0.07940131 0.04588896 -0.03543895 0.07999998 0.04583901 -0.033688 0.07999998 0.0451954 -0.03431135 0.07939702 0.04545807 -0.03304266 0.0794121 0.04477107 -0.03223025 0.07999998 0.04414057 -0.03249949 0.07933366 0.04434084 -0.03106939 0.07999998 0.04276567 -0.03152054 0.07937937 0.04334282 -0.03100621 0.07941299 0.04261779 -0.03062164 0.07941395 0.0418781 -0.03040206 0.07999998 0.04135483 -0.03036516 0.07940644 0.04122066 -0.030218 0.07932889 0.04067021 -0.03006339 0.07999998 0.04004544 -0.03003311 0.07942128 0.03970134 -0.03008878 0.07925277 0.0396803 -0.03026342 0.07906186 0.03961813 -0.03044432 0.07900309 0.03987848 -0.03039258 0.07910126 0.04067456 -0.0305683 0.07920598 0.04153591 -0.03082257 0.07901549 0.04150068 -0.0308513 0.07917559 0.04211527 -0.03130894 0.07903355 0.04253685 -0.03117352 0.07926791 0.0427885 -0.03146421 0.07915627 0.04308319 -0.03186732 0.07900208 0.04311317 -0.03209775 0.07908469 0.0437076 -0.03191375 0.07935255 0.04379779 -0.03278332 0.07900404 0.04408174 -0.0328437 0.07908606 0.04438096 -0.03324115 0.07916986 0.04477679 -0.03363019 0.07938796 0.04512906 -0.0339002 0.07922577 0.04519706 -0.03408432 0.07901155 0.04497855 -0.03435409 0.07916027 0.04534727 -0.03503042 0.07933264 0.04570186 -0.03530991 0.07912325 0.04563212 -0.03544932 0.07900881 0.04545491 -0.0363121 0.07925778 0.04591768 -0.03651541 0.07904851 0.04572331 -0.03721272 0.07917183 0.04589009 -0.03799021 0.0792638 0.04587501 -0.03777885 0.07900762 0.04558771 -0.0381748 0.07911378 0.0457251 -0.03884392 0.07921457 0.04567062 -0.03886181 0.07906025 0.04549902 -0.03997099 0.07934302 0.04532378 -0.03989082 0.07912188 0.04520535 -0.03968518 0.07900834 0.04504609 -0.04049134 0.07903915 0.04473066 -0.04081767 0.07925331 0.04479885 -0.04107648 0.07900726 0.0442503 -0.04115271 0.07913714 0.04445797 -0.04165279 0.07928997 0.04417902 -0.04191195 0.07909584 0.04371356 -0.04241144 0.07921534 0.04332745 -0.04201227 0.0790075 0.04332965 -0.04276973 0.07905757 0.04251652 -0.043011 0.07924145 0.04245871 -0.04337859 0.07936733 0.04185771 -0.04291439 0.07900452 0.04191869 -0.04339843 0.07918202 0.04158395 -0.04341304 0.07905113 0.04106259 -0.04365015 0.07920467 0.04088252 -0.04346728 0.07900667 0.04040998 -0.04385131 0.07922202 0.04001849 -0.04374462 0.07910454 0.03997325 -0.0439313 0.07924526 0.03932553 -0.04363316 0.07900816 0.03914451 -0.0438553 0.07913625 0.03896564 -0.04396039 0.07936209 0.03831881 -0.04378509 0.07912194 0.03818899 -0.04380989 0.07925552 0.03763139 -0.04357147 0.07903993 0.03758734 -0.04366028 0.07916623 0.03726482 -0.04329758 0.07900196 0.03707462 -0.04345142 0.07923078 0.03647661 -0.04328209 0.07906115 0.03651499 -0.04306614 0.07916146 0.03574723 -0.04269027 0.07904249 0.03540283 -0.04261547 0.07923746 0.0349242 -0.04210895 0.07900482 0.03480035 -0.04199874 0.07914948 0.03428453 -0.04131829 0.07900303 0.03402739 -0.04149967 0.07907295 0.03393715 -0.04128921 0.07918411 0.03359615 -0.04080396 0.07917165 0.03324794 -0.04058963 0.07902067 0.03337973 -0.03981739 0.07922291 0.03267163 -0.03966599 0.07908874 0.03274548 -0.03942722 0.07900476 0.0328595 -0.03888183 0.07920342 0.03234893 -0.03861641 0.07903885 0.03248053 -0.03809028 0.07918745 0.03218674 -0.03777527 0.07904088 0.03233128 -0.03748416 0.07935744 0.03202575 -0.03718215 0.07900172 0.03239709 -0.03719949 0.07912391 0.03216183 -0.03680074 0.07934045 0.03201532 -0.03616583 0.07921642 0.03213047 -0.03630375 0.07906466 0.03227549 -0.03527826 0.07910722 0.03239715 -0.03506141 0.07932758 0.03229022 -0.03498154 0.07900887 0.03267389 -0.03438562 0.07914811 0.03264278 -0.03350281 0.07924109 0.03300726 -0.03365975 0.07902854 0.03321474 -0.03310167 0.07908445 0.0334295 -0.03254342 0.07921355 0.03371226 -0.03280311 0.07900166 0.03390878 -0.03229594 0.07907408 0.03412538 -0.03189843 0.07919788 0.0343331 -0.03137552 0.0792647 0.03492289 -0.03170752 0.07900172 0.03509902 -0.03156179 0.07907927 0.03493857 -0.0310803 0.0791561 0.03550821 -0.03076219 0.07934123 0.03585439 -0.03108918 0.07901275 0.03595662 -0.03069174 0.07911926 0.03637093 -0.03047978 0.07924246 0.0366317 -0.03070539 0.07900381 0.03697246 -0.03040385 0.07909661 0.0373159 -0.03019011 0.07933014 0.03745162 -0.03031265 0.0790432 0.03825372 -0.03012186 0.07917791 0.03845447 -0.0300762 0.08777546 0.03880584 -0.03021591 0.08790272 0.03844469 -0.03026145 0.08794236 0.03928267 -0.03043192 0.08799827 0.03828853 -0.03027784 0.08787286 0.03768664 -0.03040456 0.0878179 0.03697335 -0.03069305 0.08797019 0.03677135 -0.03074538 0.08781278 0.03606849 -0.03156554 0.08800017 0.03529202 -0.03119438 0.08796203 0.03563106 -0.03115105 0.08782619 0.03535383 -0.03160631 0.08784025 0.03472268 -0.03226578 0.08794856 0.03420126 -0.03217816 0.08781462 0.03406786 -0.03263038 0.08799493 0.03405165 -0.03298181 0.0877574 0.03334194 -0.03313583 0.08787107 0.03334343 -0.03321319 0.08796066 0.03345608 -0.0339936 0.08788394 0.03286373 -0.03457188 0.08798909 0.03281527 -0.03478175 0.08786243 0.03251522 -0.03609913 0.08800005 0.03248792 -0.03563624 0.08794432 0.03239148 -0.03597819 0.08783012 0.03218567 -0.03706747 0.08796238 0.03228014 -0.0370348 0.0878278 0.03211504 -0.03784036 0.0878061 0.03214687 -0.03897643 0.0879963 0.03268158 -0.03818643 0.08794558 0.03235918 -0.03900533 0.08785372 0.0324285 -0.04016691 0.08776217 0.03283101 -0.04020929 0.08792215 0.03301775 -0.04095721 0.08782285 0.03335338 -0.04087066 0.08799248 0.03361219 -0.04144287 0.08777284 0.03368622 -0.04149478 0.08799558 0.03415685 -0.04190158 0.08788347 0.03423637 -0.04219269 0.08797836 0.03481191 -0.04265856 0.08786118 0.03512424 -0.04309391 0.0877341 0.03565573 -0.04294431 0.08796328 0.03589832 -0.0431714 0.08787059 0.03603631 -0.04311841 0.08799606 0.03650683 -0.04350805 0.08774667 0.03657913 -0.04353958 0.08788758 0.03702861 -0.04355686 0.08799219 0.03801649 -0.0436989 0.08791863 0.03793025 -0.04384052 0.08784317 0.03827041 -0.04392969 0.08777207 0.03895908 -0.04376488 0.08792263 0.03946018 -0.04359191 0.08799427 0.03946447 -0.04388999 0.08773928 0.03988647 -0.04371422 0.08785909 0.04043132 -0.04338747 0.08799594 0.0406953 -0.04339182 0.08792775 0.04126888 -0.04328495 0.08782428 0.04182744 -0.04301714 0.08776354 0.04244875 -0.04284119 0.08793705 0.04239815 -0.04269087 0.08799576 0.04233598 -0.04239743 0.0878331 0.04328256 -0.04220396 0.08794564 0.04328799 -0.04180258 0.08774262 0.04402005 -0.04133713 0.08799397 0.04400974 -0.04140096 0.08790028 0.04420375 -0.04120439 0.08775794 0.04451704 -0.040605 0.08778905 0.04490262 -0.04046642 0.08794975 0.04477077 -0.04001289 0.08774334 0.04525786 -0.0391826 0.08799713 0.04523444 -0.03970152 0.0879178 0.04522734 -0.0393477 0.08779764 0.04550033 -0.03833127 0.08778631 0.04579639 -0.03854304 0.08791977 0.04560273 -0.03771018 0.08793717 0.04571986 -0.03727793 0.08799481 0.04560399 -0.03701692 0.08789426 0.04581797 -0.0365082 0.08773314 0.04593354 -0.03590303 0.08786827 0.04576635 -0.03610193 0.08799135 0.04557961 -0.0349884 0.08780831 0.04560416 -0.03502792 0.08796215 0.04540717 -0.03430825 0.08787012 0.04530328 -0.0339272 0.0879969 0.04484778 -0.03352624 0.08774811 0.04501324 -0.03356909 0.0879215 0.04484862 -0.03277939 0.0878359 0.04443711 -0.03264433 0.08795255 0.04413086 -0.03224951 0.08776164 0.04405552 -0.03197729 0.08798611 0.04338198 -0.03183889 0.08779275 0.04359966 -0.03143942 0.08784359 0.04303944 -0.0313763 0.08796566 0.04264575 -0.03083515 0.08786416 0.04201167 -0.03100597 0.08799517 0.04178094 -0.03048431 0.0878148 0.04127597 -0.0306183 0.08796823 0.04100608 -0.03031116 0.08785843 0.04051846 -0.03048855 0.08799338 0.04023802 -0.03013986 0.08782631 0.03965365 -0.02900511 0.086591 0.03920775 -0.02899289 0.08599996 0.03860032 -0.02903825 0.08659499 0.03820699 -0.02927213 0.08599996 0.03688448 -0.02919769 0.08658903 0.03724324 -0.02938354 0.08666574 0.03659731 -0.02976495 0.08599996 0.03557127 -0.02972209 0.0865913 0.03568494 -0.03017926 0.08663243 0.03482854 -0.03057122 0.08599996 0.03420567 -0.03077816 0.08662307 0.03398245 -0.03126537 0.08660191 0.03342765 -0.03180658 0.08599996 0.0328989 -0.03184926 0.08661329 0.03288596 -0.03249728 0.0865724 0.03238832 -0.033288 0.08599996 0.03189116 -0.03317815 0.08657634 0.03197312 -0.03391295 0.08659297 0.0316227 -0.03496813 0.08599996 0.03124976 -0.03481304 0.08660882 0.03130471 -0.03579276 0.0866366 0.03110104 -0.03654408 0.08599996 0.03100079 -0.03659731 0.08659309 0.03101301 -0.03740936 0.08668059 0.03102898 -0.03833335 0.08599996 0.03109198 -0.03838503 0.08661401 0.0311225 -0.0393846 0.08657646 0.03136485 -0.03987854 0.08599996 0.031529 -0.04013258 0.0865913 0.03164172 -0.04130047 0.08599996 0.03223097 -0.04082906 0.08657634 0.03197711 -0.04150664 0.08661997 0.03239804 -0.04231542 0.08661186 0.03302282 -0.04269587 0.08599996 0.03336513 -0.04302197 0.08660113 0.0337395 -0.04358685 0.08599996 0.03444862 -0.04348164 0.08661222 0.03432005 -0.04404485 0.0866006 0.03520858 -0.04427969 0.08599996 0.03565323 -0.04444104 0.08659476 0.03607064 -0.04491001 0.08599996 0.03760522 -0.04469138 0.08661222 0.03681915 -0.04489797 0.08665692 0.03779625 -0.04497456 0.08661311 0.03843969 -0.0449934 0.08659774 0.03922873 -0.04496324 0.08599996 0.03999793 -0.044918 0.08667051 0.04002296 -0.04479432 0.0865792 0.04079616 -0.0445404 0.08599996 0.04169142 -0.04450637 0.08661562 0.04176217 -0.04396677 0.08599996 0.042957 -0.04410421 0.08660054 0.04267001 -0.04371207 0.08658063 0.0433501 -0.04316532 0.08599996 0.04410785 -0.04322576 0.0866124 0.04401516 -0.04255646 0.08659851 0.04475605 -0.04219347 0.08599996 0.04510098 -0.04182153 0.08659774 0.04537945 -0.04104644 0.08599996 0.04590851 -0.04115885 0.08663314 0.04582381 -0.04027646 0.08657711 0.04630136 -0.03942579 0.08599996 0.04665344 -0.03933757 0.08664178 0.04663985 -0.03859341 0.08656764 0.04683953 -0.03745585 0.08599996 0.04699915 -0.03781121 0.08660191 0.04695475 -0.0368238 0.0866003 0.04699844 -0.03560692 0.08599996 0.04690045 -0.03580415 0.08661067 0.04690468 -0.03479576 0.08658468 0.04669272 -0.03383576 0.08599996 0.04636085 -0.03389739 0.08659297 0.04637074 -0.03317838 0.0865814 0.04602634 -0.03215408 0.08599996 0.0453974 -0.03185731 0.0866084 0.04512196 -0.03129214 0.08660084 0.04459989 -0.03086549 0.08599996 0.04414731 -0.03063684 0.08660042 0.04384887 -0.02992844 0.08599996 0.04278254 -0.0300045 0.08661878 0.04287731 -0.02948534 0.08660995 0.04174065 -0.029159 0.08599996 0.04072594 -0.02919876 0.08659309 0.04075908 -0.02906101 0.08667892 0.03984916 -0.02900803 0.08099997 0.038401 -0.02901011 0.08038699 0.0393716 -0.02902656 0.08037817 0.03843885 -0.02930277 0.08099997 0.03677558 -0.02935391 0.08039081 0.0366494 -0.02972006 0.0803194 0.03572779 -0.02989614 0.08099997 0.03529453 -0.03018575 0.08040583 0.03480619 -0.03102141 0.08099997 0.03364115 -0.0308755 0.08040869 0.03385078 -0.03171628 0.08040916 0.03299105 -0.03253346 0.08099997 0.03234827 -0.0324642 0.08039873 0.03241479 -0.03412604 0.08099997 0.03151303 -0.03539866 0.0803942 0.03116643 -0.03586184 0.08099997 0.03106909 -0.03633844 0.08038288 0.03102958 -0.0378611 0.08099997 0.0310176 -0.03737038 0.0804336 0.03100878 -0.03820687 0.08040994 0.03109413 -0.03919398 0.08040291 0.03130596 -0.03979349 0.08099997 0.03149056 -0.0401377 0.08033394 0.03165757 -0.04103028 0.08041179 0.0320872 -0.0410465 0.08099997 0.03209143 -0.04184508 0.08042341 0.0326355 -0.04219347 0.08099997 0.03289896 -0.04243278 0.08040213 0.03313231 -0.04316532 0.08099997 0.03389209 -0.04348164 0.0803942 0.0343185 -0.04396682 0.08099997 0.035043 -0.04389691 0.08033061 0.03497785 -0.04428851 0.08035182 0.03572982 -0.0445404 0.08099997 0.03630858 -0.04463666 0.08039784 0.0366162 -0.04493874 0.08099997 0.03786414 -0.04490834 0.08039718 0.03779202 -0.04499083 0.08038783 0.03875523 -0.04495841 0.08099997 0.04005986 -0.04496949 0.08037286 0.03960609 -0.0448544 0.08042311 0.04053217 -0.04462832 0.08036404 0.04138523 -0.0444374 0.08099997 0.04197978 -0.04421949 0.08039033 0.04244351 -0.04362392 0.08099997 0.04351615 -0.04379624 0.08036112 0.04320532 -0.04298907 0.08039402 0.04429668 -0.04259127 0.08099997 0.04473274 -0.04242295 0.08038473 0.04487347 -0.04186677 0.08033335 0.04533028 -0.04134958 0.08099997 0.04573446 -0.0411874 0.08041226 0.04581409 -0.04025447 0.08039849 0.04630857 -0.03979349 0.08099997 0.04650938 -0.03934568 0.08041858 0.04664671 -0.03779971 0.08099997 0.04699206 -0.03841799 0.08042073 0.04687577 -0.03659343 0.08039635 0.04698544 -0.03580611 0.08099997 0.04692065 -0.03583496 0.08041089 0.04691243 -0.0348612 0.08040428 0.04670965 -0.03412604 0.08099997 0.04648691 -0.03391808 0.08032435 0.04636347 -0.03317946 0.0804007 0.04602462 -0.03253346 0.08099997 0.04565167 -0.03248929 0.08038556 0.04560041 -0.03186172 0.08042401 0.04513013 -0.03126281 0.08099997 0.04459589 -0.03111886 0.08040875 0.04442572 -0.03037416 0.08041381 0.04348671 -0.03035676 0.08099997 0.04346871 -0.02988433 0.08037006 0.0426383 -0.02958703 0.08099997 0.04205965 -0.02954447 0.08041298 0.04189544 -0.0293129 0.080388 0.0411961 -0.02907246 0.08099997 0.0401948 -0.02912926 0.08040821 0.04041582 -0.02911418 0.08017629 0.03918492 -0.02929496 0.08005428 0.03974205 -0.02911937 0.08024269 0.03995972 -0.02940666 0.08000397 0.03864693 -0.02956533 0.08000355 0.04051667 -0.02937161 0.08008074 0.04055303 -0.02933269 0.08020067 0.04095119 -0.02983301 0.08003968 0.04187732 -0.02969741 0.08019769 0.04204684 -0.03036695 0.08000653 0.04277616 -0.03019994 0.08015525 0.04297167 -0.03058087 0.08019584 0.04362392 -0.03107488 0.08008253 0.04405611 -0.0310651 0.08025395 0.04427748 -0.03162395 0.08000624 0.04442274 -0.03169208 0.08027553 0.0449267 -0.03170073 0.0801326 0.04478591 -0.03237211 0.08012199 0.04533296 -0.03310191 0.08000487 0.04553544 -0.03293687 0.08011513 0.04570502 -0.03335481 0.08019214 0.04601407 -0.03420978 0.08004248 0.04620444 -0.03458678 0.08020812 0.04653906 -0.03508096 0.08008271 0.04654741 -0.03566497 0.08021694 0.04680931 -0.0357269 0.08000457 0.04650515 -0.03624296 0.08013224 0.04682093 -0.03701037 0.08000773 0.04663532 -0.03723114 0.08034372 0.04698574 -0.03737753 0.08011597 0.04682087 -0.0378347 0.08026576 0.04690355 -0.03854966 0.08009195 0.04665631 -0.03857833 0.08021038 0.04675751 -0.03936511 0.08000868 0.04626214 -0.03951126 0.08018243 0.04649329 -0.04043352 0.08027136 0.04617154 -0.0406484 0.08000564 0.04568743 -0.04039758 0.08010357 0.04603719 -0.04126018 0.08023601 0.04569411 -0.0414288 0.08010864 0.0454514 -0.04149347 0.08000767 0.04516702 -0.04254883 0.08018898 0.04462677 -0.04231405 0.08009457 0.044712 -0.04260814 0.08002507 0.0442447 -0.04332536 0.0803098 0.04386067 -0.04338556 0.08010208 0.04352289 -0.04362773 0.0800029 0.04276043 -0.0436688 0.08004468 0.0428977 -0.04398757 0.08014738 0.04260784 -0.04437839 0.08022665 0.04189163 -0.04426449 0.08005952 0.04171085 -0.04453766 0.08012944 0.04116672 -0.04478305 0.08023661 0.04054343 -0.04446333 0.08000254 0.04035645 -0.0446524 0.08005785 0.04024374 -0.04484766 0.08016294 0.03970485 -0.04472428 0.080042 0.03877556 -0.04491627 0.08021175 0.03891074 -0.04483181 0.0802024 0.03786838 -0.04442346 0.08000177 0.03731405 -0.04454427 0.0800724 0.03709256 -0.04462838 0.08022385 0.03685945 -0.04427933 0.0801717 0.03595799 -0.04396986 0.08003371 0.03573763 -0.04377961 0.08010321 0.03511464 -0.04334026 0.08016437 0.03431373 -0.04302287 0.08000648 0.0342884 -0.04301279 0.08036577 0.03373658 -0.04242473 0.08000248 0.03368049 -0.04262721 0.08015382 0.03348892 -0.04207605 0.08019804 0.03293573 -0.04158222 0.08005034 0.03275513 -0.04148459 0.08024477 0.03245103 -0.04079234 0.08028525 0.03200399 -0.04064887 0.08009558 0.03209656 -0.04004472 0.08000743 0.03200012 -0.03963607 0.08013772 0.03159463 -0.03876096 0.08021181 0.03127801 -0.03896743 0.08000069 0.03167796 -0.03844201 0.08005464 0.03138679 -0.03778487 0.08024758 0.03109753 -0.03739452 0.08002656 0.03132992 -0.03734499 0.08013731 0.03115338 -0.03680551 0.08026027 0.03105503 -0.03630983 0.0800023 0.03143328 -0.03619909 0.08010697 0.03121292 -0.03583693 0.08004486 0.03136223 -0.03530639 0.08016097 0.03130191 -0.03468352 0.08033126 0.03135919 -0.03425258 0.0800324 0.03180503 -0.03417503 0.0801438 0.03166401 -0.03390276 0.08032572 0.03164231 -0.03313994 0.08000218 0.03244465 -0.03316974 0.08036684 0.03198635 -0.03314149 0.08010697 0.03218996 -0.03239417 0.08024048 0.03253501 -0.0323112 0.08007776 0.03279155 -0.03162562 0.08021819 0.03317809 -0.03169238 0.08003991 0.0333994 -0.03103703 0.08023965 0.0337693 -0.03122115 0.08007103 0.03380012 -0.03077095 0.08000397 0.03460019 -0.03063338 0.0801683 0.03434181 -0.03010642 0.08028286 0.0350281 -0.03023386 0.08011394 0.03506332 -0.02986192 0.08007436 0.03591167 -0.02974325 0.08000284 0.03670418 -0.02950328 0.08020782 0.03647053 -0.02938133 0.08014065 0.037059 -0.0291264 0.080352 0.03764933 -0.02936416 0.0800665 0.03761583 -0.02913558 0.08019429 0.0382114 -0.02923142 0.08007627 0.0386241 -0.02909141 0.08680319 0.03896635 -0.02921885 0.08689922 0.03825581 -0.02933937 0.08698624 0.03915876 -0.0291475 0.08676278 0.0378524 -0.02952229 0.0869922 0.03748983 -0.02943956 0.08690053 0.03703194 -0.03001087 0.08699005 0.03590661 -0.02972751 0.08682101 0.03591829 -0.03010243 0.08686447 0.03524023 -0.03068149 0.08681678 0.034258 -0.03061449 0.08692008 0.03454422 -0.03143191 0.0869947 0.03377497 -0.03142285 0.0869534 0.03364908 -0.03148007 0.08682298 0.03335493 -0.03222817 0.08676785 0.03266745 -0.03233331 0.08691906 0.03277224 -0.03282827 0.08675515 0.03224766 -0.03307718 0.08699703 0.03249984 -0.03311181 0.08692467 0.03225755 -0.03351992 0.08679187 0.03188943 -0.03421664 0.08698201 0.03187304 -0.03418755 0.08686101 0.03165572 -0.0350393 0.08673405 0.03129643 -0.03496122 0.08686763 0.03142201 -0.03539121 0.08699131 0.03153532 -0.03583663 0.08684808 0.03121942 -0.03622198 0.08696085 0.03132933 -0.0366286 0.08682858 0.03111803 -0.03748732 0.08699452 0.03139585 -0.03755855 0.08690524 0.03121531 -0.03815805 0.08682101 0.03119498 -0.03899735 0.08674097 0.03131097 -0.0387901 0.08691221 0.031412 -0.03954291 0.0869894 0.03178477 -0.0398361 0.08682143 0.03162723 -0.04068362 0.08678287 0.03198337 -0.04065304 0.08698767 0.03226971 -0.04144549 0.08681851 0.03247952 -0.04140728 0.08696484 0.03268098 -0.04210567 0.08679646 0.0329582 -0.04234492 0.08689904 0.03328806 -0.04239642 0.08699637 0.03365242 -0.04283106 0.08679634 0.03364813 -0.04322963 0.086914 0.03431737 -0.04370504 0.08675915 0.03474414 -0.04336905 0.08699172 0.03480434 -0.04384487 0.0868858 0.03520023 -0.04406678 0.08697366 0.0359888 -0.04430454 0.08681988 0.03599387 -0.04471218 0.08675336 0.03710591 -0.04458063 0.08689248 0.03707909 -0.04435777 0.08699327 0.03695815 -0.04483282 0.08684992 0.0382381 -0.0446856 0.08695518 0.03826636 -0.04458546 0.08699738 0.03936135 -0.04491513 0.08678913 0.03915792 -0.0447756 0.08691406 0.03960961 -0.04443907 0.08699202 0.04072493 -0.04472208 0.08681571 0.04067426 -0.04458808 0.08674556 0.0413562 -0.04424989 0.08693164 0.04181158 -0.04405117 0.08676588 0.04264789 -0.04363691 0.08699595 0.04269558 -0.04364502 0.08688819 0.04313915 -0.04309749 0.08695203 0.04377174 -0.04334908 0.08681482 0.04370659 -0.04210764 0.08699941 0.044622 -0.04269176 0.08678573 0.04450625 -0.04196178 0.08691513 0.04501509 -0.04181176 0.08682328 0.04526472 -0.04082906 0.08698272 0.04563403 -0.04072231 0.0868889 0.04588973 -0.0402463 0.08675611 0.04624783 -0.03943872 0.08689194 0.0464366 -0.03925508 0.08699584 0.04626214 -0.03842502 0.08675903 0.04680901 -0.03819376 0.08693301 0.04668092 -0.03745043 0.08699709 0.04657822 -0.03741759 0.0867927 0.046902 -0.03647041 0.08695542 0.04671597 -0.03660523 0.08678674 0.0469104 -0.03554916 0.08685392 0.04673677 -0.03504359 0.08675193 0.04669457 -0.03487515 0.08699202 0.04633003 -0.03434056 0.08681732 0.04643553 -0.03393447 0.08689969 0.04618364 -0.03352975 0.08676731 0.04612886 -0.03355687 0.08699494 0.04578936 -0.0330519 0.08690065 0.04574203 -0.03263098 0.08666187 0.04568636 -0.03232288 0.08696341 0.04512757 -0.03204566 0.08683484 0.04513299 -0.03130161 0.08676666 0.04451441 -0.03142327 0.08690929 0.04444599 -0.03134793 0.08699488 0.04411166 -0.03066068 0.08677935 0.04375612 -0.03087139 0.08694249 0.04374688 -0.03035843 0.08687031 0.04317575 -0.03033399 0.08699411 0.04271268 -0.02991497 0.0867238 0.04261773 -0.02985596 0.08689087 0.04220664 -0.02967089 0.08680295 0.04196047 -0.02969831 0.08699762 0.04111725 -0.02938222 0.0867868 0.0411657 -0.02946418 0.08695358 0.04073405 -0.02918928 0.08681923 0.04019892 -0.02800863 0.08138239 0.03921514 -0.0281428 0.08113932 0.03925377 -0.0280742 0.08140832 0.04013615 -0.02817946 0.08121085 0.04033863 -0.02863246 0.08100312 0.04107969 -0.0283181 0.08104985 0.0399571 -0.02822929 0.08141392 0.04101091 -0.02855294 0.08106529 0.04134047 -0.028418 0.08118265 0.04134893 -0.02853095 0.08139115 0.04204481 -0.02877581 0.08119094 0.04243135 -0.02901226 0.08139795 0.04313832 -0.02918469 0.08103889 0.0428344 -0.02904611 0.08118528 0.04299664 -0.02986437 0.08100211 0.04378598 -0.02946436 0.08137768 0.04390859 -0.02961891 0.08121114 0.04401117 -0.02983689 0.08107274 0.04407739 -0.03009301 0.08139443 0.04477185 -0.03024321 0.08123785 0.04484552 -0.03112262 0.08101475 0.04536646 -0.0306921 0.08110529 0.04516196 -0.03088325 0.08141243 0.04559898 -0.03095513 0.08121514 0.04555892 -0.0315532 0.0814082 0.04616183 -0.03167122 0.0811764 0.04612165 -0.03232127 0.08131849 0.04666638 -0.03267759 0.08100539 0.04644834 -0.03233808 0.08107233 0.04643303 -0.03309768 0.0813784 0.04710304 -0.03312826 0.08120036 0.047019 -0.03335475 0.08107304 0.04698127 -0.03416454 0.08139961 0.04754287 -0.0339604 0.08118009 0.04736137 -0.0347498 0.08101159 0.04735767 -0.03475278 0.08117687 0.04760032 -0.03525245 0.08135128 0.04781723 -0.0356639 0.08111393 0.04772537 -0.03611278 0.08141392 0.04795438 -0.03590738 0.08100676 0.04754525 -0.03613471 0.08123493 0.04788839 -0.03700006 0.08107376 0.04778498 -0.03725862 0.08141863 0.04799962 -0.03698092 0.08127194 0.04795163 -0.03785753 0.08120507 0.04787045 -0.03803491 0.08100378 0.04753792 -0.03835922 0.08137083 0.04788893 -0.0385195 0.08106267 0.04762232 -0.03899586 0.08119446 0.04768007 -0.03925865 0.08139044 0.04770702 -0.03956919 0.08104783 0.04734539 -0.04010528 0.08139699 0.04744321 -0.04003578 0.08118623 0.04736602 -0.04081237 0.08100306 0.04672062 -0.04089784 0.08137243 0.04710388 -0.0406025 0.08105808 0.04696875 -0.04109948 0.08119302 0.04690641 -0.04171562 0.08138763 0.04665958 -0.04167401 0.08113992 0.04652363 -0.04240691 0.08139985 0.0461905 -0.04211455 0.08104127 0.04605525 -0.04244571 0.0812028 0.04605764 -0.04285079 0.08100622 0.0453453 -0.04311269 0.08139652 0.04560035 -0.04306519 0.08117508 0.04550111 -0.04374825 0.08136683 0.0449422 -0.04361337 0.0811308 0.04487895 -0.04393446 0.08103001 0.04425626 -0.04431217 0.0814256 0.04424607 -0.04424732 0.08122599 0.04421353 -0.04488837 0.08140176 0.04333579 -0.04473787 0.08114582 0.0433349 -0.04454451 0.08100545 0.0431658 -0.04495853 0.08125627 0.04308098 -0.04537212 0.08140498 0.04229503 -0.04530769 0.08121275 0.0422396 -0.04518729 0.08104753 0.04205435 -0.0457282 0.08140778 0.04120576 -0.04566001 0.08123451 0.04120779 -0.04569172 0.08109462 0.0404635 -0.04552841 0.08100378 0.0402382 -0.04595571 0.08138656 0.0398879 -0.04588508 0.08122563 0.03987038 -0.04583048 0.08111321 0.03897744 -0.04598498 0.08134925 0.03875607 -0.04563128 0.08101564 0.03849828 -0.04591882 0.08138644 0.03783375 -0.04583144 0.08121937 0.0376901 -0.04508161 0.08100229 0.03603881 -0.04565721 0.08105802 0.03772395 -0.04576134 0.0813868 0.03696435 -0.04547381 0.08114522 0.03638118 -0.04543924 0.08104282 0.03680026 -0.04550623 0.08136469 0.03608709 -0.04519152 0.08132326 0.03531378 -0.04495519 0.08109402 0.03523027 -0.04479783 0.0813868 0.03451681 -0.04454332 0.08119189 0.03426033 -0.04440295 0.08103913 0.03441649 -0.04393273 0.08100169 0.03391951 -0.04430174 0.0814256 0.03373944 -0.04399776 0.08121842 0.03346383 -0.04361659 0.08109718 0.03317385 -0.04359591 0.08139282 0.0328769 -0.04306882 0.08102601 0.03280407 -0.04306113 0.08123075 0.03244006 -0.04266756 0.08132815 0.0320267 -0.04244691 0.08111971 0.03204077 -0.04207283 0.08141899 0.03156733 -0.04183638 0.08101153 0.03182858 -0.04164952 0.08126109 0.03135728 -0.04136264 0.08114314 0.03128653 -0.04128837 0.08142834 0.03108775 -0.04078912 0.08134061 0.03085374 -0.04062014 0.0810014 0.03120887 -0.04060763 0.08109617 0.03096526 -0.04006099 0.08142089 0.03053766 -0.04004681 0.0812298 0.03060686 -0.03995341 0.0810343 0.03081214 -0.03920716 0.08134311 0.0302881 -0.03918325 0.08111852 0.03044229 -0.0388531 0.08101451 0.03056365 -0.03829526 0.08137696 0.03010052 -0.0381453 0.08123534 0.03013873 -0.03789007 0.0810979 0.03022885 -0.03752613 0.08100551 0.03039795 -0.03725904 0.08140099 0.03000229 -0.03703093 0.08121472 0.03008043 -0.03638648 0.08124583 0.03007894 -0.03653097 0.08104175 0.03029459 -0.03607028 0.08140969 0.03005045 -0.03577947 0.08109569 0.03027981 -0.03499007 0.08137637 0.03022927 -0.0353474 0.08100754 0.0305444 -0.03520286 0.08121114 0.03026753 -0.0346626 0.08110982 0.03048634 -0.0339154 0.08136683 0.03055399 -0.03398495 0.08112347 0.0306878 -0.03328961 0.08133131 0.03082036 -0.03400337 0.08100426 0.03093773 -0.03291821 0.08113384 0.03114056 -0.0326904 0.08137863 0.03110617 -0.03284674 0.08102989 0.03136593 -0.03171241 0.08138823 0.03171747 -0.03202033 0.08117121 0.03163284 -0.03187733 0.08100914 0.03205245 -0.03128194 0.0811572 0.03221082 -0.03086799 0.08139413 0.03241789 -0.03055268 0.08106762 0.03304439 -0.0306192 0.08118313 0.03280276 -0.03008896 0.08137756 0.03323781 -0.03044098 0.08100402 0.03342437 -0.03010386 0.08117771 0.03338694 -0.02943342 0.08139413 0.03413456 -0.02943056 0.08118933 0.0343104 -0.02947819 0.08107411 0.03447711 -0.0289911 0.08139044 0.03490442 -0.02926582 0.08100801 0.0351535 -0.028889 0.08119064 0.03533327 -0.02863126 0.08141058 0.03569459 -0.02861058 0.08111137 0.0362392 -0.02853059 0.08124822 0.03614348 -0.02860349 0.08100241 0.0369594 -0.02833831 0.08140063 0.03656762 -0.02853584 0.08103579 0.03696972 -0.02827852 0.08119326 0.03719449 -0.02813988 0.08140748 0.03743326 -0.02811443 0.08121877 0.03815126 -0.02830904 0.08104163 0.03825062 -0.02802801 0.08140707 0.0383234 -0.02800887 0.08562475 0.03919434 -0.02802622 0.08559042 0.03834342 -0.0281803 0.08561378 0.03720933 -0.02855676 0.08559834 0.03587979 -0.02900171 0.08559477 0.03487962 -0.02942895 0.08560019 0.03414022 -0.02994692 0.08560067 0.03341484 -0.03053885 0.08561187 0.03274184 -0.03119003 0.08559173 0.0321294 -0.03191632 0.08556741 0.03157317 -0.03353619 0.08559036 0.03069573 -0.03459471 0.08558917 0.03032481 -0.03566348 0.08559614 0.03010272 -0.03681331 0.08560252 0.03000098 -0.03791767 0.08559346 0.0300495 -0.03880017 0.08559477 0.03018468 -0.03983139 0.08559566 0.03045523 -0.04091018 0.08563309 0.0309031 -0.04168498 0.08557993 0.03131687 -0.04243946 0.08559775 0.0318337 -0.04309505 0.08561182 0.03238481 -0.04389089 0.08562058 0.03321278 -0.04456347 0.08558607 0.03412538 -0.0450046 0.08559304 0.03489142 -0.04538565 0.08566743 0.03577417 -0.04573202 0.08560949 0.03682065 -0.04592889 0.0856046 0.0379036 -0.04600232 0.0855894 0.03903394 -0.04589217 0.08561289 0.04038608 -0.04565817 0.08559775 0.04144525 -0.04529523 0.08561903 0.04248839 -0.04478096 0.08559364 0.04351752 -0.04431378 0.0856018 0.04423856 -0.04370743 0.08562338 0.04499077 -0.0431115 0.08560955 0.04560035 -0.04223179 0.0856086 0.04632276 -0.04114574 0.08561968 0.0469864 -0.03988987 0.08560878 0.04752397 -0.03874188 0.08559983 0.04782658 -0.03790014 0.08559304 0.04795229 -0.03701597 0.0856018 0.04799634 -0.03584599 0.08562368 0.04792296 -0.03481245 0.08563435 0.04772114 -0.03388708 0.08559936 0.04744112 -0.03307425 0.08561241 0.04709273 -0.03213733 0.08560144 0.04657453 -0.03090423 0.0855903 0.04561853 -0.03011333 0.08560419 0.04479497 -0.02943873 0.08562779 0.04386752 -0.02894473 0.08566063 0.04298722 -0.02856737 0.085666 0.04210907 -0.02827817 0.08560478 0.04122191 -0.02806824 0.08560216 0.04007416 -0.02809786 0.08576542 0.03828477 -0.02811807 0.08582186 0.03947025 -0.02830845 0.08595424 0.03810453 -0.02835458 0.08599096 0.03903388 -0.02821803 0.08577769 0.03741466 -0.02847903 0.08591938 0.03686529 -0.02848255 0.08578062 0.03633224 -0.02888637 0.08599716 0.03614991 -0.02887248 0.08592575 0.03569167 -0.02888786 0.08581387 0.03533965 -0.02948361 0.0859965 0.03481018 -0.02923905 0.08584421 0.0346893 -0.02967804 0.08591592 0.03412908 -0.02974069 0.08576768 0.03380042 -0.03024601 0.08594524 0.03343588 -0.03027921 0.08577829 0.03312611 -0.0311402 0.08599799 0.03272825 -0.03089326 0.08575731 0.03247737 -0.0312829 0.08592516 0.03232997 -0.03158259 0.085734 0.03187614 -0.0322135 0.08588111 0.03157156 -0.03254103 0.08564782 0.031192 -0.03260022 0.08599317 0.03158611 -0.0332815 0.08576506 0.03087389 -0.03336143 0.08592319 0.03100848 -0.03424996 0.08599466 0.03082656 -0.03435379 0.08582484 0.03050595 -0.03523683 0.08581537 0.03027838 -0.03570771 0.08594989 0.03035807 -0.03638321 0.08579581 0.0301029 -0.0368697 0.08598542 0.03034341 -0.03746175 0.08580732 0.03010773 -0.0381146 0.08592182 0.03029012 -0.03850877 0.08599495 0.0305171 -0.03858965 0.08580201 0.03023147 -0.03945297 0.08595669 0.03062248 -0.03988152 0.0857619 0.03053921 -0.04033339 0.08585274 0.03078466 -0.04076838 0.08599734 0.0312761 -0.04106491 0.08589404 0.03116816 -0.04182994 0.08577072 0.03148722 -0.04190343 0.08596748 0.03180384 -0.04265224 0.08589869 0.0322268 -0.04295092 0.0857526 0.03232401 -0.04339653 0.08599907 0.03325182 -0.04371774 0.08579987 0.03314572 -0.04372656 0.08593153 0.03338384 -0.04437917 0.08579462 0.03399419 -0.04431802 0.08595693 0.03425449 -0.04493057 0.08578991 0.03492641 -0.04479509 0.08596879 0.03513044 -0.04521059 0.0858699 0.0357086 -0.04510796 0.08599442 0.03605616 -0.04559868 0.08582544 0.03671991 -0.04549133 0.08596312 0.0371015 -0.04584312 0.08578616 0.03786247 -0.04575055 0.08592122 0.03819125 -0.04558652 0.08599621 0.038594 -0.04595184 0.08573311 0.03896152 -0.04578834 0.08591681 0.03926044 -0.04586911 0.0857585 0.04008656 -0.04568064 0.08592128 0.04035359 -0.04543536 0.08599805 0.04065853 -0.04563641 0.08578431 0.04123538 -0.04536712 0.08591598 0.04172247 -0.04498583 0.08599632 0.04220181 -0.04528582 0.08578705 0.04229903 -0.04493314 0.08578372 0.04307621 -0.04471802 0.08592939 0.04316937 -0.04449117 0.08579838 0.04382032 -0.04403859 0.08594053 0.04421001 -0.04383218 0.08599662 0.04423213 -0.04397857 0.08577358 0.04456669 -0.04332709 0.08582383 0.04524284 -0.04299938 0.08596408 0.04531496 -0.0426554 0.08582025 0.04586946 -0.04105132 0.08599704 0.04661184 -0.04200685 0.08579468 0.04637092 -0.04188382 0.08591586 0.04630988 -0.041013 0.08578783 0.0469678 -0.04078137 0.08592343 0.0469315 -0.03999584 0.08574283 0.04742872 -0.03934425 0.08587288 0.04752892 -0.03917795 0.08598911 0.04736584 -0.03922259 0.08573907 0.04766547 -0.03831768 0.08584225 0.04777985 -0.03752315 0.08595311 0.04772102 -0.0374723 0.08577632 0.04791057 -0.03657186 0.08599019 0.04764628 -0.03653627 0.08578866 0.04790657 -0.03533971 0.08599603 0.04745954 -0.03545439 0.08587521 0.04771089 -0.03434312 0.08579629 0.04750764 -0.03399682 0.08595252 0.04720616 -0.03333646 0.08582383 0.04710501 -0.03295457 0.08598864 0.04663246 -0.03233379 0.08577692 0.0466054 -0.03196799 0.08590197 0.04624086 -0.03150868 0.08566367 0.04611009 -0.0312103 0.08599424 0.04539853 -0.03088176 0.08575117 0.04551792 -0.03079688 0.08588248 0.04528927 -0.03014862 0.08583837 0.04465872 -0.0300498 0.08599501 0.04409742 -0.02956736 0.08585882 0.04382151 -0.02952498 0.08594906 0.04351407 -0.02899557 0.08585095 0.04281622 -0.02906733 0.08599025 0.04242068 -0.02854657 0.08590203 0.04150623 -0.02851295 0.08599174 0.04055023 -0.02819144 0.08573973 0.0405609 -0.02828431 0.08589762 0.04031902 0.003121733 0.07890754 -0.007271647 0.003325343 0.07889562 -0.008629143 0.003215372 0.0790044 -0.008713006 0.00302881 0.07904696 -0.007231712 0.004572689 0.07890868 -0.009209573 0.00458461 0.07904773 -0.009308815 0.005646705 0.07889527 -0.008350253 0.005773246 0.07900339 -0.008406162 0.005524456 0.07890766 -0.006984889 0.005604922 0.07904577 -0.0069229 0.004246592 0.07889598 -0.006480157 0.004229068 0.0790044 -0.006343841 0.005635023 0.08057665 -0.006902873 0.004225015 0.08057647 -0.006298542 0.005815625 0.0805763 -0.008423984 0.004589021 0.08057707 -0.00934565 0.003177285 0.08057665 -0.008739709 0.002996265 0.08057659 -0.007216691 0.003469407 0.08058744 -0.00549519 0.004235148 0.07183814 -0.009289979 0.00376445 0.07183802 -0.008992493 0.004751503 0.07183796 -0.009057402 0.003410935 0.07183766 -0.008918642 0.005302906 0.07184952 -0.008724153 0.003209888 0.07183796 -0.008507847 0.003090322 0.0718376 -0.008488893 0.00556463 0.07184135 -0.008348345 0.002937495 0.07182776 -0.008008897 0.002938985 0.0718314 -0.007792711 0.005720496 0.07183879 -0.007806599 0.002991974 0.07183414 -0.007401645 0.005549788 0.07183778 -0.007081925 0.005103588 0.07183784 -0.006598532 0.004295349 0.07183945 -0.006350994 0.004607379 0.0718376 -0.006357014 0.005858004 0.07758486 -0.007632195 0.005732536 0.07757544 -0.00718975 0.005472004 0.0775184 -0.006785035 0.004871904 0.07751166 -0.006410181 0.003863871 0.0775882 -0.006660044 0.005108475 0.07758796 -0.006637513 0.004155158 0.07748556 -0.00636202 0.004486262 0.0775879 -0.006501555 0.00361216 0.07746654 -0.006571769 0.00346148 0.0775783 -0.006969034 0.003099799 0.07743638 -0.007111012 0.003216087 0.07757055 -0.007372856 0.002920269 0.07739049 -0.007721066 0.003133237 0.0775153 -0.008029937 0.002983689 0.07736939 -0.008241653 0.0034464 0.07748419 -0.008668899 0.00320363 0.07734882 -0.008690953 0.003566384 0.07733553 -0.00904721 0.003881216 0.07746022 -0.008983194 0.00403285 0.07731306 -0.00925827 0.004364073 0.07743871 -0.009095609 0.004538595 0.07728976 -0.009301483 0.004833936 0.07741743 -0.009025573 0.005026578 0.07727724 -0.009168863 0.005263507 0.07739555 -0.00876224 0.005440175 0.07725679 -0.008884668 0.005542635 0.07737576 -0.008402585 0.005732715 0.07723671 -0.008493483 0.005684077 0.0773518 -0.007890522 0.005877852 0.07723748 -0.007932901 0.005801498 0.0771926 -0.007309198 0.005598664 0.07732939 -0.007374644 0.005574524 0.07717043 -0.006901144 0.005307614 0.07730525 -0.006903409 0.005393683 0.0771861 -0.006722509 0.005044877 0.07714849 -0.006478071 0.004682838 0.07727372 -0.006569683 0.004550933 0.07712411 -0.006340146 0.004150927 0.07725048 -0.006571352 0.003966987 0.07710403 -0.006400763 0.003617763 0.07722508 -0.006810009 0.003473997 0.0770865 -0.006666541 0.003104984 0.07706332 -0.00709474 0.00325483 0.07719898 -0.007266044 0.002935051 0.07704198 -0.007610023 0.003124892 0.07717275 -0.007859468 0.002941548 0.07703751 -0.008088767 0.003269731 0.07714802 -0.008403062 0.003226995 0.07702159 -0.008715391 0.003549158 0.07712769 -0.008762836 0.003583908 0.07698249 -0.0090577 0.004005193 0.07710444 -0.0090366 0.003967165 0.07696193 -0.009239435 0.004518687 0.07693982 -0.009305536 0.004505932 0.07708227 -0.009092152 0.005073547 0.07692313 -0.009145915 0.00503844 0.07705813 -0.008933722 0.005528509 0.07690078 -0.008801341 0.005533337 0.07702714 -0.008446574 0.005818545 0.0769003 -0.008280396 0.005683481 0.07699084 -0.007620036 0.005881369 0.0768541 -0.00761801 0.005743622 0.07683157 -0.007183194 0.005369544 0.07695889 -0.00698179 0.005492806 0.07681924 -0.006812274 0.004948377 0.07693642 -0.006665945 0.005056738 0.07679998 -0.006485462 0.004520833 0.07691669 -0.006551146 0.004543304 0.07678228 -0.006341278 0.004055142 0.07689613 -0.006597161 0.004032313 0.07675963 -0.006384074 0.003625333 0.07687491 -0.006808459 0.003607273 0.07673621 -0.006571233 0.003240346 0.07672923 -0.006897985 0.003296494 0.07685279 -0.007192313 0.002985417 0.07669979 -0.007385373 0.003140985 0.07683128 -0.007663369 0.002940416 0.07669925 -0.008056521 0.00317806 0.07680827 -0.008187055 0.003148615 0.07665467 -0.008607089 0.003496766 0.07678061 -0.008719444 0.003518879 0.07663488 -0.00901246 0.003918588 0.07675868 -0.009000897 0.003918051 0.07661485 -0.009221076 0.004364609 0.07659983 -0.00930351 0.004369854 0.07673817 -0.009093761 0.004936039 0.07671278 -0.008991479 0.004991054 0.07659906 -0.00918734 0.005394577 0.07668721 -0.008627176 0.005379796 0.07655072 -0.008940696 0.005680441 0.07654201 -0.008577942 0.005626916 0.07666563 -0.008188486 0.005874395 0.07652276 -0.008058547 0.005679309 0.07664316 -0.007687509 0.005868256 0.0764954 -0.007576644 0.005759477 0.07651025 -0.00723505 0.005451977 0.07661521 -0.007079243 0.005459308 0.07648998 -0.006783604 0.005036115 0.07659053 -0.006711125 0.005153119 0.07644844 -0.006531 0.004541099 0.07656723 -0.006551325 0.004587113 0.07643091 -0.006349325 0.00404042 0.07641083 -0.006380558 0.00403136 0.07654529 -0.006600618 0.003570079 0.07639205 -0.006593585 0.003587961 0.07652294 -0.006839692 0.003213226 0.07637202 -0.006936788 0.003264248 0.07649999 -0.007254302 0.002989768 0.07635104 -0.007373094 0.003136873 0.07648009 -0.007683575 0.002921879 0.07633298 -0.007882714 0.003183364 0.07645815 -0.00818181 0.003043591 0.07631653 -0.008404493 0.003439307 0.07643467 -0.008660554 0.003431141 0.07631033 -0.008943915 0.00381577 0.07641321 -0.008948326 0.003975927 0.07628738 -0.00922966 0.00428915 0.07639199 -0.009093642 0.00451219 0.07624417 -0.00930655 0.004838943 0.07636761 -0.009025394 0.005043387 0.07622915 -0.009161174 0.005412638 0.07633721 -0.008624911 0.00541222 0.07620745 -0.008916199 0.00571084 0.07618749 -0.008533895 0.005659878 0.07630932 -0.008058786 0.005881845 0.0761643 -0.008014082 0.00562632 0.07628154 -0.00740844 0.00583893 0.07614839 -0.007441937 0.00558561 0.07611781 -0.006907463 0.005269646 0.07625269 -0.006880283 0.005300641 0.07613193 -0.006643891 0.004763543 0.07622766 -0.006592094 0.004640579 0.07610505 -0.006351828 0.00406754 0.07619726 -0.006577372 0.003996014 0.07606416 -0.00639528 0.003595113 0.07604163 -0.006574511 0.003466665 0.07616567 -0.006952285 0.003219366 0.07601726 -0.006923437 0.003207802 0.07614368 -0.00738424 0.002965807 0.07599717 -0.007452905 0.003131628 0.07611948 -0.007933795 0.002934634 0.07597965 -0.008012175 0.003120124 0.07597929 -0.00856781 0.00331372 0.07609343 -0.008488714 0.003768086 0.07606595 -0.008932769 0.003582835 0.07593309 -0.00905317 0.00408113 0.07591468 -0.009272038 0.004307031 0.07604122 -0.009093999 0.004496991 0.07589042 -0.009299993 0.004759848 0.07602089 -0.009044289 0.004934608 0.07587814 -0.009206354 0.005231857 0.07599759 -0.008799076 0.00541538 0.07585984 -0.008913159 0.005541384 0.07597547 -0.008401513 0.005733668 0.07583874 -0.008486866 0.00568521 0.07595133 -0.007864892 0.005878567 0.07581859 -0.008012473 0.005797684 0.07581347 -0.007296502 0.005540847 0.07592153 -0.007214784 0.005416393 0.07576805 -0.006737053 0.005122601 0.07589507 -0.00676763 0.004971325 0.07574635 -0.00644648 0.004716575 0.07587558 -0.006582617 0.004483819 0.07573264 -0.006339371 0.004166185 0.07585084 -0.006563842 0.004046261 0.07570999 -0.006378054 0.003659844 0.07582718 -0.006785452 0.003624737 0.07568931 -0.006558656 0.003227055 0.0756697 -0.006914019 0.003350913 0.07580727 -0.007106125 0.002978384 0.0756517 -0.007421433 0.003157019 0.07578539 -0.007562756 0.002925753 0.07563912 -0.007844865 0.00317341 0.07575786 -0.008200168 0.002998292 0.07561826 -0.008309543 0.003446578 0.07561022 -0.00895673 0.00352323 0.07572942 -0.008739411 0.003893136 0.07570993 -0.008990287 0.004064917 0.07558321 -0.00926125 0.004431545 0.07568526 -0.009100735 0.004522323 0.07554417 -0.009303748 0.004968762 0.07566154 -0.008966803 0.005010962 0.07551771 -0.009179055 0.005416631 0.07551372 -0.008906781 0.005326509 0.07564169 -0.008702874 0.005688607 0.07548964 -0.008566677 0.005606472 0.07561844 -0.008258759 0.00588423 0.07546782 -0.008010387 0.005675792 0.07558983 -0.007596909 0.005788445 0.07546186 -0.007277548 0.005395233 0.07556128 -0.007017612 0.005371868 0.07543545 -0.006697773 0.005038022 0.07554072 -0.006709992 0.005135118 0.07539612 -0.00652486 0.004639148 0.07538205 -0.006356477 0.004449069 0.0755133 -0.006539225 0.004036009 0.07536309 -0.006378352 0.003786563 0.07548391 -0.006695628 0.003540217 0.07533687 -0.006610214 0.003362715 0.07545781 -0.007091462 0.003050506 0.07533282 -0.007209539 0.003153741 0.07543617 -0.007553756 0.002928078 0.07530516 -0.007889747 0.003159821 0.07541221 -0.008090853 0.003013908 0.07526642 -0.008343875 0.003356516 0.07539069 -0.008545517 0.00325644 0.07524639 -0.00876379 0.003648459 0.07537198 -0.008846342 0.003651678 0.07522743 -0.009102165 0.004244446 0.07534438 -0.00910145 0.004165887 0.07520997 -0.009285151 0.004789948 0.07520604 -0.009252607 0.004931032 0.07531285 -0.008987605 0.005092263 0.07516831 -0.00914067 0.005412936 0.0752865 -0.008611381 0.005520761 0.0751518 -0.008800208 0.005833387 0.07514852 -0.008229017 0.005658805 0.07526081 -0.008082807 0.005877614 0.07510405 -0.007638096 0.005652129 0.07523757 -0.007559418 0.005714356 0.07508474 -0.007117092 0.005392909 0.07520979 -0.006987929 0.005358278 0.07505822 -0.006677091 0.004749596 0.07517713 -0.006585776 0.004888892 0.07506424 -0.006427228 0.004328191 0.07504284 -0.00634104 0.003997743 0.07514369 -0.006595492 0.003806591 0.07502239 -0.006474792 0.003380298 0.07500296 -0.006759405 0.003448367 0.07511454 -0.006979167 0.003035664 0.07495975 -0.00723952 0.003195762 0.07509267 -0.00740689 0.002923727 0.07493704 -0.007792353 0.003147006 0.07506263 -0.008083999 0.003020167 0.07491642 -0.008363723 0.003406584 0.07503688 -0.008613348 0.003324389 0.07489275 -0.00883907 0.003860354 0.07501149 -0.008981168 0.003884613 0.07489109 -0.009213328 0.004574 0.07497912 -0.009099125 0.004571676 0.07486444 -0.009291887 0.005017936 0.07482504 -0.009176731 0.005327343 0.07494282 -0.008728563 0.005606591 0.07481837 -0.008698999 0.005633473 0.07491409 -0.008160173 0.005876421 0.07476896 -0.008027493 0.005671739 0.07489079 -0.007629573 0.005854785 0.0747506 -0.007476687 0.005495011 0.07486867 -0.007157742 0.005649983 0.07473504 -0.007013976 0.005180895 0.07484817 -0.006810605 0.005339026 0.07471168 -0.006665885 0.004651784 0.07482206 -0.006557047 0.00493592 0.07468819 -0.006435453 0.004440367 0.07467734 -0.006333231 0.0039348 0.07479095 -0.006628811 0.003870904 0.07465463 -0.006438612 0.003375589 0.07463556 -0.006739914 0.003416359 0.07476282 -0.007006466 0.002990245 0.07460325 -0.007374286 0.003179907 0.07473886 -0.007482886 0.002923369 0.07459414 -0.00783509 0.003133058 0.07472038 -0.007914721 0.002998828 0.07456648 -0.008303761 0.003244578 0.07470047 -0.008345782 0.003273189 0.07454711 -0.008778512 0.003552019 0.07467728 -0.008771359 0.003650665 0.07452458 -0.009098052 0.004168033 0.07464748 -0.00909096 0.004117846 0.07453107 -0.009275138 0.004784166 0.074485 -0.009256005 0.004837036 0.07461762 -0.009020984 0.005280792 0.07448548 -0.009020507 0.005265414 0.07459586 -0.008769035 0.005681991 0.07446229 -0.008560717 0.005610704 0.07456827 -0.008255302 0.005866587 0.07444202 -0.008051216 0.005678951 0.07454502 -0.007722973 0.005883693 0.07440155 -0.007658541 0.005511105 0.07451933 -0.007171869 0.005736649 0.07438433 -0.007168114 0.005380928 0.07438594 -0.006703078 0.005120217 0.07449495 -0.006762504 0.00487709 0.07434535 -0.006414115 0.004706919 0.07447487 -0.006583273 0.004407525 0.07432407 -0.006336152 0.004122793 0.07444965 -0.006568908 0.003741085 0.07431972 -0.006493866 0.003480613 0.07441705 -0.006924688 0.003269851 0.07429653 -0.006880939 0.003003716 0.07427626 -0.007353127 0.003164649 0.0743879 -0.007516324 0.00291723 0.07423567 -0.007849693 0.003142952 0.0743665 -0.007988572 0.003017485 0.0742138 -0.008338809 0.003313601 0.07434403 -0.008484184 0.003297865 0.07419484 -0.008813023 0.003609716 0.07432436 -0.008815109 0.003707766 0.07418119 -0.009130239 0.003983438 0.07430541 -0.009024143 0.004124104 0.0741595 -0.009281218 0.004473805 0.07428389 -0.009094595 0.004843354 0.07415395 -0.009239733 0.00496298 0.07426136 -0.00897336 0.005415678 0.0741077 -0.008907794 0.005514919 0.07422977 -0.008484244 0.005756199 0.0740897 -0.008448481 0.005676805 0.07420217 -0.007896959 0.005881726 0.07408523 -0.007873773 0.005621373 0.07418209 -0.00743401 0.005767464 0.07403904 -0.007219672 0.005328655 0.07415658 -0.006926894 0.005515873 0.07401734 -0.006826639 0.005324184 0.07403254 -0.00666064 0.004835605 0.07413077 -0.006622493 0.004925847 0.07399368 -0.006427705 0.004323303 0.07410794 -0.006542503 0.004422187 0.0739693 -0.006333053 0.003845691 0.07394921 -0.006444275 0.003827929 0.07408529 -0.006686329 0.003377377 0.07393169 -0.006751596 0.003322362 0.07405608 -0.007115423 0.003130614 0.07391661 -0.00706762 0.002971768 0.07390403 -0.007431209 0.003121435 0.07401973 -0.007940888 0.002937316 0.0738728 -0.008053839 0.003142058 0.07387721 -0.008604586 0.003368914 0.07398962 -0.008567631 0.003606677 0.07383024 -0.00906974 0.003730714 0.07396775 -0.008900225 0.004166185 0.07394725 -0.009074985 0.004133343 0.07380843 -0.009283304 0.004675507 0.07378715 -0.009282946 0.004788815 0.07392036 -0.009050488 0.005185902 0.07376831 -0.009083092 0.005423367 0.07388567 -0.008610785 0.005608916 0.0737459 -0.008700907 0.005852997 0.07374548 -0.008156001 0.005656123 0.07385969 -0.008062779 0.005641877 0.07383364 -0.007459402 0.005861818 0.07369863 -0.007515728 0.005648016 0.07367795 -0.007005274 0.005293428 0.07380408 -0.006901681 0.0052675 0.07365858 -0.006614208 0.004847347 0.07378166 -0.006623625 0.004713237 0.07362812 -0.006361007 0.004411101 0.07376188 -0.00654608 0.004362642 0.07364368 -0.006344735 0.003868758 0.07373738 -0.006659567 0.003941059 0.07360601 -0.006408631 0.003307402 0.07359969 -0.00681889 0.003487884 0.07371693 -0.006938099 0.003246426 0.07369798 -0.007290363 0.003008902 0.07357597 -0.007355272 0.003132045 0.07367646 -0.007772743 0.002920985 0.07353657 -0.007839798 0.003198146 0.0736559 -0.008237063 0.003020882 0.07350981 -0.008360147 0.003285169 0.0734964 -0.008794546 0.003436803 0.07363462 -0.00864458 0.00379461 0.07361483 -0.008943378 0.003786504 0.07349503 -0.009179532 0.004245042 0.07359367 -0.009085416 0.004493236 0.07344502 -0.009301424 0.00476861 0.07357043 -0.009046316 0.005075514 0.07344537 -0.009144783 0.005363404 0.07354068 -0.008688807 0.005569219 0.0733956 -0.008746623 0.005827009 0.07337814 -0.008248925 0.005654036 0.07351082 -0.008082151 0.005887269 0.07336294 -0.007849335 0.005663692 0.07348906 -0.007585287 0.00584799 0.07335007 -0.007460534 0.005406796 0.07346147 -0.007022202 0.00561434 0.07332706 -0.006961643 0.005172193 0.07329666 -0.006540775 0.004988908 0.07343822 -0.006685256 0.004845738 0.07331216 -0.006410837 0.00454837 0.07341748 -0.006555855 0.004159569 0.07328736 -0.006355106 0.003949284 0.07339179 -0.006617307 0.003494381 0.07324397 -0.00664705 0.003489673 0.07336676 -0.006938934 0.003140985 0.07321721 -0.007043659 0.003190934 0.07334285 -0.00740689 0.002927064 0.07321286 -0.007694303 0.003139078 0.07331758 -0.007964909 0.003020644 0.0731678 -0.008351147 0.003362119 0.07328981 -0.008576571 0.003300607 0.0731464 -0.008815109 0.003673017 0.0731343 -0.00911051 0.003834545 0.07326227 -0.008960485 0.004234313 0.07312756 -0.009288251 0.00431168 0.07324093 -0.009092986 0.004896402 0.07310187 -0.00922513 0.004971683 0.07321184 -0.008983373 0.005437731 0.07307738 -0.008874893 0.005466163 0.07318204 -0.008528172 0.005750179 0.07303673 -0.008454322 0.005648612 0.07316207 -0.008116364 0.005885124 0.07301861 -0.007958352 0.005654752 0.07313674 -0.007532238 0.005845367 0.07299393 -0.007451474 0.005402863 0.07311183 -0.007022976 0.00557357 0.07297879 -0.006897687 0.005038678 0.07309007 -0.006713449 0.005289316 0.07295459 -0.006626546 0.004806935 0.07293927 -0.006393551 0.004598498 0.07307022 -0.006562769 0.004153966 0.07293611 -0.006355404 0.00410062 0.07304853 -0.006575882 0.003547668 0.07288914 -0.006612241 0.003609836 0.07302397 -0.006827652 0.003145694 0.07286846 -0.007029235 0.003273427 0.0730012 -0.007222294 0.002944529 0.07284474 -0.007556736 0.003136634 0.07297849 -0.007719576 0.002950608 0.07282602 -0.008105158 0.003220379 0.07295179 -0.008321464 0.003189325 0.07282441 -0.008675873 0.003573715 0.07292622 -0.008785426 0.00362277 0.07277941 -0.009080946 0.004169106 0.07289731 -0.009091973 0.004144072 0.07275754 -0.009285271 0.004697382 0.07273685 -0.009278059 0.004808783 0.0728687 -0.009029328 0.00520271 0.07271748 -0.009071648 0.005293965 0.07284402 -0.008746027 0.005704343 0.07271164 -0.008558511 0.005653977 0.07281357 -0.008138656 0.005885004 0.07266616 -0.007953464 0.00563097 0.07278257 -0.007448136 0.005843341 0.07264357 -0.007442891 0.005616843 0.07262587 -0.006960093 0.005370974 0.07275938 -0.006986618 0.005244493 0.07261246 -0.006600439 0.004799544 0.07272922 -0.006589233 0.004644095 0.07260459 -0.006352961 0.004087448 0.07269722 -0.00658375 0.003923356 0.0725553 -0.006417095 0.003616869 0.07267487 -0.006818234 0.003516077 0.07255989 -0.006640315 0.003322422 0.07265508 -0.007149279 0.003159582 0.07253944 -0.007027447 0.002969503 0.07250034 -0.007445752 0.0031479 0.07263308 -0.00761348 0.002925634 0.07247895 -0.007920026 0.003153681 0.07261377 -0.008061587 0.003053128 0.07246732 -0.008440256 0.003314912 0.07259374 -0.00848186 0.003548562 0.0724554 -0.009035766 0.003651142 0.07257211 -0.008847832 0.004099845 0.07255041 -0.00906378 0.00419104 0.0724284 -0.009285271 0.004600286 0.07252782 -0.009078085 0.004650592 0.07238936 -0.009288012 0.005042195 0.07250797 -0.008929669 0.005286037 0.07238531 -0.009013772 0.005398988 0.07248687 -0.008620262 0.005607008 0.07234561 -0.00870198 0.005639791 0.07246363 -0.008153736 0.005869328 0.07234215 -0.008042693 0.005646586 0.07243388 -0.007459759 0.005832672 0.07231736 -0.007418274 0.005513727 0.07227128 -0.006833493 0.005281925 0.07240402 -0.006894528 0.005078315 0.07227176 -0.006497502 0.004888951 0.07238346 -0.006638109 0.004371821 0.07222092 -0.006334483 0.00442624 0.07236218 -0.006549239 0.003937542 0.07234114 -0.006629705 0.003948688 0.07222831 -0.006415128 0.003458797 0.07220655 -0.006684303 0.003519833 0.07231849 -0.006905615 0.003186762 0.07216793 -0.006975889 0.003209948 0.07229483 -0.007363796 0.002953052 0.07214617 -0.007497489 0.003131926 0.07227152 -0.00788325 0.002938449 0.07213324 -0.008038103 0.003286063 0.07224613 -0.008444666 0.003199934 0.07212388 -0.008690297 0.003734767 0.07221716 -0.008914053 0.003745794 0.07207506 -0.009153723 0.004355788 0.07218915 -0.009099662 0.004280984 0.07205492 -0.009297609 0.004913747 0.07205128 -0.00921899 0.004954099 0.07216185 -0.008980154 0.005427598 0.07200479 -0.008895039 0.005443751 0.07213419 -0.008570015 0.005770802 0.07198268 -0.008416831 0.005696415 0.07210266 -0.007890045 0.005893111 0.07195681 -0.007848501 0.005843639 0.07197052 -0.007492005 0.005459785 0.07206463 -0.007075011 0.00563234 0.07195031 -0.006994485 0.005282521 0.07190883 -0.00662142 0.004974007 0.07203727 -0.006681203 0.004790544 0.07188487 -0.006386876 0.004329204 0.07200807 -0.006530165 0.004165112 0.07188719 -0.006356298 0.003720104 0.07197988 -0.006748259 0.003663659 0.07186514 -0.006549417 0.003236711 0.07184422 -0.006915628 0.003387331 0.07196205 -0.007056355 0.003184914 0.07194077 -0.00744462 0.003142893 0.07191419 -0.008026897 0.003399968 0.07188606 -0.008619725 0.004028022 0.07184857 -0.009054005 0.003136038 0.07758653 -0.008008956 0.003347694 0.07757598 -0.008543491 0.003823876 0.07753771 -0.008966147 0.004469454 0.0775085 -0.009099781 0.005159676 0.07747435 -0.008868455 0.005553424 0.07744842 -0.0083732 0.005688369 0.07742482 -0.00785017 0.005592226 0.07740271 -0.00736159 0.005276203 0.07737702 -0.006873607 0.004749298 0.07735085 -0.00659275 0.004149794 0.0773245 -0.006563603 0.003579914 0.07729649 -0.00684297 0.003174066 0.07726538 -0.007440268 0.003152251 0.07723838 -0.008045911 0.00331676 0.07721805 -0.008481562 0.003705561 0.0771926 -0.008899331 0.004271209 0.07716685 -0.009087324 0.004881799 0.07713955 -0.00902009 0.005382716 0.07711255 -0.008638203 0.005609512 0.07709211 -0.008247613 0.005680084 0.07707279 -0.007810771 0.005573272 0.07705038 -0.007300198 0.005233645 0.07702416 -0.006843686 0.004752635 0.07700133 -0.00659573 0.00430113 0.07698106 -0.006548583 0.003822505 0.07695972 -0.006684958 0.003361046 0.07693254 -0.007079064 0.003158628 0.07690972 -0.007559955 0.003159165 0.07688605 -0.008110046 0.003495573 0.07685339 -0.00873512 0.004237353 0.07681864 -0.009100139 0.004842102 0.07679134 -0.009017348 0.00531131 0.07676702 -0.008728384 0.005591928 0.07674413 -0.008288681 0.0056836 0.07671499 -0.007636249 0.005381703 0.07668387 -0.006993114 0.004813015 0.07665419 -0.006599903 0.004029691 0.07661867 -0.006587386 0.003350257 0.07658296 -0.007075846 0.00313431 0.07655209 -0.007726609 0.003183543 0.07653182 -0.008188068 0.003443002 0.07650828 -0.0086627 0.003878355 0.07648473 -0.008983552 0.004303932 0.07646518 -0.009091138 0.004936158 0.07643699 -0.008996129 0.005491316 0.07640445 -0.008506357 0.005693554 0.0763722 -0.007800161 0.0055359 0.07634663 -0.007234215 0.005171298 0.07632172 -0.006789207 0.004664659 0.07629716 -0.006573796 0.004199028 0.07627683 -0.006563961 0.003666579 0.07625138 -0.00676912 0.003281235 0.07622563 -0.007224082 0.003119289 0.07619947 -0.007787823 0.003257691 0.07617396 -0.008370637 0.003540277 0.07615208 -0.008761584 0.003941059 0.07613158 -0.009007036 0.004398286 0.07611125 -0.009095013 0.004957795 0.0760858 -0.008982598 0.005414247 0.07606005 -0.008599162 0.005676686 0.07603275 -0.008043766 0.005613684 0.07600575 -0.007417082 0.005399703 0.07598531 -0.007019281 0.005064487 0.075966 -0.006730377 0.004573643 0.07594358 -0.006553947 0.004006862 0.07591736 -0.006604254 0.003543734 0.07589453 -0.006884157 0.003267109 0.07587426 -0.007244169 0.003132641 0.07585287 -0.007723271 0.003226697 0.07582575 -0.008322834 0.003530383 0.07580292 -0.0087471 0.003919541 0.07578313 -0.008997857 0.004403531 0.07576024 -0.009100854 0.004890501 0.07573908 -0.008998453 0.005407392 0.07571184 -0.008634686 0.00565356 0.0756846 -0.008076131 0.005653083 0.07566022 -0.007525086 0.005425512 0.07563734 -0.007055759 0.004943192 0.0756095 -0.006650924 0.004240214 0.07557827 -0.006549656 0.003698766 0.07555311 -0.006760358 0.003346741 0.0755316 -0.007103681 0.003155052 0.07550889 -0.007584869 0.003148436 0.07548856 -0.008039772 0.003298997 0.07546973 -0.008451938 0.003613531 0.07544791 -0.008819639 0.004026234 0.07542741 -0.009039998 0.004590213 0.07540267 -0.009089171 0.005143404 0.07537674 -0.008865594 0.005467236 0.07535594 -0.008525669 0.005672574 0.07533162 -0.008012831 0.00558865 0.07529997 -0.007306814 0.005170941 0.0752716 -0.006799697 0.004753887 0.07525092 -0.00659275 0.004294931 0.07523143 -0.006554245 0.00385648 0.07521086 -0.006666779 0.003478944 0.07519036 -0.006947636 0.003226757 0.07517004 -0.007339119 0.003122687 0.07514458 -0.007899999 0.003308475 0.07511883 -0.00846678 0.003601074 0.07509863 -0.008812069 0.003989994 0.07507926 -0.009024858 0.004622578 0.07505178 -0.00909233 0.005172908 0.07502478 -0.008838355 0.005551636 0.07499974 -0.008399724 0.005686938 0.0749672 -0.007701694 0.005392491 0.07493424 -0.006993472 0.004916846 0.07490915 -0.006654858 0.004408776 0.07488584 -0.006541728 0.003818094 0.07485908 -0.006681561 0.003381907 0.07483416 -0.007062077 0.003160476 0.07481062 -0.007523953 0.003156363 0.07478773 -0.008065104 0.00331819 0.07476747 -0.00848931 0.00365591 0.07474607 -0.008854746 0.004215896 0.07471895 -0.009088575 0.004736423 0.07469612 -0.009052097 0.005153834 0.07467633 -0.008851885 0.005495011 0.07465344 -0.008493542 0.005662798 0.07463222 -0.00802499 0.005623638 0.07460504 -0.007394134 0.005276679 0.07457774 -0.006891906 0.004806995 0.07455343 -0.006603777 0.004288017 0.07453054 -0.006551861 0.003843128 0.07451075 -0.006678938 0.003370583 0.07448297 -0.007053494 0.003146409 0.07445663 -0.007635772 0.003161966 0.07443559 -0.008115589 0.003356993 0.07441473 -0.008543193 0.003686308 0.07439434 -0.008872509 0.004191577 0.07437044 -0.009087204 0.004872381 0.0743395 -0.009014844 0.00528413 0.07431828 -0.008743643 0.005582869 0.07429587 -0.008328378 0.00568211 0.07426995 -0.00774008 0.005562067 0.07424914 -0.007286131 0.005170226 0.07422095 -0.006782352 0.004498124 0.07418966 -0.006543636 0.003936529 0.0741648 -0.006634652 0.003498494 0.07414168 -0.006918251 0.003145754 0.07411056 -0.007548034 0.00317651 0.07408356 -0.008153557 0.003476738 0.07405602 -0.008714795 0.004098474 0.07402372 -0.009064316 0.004806041 0.07399302 -0.009044945 0.005384981 0.0739628 -0.008648097 0.005650043 0.0739361 -0.008116602 0.005669474 0.07391679 -0.007672071 0.005511641 0.07389426 -0.007174611 0.005120873 0.07386821 -0.006761491 0.004645228 0.07384645 -0.006570279 0.004191994 0.07382625 -0.006562352 0.003726363 0.07380485 -0.006739795 0.003317654 0.07377904 -0.007148802 0.003148317 0.07375735 -0.007612228 0.003158628 0.07373726 -0.008075654 0.003359496 0.07371371 -0.008561193 0.003748714 0.07369101 -0.008911311 0.004348099 0.07366383 -0.009109973 0.004944086 0.07363653 -0.008975028 0.005386352 0.07361221 -0.008646905 0.00562781 0.07358932 -0.008184373 0.005675852 0.07356953 -0.007723987 0.005549252 0.07354664 -0.0072456 0.005237996 0.07352548 -0.006857275 0.004680037 0.07349824 -0.006560325 0.003955185 0.0734657 -0.006621599 0.003461956 0.07343935 -0.00695908 0.003218472 0.07341927 -0.007360816 0.003132045 0.07339853 -0.007816791 0.003202736 0.07337892 -0.008246004 0.00347805 0.07335597 -0.008701086 0.003954231 0.07333117 -0.009016871 0.004561185 0.07330381 -0.009095847 0.005148053 0.07327616 -0.008861899 0.005468904 0.07325613 -0.00852406 0.005662798 0.07323294 -0.008048593 0.005654871 0.07321143 -0.007556378 0.005480766 0.07319182 -0.007138609 0.005079567 0.0731669 -0.006727039 0.004555761 0.07314234 -0.006556153 0.003949046 0.0731154 -0.006618559 0.003461539 0.07308924 -0.006964147 0.003211736 0.07306826 -0.007377982 0.003126025 0.07304346 -0.007926166 0.003309607 0.07301908 -0.008468091 0.003624379 0.07299727 -0.008832633 0.004045426 0.07297676 -0.009042739 0.004537701 0.07295513 -0.009090363 0.005078732 0.07292973 -0.008913695 0.005477845 0.07290524 -0.00850892 0.005691051 0.07287794 -0.007933557 0.005574226 0.07285094 -0.007314026 0.005327045 0.07283049 -0.006936728 0.004967629 0.07281118 -0.006677627 0.004434347 0.07278746 -0.006540715 0.003877758 0.07276141 -0.006657242 0.003465771 0.07273966 -0.006962358 0.00322169 0.07271945 -0.007344305 0.003129005 0.07269805 -0.007833898 0.003274321 0.07267093 -0.008422791 0.00361377 0.0726481 -0.008819282 0.004023194 0.07262831 -0.009035646 0.004513621 0.07260543 -0.009096324 0.004990696 0.07258421 -0.008952021 0.005473792 0.07255703 -0.008545517 0.005670964 0.07252973 -0.007967114 0.00562936 0.07250666 -0.007446527 0.005392968 0.07248497 -0.007013499 0.005039632 0.0724653 -0.006716668 0.004541635 0.07244098 -0.006546378 0.00402069 0.07241868 -0.006607651 0.003609597 0.0723983 -0.006825387 0.003288865 0.07237678 -0.007197856 0.003139257 0.07235401 -0.007694125 0.003171861 0.07233375 -0.008147239 0.003357827 0.07231491 -0.008545279 0.003774702 0.07228893 -0.008936941 0.004215359 0.07226908 -0.00907886 0.004699349 0.07224786 -0.009068489 0.005230545 0.07222193 -0.008798301 0.005524158 0.07220113 -0.008431196 0.005669295 0.07218074 -0.007988572 0.005632758 0.07215684 -0.007440865 0.005300402 0.07212871 -0.006909847 0.004885435 0.07210701 -0.006637692 0.004329681 0.07208287 -0.006541967 0.003759264 0.07205611 -0.006718277 0.003406882 0.07203555 -0.007031202 0.003142237 0.0720086 -0.007580935 0.003181457 0.07198238 -0.008176684 0.003403246 0.07196146 -0.008606612 0.003734946 0.07194143 -0.008907198 0.004207789 0.07191991 -0.009082317 0.00483793 0.0718916 -0.009031474 0.003732681 0.07758784 -0.009008407 0.005600929 0.0775842 -0.008700013 0.004288971 0.07758784 -0.009217381 0.004990816 0.07758766 -0.00915575 0.00579667 0.07755786 -0.008308351 0.005885899 0.07753908 -0.007814407 0.005784273 0.07751899 -0.00729382 0.005022406 0.07747495 -0.006471753 0.004423081 0.07745265 -0.006346344 0.003887355 0.07743209 -0.006435334 0.003436625 0.07741189 -0.006707429 0.003098428 0.07739108 -0.007137119 0.005890488 0.0771923 -0.007911264 0.003132641 0.0769844 -0.008579254 0.005816876 0.07685589 -0.008254528 0.002936244 0.07665675 -0.00802809 0.0049178 0.07655745 -0.009206414 0.005655229 0.07645767 -0.007028698 0.003256916 0.07627683 -0.008750438 0.003766357 0.0762512 -0.009163379 0.005074262 0.07607805 -0.006505846 0.004513263 0.07605594 -0.006344914 0.00317341 0.07593107 -0.008652806 0.005859434 0.07577955 -0.007553279 0.00567454 0.07575911 -0.007061183 0.003275156 0.07557523 -0.008767545 0.003783583 0.07555121 -0.009171426 0.005829632 0.07542335 -0.007416725 0.005560398 0.07540214 -0.006902456 0.003185093 0.07529765 -0.006994128 0.00293678 0.07527267 -0.007591664 0.004529654 0.07517254 -0.009293138 0.005817472 0.07510691 -0.008289635 0.004699289 0.07501286 -0.006367564 0.004034161 0.07498753 -0.006386995 0.003405272 0.07496058 -0.00672388 0.003784894 0.07485127 -0.00915873 0.004341721 0.07482939 -0.009301722 0.005370795 0.07478713 -0.008938908 0.005723476 0.07476562 -0.008498787 0.003200769 0.07459861 -0.006963908 0.004212796 0.07448345 -0.009290933 0.005386173 0.07443648 -0.008939445 0.005800902 0.07440841 -0.00832206 0.005359172 0.07434129 -0.006685614 0.003957271 0.07428503 -0.006412982 0.003492653 0.07426458 -0.006658494 0.003080368 0.07424008 -0.007157921 0.004548072 0.07412183 -0.009291231 0.005056619 0.07410132 -0.00914961 0.005892574 0.07403749 -0.00778228 0.003202795 0.07382953 -0.008686304 0.005849063 0.07370108 -0.008130609 0.003503739 0.07356595 -0.006644725 0.003067851 0.07353848 -0.007179975 0.003881931 0.07344657 -0.009212732 0.005101799 0.07340019 -0.009130179 0.00454986 0.07325726 -0.006352603 0.00393629 0.07323443 -0.006415069 0.002971112 0.07317817 -0.007467806 0.002937555 0.07315772 -0.007992148 0.004021823 0.0730915 -0.009245693 0.0046373 0.07306867 -0.009285271 0.005304098 0.07303971 -0.009005844 0.004151105 0.07289177 -0.006352901 0.003177046 0.07278138 -0.008649289 0.005650997 0.07267129 -0.008634686 0.004933297 0.07257211 -0.0064435 0.004412651 0.0725519 -0.006339669 0.003312528 0.07250547 -0.006813287 0.003310799 0.07242286 -0.008815407 0.003902435 0.07239633 -0.009220182 0.005087196 0.07235026 -0.009134292 0.00579524 0.07230854 -0.008316278 0.005884706 0.07228803 -0.007778406 0.00577408 0.07226735 -0.0072636 0.00495845 0.07222276 -0.006440401 0.00367099 0.07217311 -0.006531357 0.00302571 0.07209426 -0.00834167 0.003330528 0.07207262 -0.008837282 0.004888594 0.07200866 -0.009227573 0.005720794 0.07191407 -0.007128834 0.005868315 0.07758909 -0.008043944 0.004137575 0.07158893 -0.006560564 0.003678202 0.07167249 -0.006606101 0.003514766 0.07176923 -0.006653487 0.003947496 0.07161694 -0.00655514 0.003904223 0.0717771 -0.006442666 0.004072189 0.07168251 -0.006440043 0.004309117 0.07162749 -0.006462752 0.004296123 0.0717436 -0.006366848 0.004688918 0.07163679 -0.006468355 0.004855513 0.07159101 -0.006622672 0.004679203 0.07173413 -0.006393492 0.005154907 0.07164472 -0.006649196 0.004984498 0.07174718 -0.006481945 0.005322515 0.07159066 -0.006926417 0.005373716 0.07164603 -0.006827831 0.005197107 0.07183653 -0.00657016 0.005420267 0.07173264 -0.006780385 0.00555998 0.0716083 -0.007158994 0.005639374 0.07182937 -0.006999254 0.005615711 0.07168084 -0.007080554 0.005690038 0.07158911 -0.007774353 0.005748212 0.07165402 -0.007415294 0.005794763 0.07183331 -0.007310628 0.005836784 0.0717262 -0.007601201 0.005806982 0.07165884 -0.007927596 0.005888342 0.07183218 -0.007834196 0.005666434 0.07160907 -0.008240699 0.00539565 0.07158988 -0.008625328 0.005806386 0.07174956 -0.008235096 0.005705773 0.07167625 -0.008384466 0.005546629 0.07162529 -0.008568465 0.00572443 0.07183724 -0.008502781 0.0056324 0.07175248 -0.008610963 0.005419552 0.07164543 -0.008773207 0.005087196 0.07159107 -0.008905887 0.005454778 0.07182854 -0.008863449 0.005117595 0.07164275 -0.009008646 0.005244195 0.07174527 -0.009014129 0.004279971 0.07159131 -0.00911343 0.005009174 0.07173562 -0.009144842 0.00477308 0.07163619 -0.009154498 0.004584848 0.07171356 -0.00925678 0.004929184 0.07183796 -0.009208083 0.004113793 0.07170903 -0.009236097 0.004261434 0.07175987 -0.009276032 0.003937602 0.07162117 -0.009089112 0.003733873 0.07167667 -0.009070456 0.00380373 0.07183361 -0.009169161 0.003609001 0.07159435 -0.008847773 0.003469407 0.0717256 -0.008933186 0.003344833 0.07161837 -0.008653461 0.003166496 0.07159227 -0.00820291 0.003171741 0.07166659 -0.008508265 0.003185927 0.07177114 -0.008633852 0.003025054 0.07171314 -0.008245825 0.003078043 0.07160794 -0.007869362 0.003207385 0.07158988 -0.007344126 0.003002583 0.07165694 -0.007820248 0.002960324 0.07173937 -0.007667243 0.003034353 0.07169276 -0.007406115 0.003237664 0.0716179 -0.007144391 0.003119468 0.07171714 -0.007162153 0.00335884 0.07166785 -0.006874322 0.003579974 0.0716046 -0.006789922 0.003230452 0.07176125 -0.006952524 0.006229281 0.07776582 -0.009810686 0.006282687 0.07759255 -0.009520053 0.006531417 0.07777708 -0.009482502 0.006581008 0.07765674 -0.009310603 0.006778538 0.07778704 -0.009112596 0.006823599 0.07769894 -0.008939743 0.006789445 0.07759404 -0.008689463 0.006976068 0.0777707 -0.008640289 0.006978809 0.07768028 -0.008461177 0.007080793 0.07779532 -0.008202195 0.00697118 0.07760828 -0.0079391 0.00709027 0.07772403 -0.007841229 0.00707376 0.07776087 -0.007435142 0.006768345 0.07758885 -0.006988763 0.006962001 0.07762873 -0.007377445 0.006990969 0.07773697 -0.007078588 0.006803929 0.07777696 -0.006575405 0.006840467 0.07765018 -0.006833314 0.006533384 0.07761514 -0.006368398 0.006484329 0.07766848 -0.00617963 0.00646311 0.07778435 -0.006071269 0.006118655 0.0775876 -0.006004035 0.006042003 0.07775896 -0.005673527 0.005908429 0.07760733 -0.005741655 0.005891442 0.07768845 -0.005615651 0.005435824 0.07776123 -0.005325973 0.005477368 0.0776481 -0.005430638 0.005043685 0.07759743 -0.005353629 0.004888415 0.07776379 -0.005167126 0.004764258 0.07769006 -0.005188405 0.004271626 0.07777523 -0.005122482 0.004308998 0.07759475 -0.005281329 0.004309415 0.07766848 -0.005179762 0.003771483 0.0777511 -0.005203783 0.003842115 0.07762676 -0.005287826 0.003289639 0.07780921 -0.005359292 0.003476321 0.07769626 -0.005326688 0.003186643 0.07759284 -0.005599379 0.003052234 0.07769185 -0.005528867 0.002874374 0.07779437 -0.005597829 0.002720415 0.07766664 -0.005784332 0.002460241 0.07778829 -0.005944192 0.002497076 0.077591 -0.006163775 0.002382218 0.0776807 -0.006109178 0.002070128 0.07776808 -0.006466448 0.002094447 0.07762485 -0.006635427 0.001891434 0.07775223 -0.006859898 0.00177735 0.0777601 -0.007230103 0.001912534 0.07759863 -0.007313013 0.001833319 0.07764971 -0.007293701 0.001713871 0.07775813 -0.007679164 0.001782119 0.0776515 -0.00790584 0.00173217 0.07776576 -0.008162021 0.001920461 0.07759124 -0.008256435 0.001879394 0.07765233 -0.008562982 0.001841068 0.07778573 -0.008673012 0.002073705 0.0777589 -0.009175837 0.002155482 0.07760977 -0.009057998 0.002323031 0.07764923 -0.009419381 0.002378463 0.07777863 -0.009600639 0.002603709 0.07759308 -0.009597659 0.002554893 0.0776875 -0.009725511 0.002726495 0.07775437 -0.00992763 0.003140032 0.07775974 -0.01020431 0.003114044 0.07762759 -0.01007676 0.00335586 0.07758945 -0.01009142 0.003669559 0.07773673 -0.01040887 0.00382024 0.07761907 -0.01033681 0.004172623 0.07774215 -0.01050364 0.004405736 0.07759845 -0.01037222 0.004676818 0.07773399 -0.0104947 0.005008637 0.07776772 -0.01045101 0.005027055 0.07764965 -0.01036936 0.005383789 0.07759368 -0.01016455 0.005521297 0.07779502 -0.01028209 0.005512416 0.07769989 -0.01024669 0.00586766 0.07775878 -0.01008301 0.006061673 0.0776506 -0.009864151 0.00604397 0.08038222 -0.009967088 0.006670236 0.08041602 -0.009280681 0.006984829 0.08038854 -0.0086236 0.00706309 0.08041059 -0.008269906 0.007103681 0.08039659 -0.007866621 0.006802141 0.08040094 -0.006574809 0.006530404 0.08041775 -0.006163001 0.006190836 0.08042204 -0.005801498 0.005753695 0.08040291 -0.005482614 0.004722774 0.08044409 -0.005151927 0.004260778 0.08038771 -0.00512582 0.00329113 0.08040982 -0.005364894 0.002818226 0.08037614 -0.005634367 0.002423524 0.08040153 -0.005989372 0.002069413 0.08040517 -0.006465494 0.001716732 0.08038085 -0.007561445 0.001724362 0.08043998 -0.008015275 0.001791596 0.08040314 -0.008490204 0.002003312 0.08041876 -0.009048938 0.003434956 0.08039915 -0.01033973 0.004564046 0.08041018 -0.01051485 0.005381762 0.08037227 -0.01034134 0.005800604 0.08043795 -0.01012021 0.005884587 0.08056235 -0.009927093 0.005495667 0.08047771 -0.01025235 0.005379378 0.08055019 -0.01022434 0.004967033 0.08058655 -0.01026636 0.005052268 0.08042311 -0.01043438 0.00479108 0.08052676 -0.01041734 0.004064738 0.08050006 -0.01045006 0.004176735 0.08056557 -0.01037645 0.003982305 0.0803942 -0.01049 0.003637075 0.08058625 -0.01021647 0.003515064 0.0805298 -0.0102868 0.003035187 0.08044672 -0.01013249 0.00282073 0.08055925 -0.00986433 0.002725839 0.08043789 -0.009919047 0.002473175 0.08040988 -0.009699881 0.002486169 0.08058196 -0.009464561 0.002305865 0.08044248 -0.009497165 0.002158641 0.08054286 -0.009142398 0.002037525 0.08057963 -0.008750557 0.00184822 0.08053094 -0.008403718 0.001891791 0.0805844 -0.00765419 0.001782894 0.08051794 -0.007552504 0.001817345 0.08041435 -0.007063567 0.001933038 0.080536 -0.0069772 0.002129137 0.08057844 -0.006701767 0.002054691 0.08047819 -0.006569623 0.002368092 0.08058315 -0.006325423 0.002427101 0.08051371 -0.006076335 0.00286442 0.08048182 -0.005646646 0.002755105 0.08056795 -0.005868375 0.003185093 0.08054554 -0.005527019 0.003669738 0.08044826 -0.005237996 0.003788828 0.08056193 -0.005324423 0.003893375 0.08041512 -0.005176782 0.004190862 0.08049285 -0.005175232 0.004403829 0.08056277 -0.0052464 0.005211114 0.08041316 -0.005244374 0.005000948 0.08058118 -0.005356967 0.00522238 0.08052277 -0.005324482 0.005712449 0.08049625 -0.005516886 0.005925655 0.0805872 -0.005842566 0.005837142 0.08055651 -0.00566554 0.006430745 0.08054786 -0.006179213 0.006499707 0.08058172 -0.006395339 0.006789505 0.08055263 -0.00678879 0.006985485 0.08043825 -0.007057547 0.006982803 0.08052152 -0.007303297 0.007075548 0.08041715 -0.007451117 0.006912887 0.08058577 -0.007638752 0.007048964 0.0805093 -0.007919132 0.006940484 0.08055055 -0.008423507 0.006813824 0.08053678 -0.008838176 0.00683242 0.08041912 -0.008993268 0.006706476 0.08058482 -0.008830249 0.006529092 0.08052378 -0.009365022 0.006397783 0.08041507 -0.009638905 0.006184935 0.0805276 -0.00975424 0.00629872 0.08058649 -0.009471714 0.003163635 0.07889562 0.005128145 0.003326058 0.07889533 0.003790318 0.003214299 0.07900333 0.00370711 0.003037333 0.0790044 0.005184352 0.004564344 0.07889562 0.003258585 0.004582524 0.0790053 0.003120779 0.005688905 0.07890826 0.00404793 0.005782306 0.07904577 0.004009783 0.005469918 0.07889199 0.005396544 0.005590081 0.07898777 0.005486547 0.004238367 0.07890868 0.005987107 0.004226624 0.07904696 0.006086111 0.005631804 0.08057624 0.005517363 0.004223763 0.08057647 0.006121098 0.005816161 0.08057665 0.003996729 0.004587829 0.08057707 0.003074049 0.003176093 0.08057665 0.00367999 0.002995014 0.08057659 0.005203008 0.004452049 0.07183653 0.003312468 0.004187047 0.07183778 0.003140211 0.00376302 0.07183802 0.003427267 0.003708779 0.07183748 0.003292322 0.005137324 0.07185494 0.003553688 0.003283321 0.07183742 0.003637015 0.003208577 0.07183796 0.003911972 0.003034889 0.07182967 0.004044175 0.005524337 0.07184267 0.003982663 0.002955555 0.07183778 0.004323482 0.00293076 0.07182985 0.004693865 0.00581777 0.07183796 0.004161179 0.005719304 0.07183879 0.004612803 0.002980887 0.07183182 0.004995822 0.005792021 0.07183784 0.005100369 0.005548596 0.07183778 0.005337715 0.005591452 0.07183778 0.005474567 0.005102396 0.07183784 0.005821168 0.004215121 0.07184112 0.0060606 0.004546105 0.0718429 0.006059527 0.005856871 0.07758486 0.004787266 0.005731523 0.07757544 0.005229651 0.005452156 0.07751423 0.005655944 0.004871129 0.07751166 0.00600934 0.003862619 0.0775882 0.005759596 0.005107283 0.07758796 0.005782186 0.004237949 0.07746863 0.006077706 0.004485011 0.0775879 0.005918145 0.003611266 0.07746654 0.005848109 0.003460228 0.0775783 0.005450665 0.003098785 0.07743638 0.005309045 0.003214836 0.07757055 0.005046844 0.002928793 0.07741069 0.004674553 0.003130435 0.07752406 0.004593908 0.002975344 0.07737016 0.004207015 0.003226399 0.07750201 0.004111289 0.003214716 0.07734972 0.003706872 0.003484785 0.07748168 0.003713309 0.003595352 0.07733607 0.003354966 0.003880023 0.07746022 0.003436446 0.003996491 0.07731437 0.003168642 0.004362821 0.07743871 0.003324091 0.004478693 0.0772944 0.003113746 0.004832863 0.07741743 0.003394246 0.004995465 0.07727354 0.003233432 0.005262315 0.07739555 0.00365746 0.005458176 0.07725608 0.003555476 0.005541384 0.07737576 0.004017055 0.00577259 0.07723784 0.004005908 0.005682885 0.0773518 0.004529178 0.005873858 0.07721632 0.004364967 0.005855083 0.07719975 0.004911839 0.005597472 0.07732933 0.005044996 0.005713164 0.07718485 0.005292654 0.005306363 0.07730525 0.00551629 0.005469799 0.0771681 0.005640029 0.005011439 0.0771473 0.005953967 0.004681646 0.07727372 0.005850017 0.004530787 0.07712239 0.006078422 0.004149734 0.07725048 0.005848348 0.00406301 0.07711344 0.006042957 0.003616511 0.07722508 0.005609631 0.003587484 0.07709079 0.005835711 0.003179907 0.0770747 0.00544393 0.003281295 0.07720148 0.005201339 0.002995252 0.07705152 0.005071699 0.003140926 0.07718139 0.004766404 0.002922952 0.07703399 0.004529774 0.003203034 0.07715409 0.004136741 0.003095328 0.07703077 0.003899693 0.003547906 0.07712769 0.003656864 0.003472626 0.07698625 0.003445446 0.004004001 0.07710444 0.00338304 0.003989636 0.07696229 0.003169536 0.004525184 0.07694965 0.003118515 0.00450474 0.07708227 0.003327488 0.005037248 0.07705813 0.003485977 0.005010902 0.07692545 0.003243088 0.005396604 0.07690131 0.003495991 0.005532145 0.07702714 0.003973126 0.005705058 0.07689076 0.003875732 0.005874395 0.07686984 0.004407525 0.005679368 0.07699936 0.004597604 0.005824506 0.07686632 0.005042195 0.005578815 0.07697641 0.005113542 0.005445539 0.07681691 0.005657553 0.005131006 0.07694506 0.005660116 0.005064785 0.07680785 0.005926489 0.004576921 0.07691925 0.005862593 0.004580616 0.07677894 0.006077945 0.004110932 0.07689863 0.005837321 0.004002511 0.07675993 0.006026148 0.003621459 0.07687491 0.005614399 0.003606677 0.07673621 0.005848824 0.003239333 0.07672923 0.005521953 0.003282725 0.07685148 0.005200564 0.002984404 0.07669985 0.005034863 0.003139793 0.07683128 0.004756271 0.002924919 0.07668602 0.004572093 0.003176867 0.07680827 0.004232645 0.002984941 0.07666838 0.004151761 0.003268539 0.07664763 0.003646314 0.00357443 0.07677561 0.003611922 0.003759622 0.07664579 0.003261625 0.004135489 0.07674849 0.003352761 0.004363 0.07659983 0.00311619 0.004660487 0.07672524 0.0033468 0.004923284 0.07658207 0.003205358 0.005284011 0.0766955 0.003651678 0.005392074 0.07655245 0.003487706 0.005694329 0.07654082 0.003865718 0.005625665 0.07666563 0.004231214 0.005874037 0.07652407 0.004370927 0.005678832 0.07664507 0.00469768 0.005875051 0.07650393 0.004773378 0.005775392 0.07648891 0.005165278 0.005475163 0.07661634 0.005310893 0.005441427 0.07647186 0.005668938 0.005034923 0.07659053 0.005708575 0.004803836 0.07646101 0.006026804 0.004568815 0.07656848 0.005862951 0.00407201 0.0764122 0.006049573 0.003922224 0.07654058 0.005795478 0.00355637 0.07638841 0.005819141 0.003345608 0.07650774 0.005320489 0.003174006 0.07636958 0.005426526 0.002936303 0.0763421 0.004873812 0.003126859 0.07647877 0.004708468 0.002922594 0.07635724 0.004586696 0.003211855 0.07645434 0.004154264 0.003116905 0.07632952 0.003855884 0.003440618 0.07643461 0.003761887 0.003595352 0.07630252 0.003359675 0.003787875 0.07641446 0.003483653 0.00395298 0.07626384 0.003185391 0.004287898 0.07639199 0.003325998 0.00453931 0.07624322 0.0031147 0.004837751 0.07636761 0.003394305 0.004992961 0.07622224 0.003239691 0.005356431 0.07620966 0.003461599 0.005411446 0.07633721 0.003794789 0.005715191 0.0761913 0.003895103 0.005658686 0.07630932 0.004361212 0.005876481 0.0761708 0.004400551 0.005625069 0.07628154 0.00501132 0.005857944 0.07614636 0.004909813 0.005610883 0.07613092 0.005471467 0.005268454 0.07625269 0.005539417 0.005336344 0.0761069 0.005755126 0.004762291 0.07622766 0.005827605 0.004871547 0.07609355 0.006005585 0.004247903 0.07608962 0.006074726 0.004095017 0.07619839 0.005847096 0.00368452 0.07604515 0.00589472 0.003483593 0.07616686 0.005489528 0.00323522 0.07602113 0.005518853 0.003206551 0.07614368 0.005035459 0.002969026 0.07599961 0.004990279 0.003131031 0.07612186 0.004544734 0.002933382 0.07597965 0.004407823 0.003239274 0.0761007 0.004077494 0.003053724 0.07598513 0.004004359 0.003306925 0.07596737 0.003611147 0.003492414 0.07608103 0.003709554 0.003733396 0.0759201 0.003272116 0.003875255 0.07606065 0.003439903 0.004175484 0.075908 0.003134965 0.004305839 0.07604122 0.0033257 0.004563093 0.07589524 0.003120958 0.004758656 0.07602089 0.003375411 0.005089819 0.0758723 0.003283619 0.005230665 0.07599759 0.003620624 0.005566775 0.07584184 0.003662645 0.005540192 0.07597547 0.004018187 0.005740344 0.07585746 0.003967523 0.005676031 0.07595372 0.004496514 0.005874633 0.07581979 0.004372179 0.005580663 0.07592523 0.005129456 0.005871295 0.07579952 0.004834592 0.005696237 0.07577979 0.005336105 0.005342364 0.07576495 0.00574553 0.00510019 0.07589393 0.005673587 0.004954576 0.07574027 0.005976796 0.004551947 0.0758683 0.005869567 0.004510045 0.07572847 0.006080329 0.003980159 0.07570773 0.006019055 0.00405091 0.07584571 0.005820393 0.003658652 0.07582718 0.005634248 0.003533542 0.07568788 0.005799829 0.003276705 0.07567626 0.005559146 0.003349721 0.07580727 0.005313515 0.003046035 0.07565873 0.005192339 0.003148078 0.07578408 0.004828691 0.002916574 0.07564157 0.00461483 0.003161191 0.07576137 0.004303932 0.003013908 0.07561773 0.004073679 0.003434956 0.07573467 0.003760695 0.003350496 0.07561504 0.003566443 0.003891885 0.07570993 0.003429412 0.003839612 0.07559233 0.003225982 0.004430413 0.07568526 0.003318905 0.004417419 0.07554781 0.003115713 0.004956603 0.07552802 0.003219366 0.00496757 0.07566154 0.003452837 0.0053429 0.07550805 0.003450393 0.005325317 0.07564169 0.003716826 0.005646824 0.07549297 0.003788173 0.00560528 0.07561844 0.00416094 0.005873739 0.07547056 0.004350483 0.00567454 0.07558977 0.00482285 0.005850017 0.07544261 0.004954814 0.0057199 0.07545691 0.00526607 0.005394041 0.07556128 0.005402088 0.005370497 0.07543545 0.005721986 0.004934549 0.07553511 0.005772113 0.005134105 0.07539612 0.00589472 0.004638075 0.07538205 0.006063163 0.004321336 0.07550817 0.005869686 0.004072368 0.07536 0.006047487 0.003785312 0.07548391 0.005724012 0.0035699 0.07533967 0.005828082 0.003361463 0.07545781 0.005328118 0.003190815 0.07531929 0.005448698 0.00316888 0.07543849 0.004918277 0.002962768 0.07530254 0.00496608 0.003138363 0.07541739 0.004444479 0.002926051 0.07528245 0.004541695 0.002994418 0.07526856 0.004141867 0.003295183 0.07539564 0.003972411 0.003261864 0.0752502 0.003647089 0.003642201 0.07537198 0.003567218 0.003673374 0.07522809 0.003306388 0.004187285 0.07534635 0.00334227 0.004178464 0.07520556 0.003131687 0.004855453 0.07531654 0.003386497 0.004793643 0.07518255 0.003159224 0.005303263 0.07515788 0.00341922 0.005427956 0.07528519 0.003832697 0.005642175 0.07516646 0.00377351 0.005657553 0.07526081 0.004336893 0.005877137 0.07511615 0.004385471 0.005650877 0.07523757 0.004860341 0.005845189 0.07509815 0.004950284 0.005450904 0.0752148 0.005338549 0.005672454 0.07508587 0.00536561 0.005411744 0.0750643 0.005693554 0.005068898 0.07519209 0.005685329 0.004948973 0.07504546 0.005978584 0.004438638 0.07516288 0.005891382 0.004439175 0.07502585 0.006087124 0.003951072 0.07500725 0.006014287 0.00381422 0.07513469 0.005726635 0.003320872 0.0750007 0.005616486 0.003447115 0.07511454 0.005440473 0.003216981 0.07509511 0.005064308 0.002984821 0.07497364 0.005014717 0.003131866 0.07507455 0.004608988 0.002938807 0.074952 0.004434227 0.003265857 0.07504653 0.003989934 0.003003418 0.07491397 0.00410819 0.003278255 0.07489186 0.00362569 0.003806293 0.07501405 0.003465235 0.003736674 0.07487517 0.003274142 0.004256069 0.07485532 0.003117799 0.004347026 0.07498902 0.003323137 0.004875719 0.07485234 0.0031901 0.004797875 0.07496905 0.003387451 0.005343317 0.07494163 0.003713071 0.00547564 0.07482594 0.003574728 0.005828917 0.07479876 0.004175543 0.005632281 0.07491409 0.004259586 0.005670487 0.07489079 0.004790186 0.005860865 0.0747736 0.004856467 0.005661964 0.07475179 0.00537908 0.00549376 0.07486867 0.005262017 0.005113065 0.07484418 0.005664587 0.005365967 0.07471287 0.00573343 0.004987001 0.07469105 0.005963444 0.004623234 0.07482135 0.005856335 0.004467487 0.0746752 0.006085634 0.003958404 0.07479268 0.005809366 0.003908574 0.07465612 0.005994856 0.003503143 0.07463812 0.005775868 0.003399074 0.0747615 0.005389273 0.003183245 0.07461905 0.005444586 0.003178656 0.07473891 0.004936695 0.002965211 0.07462042 0.004920423 0.003131866 0.07472038 0.004504978 0.002946257 0.07459777 0.004322648 0.003315448 0.07469338 0.003912687 0.003207981 0.07455068 0.00372225 0.003654003 0.0745511 0.003315985 0.003805816 0.07466369 0.003469228 0.004315733 0.07464051 0.003324151 0.004140973 0.07450366 0.003141462 0.004577934 0.07449162 0.003125369 0.004835903 0.07461762 0.003398716 0.005087018 0.0744782 0.003278553 0.005286276 0.07459467 0.003668427 0.00545299 0.07444667 0.00354886 0.00572741 0.07443749 0.003923833 0.00561726 0.07456696 0.004193246 0.005870223 0.07442754 0.004369854 0.005677759 0.07454502 0.004696726 0.005828142 0.07441681 0.005028843 0.005557298 0.07452434 0.005139946 0.005451381 0.07438963 0.005644857 0.005191266 0.07449865 0.005618095 0.004928946 0.07436531 0.005985379 0.004444301 0.07446414 0.005888164 0.00426948 0.07431924 0.006076276 0.003739535 0.07431972 0.005925655 0.003813922 0.07443511 0.005730152 0.00340873 0.07441151 0.005398631 0.003189325 0.07426887 0.005455076 0.002977311 0.07427388 0.005002498 0.003172218 0.0743891 0.00492984 0.003134906 0.07436907 0.004489004 0.002951323 0.07424718 0.00430572 0.003271877 0.07434773 0.004013121 0.003255367 0.07419729 0.003651618 0.003710746 0.07431864 0.00350821 0.003658056 0.07418406 0.003316938 0.004089593 0.07416069 0.003147602 0.004357516 0.07428884 0.003325283 0.004561901 0.07413864 0.003123462 0.004884362 0.07426518 0.003408789 0.005089819 0.07412278 0.003276109 0.005462706 0.07423359 0.003863513 0.005545139 0.07410126 0.003651261 0.005818843 0.07408297 0.004126608 0.005686879 0.07420086 0.004550874 0.005888521 0.07406139 0.004493713 0.005797028 0.07406437 0.005088388 0.005567789 0.07417583 0.005120813 0.005479633 0.07402068 0.005631864 0.005283713 0.07415401 0.005528867 0.004986405 0.07399594 0.005962431 0.004834294 0.07413077 0.005797207 0.004437327 0.07397758 0.006085515 0.004322111 0.074108 0.005877196 0.003885328 0.07395124 0.005991339 0.003826618 0.07408529 0.005733311 0.00330919 0.07394999 0.005603551 0.00343579 0.07406395 0.005429804 0.003143727 0.07403546 0.004862427 0.002979218 0.07392328 0.004995882 0.002922952 0.07388275 0.004503905 0.003224194 0.07400172 0.0040856 0.003035247 0.07386142 0.004023671 0.003315329 0.07384371 0.003588497 0.003586351 0.0739755 0.003622949 0.00375545 0.07382434 0.003265678 0.004054307 0.07395207 0.00336796 0.004166126 0.07381069 0.003136813 0.004556655 0.07393008 0.003332197 0.004622042 0.07378429 0.003124177 0.005081415 0.07390588 0.003512561 0.005184888 0.07376831 0.003336727 0.005521059 0.0737527 0.003622829 0.005461335 0.07388216 0.003881573 0.005771636 0.07373619 0.004009902 0.005642592 0.07386225 0.004299342 0.005887269 0.07371354 0.004577696 0.005650699 0.07383483 0.004934549 0.005793511 0.07369446 0.005148887 0.005336344 0.07380729 0.005466818 0.005349218 0.0736621 0.005744278 0.004904329 0.07378399 0.00577718 0.004890739 0.0736463 0.006004393 0.00440979 0.07376188 0.00587362 0.004482269 0.07362514 0.006077229 0.004073679 0.07361078 0.00604403 0.003757119 0.07373231 0.005716204 0.0035699 0.073592 0.005827248 0.003179728 0.0735706 0.005441784 0.003282368 0.07370191 0.005209386 0.002960681 0.0735501 0.004932045 0.003115355 0.07367044 0.00450313 0.002927303 0.0735265 0.004463315 0.003028512 0.07351958 0.004044473 0.003375887 0.07363843 0.00384128 0.003285109 0.07349628 0.00362581 0.003769695 0.07361602 0.003491878 0.003696799 0.07347166 0.00329256 0.004065513 0.07346314 0.003156661 0.004186332 0.07359623 0.00334239 0.004492402 0.07344502 0.003118276 0.004768848 0.07357048 0.003368973 0.005025148 0.07342624 0.00324887 0.005293369 0.07354408 0.003677845 0.005485773 0.07340258 0.003575325 0.005631208 0.07351601 0.004223585 0.005783855 0.07338351 0.004056036 0.005889594 0.07337993 0.004685759 0.005662441 0.07348906 0.004834473 0.005737304 0.07333528 0.005251884 0.005371749 0.07345896 0.005446672 0.005411088 0.07331693 0.005691826 0.004884898 0.07343322 0.005780577 0.004878401 0.07331341 0.006000578 0.004429161 0.07341235 0.005871474 0.004487633 0.07327479 0.006079971 0.003925383 0.0733906 0.005785942 0.0039168 0.07325738 0.006005465 0.003507733 0.07336807 0.00550282 0.003292977 0.07324814 0.005583286 0.00324124 0.07334768 0.005118012 0.002962827 0.07320523 0.004954695 0.003131449 0.07332831 0.004687547 0.002927541 0.07317942 0.00444132 0.003201782 0.07330471 0.004168748 0.003080964 0.07316172 0.003932893 0.003477334 0.07328224 0.003721773 0.003450989 0.0731433 0.003448665 0.003910541 0.07325834 0.003417789 0.004138708 0.07310807 0.003137707 0.004455149 0.07323467 0.003324806 0.004609763 0.07311332 0.003129601 0.00491327 0.07321405 0.003426194 0.005166471 0.07309019 0.003333151 0.005401432 0.07318729 0.003792226 0.005502641 0.07305264 0.003595292 0.005843043 0.0730471 0.004230439 0.005669653 0.07315832 0.00438416 0.005859017 0.07300084 0.004891574 0.005585014 0.07312673 0.005115032 0.005659341 0.0729807 0.005396425 0.005307257 0.07298219 0.005771577 0.00511676 0.07309406 0.005665898 0.004780888 0.07296001 0.006025195 0.004397988 0.07306176 0.00588864 0.004415988 0.0729205 0.006085813 0.003876268 0.07290256 0.005987107 0.003778636 0.07303297 0.005709469 0.003411948 0.07288324 0.005699813 0.003306686 0.07300466 0.00527215 0.003094136 0.07286059 0.005297243 0.002937197 0.07284349 0.004828751 0.003135442 0.07297849 0.004700005 0.002955555 0.07282483 0.004280209 0.003236353 0.07294923 0.004044711 0.003174185 0.07280659 0.00375843 0.003665506 0.07292103 0.003562033 0.003593623 0.0727806 0.003357291 0.004086554 0.07290095 0.003363788 0.004088222 0.07276415 0.003147959 0.004639685 0.07287669 0.003336846 0.004511415 0.07274127 0.003115952 0.005020797 0.07272452 0.003249764 0.005249977 0.07284647 0.003635048 0.005498468 0.07270056 0.003589034 0.005563378 0.07282322 0.004064917 0.005770862 0.07268756 0.00401926 0.005671679 0.07280391 0.004489541 0.005885064 0.07266497 0.004501402 0.005635499 0.07278382 0.004944384 0.005836009 0.07264047 0.004989087 0.005670011 0.072631 0.005380034 0.005423843 0.0727632 0.005364179 0.005281209 0.0726071 0.005797684 0.005077838 0.07274276 0.005679965 0.004831254 0.07261216 0.006017506 0.004661798 0.0727232 0.005849421 0.004135251 0.07258504 0.006059408 0.004181444 0.07270181 0.005854189 0.003662228 0.07267719 0.005641102 0.003483474 0.07253599 0.005768716 0.00332117 0.07265508 0.005270302 0.003185272 0.07251828 0.005438089 0.002999484 0.07250392 0.00507158 0.003146708 0.07263302 0.00480622 0.002920687 0.0724827 0.004505455 0.003156363 0.07261264 0.004331111 0.00305289 0.07248443 0.003996372 0.003331005 0.07259243 0.00391376 0.003393948 0.07246273 0.003524363 0.00364995 0.07257211 0.003571808 0.003929078 0.07243883 0.003189563 0.004125416 0.07254916 0.003347575 0.0046494 0.07238954 0.00313425 0.004831016 0.07251781 0.003385126 0.005100965 0.07237708 0.003287971 0.005322098 0.072492 0.003712058 0.005511283 0.07235413 0.003604769 0.005626022 0.07246619 0.004208266 0.005775272 0.07233238 0.004030764 0.005889594 0.07230907 0.004541695 0.005645394 0.07243388 0.00496006 0.005819916 0.07229244 0.0050534 0.005556285 0.07227367 0.005534172 0.005280673 0.07240402 0.005525231 0.00525099 0.07226055 0.005814313 0.004862368 0.07238227 0.005793511 0.004889726 0.07223826 0.006002783 0.004406034 0.07222378 0.006083309 0.004365503 0.07235968 0.005869984 0.003946661 0.07222831 0.006004333 0.003938198 0.07234114 0.005786716 0.003483891 0.07220786 0.005754411 0.003561139 0.07232105 0.00555402 0.003201246 0.07216823 0.00546354 0.003245472 0.07229852 0.005135416 0.002953171 0.07214814 0.004931926 0.003121197 0.07226938 0.004479408 0.002937316 0.07213324 0.004380822 0.003199219 0.07212382 0.003728628 0.003353178 0.07224088 0.00387907 0.003662467 0.07222151 0.003560185 0.003745198 0.07207506 0.003265619 0.004141211 0.07219785 0.003348469 0.004271328 0.07205688 0.003123402 0.004800796 0.07216906 0.003373205 0.004803001 0.07203572 0.003163039 0.005209445 0.07201331 0.003352642 0.005431056 0.0721358 0.003821134 0.005579113 0.07199811 0.003692984 0.005815327 0.07197749 0.004135966 0.005669951 0.07210725 0.004417896 0.005891263 0.07195836 0.004602968 0.005613625 0.07208049 0.005025506 0.005787551 0.07194447 0.00513029 0.005577027 0.07192504 0.005508601 0.005288362 0.07205402 0.005523145 0.005251884 0.0719074 0.005820095 0.004755795 0.07202738 0.005831241 0.004767417 0.07188451 0.006039321 0.004021465 0.07188075 0.0060395 0.004167377 0.07200109 0.005854904 0.003718733 0.07197988 0.005671322 0.003466308 0.07185697 0.005733668 0.003386199 0.07196223 0.005363404 0.003273785 0.07183831 0.005553305 0.003156185 0.07193684 0.004896402 0.003168046 0.07190984 0.004286944 0.003367483 0.0718888 0.003853797 0.003775775 0.0718649 0.003485739 0.003133296 0.07758873 0.004432678 0.00331366 0.07757759 0.003922522 0.003822684 0.07753771 0.003453493 0.004468023 0.0775085 0.003319919 0.004985332 0.07748484 0.003463745 0.005314111 0.07746434 0.00370413 0.00557655 0.07744586 0.004099905 0.005683004 0.07742476 0.00456953 0.005602777 0.07740396 0.005031585 0.00527507 0.07737702 0.005546033 0.004748106 0.07735085 0.00582689 0.004148602 0.07732456 0.005856096 0.003578722 0.07729649 0.005576729 0.003172874 0.07726538 0.004979431 0.003151059 0.07723838 0.004373788 0.003315508 0.07721805 0.003938138 0.003704309 0.0771926 0.003520369 0.004269957 0.07716685 0.003332376 0.004722356 0.07714664 0.00336188 0.00512433 0.07712727 0.00354743 0.005452811 0.07710742 0.003873944 0.00568372 0.07708013 0.004434645 0.005589962 0.07705253 0.005065977 0.005277037 0.07702696 0.005543649 0.004751443 0.07700133 0.005823969 0.004299879 0.07698106 0.005871057 0.003821253 0.07695972 0.005734682 0.003378629 0.07693386 0.005362331 0.003139197 0.07690709 0.00480479 0.003192126 0.07688093 0.004199504 0.003517866 0.0768522 0.003666162 0.004236161 0.07681858 0.003319501 0.00484097 0.0767914 0.003402352 0.005310118 0.07676702 0.003691315 0.005590736 0.07674413 0.004131019 0.005682349 0.07671499 0.004783511 0.005380451 0.07668387 0.005426645 0.004786252 0.076653 0.005831062 0.004059553 0.07662051 0.005832672 0.00353837 0.07659411 0.005538582 0.003261446 0.07657408 0.005159854 0.003133118 0.07655209 0.004692971 0.003182351 0.07653182 0.004231512 0.00344187 0.07650828 0.00375694 0.003901362 0.0764836 0.003423452 0.004360377 0.07646274 0.0033257 0.004821062 0.07644236 0.003394365 0.005294799 0.07641845 0.003672599 0.005670726 0.07638329 0.004346847 0.005608499 0.07635402 0.005027651 0.005217492 0.07632416 0.005600094 0.004663348 0.07629716 0.005845904 0.004053354 0.07627022 0.005836009 0.003538072 0.07624405 0.005534112 0.003199398 0.07621771 0.005038678 0.003139078 0.07618969 0.004406809 0.003435432 0.07615858 0.003748297 0.003939926 0.07613158 0.003412604 0.004397273 0.07611125 0.003324687 0.004879415 0.07608944 0.003410279 0.005295872 0.07606768 0.003689467 0.005626559 0.07604104 0.004191875 0.005652189 0.07601082 0.004892587 0.005382537 0.07598412 0.005422592 0.005037367 0.07596474 0.005702495 0.004572212 0.07594358 0.005865752 0.004005491 0.07591736 0.005815327 0.003542363 0.07589453 0.005535364 0.003265798 0.07587426 0.005175411 0.003131389 0.07585287 0.00469619 0.003216922 0.07582706 0.004124104 0.003566563 0.07580029 0.003628194 0.004267692 0.07576656 0.003313899 0.004889428 0.07573902 0.003421306 0.00540632 0.07571178 0.003785133 0.005652427 0.07568454 0.004343748 0.005651831 0.07566016 0.004894793 0.005424141 0.07563734 0.00536412 0.00491625 0.07560813 0.005783736 0.004210233 0.07557708 0.005863308 0.00357747 0.07554733 0.005584597 0.003227233 0.07552021 0.005087852 0.003130197 0.07549858 0.004603385 0.003246724 0.07547354 0.004039645 0.003658592 0.07544529 0.003564476 0.004077553 0.07542502 0.003364861 0.00461775 0.07540148 0.003337442 0.00514245 0.07537674 0.003554284 0.005533397 0.0753507 0.003991246 0.005682826 0.07532417 0.004575729 0.005602538 0.07530415 0.005034208 0.005371868 0.0752837 0.005426526 0.004986047 0.07526177 0.005739629 0.00446695 0.07523858 0.005871951 0.0039016 0.07521361 0.005778133 0.003477513 0.07519036 0.005471825 0.003212869 0.07516872 0.005053997 0.00312674 0.07514214 0.004463255 0.003337919 0.07511627 0.003902733 0.003727793 0.07509142 0.003507077 0.004271984 0.0750671 0.003332436 0.004752993 0.07504528 0.003368496 0.005171895 0.07502478 0.003581523 0.005550563 0.07499974 0.004020273 0.005685687 0.0749672 0.004718303 0.005391061 0.07493424 0.005426466 0.004915356 0.07490915 0.005764961 0.004350483 0.07488328 0.005881905 0.00382024 0.0748592 0.005730509 0.003412961 0.07483679 0.005404591 0.003159165 0.07481056 0.004895329 0.003155231 0.07478773 0.004354238 0.003317117 0.07476747 0.003930091 0.003654956 0.07474607 0.003564715 0.004215061 0.07471895 0.003331065 0.004735529 0.07469612 0.003367662 0.005152881 0.07467633 0.003567993 0.005493998 0.07465344 0.003926515 0.005661666 0.07463222 0.004395008 0.005622267 0.07460498 0.005025923 0.005275189 0.07457774 0.005528032 0.004805445 0.07455337 0.005816042 0.004286408 0.07453054 0.005867779 0.003662943 0.07450133 0.005654811 0.003225505 0.07447028 0.005094885 0.003133118 0.0744394 0.004382133 0.003390371 0.07441216 0.00382924 0.0038293 0.07438653 0.003450691 0.004363 0.07436293 0.003325045 0.004821598 0.07434231 0.00339508 0.005314528 0.07431626 0.003689169 0.005615472 0.07429105 0.004203975 0.005680859 0.07426995 0.004680156 0.005560696 0.07424908 0.005133926 0.005291342 0.07422876 0.005513906 0.004829049 0.07420486 0.005810797 0.004057705 0.07416969 0.005841672 0.003520727 0.07414293 0.005516648 0.003211975 0.07411944 0.005062818 0.003133475 0.07408958 0.004405498 0.003459811 0.07405662 0.003725945 0.003961741 0.07403039 0.003402709 0.004556894 0.07400411 0.003324329 0.005147874 0.07397603 0.003555953 0.005601465 0.07394492 0.004117727 0.00567305 0.07391798 0.004719555 0.005497515 0.07389295 0.005271852 0.004973471 0.07386034 0.005752503 0.004215896 0.07382744 0.005872249 0.003678441 0.07380235 0.005644142 0.003316164 0.07377904 0.005270421 0.003126144 0.07375222 0.004693865 0.003222167 0.07372736 0.004123032 0.003499865 0.07370376 0.003692626 0.003958821 0.07368093 0.003405928 0.004404902 0.07366067 0.003321826 0.004893124 0.07363927 0.003418385 0.005385458 0.07361215 0.003773212 0.005626738 0.07358926 0.004235804 0.0056746 0.07356947 0.004696249 0.005547761 0.07354664 0.005174577 0.005236327 0.07352542 0.005562782 0.004678249 0.07349818 0.005859494 0.004068732 0.07347095 0.005826711 0.003509342 0.07344287 0.005527079 0.003208577 0.07341796 0.005030572 0.003129065 0.07339715 0.004573345 0.003295242 0.07336747 0.003940105 0.003825426 0.07333743 0.003458142 0.004299581 0.07331526 0.003327846 0.004816889 0.07329261 0.003389596 0.005355 0.07326489 0.003730475 0.00565797 0.07323408 0.004342436 0.005649149 0.07321017 0.00489068 0.005446612 0.07318931 0.005330324 0.005052983 0.07316559 0.005705296 0.004553914 0.07314229 0.005863606 0.003919601 0.07311409 0.005793333 0.003345549 0.07308143 0.005322694 0.003139257 0.07305544 0.00476402 0.003182351 0.07303106 0.004212915 0.003557503 0.07300126 0.003633141 0.00404483 0.0729767 0.003376781 0.004651606 0.07295042 0.003336131 0.005190551 0.07292336 0.003593981 0.005570173 0.07289731 0.004060983 0.005681812 0.07286733 0.004741549 0.005403637 0.07283526 0.005406439 0.004965782 0.07281112 0.005742371 0.004403412 0.07278615 0.005881965 0.003719508 0.07275354 0.005687177 0.003220856 0.07272064 0.005104422 0.003133773 0.07269549 0.004527151 0.003284633 0.07266968 0.003970324 0.003659248 0.0726456 0.003565669 0.004239678 0.07261776 0.003320991 0.004913985 0.07258784 0.003424823 0.005472958 0.07255697 0.003874778 0.005669772 0.07252973 0.004453241 0.00562793 0.07250666 0.004973888 0.00539124 0.07248491 0.005406737 0.005037784 0.07246524 0.005703389 0.004539668 0.07244092 0.005873382 0.004018783 0.07241863 0.00581175 0.003607809 0.07239824 0.005593836 0.003287315 0.07237672 0.005221188 0.003137946 0.07235401 0.00472486 0.003176331 0.0723325 0.004244923 0.003391325 0.07231241 0.003827273 0.00375843 0.07229036 0.003498375 0.004384934 0.07226067 0.003308415 0.005073189 0.07223057 0.003507733 0.005501806 0.07220339 0.003934264 0.005686223 0.07217419 0.004575192 0.005583584 0.07215178 0.005084216 0.005258977 0.07212591 0.005554199 0.004591345 0.07209336 0.005876064 0.003959536 0.07206624 0.005791723 0.003580391 0.07204651 0.005574762 0.003220081 0.07202005 0.005087971 0.003129899 0.07199352 0.004484534 0.003280878 0.07197093 0.004002451 0.003660082 0.07194501 0.003548324 0.00423634 0.0719186 0.003335177 0.004695296 0.07189792 0.003358483 0.003578722 0.07758784 0.003529667 0.00543183 0.07758516 0.003536343 0.004200756 0.07758778 0.003210425 0.004886507 0.07758778 0.00323981 0.0057199 0.07757681 0.003926098 0.005887925 0.07754117 0.004536628 0.005783438 0.07751905 0.005124807 0.004927396 0.07747137 0.005983233 0.003735601 0.07742565 0.005926668 0.003225386 0.07740008 0.005487322 0.002942681 0.07737463 0.004869997 0.003064274 0.07698911 0.003955304 0.00581175 0.07681977 0.005109608 0.003761887 0.07660144 0.003257811 0.005146384 0.07643097 0.005881905 0.004608869 0.07640957 0.006059587 0.002993941 0.07629698 0.004154026 0.003362178 0.0762704 0.003538489 0.004310846 0.07604801 0.006082713 0.003171801 0.07593107 0.00376743 0.003227055 0.07557773 0.003703474 0.003781855 0.07555121 0.003248453 0.005559504 0.07540214 0.005516886 0.005680263 0.07511913 0.003854215 0.003633201 0.07497119 0.005855858 0.003202676 0.07494908 0.005461752 0.002935409 0.0749225 0.004824757 0.004830479 0.0748105 0.003184914 0.005344867 0.07478845 0.003457546 0.005722105 0.07476562 0.003920614 0.005874276 0.07474422 0.004473268 0.005799114 0.07471925 0.005115985 0.002937853 0.07457351 0.004829883 0.002990841 0.07454723 0.00416249 0.003682076 0.07450568 0.003306746 0.005865454 0.07437914 0.004861831 0.005629181 0.07435655 0.005420744 0.005249738 0.07433599 0.005812644 0.004770278 0.0743153 0.006030023 0.003622889 0.07427078 0.005863428 0.002930819 0.07422107 0.004774034 0.002989411 0.07419836 0.004181861 0.005797863 0.07402008 0.00511372 0.003426373 0.07391113 0.005699455 0.003051757 0.07388824 0.005215764 0.005651354 0.07365751 0.005394697 0.00588876 0.07333874 0.004623055 0.005060195 0.07327741 0.005925536 0.003473281 0.07321327 0.005752861 0.003092825 0.07319098 0.005272209 0.003706395 0.07310408 0.003295004 0.004867017 0.07305896 0.003185093 0.005732595 0.07301497 0.00395137 0.005877494 0.07299447 0.004458844 0.005148589 0.07293063 0.005886197 0.004638195 0.07256078 0.006064653 0.004043996 0.07253807 0.006029367 0.003137528 0.07243269 0.003820538 0.003630459 0.07240796 0.003341495 0.004154384 0.07238608 0.003138482 0.003698527 0.07217389 0.005907177 0.003024637 0.07209426 0.004077613 0.003329575 0.07207262 0.00358206 0.005867004 0.07758909 0.004375338 0.003931105 0.07158792 0.005784511 0.003892481 0.07161515 0.005839943 0.003754675 0.0716812 0.005862712 0.003577351 0.07178097 0.005811572 0.003933906 0.07172769 0.005974531 0.004312634 0.07163214 0.005966305 0.005032718 0.07159239 0.005734324 0.004674315 0.07160407 0.005893647 0.004329383 0.07174926 0.006059288 0.00466299 0.07170701 0.006016075 0.004906475 0.07182604 0.005990922 0.005016922 0.07168483 0.005883097 0.005521059 0.07159227 0.005256831 0.005281388 0.07166284 0.005697309 0.005282521 0.07182765 0.005792796 0.005433917 0.07163405 0.005511581 0.005563199 0.07173562 0.005479335 0.005658566 0.07158809 0.004447937 0.005682528 0.07171183 0.005271732 0.005706191 0.07161694 0.004953265 0.005800008 0.07174378 0.005019247 0.005828022 0.07168793 0.0047127 0.005747675 0.07161754 0.004446923 0.005874335 0.07182931 0.004769682 0.005840122 0.07171666 0.004399776 0.005756199 0.0717101 0.004090785 0.00557506 0.07159608 0.004027247 0.005663573 0.07174581 0.003863036 0.005488753 0.07166868 0.003691911 0.004670023 0.07158756 0.003351569 0.005314469 0.0716024 0.003633737 0.005469739 0.07183432 0.003567457 0.005272328 0.07171463 0.00344634 0.004946708 0.07164347 0.003317892 0.005121529 0.07182782 0.00330621 0.004857957 0.07170987 0.003227591 0.00445789 0.07161045 0.003267168 0.004672467 0.07183277 0.003142356 0.004518568 0.07167661 0.003187 0.004166483 0.07164674 0.003229141 0.004290401 0.07174235 0.003144741 0.004024624 0.07159233 0.003367006 0.003902554 0.07174897 0.003225982 0.003735542 0.07163751 0.003387093 0.003444492 0.07159292 0.003730714 0.003475904 0.07172578 0.00348246 0.003374993 0.07166296 0.003642797 0.003179252 0.0716269 0.003999769 0.003114759 0.07159155 0.004456043 0.003161847 0.07172954 0.003850102 0.00306338 0.0716238 0.00438863 0.003000736 0.0717203 0.004246354 0.00295484 0.07173264 0.004516482 0.003282546 0.07158976 0.005207836 0.003016829 0.07165843 0.004796743 0.003148317 0.07162213 0.00513041 0.003075242 0.07173651 0.00519067 0.003481149 0.0716353 0.005625128 0.003260314 0.07170617 0.005470216 0.006098747 0.07777714 0.002496421 0.006152868 0.07763528 0.002654612 0.006458103 0.0777316 0.002863705 0.006708323 0.07777684 0.003190636 0.006465017 0.07759231 0.003133833 0.006738543 0.07765722 0.003369688 0.006934404 0.0777322 0.00368309 0.006766796 0.07759433 0.003706812 0.007041394 0.07776999 0.004018902 0.006981313 0.07764321 0.00411266 0.007098436 0.07776027 0.004522621 0.007014751 0.0776388 0.004561603 0.006906867 0.07758909 0.004680693 0.007079303 0.07773953 0.004871606 0.007018387 0.07775485 0.005258381 0.006941914 0.07762598 0.005123019 0.006770372 0.07759428 0.005500793 0.006801307 0.07766765 0.005717575 0.006863415 0.07778161 0.005710482 0.00664103 0.07778537 0.006112992 0.006502151 0.07760012 0.006033182 0.006466567 0.07766568 0.00625509 0.006284773 0.07777339 0.006535291 0.006045699 0.07772552 0.006724894 0.006000578 0.07759296 0.006560325 0.005618512 0.07776814 0.007008433 0.005726337 0.07764971 0.006873071 0.005159437 0.07764571 0.007112145 0.005072534 0.07776492 0.007214486 0.005118966 0.07759153 0.007011413 0.004565834 0.07767611 0.007245838 0.004440784 0.07777941 0.007298171 0.004214107 0.07759279 0.007124245 0.003965437 0.07773178 0.00725156 0.003657877 0.07775199 0.007186472 0.003516912 0.07762414 0.007045149 0.003181695 0.07776999 0.007003784 0.003335058 0.07760393 0.006915807 0.002819538 0.07759147 0.006560206 0.002949833 0.07766956 0.006806194 0.002772867 0.07779407 0.006749272 0.002455174 0.07766705 0.006388545 0.002459645 0.07776468 0.006469309 0.002130985 0.0777598 0.006044387 0.002287745 0.0775932 0.005985081 0.002095162 0.07764548 0.005834281 0.001926362 0.07775282 0.005652427 0.001794397 0.07778292 0.005298912 0.001957595 0.07761836 0.005416512 0.001796662 0.07766538 0.00503844 0.001706659 0.07779556 0.004736185 0.001909255 0.07759046 0.004856348 0.001779258 0.07765084 0.004522502 0.00173527 0.0777387 0.004269897 0.001837849 0.07776552 0.003761768 0.001941382 0.07760006 0.003913938 0.001933574 0.07769513 0.003608345 0.002085864 0.0776152 0.003469705 0.002043187 0.0777828 0.003291368 0.002284705 0.07765841 0.003024816 0.002372562 0.07775968 0.002825796 0.002526998 0.07758665 0.002932846 0.00267446 0.0777927 0.002526342 0.002792775 0.07764959 0.002525448 0.003008067 0.07775199 0.002295374 0.003309249 0.07761275 0.002267181 0.003356218 0.07775598 0.002116858 0.003762662 0.0777415 0.001985967 0.004182279 0.07758855 0.002102613 0.00385189 0.07762551 0.002066791 0.004224419 0.07775998 0.001908242 0.004340231 0.07763439 0.001996636 0.00470525 0.07774162 0.001924872 0.004928767 0.07761216 0.0020805 0.005151987 0.07775586 0.002008736 0.005427658 0.07764208 0.002192258 0.005577683 0.07758879 0.00239247 0.005641698 0.07777237 0.002199947 0.005764365 0.07764506 0.002354979 0.006096839 0.08039951 0.002495348 0.006391465 0.08041441 0.002779781 0.006634414 0.08040767 0.003079235 0.007040917 0.0804125 0.004023253 0.007102072 0.08039844 0.004545211 0.007080554 0.08043992 0.004871547 0.007016897 0.08042567 0.005248546 0.006744086 0.08039414 0.005943477 0.006320953 0.08041369 0.006494104 0.00588411 0.08042258 0.006857514 0.005365312 0.08039492 0.007122099 0.004868507 0.08042114 0.007253766 0.00445348 0.08041363 0.007291793 0.004023969 0.0804001 0.007273077 0.003556191 0.08044457 0.007150113 0.003042936 0.08041489 0.006926059 0.002326369 0.08041423 0.006317734 0.001896083 0.08041447 0.005594313 0.001741826 0.0803861 0.004132628 0.002039134 0.08037579 0.003292679 0.002400279 0.08041244 0.002790451 0.003113269 0.08040583 0.002227127 0.003601968 0.08037352 0.00202012 0.004142105 0.08038759 0.001907885 0.004497587 0.08044242 0.001912474 0.005755305 0.08040237 0.002265453 0.005852758 0.0805366 0.002419173 0.005515813 0.08058601 0.002349436 0.005353569 0.08052229 0.002148687 0.005406796 0.08041465 0.002095043 0.004902899 0.080554 0.002050876 0.004960119 0.08041226 0.001961171 0.00458002 0.08056175 0.002032518 0.00409317 0.08058476 0.002092003 0.00385034 0.0804854 0.001995503 0.003628492 0.08056592 0.002153575 0.00335735 0.08047491 0.002147495 0.002916514 0.08052915 0.002436697 0.002806842 0.0805844 0.002641081 0.002762615 0.08040714 0.002461433 0.002405583 0.08055198 0.002951204 0.002190113 0.08047652 0.003110945 0.001896619 0.08045285 0.003643453 0.002116084 0.08057898 0.003501534 0.001914381 0.08058327 0.004119038 0.001769065 0.08050477 0.004328012 0.001709342 0.08040285 0.004598081 0.001738965 0.08042019 0.004996955 0.001839578 0.08055543 0.004915356 0.001889407 0.08052259 0.005351424 0.002027392 0.08058148 0.005459845 0.002193152 0.0805388 0.005990087 0.002293348 0.0805844 0.005973339 0.002107739 0.08041971 0.006002783 0.002563595 0.08047795 0.006529986 0.00266236 0.08040851 0.006655693 0.002884566 0.08056247 0.006684303 0.003370761 0.08051228 0.007026314 0.00349456 0.08058601 0.006941854 0.004034519 0.08054512 0.007177889 0.004585683 0.08053141 0.007208287 0.004757285 0.08058637 0.007088005 0.005277991 0.08052361 0.007082641 0.005760014 0.08057504 0.006764531 0.005986273 0.08048176 0.006741285 0.00651282 0.08053004 0.006162881 0.006260931 0.08058083 0.006324946 0.006559312 0.08042407 0.00621277 0.00687015 0.0804345 0.005679845 0.006676137 0.08058387 0.005681931 0.006875872 0.08053356 0.005457222 0.006954014 0.08056151 0.004971742 0.007040441 0.08049482 0.004289865 0.006929457 0.08058184 0.004425227 0.006916403 0.08053606 0.003880858 0.006882309 0.08041262 0.003532767 0.006740868 0.08058524 0.003681898 0.006740868 0.08051574 0.003378987 0.006413459 0.08057832 0.003032803 0.006315529 0.0805146 0.002776443 0.01540422 0.07889527 0.003017902 0.0155251 0.07890808 0.001648187 0.01527637 0.07900339 0.003070831 0.01544463 0.07904696 0.001588106 0.01680582 0.07889598 0.00114566 0.01682072 0.0790053 0.001008391 0.01792562 0.07890665 0.001937925 0.01802086 0.07904481 0.001897335 0.01773798 0.07889932 0.003304541 0.01783686 0.07901602 0.003380477 0.01648414 0.07889598 0.003827154 0.01646614 0.0790053 0.003964066 0.0178706 0.08057624 0.003404974 0.01646095 0.08057683 0.004009723 0.01805496 0.08057665 0.001884341 0.01682662 0.08057707 9.6171e-4 0.01541483 0.08057665 0.001567661 0.01523429 0.08057624 0.003088712 0.01635891 0.07184231 0.001233041 0.01684635 0.0718376 0.001018226 0.01580339 0.07183438 0.001264989 0.01698589 0.0718379 0.0012542 0.01585847 0.071855 0.001467466 0.01547318 0.07183623 0.001583456 0.01753354 0.0718494 0.001571476 0.01543259 0.07183796 0.001818895 0.01528048 0.07183754 0.001930415 0.01780402 0.07184147 0.001963675 0.0151816 0.0718367 0.00268805 0.01807075 0.0718379 0.002110123 0.01795798 0.07183873 0.002501428 0.01527667 0.07183676 0.003033638 0.0180608 0.0718379 0.002904236 0.01778739 0.07183778 0.003225386 0.01713931 0.0718429 0.003869414 0.01750487 0.07183796 0.003688216 0.01643824 0.07184207 0.003946483 0.01668989 0.07184201 0.003961682 0.01812064 0.07758605 0.002534508 0.018031 0.07753819 0.0030061 0.0177828 0.07752281 0.003439426 0.0178318 0.0775879 0.003254115 0.01741713 0.07752549 0.00375247 0.01610141 0.0775882 0.003647267 0.01734602 0.07758796 0.003669798 0.01689922 0.07750457 0.0039348 0.01639205 0.07748556 0.003945171 0.01672381 0.0775879 0.003805756 0.015872 0.07744306 0.003758907 0.01569902 0.0775783 0.003338277 0.01546221 0.07742542 0.003379702 0.01545363 0.07757055 0.002934396 0.01518863 0.07741981 0.00279361 0.01537084 0.0775153 0.002277374 0.01522099 0.07739311 0.002081573 0.01568394 0.07748419 0.001638412 0.01546585 0.07735055 0.001578092 0.01575845 0.07733082 0.001298248 0.01611882 0.07746022 0.001324117 0.01614075 0.07731765 0.001091361 0.01675051 0.07743185 0.001202404 0.01667922 0.0772984 0.00100106 0.01718318 0.07728034 0.001102149 0.01731306 0.07740575 0.001402735 0.01761853 0.07725554 0.001364767 0.01771473 0.07738196 0.001782536 0.0179255 0.07724344 0.001744925 0.01807981 0.07722008 0.002102136 0.01790052 0.07735824 0.002272367 0.01812165 0.07720744 0.00259298 0.01787793 0.07733446 0.0028252 0.01800394 0.07719373 0.003081917 0.01754522 0.07730525 0.003403902 0.01774734 0.07716631 0.003480434 0.01734042 0.0771507 0.003795027 0.01692044 0.07727372 0.003737628 0.01678735 0.07713007 0.003967702 0.01638853 0.07725048 0.003735959 0.01622569 0.07710641 0.003911674 0.01585537 0.07722508 0.003497302 0.01573818 0.07708764 0.003660619 0.0153619 0.07706463 0.003243982 0.0154156 0.07719165 0.002887189 0.01518028 0.07704281 0.002733945 0.0151757 0.07702738 0.002240598 0.01542341 0.07715648 0.002076327 0.01533943 0.07701402 0.001767098 0.01576375 0.077129 0.001563191 0.01571267 0.07698619 0.001332104 0.0162428 0.07710444 0.001270711 0.01624107 0.07696342 0.001052379 0.01674348 0.07708227 0.001215159 0.01678943 0.07694685 0.001009643 0.01727598 0.07705813 0.001373589 0.01722216 0.07692509 0.001120686 0.01767885 0.07690727 0.001417756 0.01777088 0.07702714 0.001860678 0.01795846 0.07687962 0.001800298 0.01810199 0.07687234 0.002215802 0.01791816 0.07699936 0.002485215 0.01810675 0.07685548 0.002751111 0.01781761 0.07697641 0.003001213 0.01797455 0.07683521 0.003134489 0.01775306 0.07682043 0.003470301 0.01749938 0.07695251 0.003427505 0.01732295 0.07680118 0.003807187 0.01713532 0.07693397 0.003664314 0.0168302 0.07678246 0.003960371 0.01670044 0.07691413 0.003759562 0.01633661 0.07676196 0.003938972 0.01620846 0.07689237 0.003685235 0.01589238 0.07674062 0.003765642 0.01567399 0.07686394 0.003336489 0.01547372 0.07671946 0.003407776 0.01525264 0.07672697 0.002976119 0.01539903 0.07683622 0.002757668 0.01516479 0.07670676 0.002445518 0.01539099 0.07681208 0.002201855 0.01532548 0.07668095 0.001801073 0.01571214 0.07678186 0.001607775 0.01577627 0.07665574 0.00128901 0.01615619 0.07675868 0.001306414 0.01625043 0.07663536 0.001061558 0.0166074 0.07673817 0.00121355 0.0167061 0.0765962 0.001002728 0.01717358 0.07671278 0.001315832 0.01716226 0.07657301 0.001097381 0.01753664 0.07658427 0.00130701 0.01761209 0.07668846 0.001658737 0.01796823 0.07653754 0.001810491 0.01788878 0.07666325 0.002173244 0.01809787 0.0765435 0.002217352 0.01789468 0.07663798 0.002733707 0.01809853 0.07652306 0.002744257 0.01797461 0.07648521 0.003149867 0.01767063 0.0766139 0.00325036 0.01754993 0.07648247 0.003656148 0.01727372 0.07659053 0.003596186 0.01724439 0.07644402 0.00383985 0.0167787 0.07656723 0.003756046 0.01684141 0.07642984 0.003954887 0.01628798 0.07640963 0.003930449 0.0162689 0.07654529 0.003706693 0.01588517 0.07639652 0.003759264 0.01582556 0.07652294 0.003467679 0.01553899 0.07637661 0.003475248 0.01550185 0.07649999 0.003053009 0.01525342 0.0763573 0.003010034 0.01537436 0.07648003 0.002623379 0.01515662 0.07633328 0.002474904 0.01544237 0.07645463 0.00203967 0.01526713 0.07631653 0.001937687 0.01549053 0.07629728 0.001555621 0.0157541 0.07642984 0.001570224 0.0158171 0.07628077 0.001250922 0.016294 0.07640194 0.001247584 0.01631093 0.07626038 0.001042008 0.01678144 0.0762518 0.001009106 0.01705193 0.07636898 0.001265525 0.01721507 0.07622551 0.00111109 0.01765131 0.07633626 0.001691162 0.01782804 0.07621973 0.001587808 0.01789468 0.07631063 0.002227485 0.01810812 0.07617485 0.002233803 0.01789444 0.0762887 0.002723932 0.01809799 0.07615154 0.00277245 0.01773428 0.07626897 0.003149986 0.01793181 0.07612961 0.003224313 0.01763415 0.07611417 0.003591716 0.01737213 0.076245 0.003538608 0.017237 0.0761187 0.003834366 0.01666456 0.07621288 0.00377953 0.01671421 0.07609856 0.003966093 0.01641827 0.07605898 0.003956079 0.0160374 0.07618391 0.003605723 0.01592254 0.07604509 0.003781914 0.01566934 0.07616329 0.003310441 0.01548349 0.07602643 0.003416836 0.01544535 0.07614368 0.00292313 0.01521909 0.07599794 0.002917468 0.01536953 0.07611829 0.002343893 0.01516914 0.07598084 0.002328872 0.01532739 0.07595777 0.001790225 0.0155819 0.07609093 0.001771688 0.01566797 0.07593715 0.001367986 0.01605767 0.07606339 0.001345932 0.01614773 0.07591706 0.001082241 0.01659959 0.07603877 0.00121057 0.01662302 0.07590329 9.97988e-4 0.0170902 0.07601636 0.001291394 0.01717257 0.07587814 0.001101076 0.01765757 0.07585638 0.001397907 0.01751261 0.07599526 0.001551628 0.01777893 0.07597547 0.001905798 0.0179845 0.0758363 0.001842856 0.01792609 0.07595014 0.002471864 0.01811563 0.07583701 0.002384841 0.01807379 0.07581961 0.002851963 0.01774936 0.07591903 0.003143012 0.01794534 0.07578217 0.003208696 0.0175907 0.07576382 0.003631234 0.01731187 0.07589256 0.003571569 0.01697522 0.07575809 0.00393325 0.01684695 0.07587081 0.003749907 0.01628404 0.07571005 0.003926753 0.01620328 0.07584202 0.003691077 0.01583105 0.07569503 0.003729403 0.01573157 0.07581746 0.003379344 0.01544272 0.07567209 0.003362953 0.01547652 0.07579696 0.002994775 0.01520681 0.07565045 0.002852141 0.01535874 0.07577043 0.00240451 0.0151655 0.07562524 0.002341985 0.01526534 0.07561391 0.001920104 0.01554328 0.07574468 0.001845479 0.01559281 0.07559299 0.001436769 0.01584696 0.07572442 0.00149095 0.01590573 0.0755999 0.001208186 0.01625967 0.07570391 0.001267611 0.01633721 0.07558196 0.001040995 0.01675754 0.07568132 0.001217663 0.01693338 0.07553321 0.001027584 0.01735663 0.07565438 0.001410484 0.01738798 0.07554137 0.001207172 0.01787942 0.07551556 0.001662671 0.01781249 0.07562226 0.00196588 0.01811867 0.07547163 0.002281248 0.01792132 0.07559108 0.002682387 0.01810652 0.07544314 0.002735137 0.01795345 0.07543557 0.00317955 0.01763284 0.07556128 0.003289639 0.01762622 0.07541489 0.003601193 0.017223 0.07553756 0.003630697 0.01720088 0.07540118 0.003861546 0.01667678 0.07551318 0.003759026 0.01659286 0.07537555 0.00396955 0.01622807 0.07549345 0.003693461 0.01602727 0.07537186 0.003839731 0.0158385 0.07547348 0.003473877 0.01553982 0.07532536 0.003475308 0.01553714 0.0754528 0.003117203 0.01523542 0.07530415 0.002970993 0.01538479 0.07543373 0.002699434 0.01516193 0.07528966 0.002505958 0.01539313 0.07541346 0.002245664 0.0152229 0.07526975 0.002062082 0.01565486 0.07538509 0.001656234 0.01548397 0.0752511 0.001554846 0.01588547 0.07523012 0.00120759 0.01617139 0.07535773 0.001303613 0.01646471 0.07522749 0.001021623 0.01677203 0.0753315 0.001205563 0.01691597 0.0751906 0.001025617 0.01751637 0.07518577 0.001287996 0.01744639 0.07529884 0.001483678 0.01794129 0.07516115 0.00177747 0.01783382 0.07527053 0.002013385 0.01811283 0.0751394 0.00230962 0.01791769 0.07524663 0.002542912 0.01810318 0.0751006 0.002771615 0.01777559 0.07522201 0.00308448 0.01795208 0.07507801 0.003185153 0.01760756 0.07505995 0.003622472 0.017452 0.0751999 0.003472089 0.01695823 0.07517576 0.003726899 0.01708346 0.07504093 0.00390315 0.01655137 0.07501721 0.003971934 0.01632106 0.07514721 0.003729045 0.01620566 0.07502895 0.003902196 0.0157867 0.07512074 0.0034312 0.01564228 0.07498562 0.003579437 0.01550012 0.07510006 0.003053963 0.01530343 0.07498282 0.003124415 0.01537686 0.07507967 0.002614617 0.01516133 0.07493704 0.002514958 0.015428 0.07505643 0.002085566 0.01525461 0.07491528 0.001954317 0.01568144 0.07503432 0.001649856 0.01550513 0.07490342 0.001535475 0.01585501 0.07487988 0.001228272 0.01607447 0.07501256 0.001345098 0.01636391 0.07486009 0.001024007 0.01653146 0.07499146 0.001214265 0.01687216 0.07483679 0.001016855 0.01698023 0.07497167 0.001257896 0.01739746 0.07482188 0.001209914 0.01740109 0.07495135 0.001461148 0.01786047 0.07481706 0.001635909 0.0177558 0.0749284 0.001848816 0.01811397 0.07476896 0.002279758 0.01790934 0.0749045 0.002358675 0.01810389 0.0747599 0.002744793 0.01788324 0.07488602 0.002791404 0.01795178 0.07473224 0.003194868 0.01770079 0.07486611 0.003198266 0.01760262 0.07471293 0.003617882 0.01734846 0.07484441 0.003549456 0.01716744 0.07469189 0.003875553 0.01675039 0.07481598 0.003771424 0.01666855 0.07467854 0.003971576 0.01595103 0.07466918 0.003801941 0.01612132 0.07478821 0.003648221 0.015751 0.07476878 0.003399074 0.01543682 0.07464212 0.003342866 0.01544702 0.07474404 0.002940237 0.01520425 0.07462048 0.002809047 0.0153706 0.07472038 0.00239253 0.01515752 0.07458281 0.00245136 0.01548212 0.07470047 0.001961588 0.0152598 0.07456719 0.001942932 0.01578962 0.07467728 0.001535952 0.01550805 0.07454705 0.001526296 0.01584392 0.07452529 0.001236617 0.01616793 0.07465809 0.001304507 0.01635462 0.07453107 0.001032292 0.01658391 0.0746392 0.001212239 0.01698815 0.07448619 0.001043796 0.01707458 0.07461762 0.001286327 0.0175237 0.07446521 0.001282632 0.01750832 0.07459521 0.00154227 0.01791429 0.07444095 0.00172156 0.01782524 0.07457077 0.002006709 0.01811176 0.0744189 0.002251923 0.01792055 0.07454991 0.002474904 0.01810687 0.07439959 0.002726495 0.01784127 0.0745297 0.00292015 0.01796936 0.07438498 0.003152251 0.017475 0.07450026 0.003476619 0.01760619 0.07436597 0.003623604 0.0171163 0.07434701 0.00389266 0.01668328 0.07446414 0.003775835 0.01668059 0.07432532 0.003972887 0.01597946 0.07431977 0.003813862 0.01604783 0.07443457 0.003615736 0.01554679 0.07440584 0.003165721 0.01546782 0.07427465 0.003390669 0.0152086 0.07425546 0.00288254 0.01536101 0.07437211 0.002433419 0.01518988 0.0742473 0.002194464 0.01555228 0.07434344 0.001821219 0.01550316 0.07420462 0.001531004 0.01593303 0.07431966 0.001422107 0.01593971 0.07417476 0.001177728 0.01642137 0.07429641 0.001232624 0.01646441 0.07415586 0.001014351 0.01704764 0.07426863 0.001259624 0.01691013 0.07413518 0.001028835 0.01734298 0.07412058 0.001171946 0.01757907 0.07424074 0.001622498 0.01776218 0.07410424 0.00151509 0.0178911 0.07421392 0.00215578 0.01802903 0.07408422 0.001947522 0.01811373 0.07406723 0.002307295 0.01811134 0.07405197 0.002695441 0.01788514 0.07418668 0.002761006 0.01767325 0.07416373 0.003255426 0.01793396 0.07403111 0.003224968 0.01758784 0.07400804 0.003632903 0.01723551 0.07413852 0.00361365 0.01723521 0.07401853 0.003837168 0.01675492 0.07411646 0.003759264 0.01667529 0.07399708 0.003967165 0.01628202 0.07409566 0.003709256 0.01619887 0.07395416 0.003907322 0.01577115 0.07407033 0.003425657 0.01569187 0.07393527 0.003624022 0.01529586 0.07393217 0.003108322 0.01547199 0.0740469 0.002988994 0.01536995 0.07402616 0.002542495 0.01516455 0.07388854 0.002591729 0.01543474 0.07400649 0.002084672 0.01522815 0.07387441 0.002031028 0.01567405 0.07398468 0.001648843 0.0154044 0.07384628 0.001655459 0.01584374 0.07383024 0.001237928 0.01626408 0.07395327 0.001256763 0.0163812 0.07380962 0.001021146 0.01685249 0.07392752 0.001228511 0.01691424 0.07379376 0.001027464 0.0173695 0.07390332 0.001432061 0.01733547 0.07377183 0.001169919 0.01789188 0.07376557 0.00167787 0.01774543 0.07387852 0.001838505 0.01792377 0.0738523 0.002419114 0.01811265 0.07372117 0.002297043 0.01808875 0.07370042 0.00284028 0.01782405 0.07382762 0.00297302 0.01786822 0.07367676 0.00332874 0.01753127 0.07380408 0.003405332 0.01730978 0.07367205 0.003815948 0.01708489 0.07378166 0.003683745 0.0166701 0.0736463 0.003963828 0.0166487 0.07376188 0.003761231 0.01621335 0.07360726 0.003907322 0.01602327 0.07373362 0.003615498 0.01576942 0.07358711 0.003686785 0.01553356 0.07370328 0.003124177 0.0154187 0.07357192 0.003326356 0.01521176 0.07355171 0.002880513 0.01537358 0.07367891 0.002591967 0.01515853 0.07352805 0.002400338 0.01543152 0.07365602 0.002069532 0.01528739 0.07351899 0.001884758 0.01579123 0.07362705 0.001530826 0.01552039 0.07349628 0.001511693 0.0159049 0.07347393 0.001195669 0.01625907 0.07360386 0.001269042 0.01642268 0.07345616 0.001017034 0.01671719 0.07358336 0.001215219 0.01696789 0.07343679 0.001039385 0.01729714 0.07355678 0.001376807 0.01744145 0.07341152 0.001233458 0.01777255 0.07340025 0.001513659 0.01782536 0.07352292 0.001968324 0.01805526 0.07337933 0.002024412 0.01812505 0.0733661 0.002427399 0.01791268 0.07349276 0.002638876 0.01809161 0.07334643 0.002815961 0.01789361 0.07332783 0.003291904 0.01771384 0.07346653 0.00318855 0.01750499 0.07333046 0.003701806 0.01732182 0.07344311 0.003568172 0.01687258 0.07342165 0.003740966 0.01683789 0.07328051 0.00395745 0.01623713 0.07339352 0.003707587 0.01633679 0.0732845 0.003931224 0.01583021 0.07324713 0.003728806 0.01574671 0.07336807 0.00339061 0.0154584 0.07322186 0.00337702 0.0154801 0.07334768 0.003005802 0.01520544 0.07320314 0.002866029 0.01536935 0.07332772 0.002569675 0.01516515 0.07317948 0.002332031 0.0154705 0.07330125 0.001963913 0.01530992 0.07316219 0.001841187 0.01571613 0.0731582 0.001323699 0.0159195 0.07327032 0.001425147 0.01636785 0.0731315 0.001033008 0.01646405 0.07324421 0.001225769 0.01697105 0.07322257 0.00124818 0.01683861 0.07308936 0.001014351 0.01731932 0.0730741 0.001162946 0.01742327 0.07319986 0.001479208 0.01771503 0.07305383 0.001458168 0.01777178 0.0731765 0.001881718 0.01801133 0.07302808 0.001902222 0.01791328 0.0731545 0.002365112 0.01813131 0.07300937 0.002460479 0.01784873 0.0731303 0.002916634 0.01803451 0.07299184 0.003007531 0.01783835 0.07297855 0.003364205 0.01753199 0.07310461 0.003408014 0.01756882 0.07295894 0.003647863 0.01724851 0.07296937 0.0038293 0.01708829 0.07308113 0.003679156 0.01672059 0.07294881 0.003964602 0.01655477 0.07305812 0.003765881 0.01610368 0.07292437 0.003866136 0.01604413 0.07303428 0.003609836 0.01564526 0.0728814 0.003581643 0.01561349 0.07300966 0.003249585 0.01533347 0.07286065 0.003185868 0.01539903 0.0729863 0.002762019 0.01518869 0.07285284 0.002770721 0.01540875 0.07295858 0.002118289 0.01516842 0.0728293 0.002334833 0.01530015 0.07280915 0.001854658 0.01578629 0.07292717 0.001535534 0.01556712 0.07279366 0.001464545 0.015998 0.07277518 0.00115031 0.01646173 0.07289487 0.001205921 0.01664924 0.07277041 9.99059e-4 0.0171653 0.07286286 0.001319885 0.01735109 0.07272106 0.001180887 0.01771509 0.07272571 0.001467108 0.01758962 0.07284051 0.001629531 0.0180034 0.07270526 0.001907587 0.01782459 0.07282066 0.002005636 0.01791685 0.07280015 0.002464652 0.01812249 0.07266616 0.002352654 0.01807826 0.07264423 0.002878665 0.01784825 0.07278025 0.002909898 0.01785397 0.07262134 0.003345012 0.01762628 0.07276064 0.00329715 0.01749104 0.07260608 0.003708302 0.01726692 0.07274025 0.003597497 0.01713538 0.07261466 0.003878831 0.01684695 0.07272082 0.003746688 0.0166493 0.07259553 0.003964245 0.01632541 0.07269728 0.003723621 0.01619493 0.07255643 0.00390172 0.01583123 0.07267361 0.003472924 0.01574945 0.07253122 0.003671288 0.01539313 0.07252383 0.003290891 0.015531 0.07265251 0.003107726 0.01537674 0.07263082 0.002634704 0.01519137 0.07249802 0.0027951 0.0152145 0.07249295 0.002075195 0.01540833 0.07260978 0.002163648 0.01560264 0.07258987 0.001753032 0.01553595 0.07246792 0.001512825 0.01593542 0.07256966 0.001426041 0.01585412 0.07243096 0.001223146 0.0163657 0.0725491 0.00123924 0.01646196 0.07242721 0.001020193 0.0170421 0.07251918 0.001260519 0.01705712 0.07237845 0.001057624 0.01743721 0.07238912 0.001241683 0.01756078 0.07249206 0.001599609 0.01778513 0.07237112 0.001548707 0.01785302 0.0724675 0.002068579 0.01809489 0.07234638 0.002163589 0.01789969 0.07243633 0.002791345 0.01807081 0.07231742 0.002887129 0.01777768 0.07229453 0.003430366 0.01756012 0.07240653 0.003371834 0.01731765 0.07227182 0.003808915 0.01719748 0.07238656 0.003636896 0.01662653 0.07236117 0.003767669 0.01664382 0.07222318 0.003971159 0.01615768 0.07220923 0.003889441 0.01607692 0.07233631 0.003630459 0.01571428 0.0721836 0.003645181 0.01569461 0.07231485 0.003338217 0.01537203 0.07216703 0.003250122 0.01544243 0.07229304 0.002913296 0.01519507 0.07216966 0.002785861 0.01536637 0.07227283 0.002452731 0.0151847 0.07214915 0.002257049 0.01552349 0.07224613 0.001862883 0.01543623 0.07212394 0.001618802 0.01604336 0.07221347 0.001344144 0.0159617 0.07209694 0.001172661 0.01652246 0.07207524 0.00101608 0.01665109 0.07218647 0.001213788 0.01688522 0.07203805 0.001019775 0.01708942 0.07216709 0.001287937 0.01737165 0.07202196 0.001189768 0.0175904 0.07214009 0.001622378 0.0177055 0.07200211 0.001449823 0.01803708 0.0720027 0.001982271 0.01787561 0.07211452 0.002143621 0.01811677 0.07197558 0.002676546 0.01790571 0.07209056 0.002681791 0.01771694 0.07206732 0.003177046 0.01787114 0.07195037 0.003310978 0.01741158 0.07204765 0.003504455 0.01752114 0.07190889 0.003685176 0.01699197 0.07202714 0.003710806 0.01702916 0.07188493 0.003920137 0.01643013 0.0720027 0.003753483 0.01637417 0.0718857 0.003948807 0.01578551 0.07186061 0.003689527 0.01588243 0.07197558 0.003509163 0.01548767 0.07195103 0.003047764 0.01544964 0.07184213 0.003349304 0.01536732 0.07191669 0.002339184 0.01555252 0.07189369 0.001829087 0.01537364 0.07758653 0.002298355 0.01559662 0.07757556 0.001744091 0.01606142 0.07753771 0.001341164 0.016707 0.0775085 0.00120753 0.01734936 0.07747775 0.001412212 0.01773542 0.07745343 0.001830935 0.01792341 0.07742846 0.002374827 0.01784151 0.07740396 0.002919435 0.01751369 0.07737702 0.003433763 0.01698684 0.07735079 0.003714561 0.0165047 0.07732987 0.003752529 0.01607394 0.07730984 0.003628909 0.01571702 0.07729035 0.003359556 0.01539582 0.07726293 0.002812862 0.01541894 0.077232 0.002117395 0.01578915 0.077201 0.001520693 0.01633572 0.07717448 0.001251101 0.01693689 0.07714784 0.001232504 0.01745378 0.07712274 0.001504063 0.01778405 0.07709944 0.001906335 0.01792597 0.07707267 0.00249648 0.01778334 0.07704776 0.003057539 0.01747119 0.07702416 0.003463625 0.01699024 0.07700133 0.003711581 0.01653867 0.07698106 0.003758728 0.01606011 0.07695966 0.003622412 0.01561743 0.07693386 0.003249943 0.01541703 0.07691341 0.00282967 0.01537489 0.07689249 0.002341926 0.01555204 0.07686704 0.001818299 0.01589429 0.07684588 0.001457035 0.0164749 0.07681864 0.001207172 0.01707965 0.07679134 0.001289963 0.01754885 0.07676702 0.001578927 0.01782947 0.07674413 0.00201857 0.01792186 0.0767163 0.002641379 0.01763999 0.07668507 0.003293335 0.01702523 0.076653 0.003718674 0.01641577 0.07662582 0.003738999 0.0158798 0.07660019 0.003518462 0.01552653 0.07657653 0.003099143 0.01537793 0.07655471 0.002638638 0.01545292 0.07652574 0.001984953 0.01587462 0.07649737 0.001470208 0.01631706 0.0764749 0.001248657 0.01683259 0.07645267 0.001227319 0.01731777 0.07642972 0.001397788 0.01774197 0.07640326 0.001827299 0.01793116 0.0763722 0.002506971 0.01777356 0.07634669 0.003072917 0.01738828 0.07632052 0.003536403 0.01663959 0.076285 0.003776133 0.01590448 0.07625138 0.00353837 0.0155189 0.07622563 0.003083467 0.01537787 0.07620543 0.0026533 0.01540017 0.07618606 0.002210617 0.01567393 0.07615858 0.001636266 0.01617836 0.07613158 0.001300394 0.01672112 0.07610785 0.001207947 0.01736795 0.07607656 0.001422643 0.01784652 0.07604348 0.002027451 0.0179103 0.0760172 0.002633035 0.01773512 0.07599264 0.003153741 0.01739817 0.07597094 0.003514111 0.01698011 0.07595086 0.003714263 0.01645612 0.07592731 0.003754377 0.01596802 0.07590466 0.003565251 0.01552003 0.07587742 0.003120243 0.01537114 0.07585018 0.002527594 0.01546412 0.07582581 0.001984834 0.01576769 0.07580292 0.001560449 0.01633882 0.07577377 0.001231968 0.01704823 0.07574272 0.00127238 0.01751953 0.0757187 0.001559555 0.01784682 0.0756936 0.002032876 0.01790887 0.07566672 0.002638697 0.0177105 0.07564043 0.003209829 0.01720559 0.07561087 0.003631174 0.01659399 0.07558327 0.003773927 0.01583689 0.07554864 0.003492534 0.01542919 0.07551628 0.002895176 0.01537996 0.07548975 0.002294659 0.01552361 0.07547098 0.00188142 0.01582741 0.07544916 0.0015046 0.01626336 0.07542741 0.001267492 0.01682728 0.07540267 0.00121808 0.01738047 0.07537674 0.001441359 0.01770454 0.07535594 0.001781225 0.01788747 0.07533562 0.002209544 0.01790994 0.07531636 0.002649545 0.01774889 0.07529377 0.003124237 0.0173006 0.07526546 0.003593683 0.01673591 0.07523989 0.003755986 0.01619291 0.07521605 0.003686368 0.01575702 0.07519286 0.003401398 0.01547437 0.07517129 0.002996027 0.01536029 0.07514458 0.002408027 0.01554578 0.07511883 0.001840949 0.0158382 0.07509869 0.001495599 0.01627933 0.07507729 0.001262187 0.01685595 0.07505142 0.001224517 0.01741498 0.07502466 0.001461863 0.01778095 0.0749998 0.00191009 0.0179215 0.0749762 0.002402484 0.01783472 0.07495331 0.002937018 0.01760429 0.07493311 0.003327369 0.01720941 0.07491171 0.003631353 0.01661849 0.07488459 0.003767788 0.01611137 0.0748617 0.003644227 0.0157333 0.07484191 0.003376722 0.01545757 0.07481908 0.002966761 0.01537066 0.07479786 0.002475976 0.01551496 0.07477062 0.001861274 0.01594179 0.07474339 0.001424014 0.01639699 0.07472163 0.001233339 0.01686263 0.07470101 0.001229524 0.01729267 0.07468152 0.001391053 0.01770639 0.07465577 0.00176537 0.01790028 0.07463228 0.002281665 0.01788765 0.07461059 0.00277549 0.01762312 0.07458424 0.003318428 0.01696693 0.07454973 0.003735125 0.01638638 0.07452481 0.003731906 0.01593673 0.0745027 0.003550469 0.01557356 0.07448023 0.003183901 0.01539421 0.07445919 0.002730071 0.01538819 0.07443803 0.002245724 0.01563841 0.07441067 0.001687169 0.01624357 0.07437825 0.001262426 0.01694232 0.07434761 0.001240849 0.01744115 0.07432305 0.001489043 0.01776432 0.07430112 0.00187391 0.01792836 0.0742737 0.002484679 0.01779997 0.07424914 0.003020465 0.01753097 0.07422882 0.003400683 0.01716798 0.07420957 0.003650367 0.01670825 0.07418829 0.003758788 0.01622837 0.07416737 0.003692209 0.01582223 0.07414662 0.003464221 0.01551866 0.07412594 0.003082275 0.01537263 0.07410413 0.002623379 0.01541382 0.07408362 0.002154588 0.0156635 0.0740593 0.001661837 0.01611834 0.07403409 0.001321196 0.01661807 0.0740121 0.001213014 0.01706546 0.07399189 0.001281082 0.01744878 0.073973 0.001499176 0.01782518 0.07394576 0.001977324 0.01791304 0.07391536 0.002665042 0.01770001 0.07389044 0.003201067 0.01735919 0.07386821 0.003545343 0.01688373 0.07384651 0.003736853 0.01643055 0.07382631 0.003745138 0.01596474 0.07380491 0.003568053 0.01555573 0.0737791 0.003159344 0.01538604 0.07375741 0.002696096 0.01539564 0.07373768 0.002234399 0.01559543 0.07371342 0.001748442 0.01598542 0.07369107 0.001396536 0.01655739 0.07366502 0.001201868 0.01712745 0.07363909 0.001308202 0.01766717 0.07360976 0.001696228 0.01790171 0.07358235 0.002289533 0.01788717 0.07356029 0.002772629 0.01767539 0.07353776 0.003242313 0.01728582 0.07351541 0.003585815 0.01672935 0.07348984 0.003770828 0.01614278 0.07346343 0.003656625 0.01573807 0.0734418 0.003388285 0.01547819 0.07342177 0.003001093 0.01536661 0.07339853 0.002499759 0.01544058 0.07337951 0.002067804 0.01569318 0.07335722 0.001626849 0.01621562 0.07333004 0.001279532 0.01670831 0.07330799 0.001214206 0.01716142 0.0732876 0.001321971 0.01752948 0.07326793 0.001566886 0.01778692 0.07324862 0.001927196 0.01791292 0.07322865 0.002364695 0.0178616 0.07320541 0.00288403 0.01759588 0.07318341 0.003329277 0.01724541 0.07316291 0.003614306 0.0167945 0.0731424 0.003751039 0.0163297 0.07312202 0.003721058 0.01581746 0.07309663 0.003471374 0.01547169 0.07307088 0.002984642 0.01535987 0.0730459 0.002437114 0.01551812 0.0730217 0.001891613 0.01581865 0.07299977 0.001510024 0.01622682 0.07297927 0.001282095 0.0167728 0.0729556 0.001212537 0.01733654 0.07292819 0.001409471 0.01771479 0.0729053 0.001797378 0.01789116 0.07288509 0.002214074 0.01790624 0.0728662 0.00265491 0.0176962 0.07283902 0.003225982 0.01715642 0.07280856 0.003661155 0.01642704 0.07277619 0.003757178 0.0158779 0.07274985 0.003503203 0.01546996 0.07272267 0.003022074 0.01537233 0.07269537 0.00241816 0.01551127 0.07267099 0.001885771 0.01585024 0.07264816 0.001488864 0.0163421 0.07262444 0.00124222 0.01702308 0.07259321 0.001255989 0.01769697 0.07255834 0.001736104 0.01792478 0.07252448 0.002456545 0.01779633 0.0724982 0.003039479 0.01742923 0.07247298 0.003498792 0.0168612 0.07244473 0.003747284 0.01634287 0.07242244 0.003725647 0.0157538 0.07239383 0.003419935 0.01539856 0.07236146 0.002789318 0.01540088 0.072335 0.00218749 0.01568931 0.07230705 0.001624345 0.01626288 0.07227742 0.001263737 0.01687777 0.07225042 0.001226365 0.01744723 0.07222324 0.001489341 0.01776105 0.07220119 0.001874864 0.01790666 0.0721808 0.00231719 0.01786583 0.07215541 0.00288546 0.01754307 0.07212966 0.003388047 0.01717406 0.07210952 0.003647744 0.016743 0.07209008 0.003755927 0.01628208 0.07207018 0.003708183 0.0157963 0.07204538 0.003451049 0.01545494 0.0720191 0.002948284 0.01536494 0.07199585 0.002435028 0.01553535 0.07196891 0.001843035 0.01592588 0.07194387 0.001430332 0.01647287 0.07191848 0.001213908 0.01709687 0.07189047 0.001290798 0.01777422 0.07758301 0.001534998 0.01614177 0.07758778 0.001193165 0.01709365 0.07758748 0.001095354 0.01799708 0.07758158 0.001891136 0.0181269 0.07754105 0.002427279 0.01725798 0.07747489 0.003836452 0.01651662 0.07744771 0.003966748 0.01524996 0.07738357 0.002978205 0.0151664 0.07735663 0.002294361 0.01517951 0.07667309 0.002720057 0.01522594 0.07664775 0.002056181 0.01550102 0.07662636 0.001554012 0.01600277 0.07660138 0.001144409 0.0176649 0.07653385 0.001410424 0.01812577 0.07648962 0.002482056 0.01767569 0.0764448 0.003549933 0.0175997 0.07618761 0.001362979 0.01796388 0.07616591 0.001816511 0.01708787 0.07606863 0.00390011 0.01812607 0.07578861 0.002517938 0.01731574 0.07572847 0.003800928 0.01677697 0.07570666 0.003961741 0.01620352 0.07554334 0.00106585 0.01755672 0.07548981 0.001318812 0.0179041 0.07546967 0.00172311 0.01689493 0.07536137 0.003940463 0.01599341 0.07532662 0.003818094 0.0162869 0.07519 0.001050531 0.01727747 0.07515203 0.001149892 0.01771193 0.07513183 0.001469612 0.01805531 0.07510685 0.002018392 0.01598954 0.0749762 0.00380969 0.01528751 0.07493764 0.003090143 0.01771098 0.07478225 0.001463651 0.01798671 0.07476311 0.001872122 0.01628816 0.074638 0.003915905 0.01578587 0.07461786 0.00369215 0.01532751 0.07459092 0.003178119 0.01638448 0.07448589 0.001025855 0.01622581 0.07428634 0.003905773 0.01572996 0.07426458 0.003648638 0.01517182 0.07420974 0.002366244 0.01530063 0.07419073 0.001877248 0.0169503 0.07396394 0.003939568 0.01533704 0.07389217 0.003189802 0.01767474 0.07373416 0.001428484 0.01798242 0.07371366 0.001857161 0.01751834 0.0736373 0.003673613 0.01693123 0.07361239 0.00394535 0.01735913 0.07327997 0.003786981 0.01617419 0.07323443 0.003892362 0.01555484 0.07312333 0.001483857 0.01612246 0.07309639 0.001093745 0.01696527 0.07291388 0.003933012 0.0162301 0.07288587 0.003914475 0.01671916 0.0727238 9.91447e-4 0.01788824 0.07267129 0.001672148 0.0168454 0.07255953 0.003954589 0.01517367 0.07245898 0.002334892 0.01534664 0.07243549 0.001768529 0.01632589 0.07238858 0.001033604 0.01770204 0.07233244 0.001441895 0.01803249 0.07230859 0.001990258 0.01812225 0.07228803 0.002528011 0.01796394 0.07226198 0.003167808 0.01750975 0.07223707 0.003683924 0.01706707 0.07221794 0.003901124 0.01516002 0.07211786 0.002588987 0.01526296 0.07209432 0.001966536 0.01556742 0.07207268 0.001470804 0.01614111 0.07204514 0.001086711 0.01800632 0.07195901 0.001908004 0.01812416 0.07194018 0.002478837 0.01795876 0.07191413 0.003177702 0.01650899 0.07159137 0.003777027 0.01595968 0.07162189 0.003658473 0.01566135 0.07172322 0.003554821 0.01589727 0.07173407 0.003732085 0.01628112 0.07166618 0.003850042 0.01613068 0.0717808 0.003860712 0.01652014 0.07172238 0.003934204 0.01697391 0.07160001 0.003765344 0.0168938 0.07171994 0.003910899 0.01768833 0.07158726 0.003209769 0.01730388 0.07165294 0.00372231 0.01725775 0.07174515 0.003812074 0.01760011 0.07160329 0.00340569 0.01762127 0.07171666 0.003552496 0.01777774 0.07172888 0.003392279 0.01793533 0.07164943 0.003017842 0.01789802 0.07160478 0.002902388 0.01787984 0.07183742 0.003289461 0.01794105 0.07174098 0.003145873 0.01792627 0.07159024 0.002431452 0.01807808 0.07174438 0.002752125 0.01804292 0.07165467 0.002516508 0.01812011 0.07182842 0.002397954 0.01786512 0.07159209 0.002036094 0.01805531 0.07171785 0.002172887 0.01797944 0.07170963 0.001935303 0.01771843 0.07170802 0.001522004 0.0178675 0.07183146 0.00165379 0.01771557 0.07162171 0.001657366 0.01738828 0.07159888 0.001406669 0.01680874 0.07158803 0.001231431 0.01743191 0.07172352 0.001269102 0.0174514 0.07183742 0.001245915 0.01718199 0.07163029 0.00122857 0.01717448 0.07174235 0.001131355 0.01688969 0.07162749 0.001138865 0.01688385 0.07174402 0.001048147 0.01660448 0.07171952 0.001039683 0.01646077 0.07161253 0.001157879 0.01627504 0.07169234 0.001107573 0.01636546 0.07183432 0.001036107 0.01610875 0.07161664 0.001252055 0.01604056 0.07176989 0.001149117 0.01588559 0.07167655 0.001284897 0.01582372 0.07159185 0.001479327 0.01548326 0.07165199 0.001705408 0.01555848 0.07172429 0.001528739 0.01540464 0.07160484 0.002000629 0.0153619 0.07159215 0.002371072 0.01533013 0.07172876 0.001868367 0.01524114 0.0717405 0.002096533 0.01525092 0.07165682 0.002340257 0.01518046 0.07182961 0.002275347 0.01542884 0.07159763 0.002992987 0.0151841 0.07176327 0.002580583 0.01526135 0.07164621 0.002648234 0.01529091 0.07171642 0.003007769 0.01575869 0.07158905 0.003394722 0.01558899 0.07162296 0.003339886 0.01546812 0.07173252 0.003341913 0.01831746 0.07776826 3.7159e-4 0.01858794 0.07778173 6.15334e-4 0.01854908 0.07764518 6.865e-4 0.01885133 0.07773685 9.50859e-4 0.01865297 0.07759076 9.4561e-4 0.01900464 0.07773065 0.001205146 0.01916134 0.0777601 0.001525819 0.01904898 0.07760345 0.001602709 0.01929157 0.07780003 0.001946091 0.01923739 0.07767409 0.00194168 0.01933366 0.07775592 0.002361714 0.0191611 0.07759076 0.002421855 0.01925426 0.0776394 0.002445459 0.01932853 0.07776117 0.002743601 0.01926457 0.07772713 0.0030725 0.01912653 0.0776059 0.003110826 0.01910734 0.07776248 0.003585517 0.01904088 0.07764375 0.003554344 0.0189017 0.07778286 0.003963708 0.01874446 0.07758945 0.003850221 0.01871562 0.07766938 0.004133105 0.0185697 0.07777875 0.004380702 0.0183531 0.07760655 0.004388034 0.01816922 0.07765531 0.004635274 0.01821154 0.07776194 0.004677474 0.01781475 0.07779324 0.004923105 0.01762771 0.07759058 0.00481224 0.01759475 0.07766133 0.004947662 0.01729214 0.07776069 0.005104541 0.01696872 0.07762736 0.005062103 0.01681959 0.07774829 0.005173087 0.01628398 0.07775914 0.005158424 0.01644033 0.07766675 0.005115449 0.01634943 0.07759046 0.004993617 0.01578885 0.07778853 0.005048274 0.01590341 0.07765585 0.005014479 0.01557016 0.07762438 0.004850387 0.01539647 0.07775002 0.004873156 0.01494175 0.07775759 0.004578053 0.01495891 0.07759135 0.004375517 0.01498448 0.07764595 0.004513382 0.01458466 0.07775849 0.004227042 0.01454544 0.07764434 0.00405687 0.01432496 0.07775306 0.003853917 0.01415199 0.07778465 0.003527939 0.0142824 0.07759159 0.003380179 0.0142011 0.07765418 0.003464818 0.01400089 0.07777661 0.003031313 0.01408565 0.07765847 0.003110587 0.01394134 0.07778626 0.002532839 0.01401889 0.07765394 0.002669751 0.01413774 0.07758927 0.002453148 0.01409828 0.07761663 0.002021372 0.01397365 0.07775574 0.002137005 0.01406192 0.07776427 0.001705646 0.01419711 0.07766222 0.00149554 0.01423698 0.07776021 0.001276552 0.01445555 0.07759511 0.00120902 0.01442015 0.07779955 9.50823e-4 0.01445478 0.07767957 9.91967e-4 0.01469123 0.07774722 6.35067e-4 0.01484531 0.0776357 5.96492e-4 0.01513653 0.07759112 4.524e-4 0.01496207 0.07775264 3.81837e-4 0.01522564 0.07775986 1.96465e-4 0.01548492 0.0776447 1.33475e-4 0.01560765 0.07777082 -7.9717e-6 0.0160734 0.07767665 -9.96244e-5 0.01618111 0.07778406 -1.74311e-4 0.0162149 0.07759422 -1.77741e-5 0.01659584 0.07774245 -2.04258e-4 0.0169456 0.07765716 -1.30784e-4 0.01680296 0.07760167 -5.49731e-5 0.01716214 0.07773882 -1.55565e-4 0.01777893 0.07779169 2.9012e-5 0.01756256 0.07759368 1.22537e-4 0.01770401 0.0776804 5.48501e-5 0.01816225 0.07765042 3.38197e-4 0.01853197 0.0804153 5.62819e-4 0.01900726 0.08039671 0.001181483 0.01926249 0.08039212 0.001803994 0.0193333 0.08036714 0.002755999 0.01925307 0.08041864 0.003152906 0.01910358 0.08041006 0.003597736 0.01856774 0.0804426 0.004361867 0.01838088 0.08040595 0.004548609 0.01801156 0.08040934 0.00481224 0.01750934 0.08038884 0.005044937 0.01676464 0.08042091 0.005176961 0.01643538 0.08042401 0.00516951 0.01600497 0.08041113 0.005109071 0.01522755 0.08042329 0.004775524 0.01486235 0.08038687 0.004516839 0.01448827 0.08040541 0.004109919 0.01394289 0.08038866 0.002480864 0.01399177 0.08042025 0.001998484 0.01437592 0.08039319 0.001023769 0.01471167 0.08039218 5.96435e-4 0.01515871 0.08043146 2.3911e-4 0.01706898 0.08039546 -1.78117e-4 0.01744031 0.08040285 -9.03764e-5 0.01763892 0.08044588 -1.06228e-5 0.01815485 0.08040636 2.49561e-4 0.01818287 0.08058005 4.67874e-4 0.01797062 0.08049899 1.95719e-4 0.01762312 0.08058005 1.43984e-4 0.01714158 0.08051639 -9.93766e-5 0.01695114 0.08057117 -4.68164e-5 0.01665973 0.08044457 -2.01442e-4 0.01639187 0.08058053 -3.91979e-5 0.0162115 0.08044695 -1.66184e-4 0.01579988 0.0804457 -6.73551e-5 0.01585245 0.08056825 5.27944e-5 0.01557981 0.08042287 1.35875e-5 0.01533293 0.08058613 3.45383e-4 0.01528865 0.08053427 2.49839e-4 0.01480448 0.08054918 6.47787e-4 0.0144782 0.08052325 9.88031e-4 0.01439678 0.0805847 0.001350462 0.01417982 0.08041763 0.001390218 0.01415252 0.08052438 0.001644194 0.01399081 0.08048528 0.002220094 0.01411777 0.0805782 0.00222218 0.01397901 0.08041834 0.002887964 0.01405084 0.08053308 0.002820491 0.01418548 0.08058381 0.003084659 0.0140537 0.08042067 0.003223419 0.01415407 0.08051723 0.003357589 0.01420366 0.08038699 0.003644704 0.01431137 0.08052003 0.003712654 0.01473742 0.08058196 0.004155337 0.01468807 0.08051311 0.004262387 0.015024 0.08052432 0.004554867 0.0153433 0.08058416 0.004637539 0.01568311 0.08053529 0.004926085 0.01551771 0.08040857 0.004936516 0.01585072 0.08058118 0.004890918 0.01642656 0.08055752 0.005060017 0.01697826 0.08051913 0.005095899 0.01726371 0.08044302 0.005102992 0.01709157 0.08058249 0.004975795 0.01764416 0.08053177 0.004907071 0.01808619 0.08052986 0.004678845 0.01788467 0.08058673 0.004652261 0.01838767 0.08058053 0.004331409 0.01872217 0.08053368 0.004068374 0.01885253 0.08042293 0.004027903 0.01895433 0.08056217 0.003629565 0.01920044 0.08052349 0.003096818 0.01907503 0.08058595 0.003089606 0.01934015 0.08042001 0.002547144 0.01924693 0.0805425 0.002505004 0.01928168 0.08046644 0.002064704 0.0191648 0.08058035 0.002231359 0.0191698 0.08050906 0.001712024 0.01898854 0.08058553 0.001574516 0.01903277 0.08052092 0.001380383 0.01873356 0.0805698 0.001011371 0.01877295 0.08044528 8.4575e-4 0.01842105 0.0805239 5.50401e-4 0.01535916 0.07890868 -0.00938344 0.01552826 0.07890766 -0.01077175 0.01544576 0.0790466 -0.01083165 0.01526761 0.07904696 -0.0093441 0.01680541 0.07889497 -0.01127111 0.01682204 0.07900238 -0.01140952 0.01793068 0.07890868 -0.01048344 0.01802259 0.07904773 -0.01052272 0.01772379 0.07889533 -0.009125173 0.01783508 0.07900333 -0.009041249 0.01648002 0.07890713 -0.008547604 0.01646637 0.07904487 -0.008446514 0.01787185 0.08057659 -0.009012699 0.01646244 0.08057612 -0.008412241 0.01805669 0.08057707 -0.01053732 0.01682752 0.0805763 -0.01145553 0.01541608 0.08057707 -0.01085412 0.01523506 0.08057659 -0.00932908 0.01692771 0.0718382 -0.01118558 0.0156911 0.07183831 -0.01092892 0.01565152 0.07183784 -0.0110256 0.01743662 0.07185363 -0.01092433 0.01534426 0.07183736 -0.01063323 0.0177499 0.07184326 -0.0105791 0.01786983 0.07183796 -0.01076173 0.01517593 0.07183301 -0.009920656 0.01519954 0.07183736 -0.0102213 0.01810503 0.07183802 -0.01018208 0.01795905 0.07183873 -0.009917736 0.01526933 0.07183539 -0.009388089 0.01806616 0.07183778 -0.0095371 0.01778858 0.07183778 -0.009194314 0.01783353 0.07183796 -0.009053647 0.01739394 0.0718494 -0.008677244 0.01704853 0.0718379 -0.008509457 0.01654028 0.07183963 -0.008462429 0.01812618 0.07757163 -0.009862244 0.01803618 0.07757955 -0.009481191 0.01775866 0.07752192 -0.008947014 0.01740884 0.07750916 -0.008654356 0.01760995 0.07758796 -0.008923053 0.01610267 0.0775882 -0.008772432 0.0168873 0.07747972 -0.008472204 0.01640295 0.07747066 -0.008468389 0.01689624 0.07758814 -0.008608043 0.01590311 0.07744431 -0.008642375 0.01570028 0.0775783 -0.009081363 0.01547282 0.07742416 -0.00902611 0.01545482 0.07757055 -0.009485304 0.0151897 0.07741975 -0.009626865 0.01537203 0.0775153 -0.01014232 0.01522243 0.07739305 -0.01033896 0.0156852 0.07748419 -0.01078128 0.01545089 0.07734978 -0.01082295 0.01577925 0.07732856 -0.01113575 0.01619929 0.07745665 -0.0111351 0.01616048 0.07731872 -0.0113337 0.01668173 0.07729834 -0.01141858 0.01694226 0.07742339 -0.01119017 0.01721441 0.07727432 -0.01130729 0.0175023 0.07739555 -0.01087462 0.01767003 0.07725751 -0.01100355 0.01780891 0.07737344 -0.01046729 0.01792705 0.07724344 -0.01067411 0.01808631 0.07722449 -0.01030176 0.01791518 0.0773518 -0.01000207 0.01812082 0.07720541 -0.009815692 0.01785886 0.0773319 -0.009539902 0.01800322 0.07719153 -0.009333968 0.01752734 0.07730406 -0.008993864 0.01777881 0.07716858 -0.008972227 0.01737082 0.07715189 -0.008640468 0.01689332 0.07727247 -0.008678138 0.0168035 0.07712906 -0.008452475 0.01638972 0.07725048 -0.008683741 0.01625585 0.07711261 -0.008501708 0.01588159 0.07722628 -0.008906602 0.01582056 0.07709115 -0.008698582 0.01540714 0.07707077 -0.009100973 0.01551848 0.07720148 -0.009328842 0.01522582 0.07704985 -0.009496867 0.01536345 0.07717531 -0.009912312 0.015163 0.07703149 -0.01001727 0.01548463 0.0771504 -0.01046645 0.01531529 0.0770173 -0.01061105 0.01576501 0.077129 -0.0108565 0.01577287 0.07698506 -0.01113301 0.01624399 0.07710444 -0.01114898 0.01625889 0.07696437 -0.01136934 0.01674473 0.07708227 -0.01120454 0.01673787 0.07694917 -0.0114144 0.01722341 0.07706052 -0.01106989 0.01722085 0.07692652 -0.01130032 0.01763677 0.0769034 -0.01103669 0.01760095 0.07703942 -0.01077997 0.01794475 0.07691103 -0.01064598 0.01783245 0.07701963 -0.01039397 0.01811581 0.07688766 -0.01005095 0.01791942 0.07699936 -0.009934484 0.01811903 0.0768525 -0.009724318 0.0178188 0.07697641 -0.009418487 0.0179553 0.07683289 -0.009227693 0.01750063 0.07695251 -0.008992254 0.01742172 0.07682681 -0.008665382 0.01713657 0.07693397 -0.008755385 0.01679539 0.07678401 -0.008457422 0.01670163 0.07691413 -0.008660137 0.01630336 0.07676076 -0.008490025 0.01623791 0.07689362 -0.008726656 0.0158205 0.07673555 -0.008697748 0.01584386 0.07687377 -0.008939027 0.01547241 0.07672888 -0.009019196 0.01555144 0.07685405 -0.009280145 0.01523238 0.07670295 -0.009486138 0.01538872 0.07683372 -0.009718835 0.01516044 0.07668292 -0.009952723 0.01540136 0.07681083 -0.0102446 0.01524597 0.07666802 -0.01043099 0.01564329 0.07678687 -0.01071745 0.01553636 0.07664239 -0.01092195 0.01596331 0.07676833 -0.01101267 0.01588135 0.07663178 -0.01120281 0.01626783 0.07661217 -0.01137101 0.01637548 0.07674849 -0.01117926 0.0167936 0.076595 -0.01140755 0.01687145 0.07672655 -0.01118862 0.01727414 0.07657063 -0.01127815 0.0174809 0.07669788 -0.01091927 0.01766026 0.07656019 -0.01102125 0.01805752 0.07655131 -0.01039689 0.01784729 0.07666808 -0.01035559 0.0179224 0.07664757 -0.009890139 0.01810801 0.07652431 -0.009709358 0.01777166 0.07662135 -0.0093261 0.01790362 0.07650262 -0.009164214 0.0177291 0.07646429 -0.008916497 0.01741313 0.07659786 -0.008913457 0.01725095 0.07644295 -0.008573591 0.01698106 0.07657647 -0.008703052 0.01676809 0.07645064 -0.008465647 0.01648801 0.07655459 -0.008668303 0.01626282 0.07643127 -0.00850439 0.01604205 0.07653445 -0.008806705 0.01585334 0.07639122 -0.008672297 0.01558566 0.07650774 -0.00921148 0.01532834 0.07638555 -0.009243011 0.01537674 0.07648122 -0.009768426 0.01515698 0.07633543 -0.009967803 0.0154159 0.0764594 -0.01026535 0.01526695 0.07631677 -0.01047474 0.01564317 0.07643711 -0.01073038 0.01551538 0.07631921 -0.01088893 0.01602494 0.07627189 -0.01128661 0.01620864 0.07640606 -0.01114767 0.01655119 0.07627499 -0.01141428 0.01689153 0.07637614 -0.01118808 0.01723718 0.07622671 -0.01130026 0.01733481 0.07635468 -0.01100391 0.01772278 0.07620376 -0.01095157 0.01771676 0.07633125 -0.01063263 0.0180273 0.07618117 -0.01048529 0.01789945 0.07630926 -0.0101633 0.01813137 0.07616245 -0.009875297 0.01789569 0.07628875 -0.009695708 0.01793438 0.07615476 -0.009204268 0.01766723 0.07626307 -0.009150385 0.01757109 0.07611376 -0.008771002 0.01719069 0.07623594 -0.00878328 0.01710134 0.07609164 -0.008520066 0.01661109 0.07621055 -0.00864613 0.01669824 0.07607567 -0.008451282 0.01629954 0.07605862 -0.008484899 0.01603871 0.07618391 -0.008813917 0.01562529 0.07605397 -0.008851826 0.01567041 0.07616329 -0.009109497 0.0154466 0.07614368 -0.009496569 0.01523613 0.07600957 -0.009456634 0.01537072 0.07611829 -0.01007568 0.01516121 0.07598429 -0.00998944 0.01535892 0.07597929 -0.01068025 0.01558315 0.07609093 -0.01064801 0.01581144 0.07593476 -0.01115775 0.01610988 0.07606101 -0.01110506 0.01631635 0.07591211 -0.01138526 0.01674151 0.07603257 -0.0112068 0.01687735 0.07588905 -0.01140028 0.01738506 0.07600259 -0.01098918 0.01735997 0.07587105 -0.01123028 0.01775026 0.07585567 -0.01092714 0.01778012 0.07597547 -0.01051396 0.01794689 0.07583564 -0.0106424 0.01809912 0.07582211 -0.01022619 0.01792728 0.07595014 -0.009947896 0.01810979 0.07580256 -0.009679079 0.01773762 0.07591784 -0.009250462 0.01792049 0.0757758 -0.009168148 0.01755434 0.07576197 -0.008762836 0.01726371 0.07589006 -0.008818626 0.01719033 0.07574784 -0.008556842 0.01679205 0.0758683 -0.008662521 0.01679086 0.07572352 -0.008454084 0.01628476 0.07571005 -0.008493006 0.01629114 0.07584571 -0.008711576 0.01585566 0.07570016 -0.008677721 0.01589858 0.07582718 -0.00889784 0.01549518 0.07567375 -0.008989691 0.01558983 0.07580733 -0.009218394 0.01523625 0.07565397 -0.009468913 0.01540368 0.07578682 -0.009648382 0.01516139 0.07563143 -0.009958624 0.01537829 0.07576698 -0.01009523 0.01525443 0.07563793 -0.01044738 0.0155158 0.07574725 -0.0105229 0.01564377 0.07559061 -0.01103115 0.01588952 0.07572209 -0.0109716 0.01597768 0.07557523 -0.01125812 0.01630336 0.07558321 -0.01137357 0.01640748 0.07569682 -0.01118624 0.0169124 0.07567512 -0.01118052 0.0170595 0.07555556 -0.01136434 0.01734983 0.07565426 -0.01099807 0.01763659 0.07551044 -0.01103961 0.01767688 0.07563394 -0.01067954 0.01794207 0.07548934 -0.01065593 0.01791816 0.07560718 -0.01012253 0.0181151 0.07546257 -0.01015263 0.01810127 0.07547217 -0.00965619 0.01785701 0.07558166 -0.009541809 0.01785558 0.07544928 -0.009090006 0.01763409 0.07556128 -0.00913006 0.01742923 0.07542663 -0.008673012 0.01729536 0.07554137 -0.008834421 0.01673829 0.07551598 -0.008655309 0.01677072 0.07537895 -0.008453607 0.01628059 0.07536399 -0.0084939 0.01617807 0.07549107 -0.008744955 0.01580935 0.07533961 -0.008704304 0.01577275 0.07546967 -0.009002745 0.01543027 0.07531934 -0.009084105 0.01548492 0.07544779 -0.009404718 0.01522392 0.0753107 -0.00950706 0.01536619 0.07542645 -0.009885013 0.01515603 0.07528442 -0.009947776 0.01546043 0.07540321 -0.01040035 0.01526778 0.0752651 -0.01048851 0.01581132 0.07537543 -0.01091974 0.01553398 0.07524168 -0.01092094 0.01595264 0.07522487 -0.01124733 0.01645565 0.07534509 -0.01119655 0.01660424 0.07522267 -0.01141971 0.01695954 0.07532304 -0.01117092 0.01727747 0.07519567 -0.01127147 0.01737058 0.07530254 -0.01098001 0.01763844 0.07515722 -0.01103746 0.0177989 0.07527536 -0.0105102 0.01792693 0.07513767 -0.01067817 0.01811456 0.07512259 -0.01017779 0.01791912 0.07524538 -0.009847402 0.01809501 0.07509934 -0.009614109 0.01777333 0.07522213 -0.009337186 0.01788592 0.07507932 -0.009110152 0.01749759 0.07520246 -0.008984982 0.01735275 0.07507312 -0.008631229 0.01701611 0.07517832 -0.008708894 0.01676684 0.07502758 -0.008453905 0.01629245 0.07514613 -0.008690118 0.01628667 0.07501465 -0.008492827 0.01574999 0.07500976 -0.008758306 0.01574808 0.07511824 -0.009030282 0.01546239 0.07497042 -0.009032547 0.01548796 0.07509887 -0.009389638 0.01522457 0.07495474 -0.009493708 0.01536977 0.07507514 -0.009901702 0.01515841 0.07493478 -0.009973466 0.01546174 0.07505291 -0.0104171 0.0152567 0.07490867 -0.01046556 0.01551282 0.07491892 -0.01088315 0.01572221 0.07503169 -0.01081252 0.0159378 0.07489854 -0.0112279 0.01610261 0.07501125 -0.01108586 0.01650899 0.07487589 -0.01141178 0.01658684 0.07498908 -0.01121264 0.01720982 0.07483083 -0.01130807 0.01720482 0.07496172 -0.01108634 0.01770001 0.07480394 -0.01097917 0.0176447 0.0749368 -0.0107277 0.01796388 0.07479441 -0.01061195 0.01788824 0.07491225 -0.01023793 0.01811015 0.07477015 -0.01017421 0.01786059 0.07488 -0.009491205 0.01810985 0.07474827 -0.009701073 0.01793742 0.07473689 -0.009195327 0.01735478 0.07484471 -0.008862435 0.01760601 0.07471287 -0.008798837 0.01718991 0.0746929 -0.008550286 0.01669335 0.07481348 -0.008650779 0.0166769 0.07467448 -0.008446931 0.01616632 0.07465505 -0.008531153 0.01612263 0.07478821 -0.008771419 0.01560652 0.07465261 -0.008868694 0.01562607 0.07476079 -0.009141385 0.01526498 0.07462811 -0.009413182 0.01537907 0.07473146 -0.009773194 0.01516646 0.07460784 -0.00994575 0.01540648 0.07471066 -0.01024293 0.01522785 0.07456678 -0.01039248 0.01560038 0.07469016 -0.01066136 0.01551175 0.07454711 -0.01089054 0.0160188 0.07466489 -0.0110554 0.01594299 0.07452589 -0.01124584 0.01655584 0.07464045 -0.01120406 0.01659524 0.07452213 -0.01141518 0.01702088 0.07462012 -0.01115113 0.01730668 0.07447731 -0.01126694 0.01749008 0.0745964 -0.01089829 0.01771092 0.07444745 -0.01096343 0.01796883 0.07443684 -0.01060611 0.01783913 0.07456958 -0.01038664 0.01810508 0.07444208 -0.01016539 0.01792103 0.07454746 -0.009890317 0.01813733 0.07440286 -0.009864449 0.01782089 0.07452714 -0.009444892 0.01794141 0.07437801 -0.009205639 0.01745307 0.07449913 -0.008927702 0.01759934 0.07437306 -0.008796155 0.0171855 0.07434177 -0.008545815 0.01691693 0.07447355 -0.008690893 0.0166161 0.0743243 -0.008450508 0.01629823 0.07444638 -0.008690118 0.01598137 0.07431977 -0.00860548 0.01576548 0.07441914 -0.009011924 0.01546925 0.07427465 -0.009028673 0.01540338 0.07439035 -0.009572446 0.01521974 0.07425332 -0.009509921 0.01516175 0.0742315 -0.01003551 0.01540356 0.07436156 -0.01021754 0.01528012 0.07423698 -0.01048737 0.01568001 0.07433342 -0.01078987 0.01556396 0.07421642 -0.01094675 0.01582312 0.07417345 -0.01117062 0.01619505 0.07430666 -0.01112478 0.01629626 0.07416176 -0.01137447 0.01672029 0.0742833 -0.01121103 0.0168575 0.07414335 -0.01140546 0.01720637 0.0742613 -0.01107853 0.01734441 0.0741136 -0.01124197 0.01767748 0.07410639 -0.01100093 0.01770257 0.07423353 -0.01066875 0.01794981 0.07411056 -0.0106281 0.01811611 0.07408881 -0.01009464 0.01791489 0.07420504 -0.01006621 0.01810568 0.07405036 -0.009664833 0.01787257 0.07418411 -0.009601593 0.01767086 0.07416373 -0.009167015 0.0179544 0.07403284 -0.0092386 0.01759386 0.07403385 -0.008794248 0.01726377 0.07413983 -0.008818447 0.01716554 0.07399374 -0.008540511 0.0167275 0.07411527 -0.008655965 0.01667261 0.07396757 -0.008446872 0.01622837 0.0740931 -0.008728563 0.01618713 0.07396024 -0.008522152 0.01579874 0.07407134 -0.00897926 0.0157476 0.07393765 -0.008752405 0.01541012 0.0739144 -0.009110867 0.01542961 0.07404297 -0.009501218 0.01521706 0.07390266 -0.009523153 0.01516801 0.07387673 -0.01007837 0.01538801 0.0740152 -0.01013964 0.01526695 0.07387459 -0.01048654 0.01553446 0.07399564 -0.01056373 0.01554709 0.07384079 -0.01093858 0.0158984 0.07397103 -0.01097327 0.01620638 0.07383817 -0.01136136 0.01641023 0.07394731 -0.01118791 0.01685351 0.07392752 -0.01119118 0.01684272 0.07378995 -0.0114091 0.01739627 0.07390218 -0.01097285 0.01736563 0.0737707 -0.0112316 0.01785057 0.07376772 -0.01079547 0.0178439 0.07386988 -0.01040536 0.01802241 0.073731 -0.01048779 0.01812458 0.07372814 -0.009786069 0.01790922 0.0738421 -0.00976777 0.01775401 0.07382029 -0.00929588 0.01789593 0.07368379 -0.009132683 0.01741653 0.0737977 -0.0089221 0.01753526 0.07365977 -0.008746981 0.01703387 0.07377922 -0.008717536 0.01709622 0.07363575 -0.00851953 0.01667028 0.07362931 -0.00845009 0.01659196 0.07375931 -0.008660018 0.01618272 0.07360607 -0.008524 0.01610821 0.07373762 -0.008776247 0.01572114 0.07358026 -0.008770465 0.01568371 0.07371419 -0.009087741 0.015383 0.07356941 -0.009142696 0.01539438 0.07368671 -0.009652197 0.01516133 0.07356238 -0.009834408 0.01540452 0.07366079 -0.01024287 0.01527214 0.07353669 -0.01048141 0.01558738 0.07364106 -0.01063811 0.0155003 0.07349753 -0.01087939 0.01589095 0.07362216 -0.01096349 0.01588976 0.07347398 -0.01121276 0.01631408 0.07360136 -0.01116591 0.01636451 0.073462 -0.01139122 0.01680642 0.07357954 -0.01119804 0.01686728 0.07344031 -0.01139992 0.01743781 0.0735495 -0.01095539 0.01738685 0.073421 -0.01122289 0.01788157 0.07341533 -0.01075118 0.01787114 0.07351601 -0.01030886 0.01812261 0.07336831 -0.01009607 0.01791024 0.0734921 -0.009774982 0.01808732 0.07335013 -0.00957489 0.01776665 0.07347154 -0.00932753 0.01784354 0.07332432 -0.009058773 0.01732981 0.07344311 -0.008839547 0.01739436 0.07329833 -0.008644223 0.01708728 0.07331228 -0.00852406 0.01661115 0.07341003 -0.00865215 0.01666802 0.07327443 -0.008446633 0.01622903 0.07325273 -0.008509337 0.01606786 0.07338571 -0.008794426 0.0157476 0.07323628 -0.008745551 0.0156458 0.07336181 -0.00913459 0.01536518 0.07321602 -0.009184777 0.01541215 0.0733385 -0.009607672 0.01517337 0.07319086 -0.009710133 0.01537311 0.07332009 -0.01002669 0.01517403 0.07320255 -0.01007252 0.01556789 0.07329237 -0.01064014 0.01532775 0.07318216 -0.01059764 0.01566958 0.07316076 -0.01104938 0.01609784 0.07326138 -0.01109129 0.0161668 0.07313883 -0.01132911 0.01681405 0.07322913 -0.01121205 0.01674234 0.07311761 -0.01140987 0.01734447 0.07309281 -0.01124054 0.01737731 0.07320249 -0.01097565 0.0177409 0.0730527 -0.01093852 0.01776093 0.07317775 -0.01056385 0.01800566 0.07303267 -0.01053237 0.01791447 0.0731545 -0.01005464 0.01813185 0.07300895 -0.009997069 0.01785004 0.0731303 -0.009503245 0.01803416 0.07299184 -0.009414315 0.01773124 0.0729708 -0.008912205 0.01755172 0.07310581 -0.009032428 0.01726001 0.07294601 -0.008584916 0.01706451 0.07307994 -0.008725047 0.01670783 0.07292658 -0.008446991 0.01652944 0.07305687 -0.008661806 0.01621162 0.07290643 -0.008515179 0.01598274 0.07303118 -0.008835017 0.01580226 0.07289147 -0.008714735 0.01542556 0.07287108 -0.009084761 0.01556903 0.07300615 -0.009246885 0.01540029 0.0729863 -0.009657502 0.01519322 0.07284396 -0.009604454 0.01518177 0.07282608 -0.01017731 0.01540011 0.07296097 -0.01024252 0.01529586 0.07281714 -0.01054728 0.01566964 0.07293522 -0.01075851 0.01555109 0.07279556 -0.01094114 0.01624196 0.07290422 -0.01116037 0.01595145 0.07277595 -0.0112403 0.01643002 0.07275933 -0.01140564 0.01687884 0.07287645 -0.01118665 0.01691377 0.07273024 -0.01139211 0.01735126 0.07272112 -0.01123934 0.01747304 0.07284778 -0.01092177 0.01771509 0.07272577 -0.01095384 0.01800394 0.07270532 -0.01051366 0.01787191 0.07281577 -0.01030677 0.01812356 0.07266622 -0.01006823 0.01789641 0.07278782 -0.009666919 0.01801514 0.07266098 -0.009355008 0.01763325 0.07276034 -0.009116113 0.0178439 0.07262456 -0.009047031 0.01735264 0.07262361 -0.008637905 0.01716578 0.0727353 -0.008769512 0.01704543 0.07258588 -0.008506059 0.01664644 0.07271146 -0.008651435 0.01660108 0.07257121 -0.008448183 0.01606875 0.07255178 -0.008567273 0.01593834 0.07267987 -0.008855402 0.01569885 0.07253736 -0.008793592 0.0154227 0.07252067 -0.009086191 0.01553231 0.07265251 -0.009311795 0.01520901 0.07250046 -0.009555637 0.0153529 0.07262349 -0.009959757 0.01516586 0.07248067 -0.01010245 0.01555454 0.07259333 -0.0105955 0.01531285 0.07245135 -0.01059335 0.01563513 0.07244062 -0.01102215 0.0158897 0.07257211 -0.01096004 0.01595783 0.07244771 -0.01123911 0.0163995 0.07254713 -0.0111947 0.01642602 0.07242852 -0.01139712 0.01698321 0.07238256 -0.01137953 0.01701861 0.07252031 -0.01115298 0.01741462 0.07237136 -0.01119852 0.01743829 0.07249951 -0.01093381 0.01774847 0.07234966 -0.01093059 0.01782971 0.07247209 -0.01043641 0.01803547 0.07233124 -0.01044785 0.01811939 0.07233589 -0.009994685 0.01791584 0.07244294 -0.009794652 0.01805984 0.07231622 -0.009501278 0.01771461 0.07241684 -0.009227514 0.01786339 0.07227748 -0.009081006 0.01717793 0.07238513 -0.008760511 0.01732057 0.07227188 -0.008611619 0.01670068 0.07222819 -0.008452475 0.01656848 0.07235836 -0.008662521 0.01614928 0.07220423 -0.008531093 0.0159499 0.07233035 -0.008842766 0.01577049 0.07219207 -0.008737206 0.0154525 0.07217133 -0.009051978 0.01547044 0.07229679 -0.009424149 0.01519948 0.07215118 -0.009578704 0.0153687 0.07227408 -0.009939134 0.01517283 0.07213044 -0.01012927 0.01545739 0.07225352 -0.01039224 0.0153076 0.07211017 -0.01057457 0.01570254 0.07223296 -0.01079428 0.01573312 0.07210749 -0.01110839 0.0160585 0.07221329 -0.01106584 0.01639825 0.07205951 -0.01139843 0.01659417 0.07218915 -0.01121205 0.01691526 0.07204091 -0.01139515 0.01711565 0.07216578 -0.01112008 0.01729375 0.07202506 -0.01126527 0.01759147 0.07214015 -0.01079756 0.0176503 0.07200676 -0.01102375 0.01800161 0.07200711 -0.01053297 0.0178768 0.07211452 -0.01027619 0.01813137 0.07195842 -0.009931683 0.01789212 0.0720852 -0.009611964 0.01802879 0.07194453 -0.009405016 0.0178374 0.07192224 -0.009054541 0.01750743 0.07205289 -0.008981227 0.01753896 0.07191127 -0.008745491 0.01690959 0.07202351 -0.008681535 0.01703143 0.07188493 -0.00849986 0.01637744 0.07188576 -0.008470535 0.01635199 0.07199901 -0.008689224 0.01575434 0.07183766 -0.008749365 0.01590871 0.07197695 -0.008894562 0.01554417 0.07195651 -0.009279668 0.01538932 0.07193362 -0.009725272 0.01539653 0.07191187 -0.01019567 0.01563894 0.07188612 -0.01073229 0.01623916 0.07184761 -0.01115447 0.01537328 0.07758873 -0.01009941 0.01555371 0.07757759 -0.0106095 0.01606267 0.07753771 -0.01107853 0.01670819 0.0775085 -0.01121217 0.0172252 0.0774849 -0.01106834 0.01757448 0.07746297 -0.01080888 0.01783788 0.07744371 -0.01037937 0.01792317 0.07742208 -0.009909689 0.0178309 0.07740271 -0.009473681 0.01751625 0.07737767 -0.008987188 0.01698952 0.07735055 -0.008705496 0.01638829 0.0773245 -0.008676052 0.01595753 0.07730388 -0.008863091 0.01560103 0.07728314 -0.009190201 0.01538079 0.0772565 -0.009741842 0.01543396 0.0772292 -0.01036036 0.01589512 0.07719504 -0.01098549 0.01651012 0.07716685 -0.01119971 0.01696252 0.07714664 -0.01117014 0.01741182 0.07712525 -0.01095473 0.01780015 0.07709813 -0.01048886 0.01791852 0.0770753 -0.009980559 0.01782542 0.07705163 -0.009438276 0.01738822 0.07701897 -0.008878946 0.01659625 0.07698422 -0.008644104 0.0160135 0.07695692 -0.008827805 0.01559984 0.07693254 -0.009191393 0.01539736 0.07690972 -0.009672284 0.01538753 0.07688987 -0.01013505 0.01555329 0.07686704 -0.0106014 0.01589548 0.07684588 -0.0109626 0.01631444 0.07682549 -0.01116496 0.01680445 0.07680398 -0.01120275 0.01729285 0.07678121 -0.01102948 0.01776021 0.07675272 -0.01058763 0.01791822 0.07672429 -0.009947061 0.01783347 0.07670146 -0.00945878 0.01757633 0.07668155 -0.009067475 0.01705414 0.07665425 -0.008706927 0.0163291 0.07662189 -0.008693993 0.01581966 0.07659655 -0.008957386 0.01552778 0.07657653 -0.009320437 0.01537376 0.07655334 -0.009810268 0.01542222 0.07653182 -0.01030015 0.01563018 0.07651221 -0.01070213 0.01606392 0.0764873 -0.01107925 0.01660001 0.07646274 -0.01120638 0.01706063 0.07644242 -0.01113784 0.01757192 0.07641577 -0.01082801 0.01787179 0.07638865 -0.01027661 0.01791763 0.07636862 -0.009831607 0.01780074 0.07634913 -0.009399294 0.01753437 0.07632917 -0.009020328 0.01704752 0.07630324 -0.008712053 0.01640933 0.07627552 -0.00867927 0.01597881 0.07625508 -0.008845031 0.01564913 0.07623577 -0.009140372 0.01537418 0.07620787 -0.009709537 0.01543152 0.07618153 -0.01031875 0.01571559 0.07615572 -0.01082015 0.01617926 0.07613158 -0.01111918 0.01669281 0.07610917 -0.01121073 0.01724278 0.076083 -0.01106578 0.01765269 0.07606011 -0.01071196 0.01786458 0.07603991 -0.01031124 0.01791667 0.07601851 -0.009815692 0.01772344 0.07599139 -0.009240746 0.01735264 0.0759685 -0.008873522 0.01692682 0.07594871 -0.008691549 0.01643311 0.07592588 -0.008671283 0.01596957 0.07590466 -0.008854269 0.01553773 0.07587856 -0.009276747 0.01537173 0.07585138 -0.009862601 0.01546519 0.07582581 -0.01043444 0.01576858 0.07580292 -0.01085895 0.01631194 0.07577514 -0.01117724 0.01702207 0.07574391 -0.01115882 0.01752042 0.0757187 -0.01086044 0.01783531 0.07569479 -0.01041299 0.0179153 0.07566928 -0.009839177 0.01774317 0.07564294 -0.009257674 0.01725858 0.07561349 -0.008815884 0.01681542 0.07559305 -0.008668184 0.01616543 0.07556462 -0.008735835 0.01561892 0.07553374 -0.009168267 0.01540637 0.07551145 -0.009638965 0.01537919 0.07549107 -0.01009666 0.0155096 0.07547223 -0.01051324 0.01580721 0.07545053 -0.01089411 0.01621282 0.07542985 -0.01113492 0.01679706 0.07540452 -0.01120841 0.01737993 0.07537651 -0.01097953 0.01781988 0.07534641 -0.01046562 0.0179134 0.07531505 -0.009748995 0.01772201 0.07529205 -0.009254992 0.01741063 0.0752716 -0.008912742 0.01693987 0.07524853 -0.008687615 0.0162186 0.07521742 -0.008716344 0.01571846 0.07519042 -0.00905919 0.01543003 0.07516664 -0.00952804 0.01537704 0.07514065 -0.01009404 0.01554667 0.07511889 -0.01057815 0.01583898 0.07509869 -0.01092374 0.01627993 0.07507729 -0.01115733 0.01688492 0.07505017 -0.01119261 0.01746171 0.07502216 -0.01092141 0.01780688 0.07499724 -0.0104593 0.01792186 0.07497507 -0.009988784 0.01783615 0.07495331 -0.009483277 0.01760601 0.07493311 -0.009092867 0.01721131 0.07491171 -0.008788645 0.01662039 0.07488459 -0.008651912 0.01611328 0.07486176 -0.008775115 0.01559513 0.07483261 -0.009182155 0.01536786 0.0748015 -0.009855568 0.0155158 0.07477068 -0.01055777 0.0160399 0.07473808 -0.01106303 0.01661801 0.07471179 -0.01121169 0.01708137 0.07469171 -0.01112997 0.01749724 0.07466965 -0.01088231 0.0178579 0.07464206 -0.01036828 0.01787984 0.07460743 -0.009561061 0.01747769 0.07457512 -0.008959412 0.01693958 0.0745486 -0.008689641 0.01630693 0.07452064 -0.008692681 0.01576781 0.07449352 -0.009005963 0.01547968 0.07447165 -0.009409427 0.01536858 0.0744481 -0.009948134 0.01550894 0.07442086 -0.01053589 0.01590108 0.07439571 -0.01096576 0.01642096 0.07437032 -0.01120251 0.01704323 0.07434326 -0.01114314 0.01744157 0.07432311 -0.01093125 0.01773291 0.07430368 -0.0105955 0.0179333 0.07427626 -0.009992182 0.01780164 0.0742492 -0.009400069 0.01741206 0.07422167 -0.008897006 0.01676923 0.07419067 -0.008661031 0.01623058 0.07416743 -0.008727192 0.01577979 0.07414424 -0.008988976 0.01546972 0.07412075 -0.009442031 0.01535975 0.07409346 -0.01004004 0.01558279 0.07406586 -0.01063632 0.01601219 0.07403904 -0.01105612 0.01661831 0.07401216 -0.01120662 0.0170657 0.07399195 -0.01113891 0.0174492 0.073973 -0.01092112 0.01774996 0.07395243 -0.01056766 0.01792889 0.07392662 -0.01001638 0.0178008 0.07389944 -0.009394109 0.01745551 0.07387304 -0.008938193 0.01694321 0.07384914 -0.008695662 0.01632672 0.07382237 -0.008683025 0.01578408 0.0737946 -0.008995473 0.01550567 0.07377421 -0.00935781 0.01537978 0.07375496 -0.009779036 0.01540923 0.07373511 -0.01024127 0.01561331 0.07371234 -0.01069092 0.01596164 0.07369238 -0.01100593 0.01652932 0.07366627 -0.01121813 0.01712757 0.07363915 -0.01111197 0.01751947 0.07361876 -0.01086038 0.01784855 0.07359373 -0.01038736 0.01790624 0.07356417 -0.009732604 0.01776111 0.07354515 -0.009319722 0.01743775 0.07352286 -0.008926749 0.01686513 0.07349568 -0.008672058 0.01636791 0.07347357 -0.008690297 0.01593929 0.07345318 -0.00887233 0.01552295 0.07342666 -0.009300589 0.01537102 0.07339948 -0.009910345 0.01543843 0.07337951 -0.01035112 0.0157153 0.07335609 -0.01081186 0.01624047 0.07332891 -0.01115065 0.01673704 0.07330679 -0.01120203 0.01732182 0.07327985 -0.01103103 0.01777982 0.07324975 -0.01052182 0.01791876 0.07322621 -0.009999096 0.0178439 0.07320302 -0.009483277 0.01753914 0.0731796 -0.009026169 0.01702582 0.07315224 -0.008701443 0.01630234 0.07312071 -0.008699774 0.01578038 0.07309418 -0.008989036 0.01547342 0.07307094 -0.009433865 0.01535987 0.07304477 -0.01000851 0.01554715 0.07301914 -0.01057827 0.01584082 0.07299864 -0.01092493 0.01633638 0.0729742 -0.01117759 0.01691281 0.07294929 -0.01118046 0.01735949 0.07292711 -0.01099306 0.01771527 0.07290536 -0.01062345 0.01789206 0.07288521 -0.01020705 0.01790505 0.072865 -0.009737253 0.01770848 0.07284045 -0.009223222 0.01735788 0.07281869 -0.008875787 0.01693326 0.07279872 -0.008693456 0.01648688 0.0727787 -0.008667469 0.01599758 0.07275605 -0.008829414 0.01549625 0.07272511 -0.009346485 0.0153715 0.07269793 -0.009941697 0.01549696 0.0726723 -0.01050847 0.0158503 0.07264822 -0.01092994 0.01625931 0.07262837 -0.01114708 0.0166943 0.07260823 -0.01120883 0.01714897 0.07258808 -0.01110488 0.01767843 0.07255953 -0.01070529 0.01790159 0.07253235 -0.01014018 0.01786112 0.07250422 -0.009504318 0.0174809 0.07247561 -0.00896883 0.01684606 0.07244437 -0.008655846 0.01615035 0.07241374 -0.008756279 0.015706 0.07239007 -0.009065866 0.01546078 0.07236927 -0.009463369 0.01537114 0.07234901 -0.009920299 0.01549118 0.0723223 -0.01050728 0.01590925 0.07229524 -0.01097315 0.01631569 0.07227516 -0.0111671 0.01681816 0.07225316 -0.01119863 0.01738226 0.07222694 -0.01098233 0.01773291 0.07220375 -0.01059645 0.01789814 0.07218343 -0.01016122 0.01789718 0.07216155 -0.009669721 0.01763004 0.07213455 -0.009113788 0.01717692 0.07210958 -0.008772671 0.01674592 0.07209014 -0.008663833 0.01628506 0.07207024 -0.00871104 0.01577639 0.07204425 -0.008984386 0.01538789 0.07201039 -0.009652614 0.0154367 0.0719791 -0.01036143 0.01575475 0.07195389 -0.01084685 0.01624208 0.07192885 -0.01115399 0.01699292 0.07189548 -0.01117265 0.01779675 0.07758378 -0.01086151 0.01599019 0.07758748 -0.01116508 0.01709502 0.07758748 -0.01132428 0.01807057 0.07757133 -0.01034235 0.01799494 0.07751631 -0.009338974 0.01525044 0.07738351 -0.009443581 0.01516669 0.07735788 -0.0100941 0.01544576 0.07697921 -0.01080328 0.01802116 0.07686007 -0.01049703 0.01766687 0.07679456 -0.008870065 0.01720964 0.0767737 -0.008567333 0.0179795 0.076514 -0.01056092 0.01812511 0.07649213 -0.01000136 0.01803946 0.07647067 -0.009448707 0.01653432 0.07639813 -0.008455038 0.01551532 0.07635331 -0.008984923 0.0152316 0.07633161 -0.009492635 0.01560473 0.07627028 -0.01099616 0.01668208 0.07622545 -0.01140964 0.01798248 0.07611501 -0.00928992 0.01585817 0.07602047 -0.008688092 0.01547604 0.0760014 -0.009029507 0.01523834 0.0759477 -0.01037222 0.01545643 0.0759285 -0.01081806 0.01530343 0.07558882 -0.01056981 0.01646828 0.07553333 -0.01140236 0.01711565 0.07550883 -0.01133722 0.01804381 0.07541918 -0.009430468 0.0176596 0.07539439 -0.008860051 0.01718944 0.07537263 -0.008556127 0.01642471 0.075185 -0.01138812 0.01700592 0.07516342 -0.01137602 0.01745313 0.07503265 -0.008681654 0.01593011 0.07497364 -0.008642435 0.01566952 0.07486575 -0.01105529 0.01628333 0.07484096 -0.01136559 0.0168097 0.07482045 -0.01140338 0.01576089 0.07461649 -0.008748948 0.01542139 0.07459735 -0.009106457 0.0151863 0.07457417 -0.009670913 0.01661974 0.07447677 -0.01142245 0.01619547 0.07428503 -0.00852555 0.01573085 0.07426458 -0.008771359 0.01537626 0.07418453 -0.01070046 0.01806306 0.07405662 -0.01038092 0.01770985 0.0739966 -0.008905768 0.01613527 0.07379686 -0.01132565 0.01772445 0.0737316 -0.01094281 0.01810359 0.07369691 -0.01013976 0.01808464 0.07367676 -0.009590387 0.01518493 0.0735225 -0.009723901 0.01520824 0.07350063 -0.01029747 0.01788407 0.07337099 -0.0107662 0.01522296 0.07314848 -0.01033693 0.01549071 0.07312715 -0.01085436 0.01588821 0.07310664 -0.01120477 0.01653015 0.07308149 -0.01141387 0.01719528 0.0730552 -0.01130723 0.0178892 0.07267129 -0.01074802 0.01808589 0.07262736 -0.009608626 0.01756191 0.07258868 -0.008772611 0.01626348 0.07239121 -0.01137095 0.01812529 0.07228368 -0.009790718 0.01756572 0.07223969 -0.008778333 0.01710212 0.07221919 -0.008526802 0.01559233 0.07207137 -0.01097083 0.01605045 0.07204967 -0.01128917 0.01800721 0.07195901 -0.01051241 0.01584315 0.07167112 -0.00876975 0.01610589 0.07173693 -0.008577346 0.01644438 0.07160788 -0.008613646 0.01639515 0.07171195 -0.008510649 0.01697695 0.07159352 -0.008676707 0.01663011 0.07166218 -0.00852853 0.01678335 0.07171916 -0.00849229 0.01708441 0.07172644 -0.008550226 0.01739943 0.07159507 -0.008869946 0.01731353 0.07169514 -0.0086627 0.01758903 0.07166194 -0.00889343 0.01774674 0.07159554 -0.009231746 0.0176388 0.07176023 -0.008857607 0.01783275 0.0716986 -0.00912857 0.01794159 0.07159489 -0.009800493 0.01793861 0.07163441 -0.009480655 0.01802122 0.07172131 -0.009472668 0.01781749 0.07158893 -0.01041662 0.01809519 0.07172101 -0.009876012 0.01797938 0.07162034 -0.01014924 0.01808661 0.07173722 -0.0101242 0.01795423 0.07164901 -0.01041436 0.01801562 0.07176256 -0.01043862 0.01776355 0.07162761 -0.01071053 0.01787823 0.07173919 -0.01070612 0.01741778 0.07159101 -0.01097393 0.017699 0.07170981 -0.010917 0.01740294 0.07166707 -0.0111255 0.0175119 0.07182896 -0.01113092 0.0172379 0.07173538 -0.0112583 0.01686906 0.07161432 -0.01126474 0.01726424 0.0718376 -0.01127159 0.01691436 0.07168436 -0.01133328 0.01691842 0.07183045 -0.01138901 0.01644945 0.07158899 -0.0111922 0.01653003 0.07166707 -0.01133805 0.01659387 0.07183283 -0.01141273 0.01616853 0.07161003 -0.01118159 0.01628667 0.07172507 -0.01133853 0.0159626 0.07168805 -0.01118415 0.01587235 0.07160341 -0.01100116 0.01602697 0.07183372 -0.0112797 0.01560425 0.07158941 -0.01065522 0.01573151 0.07171112 -0.01105058 0.01555103 0.07163196 -0.0107662 0.01548802 0.07171779 -0.01080197 0.01536083 0.0715906 -0.009971797 0.01531332 0.07173234 -0.01051861 0.01538091 0.07162278 -0.01042252 0.01527887 0.07163304 -0.01006513 0.01521205 0.07171338 -0.01012647 0.01520252 0.07172334 -0.009773254 0.01531207 0.0716418 -0.00957334 0.01542496 0.07159024 -0.009539127 0.01526707 0.07174032 -0.009462893 0.01546263 0.07162654 -0.009257256 0.01540195 0.07172554 -0.009188413 0.01573359 0.07160407 -0.008979439 0.01611441 0.07159078 -0.008755803 0.01561343 0.07166868 -0.008970737 0.01551145 0.071841 -0.008986115 0.01831042 0.07774239 -0.01204872 0.01848036 0.07764935 -0.01181292 0.01868009 0.07777827 -0.01170438 0.01880156 0.07763147 -0.01140278 0.01895225 0.07777315 -0.01133376 0.01892471 0.07759219 -0.01101768 0.01911568 0.07766532 -0.0108729 0.01918256 0.07779622 -0.01086109 0.01929354 0.07773196 -0.01039367 0.01911443 0.07759004 -0.01036804 0.01920419 0.07760542 -0.01010888 0.01932966 0.07772624 -0.009970247 0.01932549 0.07775807 -0.009655356 0.01925522 0.0777775 -0.009244978 0.01918679 0.07763153 -0.009371578 0.01899659 0.07758843 -0.009081959 0.0190947 0.0776503 -0.008986234 0.01907306 0.07774996 -0.008766412 0.01890909 0.07774448 -0.008478105 0.01878976 0.07761085 -0.008520483 0.01862519 0.07777804 -0.008098423 0.01849842 0.07767564 -0.008037269 0.01843422 0.07759469 -0.008139431 0.01823294 0.07775151 -0.00775808 0.0180577 0.07759344 -0.00783056 0.01786214 0.07778465 -0.007522702 0.01793611 0.07767021 -0.007629156 0.01747214 0.0776152 -0.007492601 0.01747131 0.07772594 -0.007379293 0.0171718 0.07775557 -0.007291853 0.01683706 0.07764345 -0.007322609 0.01665604 0.07776337 -0.007233977 0.01695889 0.07759028 -0.007448136 0.01625818 0.07759189 -0.007446169 0.01619613 0.07766675 -0.00732553 0.01602536 0.07779842 -0.007303297 0.01567214 0.0776937 -0.007456362 0.0155372 0.07778447 -0.007470488 0.01569694 0.0776053 -0.007561504 0.01516854 0.07775294 -0.007680356 0.01523619 0.07763105 -0.007748842 0.01478767 0.07774955 -0.007980704 0.01509267 0.07759034 -0.007961332 0.01477026 0.07764458 -0.008108377 0.01440751 0.07774007 -0.008437216 0.01456063 0.07759654 -0.008480727 0.01418918 0.0777775 -0.008816778 0.01424896 0.07764858 -0.008864998 0.0140416 0.07776355 -0.009225606 0.014225 0.07759106 -0.009270489 0.01405918 0.07765537 -0.009430348 0.01394772 0.07778167 -0.009805262 0.01401072 0.07765829 -0.0100913 0.01411503 0.07759332 -0.009927749 0.01396656 0.07775843 -0.01021122 0.01404047 0.07777786 -0.01065307 0.0141133 0.07767373 -0.01069712 0.01422053 0.07760101 -0.01071405 0.01420581 0.07775437 -0.01107347 0.01443254 0.07764935 -0.01135629 0.01442629 0.0777651 -0.01146739 0.01463615 0.07759296 -0.01146847 0.01471149 0.077762 -0.01181077 0.01495558 0.07763397 -0.01191467 0.01496154 0.0777474 -0.0120325 0.01514118 0.07758861 -0.01194292 0.01523756 0.07772648 -0.01222157 0.01561516 0.07760804 -0.01227962 0.01558935 0.07776385 -0.01241344 0.01576018 0.07766503 -0.01242154 0.01606476 0.07776266 -0.01256734 0.01619666 0.07764315 -0.01250857 0.01641255 0.07758814 -0.01242548 0.0164324 0.07776165 -0.01261842 0.0168817 0.07768869 -0.01258611 0.0168358 0.0777896 -0.01262813 0.01679199 0.07761007 -0.01249492 0.01745045 0.07777631 -0.01251339 0.01741898 0.07769769 -0.01248323 0.01725816 0.0776003 -0.0124008 0.01783621 0.07763016 -0.0122444 0.0178942 0.07774108 -0.01231628 0.01809984 0.0775901 -0.01199144 0.01859301 0.08039855 -0.01180559 0.01922154 0.08041542 -0.01072877 0.01933544 0.08039349 -0.009729206 0.01875424 0.0803858 -0.008242785 0.01841247 0.08041375 -0.00789833 0.0179252 0.08038544 -0.007552623 0.01754808 0.08041077 -0.007394373 0.0168485 0.0803917 -0.007240951 0.01591467 0.08040797 -0.007336199 0.01534801 0.08038723 -0.007561206 0.01466745 0.08037304 -0.008091032 0.01410269 0.08039146 -0.009022533 0.01398241 0.08038508 -0.01040452 0.01415741 0.08039438 -0.01098394 0.01437264 0.08037394 -0.01139301 0.01458781 0.08044344 -0.01166057 0.0148468 0.08039784 -0.01194679 0.01520758 0.08041626 -0.01221328 0.01570153 0.08041191 -0.01246297 0.01635706 0.08040112 -0.01261854 0.01686209 0.08038085 -0.01262629 0.01726961 0.08042377 -0.01255208 0.01758122 0.08039975 -0.01246321 0.01805371 0.0804063 -0.01223742 0.01830911 0.08048862 -0.01200294 0.01820826 0.08055335 -0.01200127 0.01794916 0.08058655 -0.01207679 0.01761484 0.08052384 -0.01237773 0.01730775 0.08058559 -0.01235169 0.0169878 0.08052599 -0.0125361 0.01656687 0.08048617 -0.01259082 0.01639729 0.08058267 -0.01245552 0.01593935 0.08051586 -0.01247853 0.01549643 0.08058148 -0.01219004 0.0153371 0.0805273 -0.01220446 0.01489639 0.08049905 -0.0119208 0.01491516 0.08058309 -0.01178282 0.01453143 0.08056479 -0.01139408 0.01433676 0.08048391 -0.01125895 0.01433503 0.08058583 -0.01091599 0.01411032 0.0805096 -0.01069468 0.01411616 0.0805633 -0.01038688 0.01399201 0.08048683 -0.010082 0.01394903 0.08039981 -0.00982058 0.01409512 0.08057367 -0.009902238 0.01403695 0.08051842 -0.00958395 0.01401656 0.08042025 -0.009330809 0.01421624 0.08053988 -0.008966386 0.01432657 0.08041977 -0.008556485 0.01424264 0.08058631 -0.009218394 0.01453143 0.08057636 -0.008500218 0.01466089 0.08047634 -0.008152842 0.01490181 0.0805726 -0.008073568 0.01491498 0.0804193 -0.007869541 0.01515418 0.08052349 -0.007766187 0.01559644 0.08048373 -0.00748676 0.01554417 0.08058273 -0.007659912 0.01611524 0.08055186 -0.007390677 0.01635497 0.08041298 -0.007253885 0.01639384 0.08058053 -0.007412731 0.01674628 0.08047914 -0.007268548 0.01689594 0.080567 -0.007383108 0.01725697 0.08044743 -0.007319271 0.01730424 0.08058166 -0.007491528 0.01772534 0.08054625 -0.007565796 0.01810431 0.08046799 -0.007697403 0.01816284 0.08058583 -0.007937133 0.01846581 0.08052915 -0.00804001 0.01879298 0.08057433 -0.008548021 0.01887398 0.08047932 -0.008478224 0.01908046 0.08039879 -0.008769035 0.019082 0.08053743 -0.008975148 0.01925635 0.08039695 -0.009248018 0.01925325 0.08048415 -0.009414434 0.01911079 0.08058738 -0.009522497 0.01927232 0.08052343 -0.009795546 0.01932883 0.0804069 -0.01020961 0.01923173 0.0805481 -0.01020961 0.01916468 0.08053201 -0.01063996 0.01905637 0.08058524 -0.01062047 0.01896226 0.08054828 -0.01111221 0.01904189 0.08043837 -0.01115316 0.01889854 0.08042216 -0.0114063 0.01866406 0.08058124 -0.01146078 0.01866066 0.08050394 -0.01164156 0.004302799 0.08558785 0.002837181 0.004897475 0.07058787 0.002900779 0.004993379 0.08558785 0.00294137 0.005524694 0.08558785 0.003242552 0.005649507 0.07058787 0.003343105 0.005944967 0.08558785 0.003743946 0.006129324 0.07058787 0.00417447 0.006177365 0.08558785 0.00455439 0.006118655 0.07058787 0.004989743 0.005918979 0.08558785 0.00552386 0.005815088 0.07058787 0.005666792 0.005261182 0.08558785 0.006141304 0.005040168 0.07058787 0.006256937 0.004536628 0.08558785 0.006356 0.003965973 0.07058787 0.006322383 0.003717243 0.08558785 0.006229937 0.003218948 0.07058787 0.005897164 0.002945899 0.08558785 0.005610942 0.002761065 0.07058787 0.005259275 0.002659082 0.08558785 0.004817366 0.002655625 0.07058787 0.004334926 0.002726733 0.08558785 0.004034817 0.00295037 0.07058787 0.003606915 0.003145337 0.08558785 0.003370106 0.003472805 0.07058787 0.003100514 0.003642201 0.08558785 0.003014862 0.004142701 0.07058787 0.002858817 0.004229605 0.07058787 -0.009585261 0.005062699 0.07058787 -0.009455442 0.005277633 0.08558785 -0.00935918 0.005543768 0.07058787 -0.009156465 0.005958676 0.08558785 -0.008683085 0.00596553 0.07058787 -0.008653938 0.006155014 0.07058787 -0.007982432 0.006167411 0.08558785 -0.007835149 0.006109476 0.07058787 -0.007372796 0.006061077 0.08558785 -0.007233142 0.005825877 0.07058787 -0.006783246 0.005684435 0.08558785 -0.006594419 0.005203366 0.07058787 -0.006234288 0.004967391 0.08558785 -0.006150543 0.004185497 0.07058787 -0.006060421 0.004392981 0.08558785 -0.006066799 0.003718495 0.08558785 -0.006189703 0.00331515 0.07058787 -0.006430029 0.002947092 0.08558785 -0.006808757 0.002863109 0.07058787 -0.006980776 0.002640724 0.07058787 -0.00768876 0.002660334 0.08558785 -0.007602274 0.002687394 0.08558785 -0.008182346 0.002828419 0.07058787 -0.008629918 0.002931714 0.08558785 -0.008790254 0.003412783 0.07058787 -0.009277999 0.003596663 0.08558785 -0.00940001 0.004479885 0.08558785 -0.00958395 0.01676154 0.08558785 7.22357e-4 0.017223 0.07058787 8.07625e-4 0.01751214 0.08558785 9.53917e-4 0.01787972 0.07058787 0.001238524 0.01812404 0.08558785 0.001512944 0.01831734 0.07058787 0.001892507 0.01836901 0.08558785 0.002168595 0.01838743 0.08558785 0.002734899 0.0183869 0.07058787 0.002718746 0.01822006 0.07058787 0.003260552 0.01819258 0.08558785 0.003314256 0.01786345 0.07058787 0.00375694 0.01785004 0.08558785 0.00376594 0.01712507 0.08558785 0.004197061 0.01732653 0.07058787 0.004106044 0.01670169 0.07058787 0.004246652 0.01603531 0.08558785 0.004157721 0.01608413 0.07058787 0.004151761 0.01543956 0.07058787 0.003784 0.01532447 0.08558785 0.003650486 0.01500582 0.07058787 0.003129065 0.01491928 0.08558785 0.002910375 0.01487821 0.07058787 0.002295017 0.01492995 0.08558785 0.002095103 0.01525753 0.08558785 0.001380801 0.01524323 0.07058787 0.001407384 0.01580303 0.07058787 9.42524e-4 0.01595872 0.08558785 8.61384e-4 0.01638144 0.07058787 7.4645e-4 0.01677668 0.07058787 -0.01169085 0.01651239 0.08558785 -0.01170283 0.01731526 0.08558785 -0.0115593 0.01733851 0.07058787 -0.01154476 0.01782095 0.07058787 -0.01124465 0.0178647 0.08558785 -0.01120406 0.01823788 0.07058787 -0.01068502 0.01833748 0.08558785 -0.01047074 0.01840472 0.07058787 -0.01000714 0.01837921 0.08558785 -0.009641766 0.01823848 0.07058787 -0.009149849 0.01819378 0.08558785 -0.009105443 0.01782089 0.08558785 -0.008622169 0.01766163 0.07058787 -0.008495151 0.01708245 0.08558785 -0.008215248 0.01699435 0.07058787 -0.008205056 0.01620924 0.07058787 -0.00822252 0.01615232 0.08558785 -0.008235573 0.01558357 0.07058787 -0.008532226 0.01544553 0.08558785 -0.008640766 0.01517522 0.07058787 -0.008967697 0.01506847 0.08558785 -0.009159266 0.01490986 0.07058787 -0.009613037 0.01487803 0.08558785 -0.009845256 0.01496428 0.07058787 -0.01049804 0.01509237 0.08558785 -0.01079541 0.01547592 0.07058787 -0.01125806 0.01570123 0.08558785 -0.0114206 0.01611328 0.07058787 -0.01160979 0.01445031 0.078 -0.002506911 0.01442718 0.07599997 -0.002975583 0.01422393 0.078 -0.003814756 0.01401495 0.07599997 -0.004310607 0.01349705 0.078 -0.005124032 0.01338839 0.07599997 -0.005212187 0.01246583 0.07599997 -0.005972146 0.01232117 0.078 -0.006047129 0.0114445 0.07599997 -0.006382048 0.01099687 0.078 -0.006492555 0.01026004 0.07599997 -0.006529331 0.009503304 0.078 -0.006418704 0.008710861 0.07599997 -0.00614798 0.00848788 0.078 -0.006011486 0.007474005 0.078 -0.005248367 0.007650375 0.07599997 -0.005398273 0.007022857 0.07599997 -0.004623293 0.006732404 0.078 -0.004064977 0.006541132 0.07599997 -0.003529489 0.006464898 0.078 -0.003104388 0.0064224 0.07599997 -0.002306997 0.006441712 0.078 -0.002038538 0.00665307 0.07599997 -0.001132726 0.006732404 0.078 -9.4886e-4 0.007231175 0.07599997 -8.49757e-5 0.007233321 0.078 -8.65855e-5 0.008003711 0.078 6.9435e-4 0.008241832 0.07599997 8.78818e-4 0.009337007 0.078 0.001372933 0.009632885 0.07599997 0.001429438 0.01079744 0.078 0.001490414 0.01065653 0.07599997 0.001492619 0.01183575 0.07599997 0.001265048 0.01177215 0.078 0.001267075 0.01274931 0.078 7.75216e-4 0.01295208 0.07599997 6.09224e-4 0.01375144 0.078 -2.41433e-4 0.01380872 0.07599997 -3.23821e-4 0.01425904 0.078 -0.001325428 0.01433527 0.07599997 -0.001583337 0.02625232 0.06699997 -0.003580391 0.0262798 0.0749998 -0.002111554 0.02610796 0.06699997 -2.3463e-5 0.02604043 0.07499974 1.75074e-4 0.02549809 0.07499986 0.002437829 0.02515101 0.06699997 0.003391504 0.02439421 0.0749998 0.00498563 0.02390021 0.06699997 0.005841374 0.02312153 0.0749998 0.006983399 0.0222457 0.06699997 0.008071184 0.02126681 0.07500422 0.009072184 0.01959866 0.06699997 0.01045143 0.01876693 0.07499605 0.0109843 0.01685661 0.06699997 0.01197952 0.01627439 0.0750029 0.01222425 0.01384508 0.06699997 0.01299583 0.01364982 0.07499605 0.01302254 0.0104286 0.07499986 0.01335734 0.0104286 0.06699997 0.01334911 0.007285177 0.06699997 0.01304286 0.007605731 0.07499712 0.01308828 0.005760014 0.07500314 0.01262831 0.0039016 0.06699997 0.01195836 0.003940343 0.07500034 0.01195293 0.002212882 0.07499825 0.01103645 0.001175224 0.06699997 0.01036363 5.93871e-4 0.0750029 0.009921193 -7.07996e-4 0.06699997 0.008769273 -0.001140177 0.07499712 0.008325457 -0.002445518 0.06699997 0.006748914 -0.0026533 0.07499694 0.006445169 -0.003853261 0.06699997 0.004370808 -0.00368607 0.07500153 0.004683256 -0.004488646 0.07499712 0.002845942 -0.004713177 0.06699997 0.002163648 -0.005178987 0.07500398 2.89049e-4 -0.005293965 0.06699997 -4.23755e-4 -0.005419909 0.0750029 -0.002447187 -0.005408704 0.06699997 -0.002901852 -0.005197107 0.07500046 -0.005224168 -0.005227863 0.06699997 -0.004966735 -0.004601776 0.06699997 -0.007556855 -0.004457771 0.07499694 -0.00795412 -0.003699004 0.06699997 -0.00967139 -0.003635346 0.07499974 -0.009795546 -0.002513766 0.06699997 -0.01167398 -0.002382934 0.07499986 -0.01185584 -7.07999e-4 0.06699997 -0.01378315 -3.24496e-4 0.07500398 -0.01415967 0.001716196 0.06699997 -0.01577728 0.001851141 0.07499694 -0.01583749 0.004000484 0.0749998 -0.01699334 0.00463736 0.06699997 -0.01726287 0.006557941 0.07500398 -0.01788336 0.006587445 0.06699997 -0.01787465 0.009242534 0.06699997 -0.01833224 0.009271085 0.07499694 -0.01831638 0.01171165 0.0749998 -0.01830351 0.01230102 0.06699997 -0.01824456 0.01438319 0.07500398 -0.01786202 0.01537168 0.06699997 -0.01759248 0.01659905 0.07499819 -0.01709818 0.01894134 0.06699997 -0.01590627 0.0183857 0.07500272 -0.01621007 0.0200088 0.07499819 -0.01512432 0.02198451 0.06699997 -0.01339131 0.02156531 0.0749998 -0.01378309 0.02285653 0.07499974 -0.01232868 0.02410745 0.06699997 -0.01053375 0.02400332 0.0749998 -0.01068645 0.02523285 0.07499986 -0.00819683 0.02528733 0.06699997 -0.008020222 0.02587372 0.06699997 -0.006032228 0.02606678 0.07499986 -0.005150556 -0.005794167 0.07458192 -0.00380522 -0.005227506 0.07458651 -0.006951749 -0.00420922 0.07458633 -0.009593725 -0.00298947 0.07458633 -0.01169627 -0.001743078 0.07458615 -0.01328045 -3.07042e-4 0.07458633 -0.01472318 0.001974999 0.07458651 -0.0164141 0.004518449 0.07458633 -0.01765817 0.006842672 0.07458633 -0.01836985 0.009247064 0.07458633 -0.01872712 0.01208716 0.07458651 -0.01869714 0.0144627 0.07458615 -0.01825326 0.01640188 0.07458633 -0.01763343 0.01894766 0.07458651 -0.01637411 0.02121514 0.07458633 -0.01467835 0.0228585 0.07458883 -0.01298975 0.02404385 0.07458579 -0.01138597 0.02507179 0.07458287 -0.009589672 0.02597928 0.07458633 -0.007268071 0.02651518 0.07458633 -0.004897236 0.02667903 0.07458615 -0.002888262 0.02660757 0.07458633 -8.53932e-4 0.02627056 0.07458615 0.001133501 0.02568978 0.07458901 0.003112912 0.02486896 0.07458418 0.004955708 0.02388614 0.07458883 0.006619155 0.02235251 0.07458579 0.008556842 0.02021747 0.07459008 0.0104897 0.01791363 0.07458305 0.01193118 0.0156356 0.07458287 0.01290327 0.01319229 0.07458901 0.01351952 0.01116746 0.07458579 0.01373082 0.008808612 0.07458585 0.01368278 0.00604999 0.07458287 0.01315879 0.003708958 0.07458633 0.01230305 0.001576662 0.07458633 0.01113617 -6.92847e-4 0.07459032 0.009374976 -0.00257951 0.07458305 0.007253766 -0.003870189 0.07458633 0.005241215 -0.004717707 0.07458758 0.003392457 -0.005456149 0.07458192 0.00103414 -0.005783677 0.07458758 -0.001334071 -0.005774974 0.07199996 -8.85525e-4 -0.005114793 0.07199996 0.002287566 -0.004179418 0.07199996 0.004640519 -0.002950966 0.07199996 0.006737887 -0.001711249 0.07199996 0.008302032 -2.55984e-4 0.07199996 0.009753584 0.001944541 0.07199996 0.01137661 0.004392743 0.07199996 0.0125944 0.006808996 0.07199996 0.01335132 0.009732127 0.07199996 0.01375281 0.01245039 0.07199996 0.01362693 0.01444017 0.07199996 0.01324677 0.01646447 0.07199996 0.0125944 0.01864784 0.07199996 0.0115261 0.02030032 0.07199996 0.01040667 0.02207624 0.07199996 0.008853793 0.02410352 0.07199996 0.006325185 0.02545362 0.07199996 0.003716528 0.02609497 0.07199996 0.001826465 0.02652472 0.07199996 -1.83539e-4 0.02667981 0.07199996 -0.002173244 0.02656233 0.07199996 -0.004644513 0.02593886 0.07199996 -0.007397234 0.02507847 0.07199996 -0.009561836 0.02386832 0.07199996 -0.01166999 0.02228087 0.07199996 -0.01364272 0.02082186 0.07199996 -0.01500463 0.01881659 0.07199996 -0.0164535 0.0162757 0.07199996 -0.01768237 0.01437008 0.07199996 -0.01827645 0.01193451 0.07199996 -0.0187118 0.009112179 0.07199996 -0.01871651 0.006710886 0.07199996 -0.01833921 0.004392623 0.07199996 -0.01760822 0.002591907 0.07199996 -0.01674765 8.53064e-4 0.07199996 -0.01565194 -9.99151e-4 0.07199996 -0.0140779 -0.002852141 0.07199996 -0.01191359 -0.004267454 0.07199996 -0.009471595 -0.005268454 0.07199996 -0.006803989 -0.005763232 0.07199996 -0.00402522 -0.001301825 0.07600003 0.008773982 0.001166045 0.07600003 0.01087468 -0.003534436 0.07600003 0.00588274 0.0040012 0.07600003 0.01244473 -0.005034744 0.07600003 0.002567172 0.007091224 0.07600003 0.01342183 -0.005591273 0.07599997 2.45104e-4 -0.0058434 0.07600003 -0.0022161 0.00992161 0.07599997 0.01374804 0.01274043 0.07600003 0.01360267 -0.005578398 0.07600003 -0.005446135 0.01551181 0.07599997 0.01294112 -0.004534125 0.07600003 -0.008946657 0.01846772 0.07600003 0.01166093 -0.002717971 0.07600003 -0.01210016 0.02141362 0.07600003 0.009501099 -8.53875e-4 0.07599997 -0.01421964 0.02357518 0.07600003 0.007086396 0.001356005 0.07600003 -0.01601809 0.02539145 0.07600003 0.003932774 0.004212975 0.07600003 -0.01754784 0.007316529 0.07600003 -0.01848125 0.0265178 0.07600003 4.14505e-5 0.01002329 0.07599997 -0.01876193 0.02664911 0.07600003 -0.004007399 0.01245123 0.07599997 -0.01864683 0.01483237 0.07599997 -0.01815932 0.02599865 0.07599997 -0.00720334 0.01749181 0.07600003 -0.01717388 0.02496308 0.07600003 -0.009829044 0.02000421 0.07599997 -0.01565194 0.02345341 0.07599997 -0.01224535 0.02185642 0.07599997 -0.0140779 0.02760785 0.07500326 -8.31172e-4 0.02767968 0.07499831 -0.002957105 0.02718472 0.07500004 0.001648545 0.02622574 0.07500004 0.004487037 0.02475303 0.07500004 0.007128715 0.02341628 0.07499998 0.008853137 0.02162671 0.07500004 0.0106486 0.01915359 0.07500004 0.01238965 0.01683592 0.07500004 0.01352369 0.01397132 0.07500004 0.01440203 0.01136463 0.07499998 0.01472252 0.009245932 0.07500004 0.0147162 0.007028758 0.07499831 0.01441168 0.004896104 0.07500064 0.01384657 0.002592384 0.07500326 0.01287245 9.47151e-5 0.07500004 0.01133775 -0.002153038 0.07500004 0.00931406 -0.004017174 0.07500004 0.006968438 -0.005437254 0.07500004 0.004297971 -0.006297171 0.07499688 0.001782596 -0.00674194 0.07500326 -7.45501e-4 -0.006818473 0.07499688 -0.003337919 -0.006498336 0.07500326 -0.005884826 -0.005697429 0.07500004 -0.008704841 -0.004358172 0.07500004 -0.01141679 -0.003108978 0.07499998 -0.01320564 -0.001702427 0.07500004 -0.01478993 -6.91541e-6 0.07499831 -0.01625102 0.002126872 0.07500457 -0.01765292 0.004455626 0.07499998 -0.01869499 0.006482064 0.07500004 -0.01931351 0.009492456 0.07500481 -0.0197578 0.01291704 0.07499593 -0.01960301 0.01547181 0.07500189 -0.01900851 0.01784557 0.07499593 -0.01811003 0.02041864 0.07500004 -0.01658654 0.02210909 0.07499998 -0.01520723 0.02358382 0.07500004 -0.01368618 0.02510309 0.07500004 -0.01160061 0.02646559 0.07500004 -0.008931994 0.02742069 0.07500004 -0.005626976 0.02765226 0.07199996 -0.00379765 0.02726763 0.07199996 -0.006272375 0.02655476 0.07199996 -0.008704841 0.02500694 0.07199996 -0.01177728 0.02288103 0.07199996 -0.01448208 0.02059352 0.07199996 -0.01646083 0.0187475 0.07199996 -0.01762402 0.01683598 0.07199996 -0.01853758 0.0143752 0.07199996 -0.01931351 0.01222229 0.07199996 -0.01966834 0.009689509 0.07199996 -0.01976728 0.006692111 0.07199996 -0.01936143 0.004221737 0.07199996 -0.01861625 0.002243161 0.07199996 -0.01769673 4.38663e-4 0.07199996 -0.01658654 -0.00154823 0.07199996 -0.01494038 -0.003335595 0.07199996 -0.01293283 -0.004783928 0.07199996 -0.01066857 -0.005943834 0.07199996 -0.008007764 -0.006566047 0.07199996 -0.005503535 -0.006837844 0.07199996 -0.002937495 -0.006694257 0.07199996 -3.61131e-4 -0.00619769 0.07199996 0.002170979 -0.005000233 0.07199996 0.005265831 -0.003625452 0.07199996 0.007503628 -0.002299547 0.07199996 0.009156167 -4.19136e-4 0.07199996 0.0109229 0.001703619 0.07199996 0.01238965 0.004021346 0.07199996 0.01352369 0.006482243 0.07199996 0.01429963 0.008710443 0.07199996 0.01466417 0.01128959 0.07199996 0.01474344 0.01384794 0.07199996 0.01440775 0.01602894 0.07199996 0.01382315 0.01868903 0.07199996 0.01266157 0.02143979 0.07199996 0.01080548 0.02358388 0.07199996 0.008672237 0.02488183 0.07199996 0.006918311 0.02593564 0.07199996 0.005080401 0.02678686 0.07199996 0.002989172 0.02737104 0.07199996 8.08115e-4 0.02764075 0.07199996 -0.001293301 + + + + + + + + + + 0.975221 -0.004955112 -0.2211772 0.9641368 0.006309092 -0.2653311 0.869345 -0.003662109 -0.4941924 0.8589397 8.77195e-4 -0.5120761 0.9996826 0.002835273 -0.02503776 0.9997653 0.001550257 -0.02160996 0.990349 0.004814028 -0.1385129 0.9931126 -0.005398631 -0.1170405 0.9642654 -5.65922e-4 -0.2649378 0.9631937 -0.002763152 -0.2687944 0 1 0 0 1 1.81342e-6 0 1 -2.04495e-6 0 1 -1.13196e-6 0 1 1.15196e-6 0 1 -9.39814e-6 0 1 -4.33954e-7 0 1 2.86524e-6 0 1 1.51335e-5 0 1 -3.39897e-6 0 1 5.61484e-7 0 1 -4.13513e-6 0 1 -2.73116e-6 0 1 1.67487e-6 0 1 4.47232e-7 0 1 -3.43417e-7 0 1 4.38526e-7 0 1 -7.20903e-5 0 1 -3.85435e-6 0 1 4.14259e-6 0 1 5.86714e-7 0 1 -4.98206e-6 0 1 4.38762e-6 0 1 1.70852e-6 0 1 -3.20176e-6 0 1 2.12148e-6 0 1 -2.65169e-6 0 1 -1.65053e-6 0 1 -1.21456e-6 0 1 -4.52476e-6 0 1 2.27824e-6 0 1 2.14073e-6 0 1 -3.1413e-6 0 1 1.71415e-6 0 1 -2.41765e-6 0 1 7.57114e-7 0 1 -1.37581e-6 0 1 3.1303e-6 0 1 5.47574e-7 0 1 2.76115e-5 0 1 8.60424e-6 0 1 9.98574e-6 0 1 5.33975e-5 0 1 -5.15572e-5 0 1 -2.48276e-5 0 1 2.20596e-5 0 1 -7.69696e-6 0 1 -4.76262e-7 0 1 -3.51266e-7 0 1 -6.92736e-6 0 1 6.59985e-6 0 1 -1.14296e-6 0 1 -6.24531e-6 0 1 2.69385e-7 0 1 3.26366e-5 0 1 5.76462e-7 0 1 1.02294e-5 0 1 -3.48715e-6 0 1 -6.63787e-6 0 1 1.77027e-6 0 1 -1.54745e-5 0 1 8.78776e-6 0 1 1.01067e-6 0 1 -2.76252e-6 0 1 -5.29109e-6 0 1 3.61942e-6 0 1 1.19601e-6 0 1 -6.94877e-7 0 1 -1.27193e-6 0 1 3.26418e-6 0 1 -1.06476e-5 0 1 -1.6826e-5 0 1 -7.67427e-6 0 1 -3.54725e-6 0 1 8.08069e-6 0 1 -5.29291e-6 0 1 8.26057e-6 0 1 8.04224e-7 0 1 -1.6786e-7 0 1 -2.81903e-6 0 1 5.80466e-7 0 1 -8.0494e-7 0 1 -8.58409e-6 0 1 1.53884e-5 0 1 6.73585e-7 0 1 -1.82298e-6 0 1 2.59507e-6 0 1 -4.75061e-7 0 1 -2.41757e-6 0 1 4.15875e-7 0 1 -1.03407e-6 0 1 1.40179e-6 0 1 1.98794e-6 0 1 4.01308e-6 0 1 2.57686e-6 0 1 7.763e-6 0 1 -6.266e-6 0 1 -4.76663e-6 0 1 -4.02055e-6 0 1 2.73203e-6 0 1 4.23062e-6 0 1 -1.37301e-6 0 1 1.0102e-6 0 1 1.93816e-5 0 1 -4.92557e-6 0 1 -7.42628e-7 0 1 6.41507e-6 0 1 -1.25645e-6 0 1 3.60162e-7 0 1 -5.01971e-6 0 1 -2.17151e-5 0 1 -1.90814e-5 0 1 1.94083e-6 0 1 2.48027e-6 0 1 2.78853e-6 0 1 -3.91047e-6 0 1 1.18476e-6 0 1 1.49315e-5 0 1 -3.14065e-6 0 1 -4.25079e-6 0 1 -8.81369e-7 0 1 -4.75057e-6 0 1 2.40139e-6 0 1 1.2117e-6 0 1 -5.94128e-6 0 1 -3.69401e-6 0 1 -8.27663e-6 0 1 -1.7207e-6 0 1 1.03344e-5 0 1 -6.41069e-7 0 1 4.32479e-6 0 1 6.54212e-6 0 1 -1.97074e-6 0 1 -2.12331e-5 0 1 -7.0058e-6 0 1 1.43896e-6 0 1 -6.22005e-7 0 1 3.9908e-6 0 1 2.52127e-6 0 1 -1.59729e-6 0 1 -3.63753e-6 0 1 1.32816e-5 0 1 -6.99239e-7 0 1 4.32193e-6 0 1 -4.16813e-6 0 1 -2.39372e-6 0 1 -3.02905e-7 0 1 7.28876e-6 0 1 1.19786e-6 0 1 1.2529e-6 0 1 -7.36161e-7 0 1 -9.86159e-6 0 1 -1.12728e-6 0 1 -5.89654e-7 0 1 9.24411e-7 0 1 4.04862e-6 0 1 -1.13567e-6 0 1 4.28474e-7 0 1 -2.27686e-6 0 1 1.9646e-6 0 1 3.29866e-6 0 1 -9.83637e-6 0 1 1.80834e-6 0 1 8.47207e-6 0 1 5.09391e-6 0 1 -2.21209e-6 0 1 -1.32269e-5 0 1 -1.67619e-5 0 1 4.46115e-7 0 1 2.85346e-7 0 1 -1.5227e-7 0 1 -1.54815e-5 0 1 7.6722e-7 0 1 6.42597e-7 0 1 3.87577e-7 0 1 -2.05963e-7 0 1 -1.8508e-5 0 1 2.89681e-5 0 1 -1.26114e-5 0 1 1.17215e-5 0 1 -8.81632e-6 0 1 -5.96382e-7 0 1 -5.20901e-7 0 1 8.15419e-7 0 1 -3.26259e-7 0 1 -1.04187e-5 0 1 -1.99459e-7 0 1 9.89473e-6 0 1 -1.0957e-5 0 1 -4.85696e-5 0 1 7.2066e-7 0 1 -5.12309e-6 0 1 -2.94866e-6 0 1 1.05789e-6 0 1 1.99893e-6 0 1 -2.75049e-6 0 1 1.26512e-5 0 1 -1.34136e-5 0 1 -1.22914e-6 0 1 8.56453e-7 0 1 -7.19827e-7 0 1 -7.96584e-6 0 1 2.14458e-7 0 1 -1.13616e-6 0 1 1.54743e-6 0 1 5.49614e-6 0 1 2.52892e-6 0 1 6.47665e-7 0 1 -2.788e-6 0 1 7.81783e-6 0 1 -8.51051e-6 0 1 -1.56724e-6 0 1 5.47893e-6 0 1 -3.63843e-6 0 1 3.84341e-6 0 1 -8.1444e-7 0 1 3.60169e-6 0 1 -3.70017e-7 0 1 -9.54858e-7 0 1 5.08048e-7 0 1 1.09173e-6 0 1 5.66694e-7 0 1 2.33e-6 0 1 -1.96925e-6 0 1 -1.06329e-6 0 1 -1.1375e-6 0 1 3.90587e-6 0 1 -1.68224e-6 0 1 -9.11168e-6 0 1 1.82525e-6 0 1 3.00294e-6 0 1 -2.39485e-6 0 1 3.03804e-6 0 1 1.319e-6 0 1 9.49366e-7 0 1 3.01514e-6 0 1 -6.30317e-7 0 1 -3.88417e-6 0 1 1.55244e-6 0 1 -1.86427e-6 0 1 2.88802e-6 0 1 -5.93157e-6 0 1 2.44668e-6 0 1 2.49961e-6 0 1 -2.20788e-6 0.7149576 -0.009720385 0.6991003 0.5908413 0.01162427 0.8067041 0.5449357 -0.002310395 0.8384746 0.3186243 -0.001292705 0.9478802 0.1580569 0.001932024 0.9874281 0.150545 -0.002035796 0.9886012 0.2734125 0.002817928 0.9618929 0.2634434 -0.001720726 0.9646733 0.40959 0.004428029 0.9122591 0.3978536 -0.003527224 0.9174422 0.54607 -0.004032373 0.8377299 0.5696888 0.01110845 0.8217855 0.6427657 -0.01059949 0.7659897 0.7100136 0.01104009 0.7041015 0.7400224 -0.007760763 0.6725375 0.8114077 0.00856173 0.5844178 0.8184329 0.002312481 0.5745976 0 -1 0 0 -1 2.0713e-6 0 -1 2.99228e-6 0 -1 4.20606e-6 0 -1 -3.84985e-6 0 -1 -1.73667e-6 0 -1 3.82658e-6 0 -1 -1.32684e-6 0 -1 -7.33417e-6 0 -1 -4.85504e-6 0 -1 1.39739e-6 0 -1 -1.06784e-5 0 -1 5.1821e-6 0 -1 -6.23214e-6 0 -1 7.6264e-6 0 -1 -4.20483e-6 0 -1 -9.73444e-6 0 -1 5.80295e-6 0 -1 -2.72075e-5 0 -1 2.21037e-5 0 -1 9.18223e-7 0 -1 -2.03218e-4 0 -1 1.53954e-5 0 -1 -8.00131e-6 0 -1 -3.85775e-5 -8.17687e-6 -1 9.04895e-6 0 -1 0 0 -1 -4.72105e-7 0 -1 3.50058e-7 0 -1 1.47736e-7 0 -1 -5.28927e-6 0 -1 -2.29505e-6 0 -1 4.86098e-6 0 -1 -1.33781e-5 0 -1 -2.82002e-6 0 -1 -3.4696e-6 0 -1 -2.45128e-6 0 -1 5.64092e-6 0 -1 1.62174e-6 0 -1 -6.53473e-6 0 -1 1.48928e-6 0 -1 6.73441e-6 0 -1 -1.601e-6 0 -1 -6.93034e-6 0 -1 -2.46279e-6 0 -1 4.98514e-6 0 -1 -6.14549e-6 0 -1 2.48624e-6 0 -1 -1.30912e-6 0 -1 1.88798e-6 0 -1 -1.45916e-6 0 -1 -3.79519e-6 0 -1 5.47006e-6 0 -1 8.73596e-6 0 -1 -1.10578e-5 0 -1 -2.26603e-5 0 -1 8.37874e-6 0 -1 6.16673e-5 0 -1 -6.92338e-6 0 -1 -8.30175e-6 0 -1 -7.89203e-6 0 -1 -6.84076e-6 0 -1 1.25416e-5 0 -1 6.49323e-6 0 -1 1.88547e-5 0 -1 -4.4298e-6 0 -1 5.58201e-6 0 -1 -4.1546e-6 -4.3439e-6 -1 -4.45541e-4 0.004688322 -0.999989 -3.21364e-4 -7.29006e-4 -0.999999 -0.001263737 1.34811e-4 -1 -2.12352e-4 2.22562e-4 -1 -1.37803e-4 6.46493e-4 -0.9999998 1.9407e-4 5.45843e-4 -0.9999996 7.13223e-4 0 -1 -2.50006e-6 -1.55222e-4 -0.9999998 -6.28527e-4 -0.002002716 -0.999997 -0.001420438 -0.001511096 -0.9999924 0.00361824 0.00145179 -0.999999 -1.83806e-4 3.79954e-5 -1 -5.67437e-4 -6.46794e-5 -0.999996 0.00284934 -0.001086533 -0.9999903 0.004267871 0 -1 2.36242e-6 -1.70313e-4 -0.9999999 -5.47752e-4 1.77353e-4 -0.9999999 -5.24503e-4 -4.0292e-6 -0.9999999 -5.61459e-4 0 -1 -1.28338e-5 0 -1 8.40818e-6 0 -1 -2.4735e-6 0 -1 -5.42734e-6 2.55615e-4 -0.9999998 -6.26021e-4 0 -1 5.29712e-6 0 -1 1.23106e-5 0 -1 -1.4228e-5 0 -1 -2.90263e-6 0 -1 1.05711e-6 7.24446e-5 -0.9999998 -7.05855e-4 0 -1 -3.67254e-7 2.74664e-4 -0.9999998 -6.45602e-4 -0.001775741 -0.999998 9.09003e-4 0 -1 4.76883e-6 0 -1 -9.10548e-7 5.3212e-4 -0.9999998 -5.95317e-4 8.27115e-4 -0.9999986 0.001483619 0.002080917 -0.9999939 -0.002842605 6.39101e-4 -0.9999984 -0.001672148 0.00323379 -0.9999948 -3.54966e-4 0.001164138 -0.9999988 0.001000344 -0.002538919 -0.9999932 0.002672731 0 -1 3.17879e-6 0 -1 -6.5659e-6 0 -1 -1.25809e-6 -0.001053392 -0.9999975 -0.002014875 0 -1 3.15712e-6 -0.006717741 -0.9999715 -0.003487706 -7.79935e-4 -0.9999993 -9.69919e-4 0 -1 -5.08045e-4 -2.86073e-4 -1 -2.47926e-5 -3.10511e-4 -1 1.11365e-5 -1.90477e-4 -1 -9.14909e-5 0 -1 2.83922e-6 0 -1 -3.5575e-6 -1.31753e-4 -1 -1.48177e-4 0.003424346 -0.9999837 0.004583895 4.2152e-4 -0.9999991 0.001350224 -5.04375e-4 -0.9999999 2.50645e-4 0 -1 4.69363e-6 0 -1 -7.63507e-6 0 -1 1.52897e-6 0 -1 1.33367e-6 0 -1 -1.29334e-5 0 -1 7.77045e-7 0 -1 2.69835e-6 0 -1 2.32927e-7 0 -1 -1.7067e-7 0 -1 -3.18146e-7 -5.16605e-4 -0.9999998 5.42137e-4 0.01004225 -0.9999406 0.004247426 -2.97251e-4 -0.9999998 6.95793e-4 -0.002726554 -0.9999943 -0.001988053 0 -1 -1.49265e-7 0 -1 9.2071e-7 0 -1 -9.27444e-6 0 -1 -1.69205e-6 0 -1 1.52305e-5 0 -1 3.64321e-7 0 -1 -2.66407e-7 0 -1 -1.92372e-6 0 -1 4.85732e-6 0 -1 -1.23068e-6 0 -1 -7.78316e-6 0 -1 0 0 -1 -2.18482e-6 0 -1 2.22119e-6 0 -1 -4.30313e-6 0 -1 2.19809e-6 0 -1 4.38943e-6 0 -1 -1.61552e-6 0 -1 7.50585e-7 0 -1 -6.06255e-7 -0.9681788 -0.008695065 -0.2501088 -0.9367655 0.01160317 -0.3497655 -0.8589024 -0.01147657 -0.5120108 -0.7999491 0.008755087 -0.6000041 -0.1939581 -0.002200603 0.9810073 -0.1957082 -0.001680135 0.9806607 -0.3923894 0.0055902 0.9197822 -0.4596015 -0.005030333 0.888111 -0.668106 8.65966e-5 0.7440661 -0.692038 0.00651443 0.7218317 -0.8872364 -0.006525814 0.461269 -0.9038552 8.04051e-4 0.4278379 -0.9830217 0.003972411 0.1834464 -0.9962088 -0.01013642 0.08640277 -0.9907369 0.01034051 -0.1354012 -0.9629524 -0.007256984 -0.2695737 -0.8647058 0.005124449 -0.5022527 -0.8728894 0.001658976 -0.4879155 -0.6843988 -0.001300036 -0.7291067 -0.6866207 -0.001981437 -0.7270132 -0.725326 0.006660759 0.6883735 -0.6551656 -0.007373988 0.7554494 -0.5529537 0.006130576 0.8331896 -0.4573001 -0.008602857 0.8892709 -0.3470588 0.009274244 0.9377976 -0.09098887 -0.002918124 0.9958477 -0.05325973 0.01328253 0.9984924 -0.2371044 -0.004787385 0.9714724 -0.2241279 0.003814756 0.9745523 -0.4176608 -0.009444952 0.9085539 -0.3975213 0.004787981 0.9175805 -0.5372109 0.01140582 0.8433709 -0.5748587 -0.008776009 0.8182057 -0.6569347 0.006067395 0.7539231 -0.6718787 -0.003046154 0.740655 -0.7570794 0.00304681 0.6533158 -0.7640691 -0.001861393 0.6451317 -0.8223658 -0.002267956 0.5689547 -0.8177081 0.001232028 0.5756319 0.7897816 0.001306593 -0.6133869 0.7929635 4.54685e-5 -0.6092693 0.955122 -0.005441069 -0.296163 0.9716443 0.008081436 -0.2363092 0.9957033 -0.007263362 0.09231543 0.9913462 1.78812e-4 0.1312735 0.9270319 0.004817605 0.3749518 0.884461 -0.009987711 0.4665074 0.7575377 0.01027178 0.6527107 0.638449 -0.01143777 0.7695792 0.4876434 0.008073806 0.8730056 0.3308518 -0.004418194 0.9436724 0.005299448 -0.9999854 -0.001075506 0.005783498 -0.9999734 -0.004459977 0.002062797 -0.999998 1.21844e-4 0.001249551 -0.999999 -7.08937e-4 0.001332998 -0.9999991 -3.06484e-4 0.001365363 -0.9999991 -3.93916e-4 0.00152868 -0.9999989 -3.99573e-5 0 -1 7.42488e-7 0 -1 3.93645e-6 0 -1 7.47652e-7 0 -1 -4.6228e-6 0.001174032 -0.9999994 -1.62532e-4 0.001388251 -0.9999989 4.57862e-4 0 -1 4.164e-6 0 -1 1.10211e-6 0 -1 -3.92326e-6 9.32482e-4 -0.9999996 -2.59823e-4 0.001062452 -0.9999994 2.32725e-4 0 -1 2.62791e-6 0 -1 3.16859e-6 0 -1 -9.15227e-6 0 -1 -5.438e-7 9.50558e-4 -0.9999995 -3.65251e-4 0.001634716 -0.9999973 -0.001687169 0 -1 1.1869e-6 0 -1 -7.35762e-6 0.001549839 -0.9999986 -7.97408e-4 0 -1 1.26969e-6 0 -1 5.60271e-6 0.001533031 -0.9999986 -7.51672e-4 0 -1 6.33661e-6 0 -1 -1.41993e-6 8.64343e-4 -0.9999901 0.004392266 0 -1 -7.69811e-6 0 -1 6.92559e-6 0 -1 -6.48199e-6 0 -1 4.98634e-6 0 -1 -5.60796e-6 0 -1 1.51179e-6 0 -1 -1.88458e-6 8.27009e-4 -0.9999995 5.51879e-4 0 -1 -1.68398e-6 -1.89343e-4 -0.9999997 8.03841e-4 -0.002054393 -0.9999976 9.05552e-4 -5.07623e-5 -1 4.40376e-4 1.90902e-4 -1 4.26963e-4 5.4691e-4 -0.9999998 3.44198e-4 1.59368e-4 -1 5.39049e-4 0.001101434 -0.9999995 -2.20591e-4 0.002399086 -0.9999959 -0.001619279 -0.004704117 -0.9999889 -3.36777e-4 -0.002092957 -0.9999971 -0.001168727 -0.001685559 -0.999997 -0.001785159 -0.001573204 -0.9999984 -9.39489e-4 -0.002910733 -0.9999904 -0.003308355 -0.003644227 -0.999993 -9.38631e-4 -0.003627538 -0.9999935 -2.08426e-4 -0.00115776 -0.999992 0.003823041 -0.001299262 -0.9999992 -4.02084e-5 -0.001224696 -0.9999992 -2.44684e-4 -8.38287e-4 -0.9999987 0.001400053 -5.50231e-4 -0.9999999 1.05137e-4 -6.85648e-4 -0.9999998 -2.59242e-4 -0.00106877 -0.9999897 -0.004434943 -2.51576e-7 -0.9999989 0.001537263 -0.003792524 -0.9999868 -0.003502428 -2.29238e-4 -1 4.34306e-4 -5.0587e-5 -0.9999999 5.83838e-4 0.003590226 -0.9999904 0.002513468 -0.006736457 -0.9999771 -7.54658e-4 -0.001237213 -0.9999991 -6.3917e-4 3.56827e-5 -1 2.70283e-4 0.003796756 -0.9999914 0.001747965 -9.64195e-4 -0.9999991 0.001010894 -9.5471e-4 -0.9999994 -6.27372e-4 1.28754e-4 -0.9999996 9.07378e-4 2.50491e-4 -0.9999996 9.152e-4 -7.16865e-4 -0.9999996 7.0812e-4 0 -1 2.50706e-6 0 -1 -2.31006e-6 0 -1 -1.03881e-6 0 -1 6.06476e-7 0 -1 2.07146e-6 0 -1 0 0 -1 9.00715e-7 0 -1 3.56724e-6 0 -1 -1.79421e-6 0 -1 -3.028e-6 0 -1 -1.87836e-6 0 -1 -1.96907e-6 0 -1 4.16113e-6 0 -1 -6.20854e-6 0 -1 1.59384e-6 0 -1 -7.89949e-6 0 -1 2.52046e-6 0 -1 -3.0619e-6 0 -1 7.15837e-6 0 -1 -7.49861e-6 0 -1 -1.54097e-6 0 -1 -6.17487e-6 0 -1 9.71674e-6 0 -1 -3.05003e-6 0 -1 4.67743e-6 0 -1 7.39016e-6 0 -1 -2.66772e-7 0 -1 1.27516e-6 0 -1 -4.79439e-6 0 -1 2.35102e-6 0 -1 4.54438e-6 0 -1 -2.63439e-6 0 -1 -4.99186e-6 -0.9975661 -0.002483367 -0.06968319 -0.9959961 0.01440113 -0.08822935 -0.9526205 -0.01878678 -0.3035809 -0.9308274 0.02608793 -0.3645271 -0.8732691 -0.01928406 -0.4868565 -0.8124291 0.01740562 -0.5828003 -0.7756331 -0.0139923 -0.631029 -0.6748514 0.01921474 -0.7377035 -0.6029592 -0.02957302 -0.7972238 -0.522746 0.01969027 -0.8522611 -0.3745445 -0.004630327 -0.9271974 -0.3569052 -0.01980447 -0.9339307 -0.1851556 0.02060729 -0.9824932 -0.1210998 -0.01763468 -0.9924837 0.06907385 -0.01080733 -0.9975531 0.03060197 0.01081198 -0.9994732 0.2193169 0.0176233 -0.9754946 0.2820398 -0.02060276 -0.9591816 0.4308539 0.01545292 -0.9022895 0.4720107 -0.01164525 -0.8815159 0.6148774 0.01575875 -0.7884653 0.6497567 -0.01918822 -0.7599 0.8221553 -0.006834924 -0.5692222 0.8048837 0.01691937 -0.5931915 0.9197313 0.001980602 -0.3925435 0.9143397 -0.01020497 -0.4048194 0.9792168 0.02419978 -0.2013676 0.9903825 -0.02550673 -0.1359853 0.9974077 0.01851177 0.06953573 0.9972081 0.01539152 0.07306963 0.9691091 -0.02453941 0.2454087 0.9360698 0.03325343 0.3502393 0.8940956 -0.02026951 0.4474173 0.7979215 -0.005681216 0.6027346 0.8161799 0.01597243 0.5775772 0.6435764 -0.01001292 0.7653164 0.6606792 0.005676746 0.750647 0.5130174 0.01297664 0.8582803 0.4567902 -0.0255621 0.8892072 0.3095335 0.02842932 0.9504635 0.2071644 -0.02525055 0.9779802 0.09610086 0.02278232 0.9951109 -0.0156179 -0.02661436 0.9995238 -0.1516288 0.02836424 0.9880305 -0.2620565 -0.03190308 0.9645251 -0.3857752 0.03318816 0.9219957 -0.5132634 -0.02958047 0.8577212 -0.6057196 0.02560979 0.7952661 -0.6913305 -0.02412271 0.722136 -0.7834395 0.03104931 0.620692 -0.8345012 -0.0208615 0.5506111 -0.920942 0.005885183 0.3896553 -0.921765 0.007810115 0.3876703 -0.9854009 -0.001022696 0.1702467 -0.9856709 -0.002479851 0.1686618 0 -1 -9.4302e-6 0 -1 5.32927e-6 0 -1 6.01726e-6 0 -1 -2.18349e-6 0 -1 3.77688e-6 0 -1 5.0052e-6 0 -1 -1.48392e-5 0 -1 -2.4408e-6 0 -1 3.36879e-6 0 -1 -1.7325e-6 0 -1 -1.8985e-6 0 -1 5.37292e-6 0 -1 -1.90464e-6 0 -1 -2.99512e-6 0 -1 4.53631e-6 0 -1 1.09818e-6 0 -1 -6.74006e-6 0 -1 -4.69832e-6 0 -1 7.24084e-7 0 -1 8.24188e-6 0 -1 1.08746e-6 0 -1 1.18085e-6 0 -1 -5.55534e-6 0 -1 5.68908e-6 0 -1 1.45111e-6 0 -1 -3.88568e-6 0 -1 -2.69402e-6 -0.9964704 0.01902502 -0.08176034 -0.9868152 -0.02025246 -0.1605787 -0.9605224 0.01828509 -0.2776017 -0.927154 -0.02526307 -0.3738282 -0.8781365 0.03271239 -0.4772906 -0.7962195 -0.03271096 -0.604123 -0.7160651 0.02956908 -0.697407 -0.6480772 -0.01921683 -0.7613322 -0.5296831 0.0139932 -0.8480802 -0.477255 -0.01741045 -0.8785925 -0.3744836 0.01928126 -0.9270331 -0.243511 -0.02692776 -0.9695243 -0.1851706 0.01626193 -0.9825718 0.04414254 -0.01547086 -0.9989055 0.0306034 -0.004049897 -0.9995234 0.2193159 0.01762443 -0.9754947 0.2820461 -0.02060091 -0.9591796 0.4308521 0.01545399 -0.9022904 0.4720113 -0.01164644 -0.8815157 0.6148725 0.0157569 -0.7884691 0.6497579 -0.01919609 -0.7598989 0.8221573 -0.006837069 -0.5692193 0.8048856 0.01691752 -0.593189 0.9121901 0.001161754 -0.4097656 0.9143793 0.004904568 -0.4048287 0.9756758 -0.005465865 -0.2191506 0.9745073 -0.00964576 -0.2241482 0.9987786 0.0199688 -0.04519516 0.9994877 -0.02374017 0.02146625 0.9752939 0.001156449 0.2209085 0.9793947 0.01501524 0.2013965 0.9252669 -0.006089448 0.3792678 0.9109563 0.01595658 0.4121944 0.8264742 -0.02305805 0.5625024 0.7913339 0.01966834 0.611068 0.6498352 -0.01119041 0.7599929 0.6541991 -0.006674766 0.7562929 0.5130289 0.01297914 0.8582733 0.4567834 -0.02556353 0.8892107 0.30954 0.02842807 0.9504614 0.2071644 -0.02525126 0.9779802 0.09610122 0.02278351 0.9951108 -0.01561796 -0.02661442 0.9995238 -0.162357 0.03273361 0.986189 -0.262043 -0.03426271 0.9644478 -0.4329649 0.03417313 0.9007629 -0.5133186 -0.02547812 0.8578199 -0.6401504 0.0179218 0.7680406 -0.6836324 -0.01308321 0.7297093 -0.7749442 0.01195788 0.6319166 -0.8198412 -0.02301555 0.5721285 -0.8751972 0.02610766 0.4830615 -0.9466196 -0.02357804 0.3214897 -0.9572163 0.002683222 0.289361 -0.9937551 0.00780493 0.1113113 -0.997379 -0.0195102 0.06967437 0 -1 3.46662e-6 0 -1 -2.20628e-6 0 -1 2.3492e-6 0 -1 5.01149e-6 0 -1 -5.64673e-6 0 -1 1.88207e-6 0 -1 3.91004e-6 0 -1 6.31743e-6 0 -1 -3.00259e-6 0 -1 8.69029e-6 0 -1 -2.43415e-6 0 -1 -2.68553e-6 0 -1 -1.68426e-6 0 -1 3.48535e-6 0 -1 -2.0979e-6 0 -1 4.11089e-6 0 -1 -2.19203e-6 0 -1 6.55358e-7 0 -1 1.60263e-6 0 -1 -1.72753e-6 0.04475688 0.01479679 -0.9988884 0.1788265 -0.02522015 -0.9835574 0.3501438 0.02087384 -0.9364634 0.5238825 -0.01813757 -0.8515974 0.606195 0.01010555 -0.7952519 0.7626715 -0.007532954 -0.6467422 0.7835573 0.004098832 -0.6213061 0.9168273 -0.005087554 -0.3992519 0.9377934 0.01340979 -0.3469347 0.9845613 -0.01446056 -0.1744417 0.999789 0.02053844 4.59585e-4 0.9958696 -0.009310722 0.09031748 0.9454561 -0.004135549 0.3257233 0.926576 0.01785886 0.3756833 0.8024451 -0.01525503 0.5965311 0.7424966 0.01255214 0.6697323 0.6041606 -0.01202517 0.7967719 0.5398526 0.01105856 0.841687 0.3029415 -0.01098155 0.952946 0.2782717 5.44602e-4 0.9605023 -8.12681e-4 0.00686711 0.9999762 -0.04889577 -0.009124577 0.9987622 -0.2235301 0.006879568 0.9746727 -0.2858361 -0.007734119 0.9582473 -0.4715778 0.01075339 0.8817589 -0.5209661 -0.01014292 0.8535171 -0.7656473 -0.008591592 0.6432034 -0.7390154 0.006280481 0.6736594 -0.882568 0.01060146 0.4700652 -0.927505 -0.01723951 0.3734133 -0.9767537 0.01608186 0.213761 -0.997655 -0.01212108 0.06736183 -0.9981845 0.01281011 -0.05885308 -0.9848597 -0.01319885 -0.1728502 -0.9327709 0.01182454 -0.3602758 -0.894914 -0.0136643 -0.4460293 -0.8151094 0.01382189 -0.5791423 -0.7136341 -0.01419538 -0.7003748 -0.6401869 0.009492158 -0.7681606 -0.4971579 -0.00911647 -0.8676123 -0.4456799 0.007983386 -0.8951568 -0.2008976 -0.01036673 -0.9795575 -0.1874766 -0.004394769 -0.9822593 0.08624815 0.009043276 -0.9962326 0.1627997 -0.009224355 -0.986616 0.3855822 0.004526495 -0.9226624 0.3760657 0.008897304 -0.9265503 0.6294593 -0.01254212 -0.7769323 0.705914 0.0250737 -0.7078537 0.8256573 -0.01939469 -0.5638386 0.9469218 -0.005079865 -0.321424 0.9287784 0.01408284 -0.370368 0.9998939 -0.01432365 -0.002676963 0.9979649 0.007142007 -0.06336498 0.9795374 0.01467007 0.200727 0.9377289 -0.01765435 0.3469194 0.9031245 0.008635997 0.4292922 0.7759844 -0.003053426 0.6307449 0.7608988 -0.01169055 0.6487653 0.6161408 0.01388669 0.7875136 0.5004013 -0.01764559 0.8656138 0.372483 0.01571154 0.927906 0.1983888 -0.01890844 0.9799411 0.07157802 0.02023458 0.9972298 -0.173166 -0.02048581 0.9846796 -0.2572384 0.01095473 0.966286 -0.4956115 -0.004432976 0.8685331 -0.5067836 -0.0096367 0.8620195 -0.6869296 0.01127392 0.7266365 -0.7656 -0.01472359 0.6431486 -0.8359386 0.01274985 0.548675 -0.9274941 -0.0179128 0.3734086 -0.9604464 0.0129075 0.2781658 -0.9994965 -0.01534348 0.02777504 -0.998786 -0.006897807 0.04877585 -0.9825896 0.01725494 -0.1849867 -0.9287373 -0.01701259 -0.3703479 -0.9103593 0.001326322 -0.4138168 -0.7481229 -7.32677e-4 -0.6635599 -0.7516304 0.001327276 -0.6595833 -0.5790712 -7.34939e-4 -0.8152768 -0.5747934 9.34655e-4 -0.8182981 -0.3677868 9.40801e-4 -0.9299097 -0.3526812 -0.004780411 -0.9357314 -0.1300108 0.005869448 -0.9914953 -0.07790291 -0.008375942 -0.9969258 0.9946128 -0.004690468 -0.1035543 0.9998019 -7.54082e-4 -0.01988953 0.9703534 0.003730714 -0.241662 0.9476727 -0.006251871 -0.3191825 0.8784257 0.007986307 -0.4778124 0.8016703 -0.01236408 -0.5976386 0.661712 0.01621997 -0.7495827 0.4925372 -0.01757377 -0.870114 0.3031507 0.01490163 -0.9528262 0.107496 -0.01377224 -0.9941101 -0.04082459 0.009527325 -0.999121 -0.271143 -0.006339132 -0.9625183 -0.3260047 0.004833281 -0.9453558 -0.5843488 -0.009539663 -0.8114466 -0.6359225 0.006781399 -0.7717233 -0.8441962 0.003024935 -0.5360258 -0.8619228 -0.005031406 -0.5070146 -0.9672314 0.002189576 -0.2538874 -0.9736796 0.008415699 -0.2277662 -0.9998522 -0.009204328 0.01451903 -0.9980071 -0.02347964 0.05857205 -0.9939766 0.009505212 0.1091802 -0.9274466 -0.01730573 0.3735551 -0.9062546 0.03244972 0.4214853 -0.7379532 -0.03608316 0.6738865 -0.6653198 0.04058277 0.7454547 -0.5255605 -0.02886563 0.8502664 -0.391262 0.02784246 0.9198581 -0.2816948 -0.02710646 0.9591211 -0.1022386 0.04152721 0.9938928 -7.43062e-4 -0.03248178 0.999472 0.2866038 -0.003902494 0.9580413 0.2974033 0.009096086 0.9547086 0.5590032 0.0228092 0.8288517 0.6333469 -0.04489856 0.7725645 0.7672782 0.03986907 0.640074 0.8663951 -0.05175012 0.4966704 0.9429403 0.05494177 0.3283978 0.984928 -0.04328024 0.1674627 0.9999482 -0.002099752 0.009974062 0 -1 6.5592e-6 0 -1 -7.76446e-6 0.1857133 -0.982604 -1.66205e-4 -4.15591e-4 -1 -2.60444e-5 7.92093e-4 -0.9999997 -9.65823e-5 0 -1 -3.75144e-6 0 -1 -5.08861e-6 0 -1 -4.08565e-6 0 -1 4.07677e-6 0 -1 5.14305e-6 1.0042e-4 0 -1 -0.008825719 -0.01236003 -0.9998847 -0.9999422 -0.004039883 -0.009973824 -0.9703989 -0.067025 0.2320211 -0.9238274 0.08160912 0.3740094 -0.769451 -0.07049977 0.6348032 -0.6481478 0.0645318 0.7587754 -0.4991621 -0.04058295 0.8655579 -0.3193093 0.02440607 0.9473363 -0.2379403 -0.02368646 0.970991 -0.06706279 0.03339731 0.9971897 0.1081976 -0.05387753 0.9926685 0.2378202 0.03859484 0.9705421 0.4995022 -0.01711016 0.8661437 0.4929159 -0.008738636 0.8700331 0.7446476 3.25584e-4 0.6674577 0.7708026 0.03821754 0.6359269 0.9136211 -0.05736553 0.4024994 0.9718743 0.07541638 0.2230979 0.9975453 -0.03961962 0.05773794 0.9958717 0.003323197 -0.09071195 0.9882888 0.007592439 -0.1524066 0.9747448 -0.005904614 -0.223244 0.8686124 -3.15147e-4 -0.4954921 0.8575012 0.005170524 -0.514456 0.6843173 -0.003576815 -0.7291756 0.6593703 0.002291798 -0.751815 0.4754555 -0.001907169 -0.8797377 0.4589145 0.001482546 -0.8884792 0.2195097 -0.001483798 -0.9756092 0.1765527 0.006460607 -0.98427 -0.02774006 -0.008922755 -0.9995754 -0.1872755 0.01216512 -0.9822322 -0.3448649 -0.01237821 -0.9385707 -0.5093605 0.01047337 -0.8604896 -0.6680758 -0.009193181 -0.7440365 -0.7352371 0.007911205 -0.6777638 -0.8900041 -0.01242476 -0.4557832 -0.9448593 0.01648199 -0.3270618 -0.9898359 -0.00798273 -0.1419904 -0.9999956 -0.001175105 0.002744972 9.0797e-4 -0.9999997 8.86696e-5 -0.01242357 -0.999915 -0.003957808 0.003300249 -0.9999932 0.001667797 0 -1 2.73676e-5 0 -1 -1.03033e-5 0 -1 -2.49464e-5 0 -1 -5.40837e-6 0 -1 -4.35887e-5 0 -1 7.66295e-6 0 -1 7.32944e-7 0 -1 -2.80102e-6 1.21716e-4 -0.004591524 -0.9999895 9.03935e-4 -0.00797677 -0.9999678 -0.9999503 -0.001056253 0.009920537 -0.9746321 -0.006519019 0.2237182 -0.9747756 -0.006692171 0.223087 -0.8701933 0.01167744 0.4925723 -0.781439 -0.01999676 0.6236613 -0.6240313 0.01504683 0.7812546 -0.418807 -0.01049876 0.9080146 -0.3736656 -2.26428e-5 0.9275635 -0.08343887 0.002067983 0.9965108 -0.0660243 -0.002066612 0.9978159 0.2312588 2.34691e-5 0.9728923 0.2625312 0.006899476 0.9648988 0.4934099 -0.01008969 0.8697385 0.5898372 0.01008468 0.8074592 0.7715166 -0.006895124 0.6361718 0.7968093 0.001779735 0.6042282 0.9434913 -0.001904845 0.3313918 0.9421865 -0.002832055 0.335077 0.9937694 0.004567325 0.1113622 0.999417 -0.03222852 0.01127994 0.9974575 -6.96278e-4 0.07126265 0.9886025 0.04158169 -0.1446937 0.9470331 -0.04775172 -0.317566 0.8578354 0.05328166 -0.5111551 0.7859423 -0.05184072 -0.6161229 0.5695696 0.06028664 -0.8197292 0.4563161 -0.04910123 -0.8884621 0.2577334 0.03075748 -0.9657264 0.1161887 -0.04145169 -0.9923618 -0.01406037 0.04003196 -0.9990996 -0.2941499 -0.03850024 -0.9549836 -0.3678152 0.03941321 -0.9290633 -0.6416593 -0.04909795 -0.7654168 -0.7282423 0.05230337 -0.683321 -0.8758091 -0.04893279 -0.4801709 -0.9212404 0.03079187 -0.3877732 -0.9929237 -0.004886627 -0.1186533 -0.9888409 0.02123212 -0.1474555 9.13447e-4 -0.9999996 1.13936e-4 -0.01172989 -0.9999235 -0.003940403 0.002842426 -0.9999948 0.001540422 0 -1 -3.26203e-5 0 -1 2.62784e-5 0 -1 3.07269e-6 0 -1 -9.33254e-6 0 -1 -4.05682e-6 0 -1 -3.91655e-7 0 -1 -7.67816e-6 -6.28232e-4 -0.001057565 0.9999993 -7.01794e-5 -0.003472387 0.999994 0.9890755 0.01858651 -0.1462342 0.9839426 -0.008882761 -0.1782646 0.857277 0.00100255 -0.5148546 0.8660481 -0.02200794 -0.499476 0.6296268 0.04278308 -0.7757188 0.5629087 -0.03642559 -0.8257161 0.2860585 0.01846647 -0.9580343 0.3112766 -0.009899199 -0.9502678 0.02543216 0.02026891 -0.999471 -0.02543294 -0.02026951 -0.999471 -0.3112813 0.009901523 -0.9502663 -0.3103004 0.008779466 -0.9505981 -0.6301796 -0.00878477 -0.7763997 -0.6424102 0.008267521 -0.7663165 -0.8703843 -0.008663475 -0.4922968 -0.878101 0.009654045 -0.4783779 -0.9960281 -0.01017504 -0.08845698 -0.9918032 -0.04790955 -0.1184539 -0.9999731 -6.38774e-4 0.007303237 -0.995549 0.00749886 0.09394794 -0.9433382 -0.006249427 0.3317741 -0.9548375 0.0040012 0.2971019 -0.8382847 -0.006313443 0.5451962 -0.7784811 0.01027202 0.627584 -0.627335 -0.01228928 0.7786526 -0.5382637 0.007668972 0.8427416 -0.3129135 0.002961516 0.949777 -0.2741991 -0.006918787 0.9616481 0.0218327 3.74409e-4 0.9997616 0.06932967 0.01194763 0.9975224 0.3552198 -0.01560801 0.9346525 0.5023019 0.01811075 0.8645026 0.6939339 -0.01206457 0.7199377 0.8087573 0.01195746 0.5880212 0.8675946 -0.006296992 0.4972325 0.9787043 0.003652393 0.2052425 0.9705737 -0.006532728 0.240716 0.9999477 -6.37708e-4 0.01020973 0 -1 6.30807e-6 4.20969e-4 -0.9999999 3.33175e-4 -1.37725e-5 -1 9.18812e-5 0.2240787 -0.9745702 -0.001335918 0 -1 -5.81921e-5 0.002169847 -0.9999976 -4.98907e-4 0 -1 -6.52979e-6 0 -1 2.46461e-6 0 -1 -4.61645e-6 0 -1 2.49928e-6 -1.14739e-4 -1 -1.91201e-4 0 -1 2.46614e-6 0 -1 1.80512e-5 2.48784e-6 -1.962e-4 1 5.47285e-6 -2.33447e-4 1 0.9602181 -0.005546748 -0.2791963 0.9768121 0.005546748 -0.2140266 0.8397055 -0.006630599 -0.5430015 0.6927176 0.007531583 -0.7211697 0.5967485 -0.004053175 -0.8024182 0.2789104 0.004666984 -0.9603058 0.2223948 -0.001997947 -0.9749547 -0.1577966 -9.97111e-4 -0.9874712 -0.2226956 0.006879806 -0.9748638 -0.5426875 -0.007555127 -0.8399007 -0.697636 0.007484018 -0.7164133 -0.8121945 -0.004855632 -0.5833666 -0.9337525 0.005184471 -0.357882 -0.9711531 -0.004537463 -0.2384138 -0.9994498 0.004163146 0.03290653 -0.9941214 -0.002241671 0.1082481 -0.9112898 9.10721e-4 0.4117645 -0.8972705 0.004340708 0.4414601 -0.7096576 -0.006672322 0.7045152 -0.5565484 0.009821236 0.8307572 -0.3574016 -0.007678091 0.9339193 -0.06707161 0.006179869 0.9977291 0.04189449 -0.003858566 0.9991146 0.3255924 0.003241539 0.9455047 0.4290686 -0.004593849 0.9032604 0.590153 0.004581451 0.8072785 0.7515484 -0.005525708 0.6596549 0.8532559 0.006600618 0.5214509 0.9565543 -0.008764028 0.2914226 0.994928 0.007470905 0.1003125 0.9977502 -0.007131934 -0.06666249 0.9150859 0.006480395 -0.4032069 0.8443658 -0.007388651 -0.5357162 0.6680353 0.007319688 -0.7440936 0.4999382 -0.007347404 -0.86603 0.2951414 0.006308913 -0.9554328 0.1240193 -0.004737496 -0.9922685 -0.09071511 0.003689408 -0.9958701 -0.2315041 -0.005267977 -0.9728197 -0.4033098 0.005833923 -0.915045 -0.6553352 -0.00434035 -0.7553257 -0.6920585 8.52938e-4 -0.721841 -0.9184766 -0.001008749 -0.3954742 -0.9078134 -0.004499971 -0.4193503 -0.994106 0.005850613 -0.1082555 -0.9921562 -0.008891642 0.1246876 -0.9647788 0.0058977 0.2629964 -0.7606769 -0.0058645 0.6491042 -0.7335756 -1.08786e-4 0.679608 -0.419108 0.003785431 0.9079285 -0.3343684 -0.005337357 0.9424274 -0.05027675 0.003895521 0.9987277 0.0586422 -0.004543781 0.9982688 0.3103139 0.005499243 0.9506183 0.4489333 -0.0050655 0.893551 0.6552808 0.004676997 0.755371 0.7162705 -0.002433061 0.6978185 0.9184732 0.001197874 0.3954815 0.90785 -0.00228393 0.4192891 0.9991267 0.004445314 0.04154556 0.9950873 0.006054759 -0.09881675 0.9422789 -0.005650222 -0.3347815 0.8782847 0.006233274 -0.4780974 0.6921654 -0.006465613 -0.72171 0.5767301 0.0081169 -0.8168944 0.318323 -0.008172452 -0.9479471 0.05018126 0.008560717 -0.9987035 -0.05864858 -0.003062307 -0.9982741 -0.4933551 0.001450657 -0.8698267 -0.4555069 -0.005536377 -0.890215 -0.782046 0.007997334 -0.6231694 -0.8699499 -0.008890211 -0.4930599 -0.9910822 0.006055355 -0.1331146 -0.9958483 9.24388e-4 -0.09102445 -0.960191 -0.00355947 0.2793219 -0.9370278 0.004156887 0.3492301 -0.7445381 7.65351e-4 0.6675797 -0.7659392 -0.00240916 0.6429085 -0.4563319 -0.001032888 0.889809 -0.4555281 -9.17357e-4 0.890221 -0.05864286 0.003061354 0.9982744 0.05017352 -0.008559405 0.9987039 0.3103279 0.007659673 0.9505988 0.5904097 -0.0077219 0.8070667 0.6552878 0.002164304 0.7553763 0.9215066 -9.72616e-6 0.3883628 0.9148182 0.002527177 0.4038581 0.9994491 -0.00488317 0.03282636 0.9999227 0.00980699 -0.007644116 0.9801596 -0.009320437 -0.197991 0.8861457 0.00790745 -0.4633392 0.7659922 -0.007348716 -0.6428079 0.6108256 0.00579518 -0.7917439 0.4334993 -0.005821406 -0.9011352 0.2628239 0.006635427 -0.964821 0.03311014 -0.006387114 -0.9994313 -0.2226923 0.007457137 -0.9748603 -0.2952963 -5.72606e-4 -0.9554056 -0.6240782 -0.005061686 -0.7813456 -0.691586 0.005670666 -0.7222719 -0.9112716 -0.00170803 -0.4118025 -0.9114329 -0.001748561 -0.411445 -0.9965463 0.001664578 -0.08302372 -0.997827 -1.67751e-4 -0.06588917 -0.9394186 -0.002114832 0.3427657 -0.9214061 0.004829645 0.3885713 -0.6301532 -0.004668653 0.7764568 -0.5636035 0.006437599 0.8260204 -0.1977949 -0.007122576 0.9802176 -0.06709468 0.006720066 0.9977241 0.2950788 -0.005695402 0.955456 0.3256225 -0.001868367 0.9454981 0.5901405 0.00553745 0.8072817 0.7214965 -0.006792306 0.6923849 0.8619993 0.007415294 0.5068553 0.9427724 -0.008906006 0.3333182 0.08196091 0.03793275 0.9959135 0.3391074 -0.008190333 0.940712 0.3628125 -0.0352745 0.9311943 0.6493874 0.03374361 0.7597088 0.7006277 -0.03444385 0.7126953 0.8915835 0.03460443 0.4515324 0.9216694 -0.03529942 0.3863673 0.9931166 0.02667564 0.1140524 0.9993075 -0.03611868 0.008956253 0.9981753 -1.45912e-4 -0.06038224 0.9933893 0.006907463 -0.1145874 0.9374713 -0.01094251 -0.3478904 0.8920497 0.01246505 -0.4517654 0.735494 -0.0124644 -0.6774167 0.6497184 0.01233035 -0.760075 0.4461892 -0.009411215 -0.8948891 0.3391237 0.006381571 -0.9407202 0.2098588 -0.005224585 -0.9777178 0.1098766 0.005469441 -0.9939302 -0.019064 -0.001702487 -0.9998168 -0.1212262 -0.0245738 -0.9923208 -0.07163631 0.03124922 -0.9969412 -0.3466036 -0.04720985 -0.936823 -0.4940408 0.06314289 -0.8671429 -0.6462315 -0.04813539 -0.7616218 -0.7845708 0.04150563 -0.6186487 -0.8597081 -0.03804463 -0.5093671 -0.9502794 0.05031657 -0.307307 -0.9840006 -0.06697928 -0.1650961 -0.990591 0.06841129 0.1185303 -0.9561366 -0.06453359 0.2857243 -0.884937 0.04527807 0.4635046 -0.7711769 -0.03791129 0.6354911 -0.6788096 0.04869121 0.7326983 -0.5059297 -0.07017207 0.8597158 -0.2939328 0.08074861 0.9524092 -0.0752207 -0.07567995 0.9942909 0 -1 5.74204e-6 0 -1 -2.26838e-6 0 -1 -3.7544e-6 0 -1 9.2687e-6 0 -1 -3.57077e-6 0 -1 6.0013e-6 0 -1 8.97916e-6 0 -1 2.49065e-6 0 -1 -9.55543e-6 0 -1 5.01386e-6 0 -1 -8.81957e-6 0 -1 -3.77833e-6 0 -1 -7.22447e-6 0 -1 5.82144e-6 0 -1 9.0174e-6 0 -1 -6.45059e-6 0 -1 7.46661e-6 0 -1 -1.9967e-5 0 -1 -2.91981e-7 0 -1 2.91316e-7 0 -1 1.38566e-5 0 -1 -1.93258e-5 0 -1 -2.25758e-5 0 -1 3.73622e-7 0 -1 2.77882e-7 0 -1 -2.0068e-5 0 -1 -7.65632e-6 0 -1 1.45315e-5 0 -1 1.60079e-6 0 -1 9.86987e-6 0 -1 -4.05003e-7 0 -1 1.38658e-7 0 -1 1.5279e-5 0 -1 -5.11763e-6 0 -1 -1.02141e-5 0 -1 -3.7609e-5 0 -1 1.9249e-7 0 -1 0 0 -1 -2.46841e-6 0 -1 4.51522e-7 0 -1 -2.37042e-7 1 -4.38009e-4 -2.92815e-4 0.9999898 -0.004516661 2.13078e-5 0.02763122 -0.05246835 0.9982402 0.1090883 0.003247261 0.9940268 0.1099431 0.003393471 0.9939321 0.3391087 0.004886388 0.9407346 0.4139848 -0.01256483 0.910197 0.6497213 0.01233232 0.7600726 0.7354972 -0.01246303 0.6774131 0.8920505 0.01246631 0.4517641 0.9374713 -0.01094418 0.3478904 0.9994897 -0.0319333 -8.24668e-4 0.9933888 0.006907522 0.1145907 0.9981725 -1.38907e-4 0.06042999 0.9940438 0.02341496 -0.1064362 0.9478439 -0.02497625 -0.3177552 0.9115851 0.03430098 -0.4096781 0.8400189 -0.03258538 -0.5415779 0.7230134 0.03883844 -0.6897415 0.6372888 -0.03088712 -0.7700059 0.4666581 0.03167045 -0.8838706 0.4052993 -0.01897233 -0.9139873 0.1017806 0.006952941 -0.9947826 0.08800548 0.02356112 -0.9958413 -0.2914131 -0.03032588 -0.9561165 -0.358331 0.0393601 -0.9327647 -0.5938873 -0.03783017 -0.8036583 -0.6794958 0.04706746 -0.7321681 -0.8499404 -0.05003952 -0.5244973 -0.9063646 0.04984903 -0.4195453 -0.9868386 -0.04984927 -0.1538327 -0.9981181 0.04967004 -0.03596192 -0.9692697 -0.04966455 0.2409354 -0.9342273 0.04947537 0.3532303 -0.7999841 -0.04948115 0.5979775 -0.724646 0.04929101 0.6873562 -0.5339118 -0.03778237 0.8446957 -0.4330511 0.02576339 0.901001 -0.3011738 -0.02298349 0.9532924 -0.1725085 0.04013919 0.9841898 0 -1 -6.07249e-6 0 -1 -5.09822e-6 0 -1 2.42234e-6 0 -1 -1.06323e-5 0 -1 1.65409e-5 0 -1 -1.25336e-6 0 -1 1.00829e-5 0 -1 -4.90651e-6 0 -1 2.49046e-6 0 -1 -8.3777e-6 0 -1 5.17746e-7 0 -1 -1.44291e-5 0.04197084 -0.05903959 0.997373 0.2460646 0.03910791 0.9684643 0.3733568 -0.03723418 0.9269404 0.5276547 0.04571247 0.8482281 0.6854569 -0.05391865 0.726114 0.7958605 0.04974609 0.6034331 0.90679 -0.05803507 0.4175688 0.9624391 0.07049357 0.2621862 0.9973743 -0.07049494 -0.01658052 0.9777668 0.07104992 -0.1972919 0.9161385 -0.06388241 -0.3957392 0.8007872 0.06386917 -0.595534 0.6790381 -0.05490517 -0.732047 0.5134172 0.05952757 -0.856072 0.3642277 -0.06096202 -0.9293126 0.1269148 0.03800719 -0.9911853 -0.02744746 -0.04674929 -0.9985295 -0.08475089 -0.004018664 -0.9963942 -0.1424912 0.006787359 -0.9897729 -0.3850857 0.003734171 -0.9228733 -0.4511564 -0.01332134 -0.8923455 -0.6864157 0.01234936 -0.7271046 -0.7681978 -0.01247966 -0.640091 -0.9098501 0.01173502 -0.4147713 -0.9510474 -0.009589612 -0.3088965 -0.9986856 -0.04824799 0.01729941 -0.994323 0.005833387 -0.1062445 -0.9954036 0.004659116 -0.09565579 -0.9753976 0.06381809 0.211014 -0.9206808 -0.05821472 0.3859509 -0.8143483 0.05803143 0.577468 -0.699858 -0.0583657 0.7118934 -0.5296484 0.0581538 0.8462214 -0.3622846 -0.06389856 0.9298747 -0.1548211 0.06912243 0.9855214 0 -1 -6.07054e-6 0 -1 5.05623e-6 0 -1 -1.44378e-5 0 -1 -2.77647e-6 0 -1 1.79312e-6 0 -1 8.53121e-6 0 -1 1.44133e-5 0 -1 -7.58139e-6 0 -1 9.46078e-6 0 -1 4.31858e-6 0 -1 2.6802e-6 0 -1 -9.96615e-6 0 -1 -8.15077e-6 0 -1 -4.68095e-6 0 -1 1.0069e-5 -0.9999821 -0.005994439 7.75157e-5 -0.9999993 -0.001186549 -2.92813e-4 0.172506 0.04013448 0.9841905 0.340934 -0.04304856 0.9391012 0.4330186 0.02887004 0.9009226 0.6967369 -0.02705895 0.7168163 0.7254284 0.01754838 0.6880739 0.9236378 -0.0174427 0.3828697 0.935235 0.01716434 0.3536115 0.9998402 -0.01708215 -0.005281805 0.9992105 0.01680356 -0.03600394 0.9291819 -0.01442706 -0.3693414 0.906962 0.0340926 -0.4198306 0.7784938 -0.04248815 -0.6262126 0.666521 0.06425297 -0.7427121 0.4884369 -0.06977546 -0.869805 0.295695 0.06966423 -0.952739 0.09687423 -0.05418765 -0.9938205 -0.1046236 0.04963064 -0.9932727 -0.2164698 -0.02744394 -0.9759035 -0.4799296 0.01277655 -0.8772141 -0.4668898 -0.003747344 -0.8843076 -0.7118807 0.01759982 -0.7020798 -0.7608599 -0.03734183 -0.647841 -0.8823196 0.04289358 -0.4686922 -0.9360188 -0.0459308 -0.3489403 -0.9920916 0.02352595 -0.123292 -0.9977324 -0.01056581 -0.06647276 -0.9991375 -0.006750822 -0.04097497 -0.9834387 0.001068949 0.1812382 -0.9771862 0.009231328 0.212184 -0.8546609 -0.00874865 0.519113 -0.8157031 0.008575618 0.5784073 -0.5875099 -0.008531153 0.809172 -0.5305591 0.008357346 0.8476068 -0.2587292 -0.006767213 0.9659263 -0.17515 0.008539319 0.9845048 0.005534291 -0.03726118 0.9992904 -0.09401535 0.001038491 0.9955703 0 -1 7.80817e-6 0 -1 -1.26786e-5 0 -1 -1.0023e-5 0 -1 -7.10407e-6 0 -1 1.22911e-5 0 -1 -8.81613e-6 0 -1 5.82011e-6 0 -1 1.00923e-5 0 -1 9.33108e-6 0 -1 -5.38451e-6 0 -1 4.62105e-6 0 -1 -9.98754e-6 0 -1 1.2283e-5 0 -1 -5.16406e-6 0 -1 5.003e-6 0 -1 -8.1696e-6 0 -1 -5.25699e-6 0 -1 3.0153e-6 0 -1 -1.17269e-5 0 -1 4.71029e-6 0 -1 -5.59477e-6 0 0 -1 -2.53318e-5 -1 -3.27021e-4 0 -1 -3.16438e-4 0.0206691 2.85748e-4 0.9997864 0.1125719 -0.004762172 0.9936322 0.2893803 0.005809009 0.9571967 0.4016109 -0.009271323 0.9157634 0.6415863 0.005182921 0.7670334 0.6600863 5.61702e-4 0.7511896 0.8437618 -0.00446999 0.5366992 0.8735859 0.002266228 0.4866646 0.9344962 -0.006381094 0.355916 0.9709746 0.003157436 0.2391619 0.9887266 -0.004454314 0.1496666 0.9974479 0.001025497 -0.0713917 0.999522 -0.005125999 -0.03048908 0.9720676 -0.001428723 -0.2346968 0.9616199 0.002722918 -0.274372 0.91516 -0.006103396 -0.4030446 0.8270391 0.0040434 -0.56213 0.7852194 -0.002774 -0.6192114 0.6574689 7.18082e-4 -0.7534814 0.6264938 -0.003375053 -0.7794193 0.4856503 -0.004297196 -0.8741427 0.4237923 0.004525303 -0.9057481 0.1877478 -0.004065096 -0.982209 0.08450573 0.00480771 -0.9964115 -0.004989743 -0.003936827 -0.9999799 -0.2540909 -9.04577e-4 -0.96718 -0.294574 0.004028975 -0.9556202 -0.4641867 -0.007489502 -0.8857057 -0.6228072 0.005171954 -0.7823583 -0.6722634 -0.002880513 -0.7403065 -0.8309239 -0.00532937 -0.5563607 -0.888849 0.006300926 -0.458157 -0.935378 -0.005374968 -0.353609 -0.9885401 -0.00216633 -0.1509438 -0.9969481 0.005590677 -0.0778678 -0.9964814 -0.006873548 0.08353126 -0.9542039 0.002929687 0.299143 -0.9588954 0.005442619 0.2837078 -0.8878003 -0.008176803 0.4601563 -0.7964909 -0.004904925 0.6046307 -0.7253388 0.008134305 0.688344 -0.6281874 -0.005135834 0.7780452 -0.5053759 -0.005711257 0.8628804 -0.4244765 0.002523899 0.9054355 -0.303995 -0.003717601 0.9526665 -0.1951777 0.002099156 0.9807657 -0.08186733 -0.0048514 0.9966315 -0.01730048 -0.9473776 0.3196504 -0.03976058 -0.9961296 0.07838994 -0.1829655 -0.9598214 0.2127594 -0.2620749 -0.9556266 0.1345161 -0.1438747 -0.9895076 -0.01322615 -0.07240945 -0.9962615 -0.04711669 -0.1778528 -0.9696668 -0.1676741 -0.1588715 -0.9520773 -0.2613593 0.4275445 -0.1618311 -0.8893911 -0.01440161 -0.9640779 -0.265229 0.1939119 -0.956174 -0.2193844 0.2163475 -0.9681968 -0.1256535 0.276999 -0.951371 -0.1347779 0.04488039 -0.9989727 -0.006279706 0.2745532 -0.933422 0.2309632 0.1557003 -0.9504939 0.2689214 0.06289184 -0.8187991 0.5706249 0.01046633 -0.9428244 0.3331257 -0.08848571 -0.1904195 0.9777069 -0.07750242 -0.520756 0.8501803 -0.3204393 -0.2532327 0.9127935 -0.2343705 -0.3703474 0.8988401 -0.2224953 -0.4215238 0.8790981 -0.4343212 -0.2317722 0.870429 -0.1008989 -0.7588061 0.6434538 -0.6573982 -0.2265471 0.7186822 -0.5219293 -0.4114112 0.7472153 -0.5010468 -0.4942888 0.7103737 -0.3815777 -0.5883477 0.7129134 -0.5667234 -0.5715761 0.5934014 -0.14475 -0.9000391 0.4110683 -0.315451 -0.775603 0.5467457 -0.7307291 -0.2500799 0.6352126 -0.6213622 -0.5381244 0.5695009 -0.7348278 -0.3840047 0.5590782 -0.3967564 -0.8100507 0.4317434 -0.2034606 -0.9416109 0.2682773 -0.4093529 -0.8039504 0.4313861 -0.8041133 -0.4089721 0.4314439 -0.8287014 -0.3827972 0.408314 -0.6820245 -0.6288933 0.3732771 -0.6384252 -0.7045304 0.3099196 -0.8720891 -0.3871859 0.2992453 -0.4949772 -0.8127313 0.3073524 -0.9656695 -0.259329 0.01519644 -0.88543 -0.4455254 0.1323657 -0.3581163 -0.920717 0.1550257 -0.9559974 -0.283524 -0.075387 -0.8815088 -0.3126335 -0.3538398 -0.9063271 -0.3972633 -0.144059 -0.886776 -0.4114152 -0.2106317 -0.8542486 -0.3365402 -0.3962324 -0.7995383 -0.2069045 -0.5638521 -0.7274612 -0.5350964 -0.4295022 -0.4185123 -0.905292 -0.07275956 -0.7431253 -0.2703478 -0.6121087 -0.6491602 -0.6785795 -0.3436874 -0.6261749 -0.6979229 -0.3475754 -0.6816724 -0.2092771 -0.7010891 -0.6890794 -0.4593003 -0.5605469 -0.5618778 -0.5657826 -0.6034762 -0.377602 -0.9010711 -0.2132781 -0.5438942 -0.3726134 -0.7518898 -0.5125505 -0.7004612 -0.4966349 -0.5096157 -0.5042648 -0.6971434 -0.4424178 -0.2316482 -0.866375 -0.3400451 -0.3292549 -0.8808863 -0.3281459 -0.9175175 -0.2246822 -0.3811879 -0.8036576 -0.4569795 -0.2232638 -0.305577 -0.9256219 -0.364656 -0.5900719 -0.7203064 -0.3651372 -0.5906941 -0.7195522 -0.2277687 -0.3137404 -0.9217855 -0.3007823 -0.8132503 -0.4981507 -0.304611 -0.742215 -0.596933 -0.02265578 -0.2667631 -0.9634958 -0.2328698 -0.8651801 -0.4441118 0.01075029 -0.3073478 -0.9515365 0.1667631 -0.3351473 -0.9272899 0.2300377 -0.1599414 -0.9599487 -0.009746789 -0.9652974 -0.2609715 0.4336377 -0.2438722 -0.8674587 0.3229352 -0.4464308 -0.8345133 0.08670288 -0.9156721 -0.3924632 0.657058 -0.2271883 -0.7187909 0.5404828 -0.3884788 -0.7462993 0.5090549 -0.5060857 -0.696233 0.4006793 -0.5767443 -0.7119145 0.3174452 -0.6954638 -0.6446384 0.5670345 -0.5620144 -0.6021726 0.3190517 -0.7985566 -0.5104051 0.7464332 -0.2530874 -0.6154546 0.7756108 -0.2100848 -0.5952246 0.6890789 -0.4593177 -0.5605334 0.1882711 -0.9115894 -0.3654569 0.5037696 -0.7329767 -0.4571231 0.8619542 -0.2415108 -0.4457663 0.209152 -0.9406219 -0.2673689 0.7237195 -0.5265514 -0.4460648 0.4460257 -0.7855522 -0.4289159 0.4237151 -0.8180865 -0.3888447 0.8449171 -0.390656 -0.3653807 0.6436579 -0.6569315 -0.3926137 0.8930923 -0.3914521 -0.2217014 0.8568643 -0.4170544 -0.3030665 0.955981 -0.2934261 -0.001208722 0.4334273 -0.8777331 -0.2042684 0.8986077 -0.4158091 -0.1400247 0.9487667 -0.3083822 0.06886422 0.8788372 -0.3245425 0.3497392 0.9012992 -0.4072988 0.1475382 0.8732469 -0.330988 0.3576127 0.7964028 -0.2313054 0.5587849 0.4339587 -0.9007492 0.01819491 0.7750817 -0.2558487 0.5777456 0.676392 -0.5367564 0.5043674 0.6824839 -0.6430943 0.3473408 0.7060281 -0.5932227 0.3867961 0.6517524 -0.2118451 0.7282449 0.553531 -0.780134 0.2915382 0.3446299 -0.9340173 0.09403234 0.2439463 -0.9649339 0.09691601 0.6177552 -0.2621052 0.7414037 0.5817594 -0.4232115 0.6945849 0.5994045 -0.5715092 0.5604386 0.4519305 -0.7221727 0.5236654 0.4230208 -0.8284609 0.3670232 0.4344512 -0.2408195 0.8679044 0.4013135 -0.1962219 0.8946756 0.4140668 -0.7762157 0.4754343 0.4113699 -0.5726913 0.7090836 0.3729397 -0.5620066 0.7382849 0.2418413 -0.3313507 0.9119867 0.2611739 -0.8441517 0.4681838 0.1300673 -0.2707099 0.9538338 0.05632311 -0.3328887 0.9412826 0.01261174 -0.4923604 0.8703001 0.1077427 -0.5754529 0.8107068 0.06922173 -0.8147746 0.5756306 -0.2986985 -0.5758631 0.7610262 -0.1611099 -0.7767297 0.6088799 -0.1877557 -0.8247463 0.5334243 -0.864083 -0.4544019 0.2165172 -0.6877118 -0.6895083 0.2272241 -0.7954137 -0.6060641 -0.001835584 -0.6474182 -0.7532834 0.1158184 -0.7954313 -0.6058562 -0.01507478 -0.5086625 -0.8589496 0.05889034 -0.675029 -0.7271273 -0.1249871 -0.1103429 -0.9936081 0.02382522 -0.4751188 -0.8784781 -0.0503835 -0.7062835 -0.6669943 -0.2372387 -0.1672584 -0.5456376 -0.8211603 -0.08252257 -0.6160405 -0.7833799 -0.1140876 -0.8791584 -0.4626713 -0.04026883 -0.727051 -0.6854016 -0.03939944 -0.6914805 -0.7213199 -0.09149348 -0.7823537 -0.6160777 0.2123204 -0.4564794 -0.8640292 0.1717347 -0.5866655 -0.7914106 0.08175516 -0.8302312 -0.5513912 0.2209898 -0.6970788 -0.6820884 0.6384322 -0.736739 -0.2227558 0.6363302 -0.7395125 -0.2195572 0.5443468 -0.8168749 -0.1907933 0.755298 -0.6517627 -0.06877821 0.7976043 -0.5897734 0.1264709 0.5162047 -0.856437 -0.00697124 0.683842 -0.7283543 0.0431292 0.7137713 -0.6992592 0.03958743 0.5085796 -0.8399164 0.1894391 0.2316355 -0.9684613 0.09180313 0.2919437 -0.5980895 0.7463631 0.2252886 -0.5350234 0.8142451 0.2033032 -0.7899062 0.5785464 0.03275805 -0.997708 0.05920898 0.08340346 -0.9734671 0.2130861 -0.003201782 -0.999988 0.003717064 0.002174079 -0.9997175 -0.02366876 -0.003594875 -0.9999922 -0.001639604 -0.001061856 -0.9999781 -0.006536483 0.0041399 -0.9999663 0.007092714 -0.02009606 -0.8261389 0.5631081 -0.1198291 -0.9611087 0.2488195 -0.2384662 -0.9525327 0.1892498 -0.0590592 -0.9982254 0.007620513 -0.8571411 -0.02405434 -0.5145198 -0.314271 -0.949307 0.00707072 -0.06581181 -0.9978144 0.005950033 -0.2415934 -0.9601832 -0.140289 -0.2158116 -0.9582753 -0.1874403 -0.1497224 -0.970979 -0.1865024 -0.006753385 -0.9620643 -0.2727395 0.1074572 -0.966391 -0.2335413 0.1476482 -0.9557859 -0.2543097 0.2234856 -0.9562324 -0.1888753 0.0757488 -0.9970577 -0.01175278 0.2709755 -0.9620498 0.03213375 0.2367935 -0.9714992 -0.01086968 0.2601394 -0.9455177 0.1957648 0.1576854 -0.9701854 0.1840535 0.02715492 -0.836732 0.5469389 0.01473069 -0.9615987 0.2740638 -0.1272841 -0.3132206 0.9411119 -0.02071714 -0.4556176 0.8899345 -0.3214097 -0.2716196 0.9071486 -0.3080268 -0.2906915 0.9058797 -0.4300241 -0.2470787 0.8683499 -0.1228404 -0.6168937 0.7774012 -0.2991774 -0.597802 0.7437242 -0.5184721 -0.412014 0.7492871 -0.3609898 -0.6078587 0.7072442 -0.6134192 -0.3855683 0.6892417 -0.3040991 -0.8318934 0.4641953 -0.3817501 -0.695517 0.6087061 -0.8149167 -0.2335417 0.5304425 -0.172881 -0.8996528 0.4009203 -0.6376896 -0.4187406 0.6465357 -0.5305578 -0.6712949 0.5175633 -0.7092595 -0.3951327 0.583799 -0.5297835 -0.7159454 0.4546996 -0.8656384 -0.252524 0.4323215 -0.4106581 -0.8331519 0.3704295 -0.4547608 -0.8033766 0.38442 -0.9311538 -0.3134373 0.1863055 -0.8505491 -0.4237639 0.3114331 -0.7105796 -0.597501 0.3715767 -0.7239291 -0.5787925 0.3754013 -0.852204 -0.4232648 0.3075634 -0.2677924 -0.9424746 0.2000728 -0.9547803 -0.2971609 0.009485185 -0.939143 -0.3368725 0.06728678 -0.4032836 -0.9025485 0.1508925 -0.9361901 -0.3408094 -0.08600562 -0.9370085 -0.2683126 -0.2236592 -0.874711 -0.3773919 -0.3040658 -0.8474599 -0.3658199 -0.3846915 -0.3979916 -0.9161775 -0.04713392 -0.7429918 -0.2698283 -0.6124997 -0.7350149 -0.3902161 -0.5545129 -0.7608702 -0.4447904 -0.4724808 -0.6280487 -0.746981 -0.218115 -0.6730545 -0.6208592 -0.40191 -0.6713225 -0.2046162 -0.7123612 -0.4896875 -0.8338873 -0.2546334 -0.3380804 -0.9319568 -0.1309897 -0.5253287 -0.7175716 -0.4572975 -0.5590991 -0.5804575 -0.5920113 -0.503152 -0.5328283 -0.6803912 -0.5018478 -0.4432216 -0.7427675 -0.440129 -0.8058732 -0.3960492 -0.43325 -0.8098495 -0.3955232 -0.3653755 -0.2836781 -0.8865819 -0.4103091 -0.387314 -0.8256116 -0.3300266 -0.2818847 -0.9009015 -0.1896569 -0.07839757 -0.9787156 -0.2981608 -0.8174264 -0.4928634 -0.3054913 -0.7380854 -0.6015855 -0.04429858 -0.2831966 -0.9580384 -0.157231 -0.4565119 -0.8757142 -0.1284641 -0.4470218 -0.8852506 -0.1576732 -0.9187405 -0.3620156 0.03482383 -0.2645219 -0.9637508 0.3340243 -0.2637347 -0.9049154 0.1379881 -0.3984551 -0.9067486 -0.1157208 -0.9182131 -0.3788052 0.2731893 -0.3770608 -0.8849818 0.517976 -0.2553531 -0.8163919 0.334756 -0.5780478 -0.7441769 0.04999655 -0.9414331 -0.333473 0.5480614 -0.3849404 -0.7425965 0.3958893 -0.5738729 -0.7168972 0.6380471 -0.4086281 -0.6526248 0.6450287 -0.4228692 -0.6364902 0.8169631 -0.2563593 -0.5165766 0.4494493 -0.7271632 -0.518873 0.2460693 -0.8557065 -0.4552104 0.7056472 -0.4116381 -0.5767289 0.4965949 -0.7005842 -0.512421 0.3667178 -0.8081898 -0.4608117 0.8711453 -0.3278493 -0.3655418 0.8801766 -0.3166866 -0.3535518 0.7193108 -0.586273 -0.3726608 0.7224029 -0.5844701 -0.3694981 0.5805664 -0.7163918 -0.3869436 0.317705 -0.9195862 -0.2311384 0.9476355 -0.3109157 -0.07292866 0.8995474 -0.403942 -0.166269 0.4449033 -0.8688126 -0.2173147 0.9536743 -0.3008006 0.004939138 0.906744 -0.3014385 0.2948735 0.9006699 -0.4177214 0.1195937 0.8845275 -0.418232 0.2066234 0.8733398 -0.2843746 0.3954857 0.737932 -0.3735824 0.5620433 0.7664818 -0.4105553 0.4939129 0.6158537 -0.6877624 0.3843269 0.7089421 -0.5821246 0.398161 0.5400249 -0.8026053 0.253373 0.6071552 -0.3819708 0.6967504 0.6393742 -0.4230563 0.6420468 0.5228032 -0.6825163 0.5107331 0.4897774 -0.4038855 0.7726543 0.5080527 -0.6923721 0.512351 0.4880511 -0.4052882 0.773012 0.3271967 -0.913578 0.2414907 0.3734597 -0.8218816 0.4301611 0.2893395 -0.3097544 0.9057235 0.3681613 -0.6536847 0.661176 0.3684204 -0.6482386 0.6663732 0.2580505 -0.3372756 0.9053481 0.2689893 -0.8384227 0.4740172 0.272248 -0.8031319 0.5299627 0.1259735 -0.3142948 0.9409301 -0.0217694 -0.4556039 0.8899164 0.172599 -0.9213528 0.3483085 0.1283257 -0.6359362 0.760998 0.08072984 -0.7949498 0.60128 0.05240029 -0.9243656 0.3778923 -0.2542803 -0.6250389 0.7380163 -0.1278067 -0.8503851 0.5104024 -0.08489847 -0.9735717 0.2120155 -0.579277 -0.7914375 0.1951026 -0.540315 -0.8178297 0.1980264 -0.7351782 -0.6759479 0.05106425 -0.6761717 -0.733777 0.06605446 -0.7677751 -0.6368118 0.07065582 -0.7949281 -0.5933029 -0.1268105 -0.7672988 -0.6119351 -0.191802 -0.483428 -0.8737536 -0.05340611 -0.6743658 -0.7007924 -0.232639 -0.2172257 -0.670768 -0.7091426 -0.2174577 -0.6707783 -0.7090618 -0.07954573 -0.7680603 -0.6354179 0.04127895 -0.5875343 -0.8081457 -0.0644319 -0.8276578 -0.5575224 0.04368066 -0.6658576 -0.7447991 -0.01894265 -0.9985103 -0.05116981 0.05664134 -0.8911179 -0.450223 0.179485 -0.7570567 -0.6282122 0.1761067 -0.7863309 -0.5921741 0.7806674 -0.6015371 -0.1694455 0.7338414 -0.6379234 -0.233518 0.4765135 -0.8731704 -0.10251 0.482367 -0.8611192 -0.1606112 0.6931554 -0.7206389 -0.01467341 0.7010231 -0.7130212 0.01293879 0.8207139 -0.518386 0.2402181 0.6341232 -0.759935 0.1427819 0.5693728 -0.8033791 0.1743471 0.2200129 -0.5762308 0.7871165 0.03812938 -0.9967836 0.0704897 0.07835572 -0.002771198 0.9969216 0.124327 0.003232002 0.9922361 0.3389441 -0.006524503 0.940784 0.4658447 0.004760384 0.8848537 0.5221678 -0.001886844 0.8528408 0.6695019 -0.006550908 0.7427816 0.7982175 -0.003941059 0.6023566 0.7590789 0.001967251 0.6509957 0.8803636 -0.004110217 0.4742818 0.9252322 0.0040524 0.3793799 0.9609097 -0.005325615 0.276811 0.9980125 -0.001880526 0.06298851 0.9999131 0.005169212 0.01212763 0.9854206 -0.005007982 -0.1700625 0.934497 0.004026234 -0.3559483 0.9270998 7.36708e-4 -0.3748141 0.8310455 -0.007726013 -0.5561509 0.7127078 0.002843618 -0.7014553 0.7105262 0.003251969 -0.7036632 0.5721318 -0.007205545 -0.8201301 0.383796 0.005615353 -0.9234008 0.3148166 -0.004210948 -0.9491432 0.08562809 -0.003766 -0.9963201 0.02250468 0.003693163 -0.99974 -0.1840301 -0.004518091 -0.9829103 -0.2710062 0.005110919 -0.9625641 -0.4787143 -0.005473077 -0.8779537 -0.5447497 -2.12857e-4 -0.8385987 -0.6449677 -0.006021976 -0.7641861 -0.7099393 0.002125322 -0.7042597 -0.8589024 -0.005390048 -0.5121111 -0.8929814 0.003787934 -0.4500776 -0.9680717 -0.008193373 -0.2505397 -0.9933144 0.004713952 -0.1153448 -0.9997121 -0.005567789 0.02334088 -0.9880999 0.002533078 0.1537933 -0.9751421 -0.004694342 0.2215311 -0.9194325 -0.003276884 0.3932344 -0.8941188 0.004033505 0.4478119 -0.8090389 -0.006300926 0.5877214 -0.7382435 0.001070857 0.6745336 -0.658261 -0.006623268 0.7527608 -0.5494989 0.001291275 0.8354935 -0.5054747 -0.003569781 0.8628342 -0.3054293 -0.00194931 0.9522128 -0.2455717 0.005332529 0.9693638 -0.07811897 -0.007161855 0.9969183 -2.8406e-4 -0.9999952 0.003126919 -6.73962e-4 -0.9999576 -0.009183585 -7.16978e-4 -0.9999998 3.58708e-4 4.90248e-4 -0.9999988 0.001508355 0.1223742 -0.6753534 -0.7272706 0.1252413 -0.6809553 -0.7215362 0.09507977 -0.7610886 -0.6416417 0.1005853 -0.8073538 -0.5814315 0.07206362 -0.911772 -0.4043249 0.101838 -0.8057923 -0.5833762 0.1863305 -0.6579295 -0.7296642 0.07262516 -0.7657432 -0.6390328 0.1924734 -0.6751669 -0.7121121 0.04008603 -0.957775 -0.284711 0.1667067 -0.7537127 -0.6357092 0.08511394 -0.8668397 -0.4912685 0.08972477 -0.9318454 -0.3515874 0.1722558 -0.8085544 -0.5626436 0.04144811 -0.9793593 -0.1978319 0.01871985 -0.9913477 -0.129921 0.1375348 -0.8611267 -0.4894334 0.133511 -0.9128201 -0.3859203 0.2724252 -0.7106567 -0.6486538 0.2434185 -0.6649925 -0.7060683 0.2174457 -0.796494 -0.564194 0.2720972 -0.7152889 -0.6436808 0.07981592 -0.9422216 -0.325343 0.07394737 -0.9679278 -0.2400993 0.03109562 -0.9936734 -0.1079179 0.3534938 -0.5908859 -0.725187 0.1945688 -0.8683954 -0.456106 0.3188679 -0.698535 -0.6406028 0.2442962 -0.7732033 -0.5852147 0.3050438 -0.7165209 -0.6273326 0.1945919 -0.8669495 -0.4588382 0.2525125 -0.8087915 -0.5311252 0.08651947 -0.951856 -0.2940828 0.3013136 -0.7753359 -0.5550357 0.4061661 -0.61563 -0.6752992 0.1328382 -0.9368431 -0.3235414 0.06101489 -0.9875132 -0.145241 0.1284713 -0.9526763 -0.2755052 0.4028113 -0.6748509 -0.6183198 0.05835866 -0.9891532 -0.1347979 0.2416471 -0.8668929 -0.4360084 0.244776 -0.8546859 -0.4578174 0.3750521 -0.7109212 -0.5949175 0.4627099 -0.6311899 -0.6224941 0.3090962 -0.7954936 -0.5212001 0.1535674 -0.9470856 -0.281862 0.1819138 -0.9382173 -0.2943736 0.3655766 -0.7619457 -0.5345957 0.494427 -0.6483659 -0.5789331 0.2827169 -0.8660466 -0.4123527 0.1994214 -0.9415089 -0.2716472 0.4368634 -0.6667773 -0.6037868 0.2873575 -0.8631461 -0.4152163 0.4841938 -0.6616717 -0.572492 0.3738635 -0.7977205 -0.4731471 0.2062601 -0.9318475 -0.2985251 0.4375429 -0.733635 -0.5199385 0.3915864 -0.7859795 -0.4784314 0.1387302 -0.9617733 -0.236106 0.06990426 -0.9932219 -0.09286415 0.4738689 -0.708114 -0.5234719 0.3337116 -0.8618648 -0.3818711 0.2166858 -0.9337301 -0.2849479 0.3050546 -0.8805035 -0.3628436 0.1065465 -0.9844558 -0.1396235 0.3981275 -0.8207632 -0.4096856 0.543713 -0.6182286 -0.5675999 0.2151869 -0.94728 -0.2373927 0.2262132 -0.9259858 -0.302288 0.4793497 -0.7593576 -0.4399998 0.5413237 -0.6854092 -0.4870144 0.4236772 -0.8052445 -0.4148242 0.5932045 -0.6758973 -0.4373459 0.3056529 -0.9036188 -0.3000823 0.425337 -0.800216 -0.4227797 0.6029868 -0.6502155 -0.462198 0.525971 -0.7314423 -0.4339893 0.2320535 -0.9415683 -0.2441321 0.3694702 -0.8771246 -0.3068295 0.4761086 -0.7991169 -0.3670598 0.1482844 -0.9788367 -0.141034 0.06954163 -0.9941133 -0.08308333 0.3821816 -0.8632974 -0.3296286 0.6471388 -0.6242976 -0.4375661 0.4452791 -0.8478366 -0.287923 0.272897 -0.9324201 -0.2368966 0.09836727 -0.9914792 -0.08539903 0.5769879 -0.7329607 -0.3603522 0.2185813 -0.961197 -0.1682932 0.6653243 -0.644329 -0.3770726 0.6217305 -0.7085674 -0.3337418 0.4843297 -0.812093 -0.3254689 0.09678184 -0.9920843 -0.08001196 0.4400665 -0.8509506 -0.2867482 0.268602 -0.9455144 -0.1839988 0.1118323 -0.990369 -0.08162546 0.6744503 -0.6635608 -0.3237344 0.4556626 -0.8603826 -0.2282833 0.5733186 -0.7686657 -0.283653 0.5592207 -0.7840253 -0.2694005 0.7319921 -0.6117944 -0.2998253 0.3381328 -0.9231659 -0.1828418 0.4716537 -0.84777 -0.2425464 0.6499014 -0.7027016 -0.2895489 0.345404 -0.9174647 -0.1973697 0.5990581 -0.7653989 -0.235147 0.2063924 -0.9695436 -0.1318609 0.1030061 -0.9931503 -0.05515718 0.1101747 -0.9918425 -0.06411087 0.5916761 -0.7746291 -0.2233143 0.7044914 -0.661475 -0.2571825 0.6019621 -0.7667484 -0.2230215 0.6984295 -0.6880772 -0.19684 0.7133084 -0.6673035 -0.2142364 0.6339449 -0.7511339 -0.1841516 0.5641143 -0.8021678 -0.1957086 0.750636 -0.6393914 -0.1665061 0.7372558 -0.6624532 -0.1327018 0.6250078 -0.7665781 -0.1473881 0.6211919 -0.7704382 -0.1433379 0.743923 -0.6557322 -0.1288175 0.4711296 -0.8753141 -0.1089143 0.489644 -0.8635808 -0.1203204 0.3378808 -0.9384295 -0.07201921 0.3503001 -0.9342536 -0.06678462 0.667163 -0.7354675 -0.1182418 0.6137481 -0.7855504 -0.07889169 0.7654021 -0.6403909 -0.06371116 0.7534398 -0.6550793 -0.05656576 0.5006918 -0.8637489 -0.05697113 0.6248306 -0.7790963 -0.05095082 0.4878432 -0.8708644 -0.0600357 0.3032835 -0.9508821 -0.06198751 0.3245666 -0.9450395 -0.03945827 0.1299186 -0.9912082 -0.02505236 0.1133825 -0.9934651 -0.01310443 0.6639381 -0.7477865 -0.001261055 0.7313094 -0.6814395 0.02875328 0.7628021 -0.6463651 0.01857984 0.6611116 -0.7502743 0.004477977 0.6758544 -0.7368478 0.01662063 0.4791663 -0.8765897 -0.04461437 0.3869273 -0.9219235 -0.01855504 0.1479423 -0.9889733 -0.006712257 0.533267 -0.8457298 0.01917463 0.01283651 -0.9999175 -5.54141e-4 0.5112217 -0.8594016 0.009017169 0.8162667 -0.5697469 0.09537976 0.1950852 -0.9807579 -0.00747919 0.3266169 -0.9450932 0.0109694 0.6702923 -0.7372754 0.08445864 0.6722179 -0.7353456 0.08596539 -0.02247971 -0.9997256 -0.006583452 0.5165604 -0.8537116 0.06589245 0.4818409 -0.8730872 0.07448661 0.3454519 -0.9382079 0.0207144 0.6937808 -0.7008749 0.1656579 0.7262339 -0.6684989 0.1602922 0.288583 -0.9572044 0.02190297 0.1021906 -0.9947577 0.003768026 0.1299465 -0.9914056 0.01512986 0.6255694 -0.7647461 0.1543582 0.4542925 -0.888639 0.06276243 0.2503744 -0.9662923 0.05993312 0.5454022 -0.8282182 0.1288065 0.3860383 -0.918867 0.08159697 0.5886416 -0.7993341 0.1206901 0.7493688 -0.6097504 0.2581684 0.1316919 -0.9908559 0.02935606 0.6455227 -0.7349407 0.2077564 0.5692531 -0.7957704 0.2066413 0.3723301 -0.9175922 0.1392659 0.4541063 -0.8812299 0.1312299 0.6857867 -0.6618313 0.3027805 0.6799107 -0.6679971 0.3024919 0.3706355 -0.9185811 0.1372526 0.1015369 -0.9942747 0.03328943 0.5845974 -0.7668388 0.2649607 0.5146486 -0.8280007 0.2226023 0.384747 -0.9124902 0.139038 0.3479054 -0.93136 0.1073806 0.1088631 -0.9934745 0.03401905 0.2810016 -0.9551423 0.09349524 0.6189932 -0.6876879 0.3793848 0.6014373 -0.743332 0.2927983 0.6663055 -0.6435431 0.3766822 0.4492534 -0.8616361 0.2361246 0.1243568 -0.9906123 0.056768 0.5614374 -0.7687979 0.3061668 0.4102351 -0.8879107 0.2081393 0.6337568 -0.6601183 0.4032324 0.3023113 -0.9416478 0.1480118 0.2392386 -0.9624683 0.1281396 0.5430403 -0.7556229 0.3662533 0.532916 -0.7724868 0.3453475 0.4149049 -0.8856695 0.2084311 0.3922432 -0.880673 0.2656323 0.6068555 -0.6386268 0.4731621 0.218841 -0.9689661 0.1149504 0.2615112 -0.951387 0.1627106 0.0831809 -0.9949728 0.05576831 0.4376469 -0.8555198 0.2766788 0.5653589 -0.6625847 0.4912747 0.4959644 -0.772345 0.3968662 0.5243279 -0.7093313 0.4710939 0.4891832 -0.7832087 0.383776 0.2952541 -0.9313111 0.2132715 0.3769256 -0.8748601 0.3042154 0.1324076 -0.9864204 0.09717541 0.5424937 -0.6563475 0.5243175 0.3967688 -0.84561 0.3570972 0.4411743 -0.7862504 0.4326378 0.5613641 -0.6366181 0.5287606 0.4108032 -0.8373149 0.3607556 0.3613594 -0.876922 0.3169029 0.2223513 -0.9535553 0.2032051 0.4681861 -0.6800274 0.5642379 0.4712925 -0.6769479 0.5653538 0.3986532 -0.7956659 0.4560607 0.1480483 -0.9807601 0.1272455 0.2983769 -0.9043438 0.3051782 0.3946174 -0.7981562 0.4552187 0.4572892 -0.6385033 0.6190317 0.2025678 -0.950518 0.2355459 0.2469658 -0.9328367 0.2623428 0.3100705 -0.8864158 0.3436908 0.1119749 -0.9865131 0.1193883 0.4239248 -0.7153663 0.5554628 0.3996766 -0.6561102 0.6401391 0.1171612 -0.9847139 0.1288867 0.3999956 -0.6455544 0.6505867 0.3489569 -0.7889259 0.5057916 0.2965031 -0.8630267 0.4089878 0.3314771 -0.7726399 0.5414339 0.3278536 -0.6646935 0.671338 0.2531932 -0.8921216 0.3741824 0.1783649 -0.9544346 0.23925 0.24936 -0.8624045 0.4405431 0.3171267 -0.7438861 0.5882723 0.1084635 -0.9791619 0.1716905 0.3284437 -0.6546839 0.6808185 0.1915752 -0.9307916 0.3113293 0.05649715 -0.9956222 0.07446086 0.2946017 -0.7589211 0.5807313 0.249114 -0.8625326 0.4404314 0.1087714 -0.979062 0.1720653 0.2097505 -0.8478198 0.4870383 0.173272 -0.9384005 0.2989674 0.2568457 -0.7037329 0.6624126 0.2481487 -0.7879014 0.56359 0.3111912 -0.6336496 0.7082713 0.1955513 -0.8552879 0.4798359 0.06646937 -0.9906128 0.1194494 0.2131912 -0.6770846 0.704348 0.214348 -0.67537 0.7056419 0.1910607 -0.8925846 0.4083977 0.1295099 -0.9397935 0.3162522 0.1925151 -0.8336116 0.5177159 0.1891968 -0.7789884 0.5978141 0.08877229 -0.9789705 0.1836749 0.1841174 -0.784399 0.5922998 0.1264169 -0.9250302 0.3582429 0.04849725 -0.9920374 0.1162318 0.1503152 -0.8704518 0.4687419 0.1015657 -0.9588696 0.2650539 0.1546836 -0.6266313 0.7638104 0.04465347 -0.9928977 0.1102734 0.06126636 -0.9685372 0.2412101 0.1184642 -0.6691961 0.7335823 0.1362715 -0.7615745 0.6335885 0.1235452 -0.777434 0.6167114 0.05831527 -0.9701758 0.2352834 0.1141791 -0.9060189 0.4075451 0.105951 -0.8601407 0.4989312 0.1140605 -0.8523988 0.5103005 0.07494235 -0.6122639 0.7870937 0.06273812 -0.9392634 0.337414 0.03542077 -0.9909191 0.1297107 0.0352649 -0.9909527 0.1294962 0.05683666 -0.7610917 0.6461495 0.07568776 -0.7202473 0.6895762 0.02695083 -0.6756522 0.7367278 0.05742686 -0.8287193 0.5567104 0.04197484 -0.8607667 0.5072662 0.00528866 -0.6204235 0.7842493 0.04912948 -0.902539 0.4277965 0.01940947 -0.9901199 0.1388738 0.004266381 -0.7521739 0.6589511 0.03402543 -0.9350942 0.3527624 0.0366761 -0.9322728 0.3598922 0.02739983 -0.9568004 0.2894518 0.02320015 -0.9818117 0.1884351 0.004163563 -0.9940084 0.1092249 -0.01620936 -0.7271162 0.6863232 -0.01015424 -0.878022 0.4785128 -0.06981718 -0.6593441 0.7485926 -0.02496373 -0.8292344 0.5583433 -0.06187921 -0.6372681 0.7681539 0.003825008 -0.950671 0.3101777 -0.007811963 -0.8719745 0.489489 -0.07010638 -0.7714198 0.6324529 -0.1567835 -0.6845593 0.7118971 -0.1021228 -0.7457893 0.6583079 -0.1483351 -0.6593344 0.7370719 -0.07622516 -0.8308467 0.5512563 -0.08058202 -0.8502675 0.520146 -0.04319691 -0.9207002 0.3878729 -0.1106025 -0.7584186 0.6423149 -0.02197307 -0.955277 0.2948951 -0.04209017 -0.9172933 0.3959819 -0.02091592 -0.9817417 0.1890652 -0.170876 -0.6680964 0.7241882 -0.001328706 -0.9958388 0.09112292 -0.1762157 -0.7338621 0.6560447 -0.1434718 -0.8019057 0.5799684 -0.1019549 -0.8883488 0.4477072 -0.140927 -0.8292356 0.5408402 -0.06362891 -0.9395525 0.336441 -0.01837539 -0.9912656 0.1305949 -0.1011685 -0.8847754 0.4549038 -0.05841702 -0.9709036 0.2322361 -0.2516199 -0.5714206 0.7811313 -0.03262227 -0.9911836 0.1284173 -0.2442373 -0.7199996 0.6495758 -0.2040067 -0.7763181 0.5964156 -0.1764683 -0.8597773 0.4792097 -0.2783491 -0.680878 0.6774415 -0.1148007 -0.9425552 0.3137047 -0.1229844 -0.9094727 0.3971579 -0.3304041 -0.646171 0.6879653 -0.2172291 -0.8186143 0.5316789 -0.0680803 -0.965673 0.2506811 -0.2895758 -0.7121398 0.6395332 -0.0312792 -0.9966416 0.07567858 -0.1959748 -0.8962098 0.3979976 -0.0655784 -0.9762087 0.2066789 -0.2759224 -0.7860336 0.553189 -0.3867042 -0.6332553 0.6704086 -0.1995175 -0.8740345 0.4430084 -0.2770691 -0.79282 0.5428344 -0.4110977 -0.6372669 0.6518356 -0.1517671 -0.926394 0.3446173 -0.4093572 -0.6842247 0.6035422 -0.08773392 -0.9814551 0.1704371 -0.3132836 -0.7781877 0.5443137 -0.508087 -0.4338837 0.744038 -0.273344 -0.8553826 0.4400042 -0.4490303 -0.6408016 0.6226919 -0.2378883 -0.8835346 0.4034549 -0.3258082 -0.8056643 0.4947264 -0.0963993 -0.9791273 0.1789332 -0.1704253 -0.9476161 0.2701467 -0.0162186 -0.9994626 0.02848893 -0.3980409 -0.7682343 0.5013775 -0.4973171 -0.622553 0.6042381 -0.1963297 -0.9358971 0.2924914 -0.4042222 -0.7772567 0.4821581 -0.2549285 -0.8975372 0.3597755 -0.1145746 -0.9789132 0.1691201 -0.4957299 -0.6782904 0.5423782 -0.09465247 -0.9877243 0.1242647 -0.3451571 -0.8555555 0.3858644 -0.4472965 -0.7533813 0.4820194 -0.2684292 -0.9070976 0.324222 -0.5580829 -0.6329164 0.5366194 -0.1910422 -0.9549134 0.2272516 -0.3455572 -0.855017 0.3866991 -0.4479659 -0.770893 0.4528251 -0.5513921 -0.676251 0.4885195 -0.2496122 -0.9313051 0.2652633 -0.4997807 -0.7412533 0.4480656 -0.4081499 -0.8370512 0.3643609 -0.1165305 -0.9852327 0.1254477 -0.5920835 -0.6389884 0.4910507 -0.3726018 -0.8612433 0.3455837 -0.5003158 -0.7802259 0.3754087 -0.3253908 -0.901109 0.2865718 -0.1336826 -0.981759 0.1351982 -0.587329 -0.6917693 0.420119 -0.225588 -0.9501179 0.2153741 -0.6675546 -0.637785 0.3841892 -0.4857737 -0.7909148 0.3721261 -0.4186072 -0.8600068 0.2918156 -0.3491468 -0.8990979 0.2640447 -0.303047 -0.9284129 0.2149698 -0.6166943 -0.6899187 0.3790784 -0.2214196 -0.9608215 0.1667203 -0.6606916 -0.6679527 0.3425287 -0.6433109 -0.6925788 0.3263215 -0.5003549 -0.8145827 0.2934283 -0.1550099 -0.9818726 0.1090787 -0.5000649 -0.8147723 0.2933961 -0.1024692 -0.9916011 0.07891374 -0.01819992 -0.9997642 0.01184791 -0.5955787 -0.7415743 0.3087939 -0.3725719 -0.9017949 0.2189893 -0.3589115 -0.9113151 0.2017113 -0.6356979 -0.7127683 0.2963946 -0.7617835 -0.5703608 0.3072043 -0.5324513 -0.8119714 0.2391611 -0.5101757 -0.8266791 0.237324 -0.1133119 -0.9919414 0.05668026 -0.6166818 -0.7495657 0.2405303 -0.2169813 -0.969859 0.1108726 -0.4410968 -0.8739696 0.2039875 -0.3619529 -0.9209436 0.1444063 -0.6868353 -0.6966639 0.2071633 -0.7175569 -0.6629616 0.2135279 -0.5807077 -0.7888041 0.2014114 -0.3012107 -0.9449399 0.1279091 -0.7023637 -0.678524 0.2151522 -0.5329294 -0.8274112 0.1771359 -0.1076744 -0.992851 0.05151015 -0.526257 -0.8317865 0.1765927 -0.3098252 -0.9415004 0.1326107 -0.3857023 -0.9143533 0.1232551 -0.1294412 -0.9901522 0.05332684 -0.7356516 -0.666626 0.1201113 -0.6485623 -0.7476429 0.1428186 -0.7522616 -0.6459537 0.1297938 -0.4987893 -0.8580631 0.1222172 -0.1533594 -0.9875655 0.03457468 -0.619203 -0.7767465 0.1151208 -0.4263894 -0.8965888 0.1196694 -0.2967632 -0.9525969 0.06701517 -0.5343561 -0.8378857 0.1114054 -0.6699633 -0.73655 0.09296941 -0.1763194 -0.9829604 0.05196654 -0.3649517 -0.9293662 0.05557793 -0.5007801 -0.8634591 0.06048113 -0.7960764 -0.6047318 0.02370142 -0.3674122 -0.9284738 0.05426639 -0.6779688 -0.7344924 0.02965199 -0.5191264 -0.8534556 0.0460599 -0.6449492 -0.764083 0.01475614 -0.6897282 -0.7238755 -0.01671779 -0.1986067 -0.979899 0.01879954 -0.222056 -0.9746397 0.02772617 -0.3156383 -0.9487335 0.0166589 -0.05146628 -0.9986309 0.009360253 -0.497327 -0.8673591 0.01881599 -0.8047162 -0.5903436 -0.06265932 -0.6769906 -0.7337861 -0.05693638 -0.690715 -0.7211398 -0.05357474 -0.528559 -0.848658 -0.02012145 -0.6179231 -0.7854285 -0.03568416 -0.3925808 -0.9197052 -0.004790186 -0.486458 -0.8724896 -0.04605001 -0.3351212 -0.942083 -0.01317667 -0.06527632 -0.9978352 0.007989466 -0.2960444 -0.9551447 -0.00752592 -0.174165 -0.9846777 -0.008743405 -0.05599546 -0.9984311 2.95456e-4 -0.7155106 -0.6916511 -0.09830218 -0.7526497 -0.6384958 -0.1607534 -0.7282823 -0.6655187 -0.1633703 -0.6068325 -0.7872118 -0.1097816 -0.5289128 -0.8443211 -0.08586728 -0.6202231 -0.7710317 -0.1443383 -0.1915663 -0.9813979 -0.01267337 -0.0421735 -0.9990889 -0.0065521 -0.5112038 -0.854959 -0.08784037 -0.3892529 -0.9191473 -0.06041997 -0.2916154 -0.9564401 -0.01352584 -0.6469684 -0.7388689 -0.1884267 -0.4096693 -0.9058871 -0.1074234 -0.5278661 -0.8376187 -0.1405429 -0.3645864 -0.9278373 -0.07870686 -0.521163 -0.8411979 -0.144136 -0.744512 -0.6159511 -0.2574999 -0.09721004 -0.9949475 -0.02509427 -0.5957117 -0.7734916 -0.2164216 -0.6285933 -0.747306 -0.2154167 -0.6774139 -0.6841475 -0.2702825 -0.2274935 -0.9730959 -0.03648602 -0.712909 -0.6210566 -0.3256525 -0.6333349 -0.7346693 -0.2432032 -0.673045 -0.7111371 -0.2032102 -0.5812442 -0.7714813 -0.2587894 -0.6768079 -0.6257153 -0.3878291 -0.6450711 -0.6819367 -0.34474 -0.5739246 -0.7497898 -0.329281 -0.52309 -0.8056054 -0.2781669 -0.4192827 -0.876323 -0.2371922 -0.5922638 -0.6857934 -0.4229788 -0.384822 -0.8999249 -0.2050546 -0.298765 -0.9373153 -0.1793866 -0.5881004 -0.6900355 -0.4218876 -0.5616486 -0.7333591 -0.3830604 -0.1980023 -0.976341 -0.08691161 -0.4813686 -0.8035354 -0.3501648 -0.4314575 -0.8552385 -0.2870742 -0.2342213 -0.958046 -0.165192 -0.6206416 -0.5928813 -0.5131236 -0.347032 -0.902437 -0.2552964 -0.2433738 -0.9556843 -0.1656409 -0.5054529 -0.7385657 -0.446137 -0.3489376 -0.8762855 -0.3322145 -0.4711191 -0.7975392 -0.3767997 -0.04005426 -0.9987047 -0.03138178 -0.1729546 -0.9785524 -0.1119014 -0.2553569 -0.9474158 -0.1928632 -0.4941196 -0.6947132 -0.5227039 -0.5140463 -0.6709687 -0.5343759 -0.451462 -0.7630788 -0.4624854 -0.08960276 -0.99312 -0.0753923 -0.4691033 -0.7484966 -0.4687163 -0.390006 -0.8427818 -0.3709639 -0.2002502 -0.9594067 -0.1985915 -0.3484167 -0.8732721 -0.3405901 -0.2902073 -0.9207895 -0.2606272 -0.4989485 -0.6191449 -0.606391 -0.4219226 -0.7270724 -0.5416154 -0.08017671 -0.993846 -0.07643324 -0.4301207 -0.6562069 -0.6199911 -0.2046607 -0.9545583 -0.2166388 -0.4142757 -0.7532504 -0.5108716 -0.29308 -0.8932243 -0.3409612 -0.4353587 -0.65011 -0.6227518 -0.340066 -0.8367277 -0.4292344 -0.1942674 -0.9577987 -0.2118535 -0.3406615 -0.8357943 -0.4305786 -0.3747174 -0.7691113 -0.5177401 -0.2486861 -0.9144738 -0.3192068 -0.09719437 -0.9873104 -0.1255846 -0.1964913 -0.9414555 -0.2739579 -0.3609271 -0.7429838 -0.5636548 -0.3447822 -0.6760571 -0.6512082 -0.2482461 -0.9151847 -0.3175074 -0.127401 -0.9805222 -0.1494831 -0.386875 -0.6260958 -0.6770022 -0.2744601 -0.8582851 -0.4336107 -0.3094621 -0.7758318 -0.5498347 -0.2788633 -0.8430609 -0.4598737 -0.3233467 -0.5990959 -0.7324829 -0.2972381 -0.7548587 -0.584669 -0.1074702 -0.9746306 -0.1963302 -0.1927784 -0.9180514 -0.3464364 -0.1733646 -0.9446603 -0.2784994 -0.2178086 -0.869978 -0.4423774 -0.2483536 -0.7825211 -0.5709478 -0.5240733 -0.4266001 -0.7371293 -0.07815027 -0.9893733 -0.1226096 -0.1989343 -0.8365246 -0.5105406 -0.2290332 -0.6687766 -0.707306 -0.2271119 -0.6723484 -0.7045338 -0.2440001 -0.7771994 -0.5800215 -0.1893361 -0.8873329 -0.4204664 -0.1273762 -0.9427245 -0.3082951 -0.1278283 -0.9414994 -0.3118318 -0.212538 -0.7411957 -0.6367546 -0.181211 -0.7816492 -0.5968142 -0.1847466 -0.8240272 -0.535582 -0.1327094 -0.8965073 -0.4226855 -0.103197 -0.9651833 -0.2403576 -0.1497946 -0.6231842 -0.7675957 -0.05263251 -0.9905589 -0.1265818 -0.02422475 -0.9956679 -0.08977025 -0.145457 -0.6333221 -0.7600957 -0.1608008 -0.724157 -0.6706265 -0.1265593 -0.8122535 -0.5694096 -0.1355793 -0.857795 -0.4957883 -0.1275187 -0.7552977 -0.6428565 -0.1207653 -0.875073 -0.4686823 -0.09783864 -0.9456763 -0.310039 -0.09347933 -0.9247494 -0.3689178 -0.1021273 -0.7225425 -0.6837415 -0.04835826 -0.9833899 -0.174945 -0.09707188 -0.8261435 -0.5550352 -0.07200759 -0.8470705 -0.5265799 -0.05635166 -0.9285295 -0.3669571 -0.06322461 -0.9237447 -0.3777547 -0.03421473 -0.9784139 -0.2038027 -0.03250253 -0.978981 -0.2013448 -0.1277578 -0.6990082 0.7036089 -0.1429233 -0.7178644 0.6813542 -0.2239109 -0.709593 0.6680881 -0.2513114 -0.6836717 0.6851539 -0.3093672 -0.7281891 0.6115821 -0.3842452 -0.6785612 0.6260276 -0.4016983 -0.7306287 0.5521052 -0.5018051 -0.6763084 0.5392574 -0.4979698 -0.7261515 0.4740571 -0.5823704 -0.7049337 0.4048621 -0.5883842 -0.6896008 0.4222022 -0.623956 -0.7156124 0.313971 -0.6659601 -0.682928 0.3001775 -0.6487814 -0.7242887 0.2334282 -0.7078623 -0.6876024 0.1616601 -0.6969394 -0.7014556 0.1491161 -0.687764 -0.7235311 0.059022 -0.7371509 -0.6754652 0.01885443 -0.6797849 -0.7308588 -0.06113839 -0.7236179 -0.6784668 -0.1267277 -0.6733119 -0.7210125 -0.163683 -0.6653953 -0.7029318 -0.2512691 -0.6738522 -0.6904108 -0.2631656 -0.5943539 -0.7208411 -0.3565553 -0.6102096 -0.6883385 -0.3922175 -0.5199627 -0.7204583 -0.4588887 -0.5238963 -0.6835426 -0.5082346 -0.4552809 -0.7237272 -0.5185927 -0.410911 -0.6876689 -0.5985513 -0.3962705 -0.7005891 -0.5934178 -0.3143398 -0.7226712 -0.6155786 -0.2879098 -0.6783826 -0.6759475 -0.2283593 -0.7220624 -0.6530528 -0.1497249 -0.7007891 -0.6974791 -0.1460456 -0.6919855 -0.7069842 -0.03235226 -0.7176604 -0.6956414 -0.009444952 -0.6911491 -0.7226506 0.05417734 -0.7202609 -0.6915845 0.1109403 -0.684437 -0.7205818 0.1444628 -0.7207804 -0.6779426 0.2277109 -0.7040955 -0.6726049 0.2446123 -0.6871548 -0.6840928 0.3108514 -0.7260724 -0.6133437 0.3791267 -0.6785839 -0.6291161 0.3964915 -0.7210919 -0.5681735 0.4703058 -0.7037341 -0.5325137 0.4911608 -0.6862434 -0.5364991 0.5244668 -0.7286822 -0.4404054 0.5957141 -0.6753143 -0.434828 0.5931583 -0.734434 -0.3298033 0.6698048 -0.6754304 -0.3084726 0.6485221 -0.7310985 -0.2119292 0.7148468 -0.6784616 -0.1693636 0.6749715 -0.7308092 -0.1016439 0.736897 -0.6755489 -0.02483069 0.6781722 -0.7343618 0.02820122 0.7273691 -0.6754382 0.1213155 0.6567746 -0.7361828 0.1633468 0.6898931 -0.674446 0.2630023 0.6119257 -0.734999 0.2921019 0.6240921 -0.6747219 0.3940299 0.5438665 -0.733656 0.4073796 0.5336467 -0.6751186 0.5093488 0.4527125 -0.7347387 0.5051836 0.4225112 -0.6750115 0.6048502 0.3434846 -0.7348267 0.5848487 0.2946738 -0.674919 0.6764996 0.2344592 -0.7244241 0.6482582 0.155806 -0.6986691 0.6982737 0.1569251 -0.7011466 0.6955344 0.2012471 -0.004256546 0.9795313 0.2184498 0.005223989 0.9758343 0.3401677 0.003055334 0.9403599 0.3618503 -0.01254755 0.9321519 0.5063898 0.01289457 0.8622083 0.5310195 -0.007336914 0.8473278 0.6673476 0.009912073 0.7446805 0.6581876 0.001310765 0.7528529 0.7682023 -0.01342839 0.6400666 0.801094 0.01796591 0.5982689 0.87186 -0.01472699 0.4895337 0.9010757 0.0173794 0.4333136 0.9408681 -0.01907223 0.3382357 0.9705618 0.02167761 0.239875 0.9879275 -0.02117443 0.1534634 0.9989137 0.02114433 0.04152572 0.9991404 -0.01732116 -0.03766345 0.9887675 0.01310616 -0.1488862 0.978681 -0.01414608 -0.2048992 0.9503517 0.01894688 -0.3106006 0.9189424 -0.02147519 -0.3938066 0.8738009 0.02035087 -0.4858579 0.835503 -0.01329737 -0.549325 0.7616745 0.008108854 -0.6479091 0.7658188 0.00361222 -0.6430464 0.6634045 -0.00327301 -0.748254 0.662019 -0.002162754 -0.749484 0.5709675 0.005554556 -0.8209539 0.5495901 -0.006301105 -0.8354108 0.4544251 0.00543636 -0.8907684 0.4428049 -0.00156933 -0.8966166 0.3107938 -0.001652419 -0.950476 0.3192701 -0.008108377 -0.9476291 0.2068585 0.01187998 -0.9782988 0.1407725 -0.01190048 -0.9899705 0.08056813 0.007678329 -0.9967196 8.4932e-4 -0.009495794 -0.9999547 -0.04903465 0.0120002 -0.9987251 -0.2081742 0.009051442 -0.97805 -0.158659 -0.0117402 -0.9872636 -0.2805582 -0.007425665 -0.9598083 -0.3285799 0.009563028 -0.9444279 -0.4185789 -0.01126182 -0.9081107 -0.4561841 0.006769001 -0.8898597 -0.5521981 -0.006588578 -0.833687 -0.5565414 -0.003288924 -0.8308135 -0.6578229 0.01071429 -0.7530965 -0.6983507 -0.01301097 -0.7156375 -0.7503104 0.01141548 -0.6609871 -0.8029106 -0.01719838 -0.5958514 -0.8580124 0.0207768 -0.5132086 -0.8971134 -0.01672399 -0.4414837 -0.9348301 0.01158571 -0.3549063 -0.9716725 0.008880138 -0.2361646 -0.9556646 -0.009887218 -0.2942915 -0.9958766 0.01451295 -0.08955103 -0.9899972 -0.01265531 -0.1405186 -0.9963021 0.009264886 0.08541846 -0.9993216 -0.01301014 0.03445315 -0.9778204 0.008865833 0.2092574 -0.9872145 -0.00700736 0.1592437 -0.9412348 0.007838845 0.3376621 -0.9551312 -0.01088529 0.2959833 -0.8928209 -0.001659393 0.4504089 -0.8968136 -0.007216751 0.4423499 -0.8204195 0.007290184 0.5717156 -0.8012858 -0.01112526 0.5981783 -0.7250043 0.01186472 0.6886422 -0.6954376 -0.01080632 0.7185053 -0.5883374 0.007950544 0.8085765 -0.5679004 -0.007643043 0.823062 -0.4525433 0.00999701 0.8916864 -0.4149588 -0.01225268 0.9097577 -0.3162591 0.008229315 0.9486372 -0.2502838 -0.01644736 0.9680328 -0.2030236 0.009363472 0.9791291 0.9999997 8.73123e-4 -3.02777e-4 0.9999979 -0.002016842 2.66571e-4 1 -1.91815e-4 2.0971e-4 0.9999961 -0.002654731 -9.63763e-4 1 -1.42016e-6 -4.82095e-6 1 -2.24688e-5 1.09544e-5 1 0 0 1 -5.71247e-6 1.98913e-6 0.9999975 -0.002234101 -3.57943e-7 1 -7.18366e-6 0 1 1.41742e-5 -9.98705e-6 -0.9974178 0.01033151 0.0710709 -0.9509387 0.006574869 0.3093098 -0.9448377 -0.005227208 0.3274973 -0.8323569 -0.01362919 0.5540726 -0.7913196 0.02204835 0.6110052 0.7015785 0.009505212 -0.7125288 0.7286735 -0.01332569 -0.6847316 0.3928027 0.01118779 -0.9195547 0.4203518 -0.01100707 -0.9072945 0.005408465 0.01143169 -0.9999201 0.03627455 -0.01125138 -0.9992786 -0.3828313 0.01167643 -0.9237445 -0.3534551 -0.01149344 -0.9353809 -0.688044 -0.01173925 -0.725574 -0.7111372 0.01192253 -0.7029522 -0.9153134 -0.01195973 -0.4025648 -0.9153013 -0.01198494 -0.4025915 -0.9852545 0.0199517 -0.1699279 -0.9993485 -0.03027743 -0.01964753 -9.79653e-4 -0.9999995 3.12643e-4 1.692e-5 -1 -1.79738e-5 -3.49155e-4 -0.9999999 4.93014e-4 1.33516e-4 -1 1.56617e-4 -2.96868e-4 -1 2.73955e-4 -3.7238e-4 -1 2.72605e-4 -1.60205e-4 -1 2.68037e-4 -2.51509e-4 -1 4.18943e-5 -2.16766e-4 -1 3.46415e-4 2.6225e-5 -1 -1.33139e-5 6.9011e-6 -1 -1.65404e-5 0.002074837 -0.9999744 0.006858587 -2.62643e-4 -1 -3.1948e-4 -0.003418743 -0.9999899 0.002956986 -5.52121e-4 -0.9999999 1.3272e-4 -2.64175e-4 -1 3.18764e-4 -8.04373e-5 -1 4.9198e-4 -2.08263e-4 -1 3.59583e-4 -1.18902e-4 -1 4.41409e-6 1.07103e-5 -1 2.81928e-4 -1.89497e-4 -1 0 -3.4581e-5 -1 5.57011e-5 8.28006e-5 -1 -2.2406e-5 1.20526e-5 -1 2.19126e-6 1.66915e-5 -1 9.69435e-5 4.60599e-6 -1 -7.41993e-6 2.09326e-5 -1 9.7949e-5 -8.28768e-5 -1 -1.10013e-4 0 -1 2.2358e-6 3.20197e-5 -1 7.03326e-5 4.99666e-4 -0.9999998 3.35178e-4 7.26236e-4 -0.9999974 -0.002182543 -2.03341e-5 -0.9999998 7.26045e-4 -0.002194225 -0.9999967 -0.001388311 5.33179e-5 -1 7.93269e-5 -0.001618802 -0.9999985 7.131e-4 3.2169e-5 -1 7.68562e-5 5.62267e-5 -1 5.72255e-5 3.81668e-5 -1 3.52078e-5 3.07279e-5 -1 -5.92344e-5 4.55856e-4 -1 8.09229e-5 -2.63782e-5 -1 -4.46365e-5 -1.76641e-5 -1 8.77923e-5 4.06335e-4 -0.9999999 2.59867e-4 4.03017e-4 -1 2.60285e-4 2.21953e-5 -1 3.11812e-5 1.45346e-5 -1 3.91629e-5 4.45791e-4 -1 2.00489e-4 4.3094e-4 -1 1.67396e-4 2.84496e-4 -0.9999999 -5.60322e-4 -1.67607e-4 -0.9999998 -7.4174e-4 -2.81993e-5 -1 -5.5008e-6 2.77742e-4 -1 2.87719e-4 -6.69144e-4 -0.9999998 6.76944e-5 2.38384e-5 -1 -7.54502e-5 1.06666e-4 -1 -2.34585e-6 4.29879e-4 -1 -3.76094e-4 0.001036047 -0.9999837 -0.005620777 0.004019498 -0.9999903 -0.00181514 5.60008e-5 -1 -1.21404e-5 5.44156e-4 -0.9999998 2.69934e-4 -0.002461373 -0.9999841 -0.005075812 8.1337e-4 -0.9999989 -0.001327037 4.3147e-4 -0.9999993 -0.001174688 2.61431e-5 -1 -1.3224e-5 0.001924932 -0.9999981 4.49314e-4 -4.82389e-4 -0.9999997 -5.74235e-4 2.98189e-5 -1 -2.77405e-5 -2.06989e-5 -1 3.09759e-5 3.71338e-5 -1 -3.12955e-5 -1.03854e-6 -1 1.96914e-5 3.44533e-4 -0.9999997 -7.88206e-4 1.13296e-4 -1 9.68056e-5 5.97337e-4 -0.9999998 -8.7105e-5 1.33926e-4 -1 -1.45434e-4 -1 5.51122e-4 1.51373e-4 -1 2.72491e-5 -1.16386e-5 -0.9999988 0.001116514 -0.001085519 -1 8.70191e-5 1.83314e-4 -0.9999996 -7.56007e-4 5.81109e-4 -1 3.53324e-4 4.21299e-4 -1 -1.9747e-5 7.0083e-6 -1 0 0 -1 -7.27597e-7 0 -0.6107938 -0.7917898 -2.59697e-4 -1 3.02451e-6 1.16957e-4 0.01100385 0.9998645 0.0122441 0.01240986 0.999833 0.01341789 0.01919138 0.9997412 0.01222127 0.006435573 0.9999139 0.01143193 0.01054477 0.9999308 0.005226075 0.009396791 0.9997037 0.0224626 0.03248989 0.9994189 0.01031869 0.004586637 0.9998824 0.01464098 0.003110706 0.999745 0.02236801 0.001572489 0.9998701 0.01604348 0.03100997 0.9995191 3.21389e-4 0.0153439 0.9998819 9.57596e-4 -0.001576662 0.9998618 0.01655489 -0.008751749 0.9987262 0.04969352 0.03306192 0.9993949 -0.01080667 -0.007317304 0.9998148 0.0177983 0.1293863 0.002534925 0.991591 0.1000844 -0.007570087 0.9949502 0.372291 -0.001112937 0.9281154 0.3683539 -0.002712249 0.9296817 0.5898007 0.005053162 0.8075332 0.6384922 -0.01526898 0.769477 0.7652816 0.01451766 0.6435321 0.8883422 0.001136481 0.4591807 0.8686784 -0.01294821 0.4952073 0.9791269 0.001131832 0.2032471 0.9790243 0.001339197 0.2037395 0.9975595 -0.005361437 -0.06961548 0.9962875 0.001644313 -0.08607447 0.9379168 0.008104741 -0.3467658 0.913675 -0.01375955 -0.4062128 0.812164 0.01297229 -0.583285 0.7477757 -0.01735675 -0.6637246 0.5702791 0.0220825 -0.8211542 0.4900034 -0.01259708 -0.8716295 0.261902 -3.80925e-4 -0.9650944 0.247676 0.005537211 -0.9688271 8.12663e-4 3.02663e-4 -0.9999997 -8.12662e-4 -3.01498e-4 -0.9999997 -0.2235386 -0.005026876 -0.9746821 -0.2944279 0.01675105 -0.9555269 -0.4422026 -0.01494771 -0.8967906 -0.6230993 0.01040929 -0.7820735 -0.6242775 0.01107263 -0.7811241 -0.8074054 -0.01431143 -0.5898236 -0.8528863 0.01571494 -0.5218601 -0.962661 -0.009899258 -0.270529 -0.9667402 -0.003728687 -0.2557336 -0.9996379 0.007851004 -0.02574187 -0.9981132 -0.01791036 0.05873197 -0.9676002 0.01932221 0.2517471 -0.9136255 -0.0173524 0.4061865 -0.8589193 0.01213884 0.5119673 -0.7696709 -0.009776115 0.6383661 -0.69631 0.009331941 0.7176805 -0.618984 -0.008830785 0.785354 -0.4826995 0.01431179 0.8756692 -0.4164745 -0.008497416 0.9091077 -0.203127 -0.00592941 0.9791345 -0.1544839 0.01333588 0.9879053 0.104914 0.02024108 0.9942753 0.2737224 -0.01832473 0.9616342 0.4084097 0.01414954 0.9126891 0.5101407 -0.0113092 0.8600168 0.6658568 0.01605331 0.7459069 0.7291176 -0.01209169 0.6842817 0.8807162 0.006176769 0.4736042 0.8809102 0.006361067 0.4732407 0.9790004 -0.007238864 0.2037299 0.9909813 0.01736682 0.1328704 0.9973568 -0.02085876 -0.06960159 0.9729914 0.02149271 -0.2298392 0.9136498 -0.01559865 -0.406203 0.8619233 0.01519936 -0.5068109 0.769611 -0.0151304 -0.6383337 0.6143516 0.01313096 -0.7889232 0.6304145 0.003468632 -0.776251 0.373957 0.002179861 -0.9274435 0.3876712 -0.002749621 -0.9217937 0.141475 0.003174304 -0.9899368 0.1563251 -0.002344489 -0.987703 -0.1414758 -0.003174066 -0.9899367 -0.1563212 0.002344012 -0.9877035 -0.3739469 -0.002180218 -0.9274476 -0.3876707 0.002749145 -0.9217939 -0.6360243 0.008875012 -0.7716181 -0.6109058 -0.002926409 -0.7916979 -0.7875379 -0.01127445 -0.6161631 -0.852899 0.01472383 -0.5218684 -0.9049044 -0.01082026 -0.4254775 -0.9666906 0.01081591 -0.2557192 -0.9849057 -0.008969366 -0.1728595 -0.9996284 0.008974313 -0.02574211 -0.9981931 -0.01082193 0.05910587 -0.9626021 0.01485615 0.2705115 -0.9450116 -0.007391989 0.3269535 -0.8258072 -0.003811359 0.5639397 -0.7937747 0.01808238 0.6079431 -0.633919 -0.01707559 0.7732111 -0.5044854 0.02202594 0.8631393 -0.3988402 -0.01441317 0.9169073 -0.1627002 0.00858581 0.9866383 -0.09412074 -0.01508527 0.9954465 0.04455733 -0.01732701 0.9988566 0.1787581 0.01469832 0.9837833 0.3036154 -0.010854 0.9527329 0.4533658 0.008672118 0.8912824 0.5101655 -0.008012115 0.8600389 0.6721 0.01339232 0.7403393 0.7291189 -0.01209264 0.6842803 0.875481 0.001133263 0.4832514 0.8809112 0.006363093 0.4732389 0.9812837 0.001130342 0.1925646 0.9842877 -0.006395876 0.1764562 0.9879871 0.009116709 -0.1542681 0.9839023 -0.00226581 -0.1786927 0.9021079 -0.005266904 -0.4314785 0.8824647 0.009631872 -0.4702803 0.769684 -0.006854116 -0.6383883 0.7279301 0.00807017 -0.6856039 0.614373 -0.009843945 -0.7889543 0.5145789 0.01750934 -0.8572642 0.3876175 -0.01596146 -0.9216821 0.174104 0.003906071 -0.9847195 0.1563079 0.01305484 -0.9876222 -0.1414718 -0.003174066 -0.9899373 -0.1563212 0.002345025 -0.9877035 -0.3663172 -0.002015531 -0.9304879 -0.3798298 0.002312242 -0.9250536 -0.5931385 -0.002887725 -0.8050954 -0.6100983 0.005895972 -0.7923039 -0.8182033 -0.008222877 -0.5748702 -0.8485442 0.01255708 -0.5289754 -0.9461904 -0.01412886 -0.3233021 -0.974654 0.0205484 -0.2227724 -0.9988527 -0.02326411 0.04185724 -0.9915148 0.01209843 0.1294301 -0.9169599 -0.001026511 0.3989783 -0.913752 -0.004678547 0.4062458 -0.7478161 0.009423255 0.6638391 -0.7697023 -0.001627445 0.638401 -0.6057532 -0.01113182 0.7955747 -0.5116828 0.02099627 0.858918 -0.3078624 -0.02666968 0.9510571 -0.1518849 0.0245338 0.9880937 0.1293793 0.002534866 0.991592 0.1000818 -0.007569968 0.9949505 0.3722874 -0.001112222 0.9281169 0.3683524 -0.002710223 0.9296823 0.6101076 0.00567013 0.7922983 0.6190166 7.50403e-4 0.7853777 0.7940109 -0.01096004 0.6078049 0.8515266 0.01921975 0.5239592 0.9161322 -0.01181983 0.4007023 0.9795821 0.01048976 0.2007709 0.9852864 -0.00132966 0.1709062 0.9879569 0.01202446 -0.1542615 0.9928532 -0.001332461 -0.1193351 0.9392499 -0.01284581 -0.3429936 0.8824253 0.01374274 -0.4702518 0.8210322 -0.01374 -0.5707166 0.7337299 0.01284414 -0.6793199 0.5900862 -0.01169049 -0.8072557 0.5709869 -0.003055691 -0.8209536 0.3424754 0.00957024 -0.939478 0.2863563 -0.0126686 -0.9580395 0.02548623 0.009566128 -0.9996295 -0.02548623 -0.009567081 -0.9996295 -0.2863647 0.01266831 -0.958037 -0.3424664 -0.009570181 -0.9394814 -0.5709836 0.003055989 -0.8209558 -0.576384 0.005477547 -0.8171608 -0.7337772 -0.006240665 -0.6793616 -0.7708065 0.008474528 -0.637013 -0.8824594 -0.00999242 -0.4702826 -0.9005089 0.003211438 -0.4348257 -0.9783653 0.006614685 -0.2067793 -0.9887417 -0.01774013 -0.1485775 -0.9914692 0.01545071 0.1294229 -0.9707944 -0.02132856 0.2389631 -0.9168027 0.01864171 0.3989055 -0.8101143 -0.01961147 0.5859439 -0.7438827 0.01520657 0.6681373 -0.567785 -0.01546734 0.8230316 -0.492196 0.0170691 0.8703171 -0.2357804 -0.01897805 0.9716211 -0.1544845 0.01333606 0.9879053 -0.6587548 -0.008002996 0.7523152 -0.6102648 0.01665329 0.7920225 -0.4585728 0.004209876 0.888647 -0.4611284 0.003010869 0.8873285 -0.1740009 0.01240432 0.9846674 -0.2053962 -0.004094898 0.9786704 0.05762755 -0.01787179 0.9981783 0.1381753 0.01587754 0.9902805 0.35532 -0.01308202 0.9346532 0.3850259 0.005021214 0.9228921 0.6697254 0.004209101 0.742597 0.6581949 -0.005277276 0.7528291 0.8449472 -0.004834294 0.534828 0.8457728 -0.00396341 0.5335286 0.9528773 0.01281642 0.3030854 0.9763119 -0.03125768 0.2140985 0.9993703 0.03397798 0.01022911 0.9848338 -0.02646875 -0.1714696 0.9416311 0.02759653 -0.3355135 0.9062171 -0.005849242 -0.4227724 0.8392153 0.0198661 -0.5434364 0 -1 -5.93276e-6 0 -1 -2.97109e-6 0 -1 -5.3927e-6 0 -1 1.06183e-5 0 -1 2.60763e-6 0 -1 6.53892e-6 0 -1 1.38906e-5 0 -1 -6.04663e-6 0 -1 -9.3234e-6 0 -1 -4.3781e-6 0 -1 -4.04964e-6 0 -1 2.66843e-6 0 -1 -4.4534e-6 0 -1 -1.35113e-6 0 -1 1.72802e-6 0 -1 1.51221e-6 0 -1 -5.38796e-6 0 -1 2.21089e-6 0 -1 -2.6602e-6 0 -1 -8.42197e-6 0 -1 5.40549e-6 0 -1 1.60831e-6 0 -1 -1.37332e-5 0 -1 -3.48762e-6 0 -1 1.3898e-6 0 -1 6.539e-6 0 -1 -1.91593e-6 0 -1 -2.67454e-6 0 -1 6.01428e-6 0 -1 3.48088e-6 0 -1 -9.26733e-6 0 -1 -8.61363e-6 0 -1 -2.68729e-6 0 -1 -7.13632e-6 0 -1 3.13694e-6 0 -1 4.42708e-6 0 -1 -8.10476e-6 0 -1 3.04771e-6 0 -1 -3.2899e-6 0 -1 3.42711e-6 0 -1 -2.74949e-6 0 -1 4.96399e-6 0 -1 -1.76211e-6 0 -1 -4.80303e-6 0 -1 -3.01725e-6 0 -1 -6.80052e-6 0 -1 -3.32448e-6 0 -1 8.65482e-6 0 -1 -4.45117e-6 0 -1 -1.72999e-6 0 -1 1.94173e-6 0 -1 2.95126e-6 0 -1 5.35506e-6 0 -1 -2.43117e-6 0 -1 5.938e-6 0 -1 -6.07107e-6 0 -1 5.94253e-6 0 -1 -3.04107e-6 0 -1 2.69447e-6 0 -1 -6.43074e-6 0.7022736 -7.98796e-4 0.7119068 0.7013585 -0.003189861 0.7128016 0.5823464 -0.002227008 0.8129378 0.5908153 0.003856003 0.8067978 0.4810767 -0.003321588 0.8766723 0.4903362 0.002029299 0.8715311 0.3541531 -0.006615638 0.9351642 0.3724893 0.003321826 0.9280306 0.2638728 0.008355498 0.9645214 0.2219571 -0.008355379 0.9750207 0.1144919 -0.00145179 0.9934231 0.130381 0.006316721 0.9914439 1.63534e-4 -8.64745e-4 0.9999997 -1.63533e-4 8.64743e-4 0.9999997 -0.5690858 0.01277488 0.822179 -0.589709 -0.0024001 0.8076123 -0.4902998 -0.01249533 0.8714643 -0.3988317 0.01535564 0.9168957 -0.36561 -0.006645262 0.9307445 -0.2294709 0.002328991 0.9733128 -0.2322786 5.63791e-4 0.9726492 -0.1144939 0.00145173 0.9934229 -0.121457 -0.001952111 0.9925948 -0.7007112 -0.001094996 0.7134442 -0.7007558 -9.73407e-4 0.7134007 -0.5773957 -0.002253174 0.8164614 -0.5691304 0.005009114 0.822232 -0.4187059 -0.004639744 0.9081101 -0.4067448 0.003696441 0.9135344 -0.2797384 -0.002952575 0.9600718 -0.2607969 0.005880475 0.9653759 -0.1663243 -0.007672429 0.9860413 -0.1265107 0.007150292 0.9919395 -0.02675294 -2.52241e-4 0.9996421 -0.02108037 -0.003240287 0.9997726 0.9893934 6.43787e-4 0.1452596 0.9878367 -0.003124117 0.1554635 0.9235634 0.003387689 0.3834308 0.9178677 -0.00268191 0.3968777 0.8259992 0.002087354 0.5636675 0.8185293 -0.001662492 0.5744626 0.7175882 0.001841127 0.6964653 0.7080399 -0.002643227 0.7061675 0.5392134 0.003124117 0.8421635 0.5307812 -0.00115478 0.8475082 0.3268257 6.48771e-4 0.9450845 0.3316397 -0.001155138 0.9434055 0.164722 6.49217e-4 0.9863398 0.1589178 -0.00119996 0.9872911 0.9999997 3.45667e-4 8.03402e-4 0.9998679 -0.005825996 -0.01518046 0.9900763 0.009736716 -0.1401942 0.9680906 -0.01072448 -0.2503707 0.9463 0.007704675 -0.3231981 0.8907169 -0.008631527 -0.4544768 0.8684787 0.004784882 -0.4957035 0.7751217 7.20248e-4 -0.6318116 0.7522541 -0.01124531 -0.6587772 0.6284506 0.01489871 -0.7777068 0.5470699 -0.01489561 -0.8369545 0.368274 -0.002726852 -0.9297134 0.409857 0.008926153 -0.9121061 0.9326023 0.002317011 -0.3608983 0.9294239 -0.002348721 -0.3690062 0.889207 0.002747714 -0.457497 0.8842662 -0.004496574 -0.4669617 0.8213636 0.004498243 -0.5703873 0.8152332 -0.002747714 -0.5791264 0.7549629 0.002364218 -0.6557633 0.7492061 -0.002363979 -0.6623328 0.6811516 0.002747774 -0.7321373 0.6801206 0.001789629 -0.7330982 0.6043622 -0.006624996 -0.7966822 0.5789971 0.009374618 -0.8152758 0.5163781 -0.00892049 -0.8563143 0.4795852 0.01108121 -0.8774254 0.3988505 -0.01560962 -0.9168832 0.3534442 0.01168817 -0.9353826 0.2602838 4.18623e-4 -0.9655321 0.2718889 -0.006508827 -0.9623067 0.02304935 -0.001042068 0.9997339 0.01981985 9.85839e-4 0.9998031 0.9915889 6.11704e-4 0.1294261 0.990305 -0.00203818 0.1388954 0.9466218 0.002681851 0.3223356 0.9473212 0.003594338 0.320265 0.8581032 -0.009669661 0.5133864 0.8353583 0.006664276 0.5496654 0.7175881 0.003006041 0.6964613 0.696106 -0.00825262 0.7178916 0.5479213 0.005051672 0.8365147 0.5363854 5.38038e-4 0.8439731 0.3736398 7.06374e-4 0.9275736 0.3838955 -0.003006994 0.9233717 0.2104269 0.004868328 0.9775975 0.1768917 -0.006258487 0.9842105 1 3.47393e-4 -1.2157e-4 0.9999537 -0.009569823 -0.001032292 0.2164757 0.001387417 -0.976287 0.2104254 0.003947436 -0.977602 0.3736324 -0.007010638 -0.9275504 0.4358077 0.009783208 -0.8999868 0.5479059 -0.009783148 -0.8364828 0.6223502 0.01290881 -0.7826325 0.7234728 -0.01371783 -0.6902167 0.808363 0.0132187 -0.588536 0.8529419 -0.009520053 -0.5219189 0.9273038 0.00952363 -0.3741886 0.9554511 -0.01437503 -0.2947992 0.9837731 0.01257872 -0.178976 -1.86657e-4 -0.003582477 -0.9999936 2.58575e-5 4.96317e-4 -1 -0.9842287 0.0010432 -0.1768984 -0.9838516 2.61806e-4 -0.1789859 -0.930459 -0.003329336 -0.3663809 -0.9138596 0.01103246 -0.4058807 -0.8456833 -0.01080298 -0.5335758 -0.7724688 0.008912801 -0.6349903 -0.7474859 -0.00208795 -0.6642745 -0.6206857 0.002283632 -0.7840562 -0.6097273 -0.002280414 -0.792608 -0.4486798 0.002480685 -0.8936892 -0.4434031 2.84148e-4 -0.8963223 -0.226909 0.005203187 -0.9739022 -0.2480792 -0.003553032 -0.9687333 -1 -4.99348e-4 2.55381e-4 -0.9999999 4.05913e-4 1.72963e-4 -0.9779851 -0.001356422 0.2086706 -0.9776069 -6.85992e-4 0.2104384 -0.9275656 0.002834796 0.3736497 -0.9104248 -0.009769141 0.4135596 -0.8410541 0.01209539 0.5408158 -0.7774298 -0.00999546 0.6288904 -0.7076367 0.01061195 0.7064968 -0.6458373 -0.01005887 0.7634089 -0.4702411 -0.003005981 0.8825329 -0.5008046 0.008719265 0.8655166 -0.3121306 5.37582e-4 0.9500391 -0.2871542 0.009128689 0.9578409 -0.1254671 -0.01360559 0.9920045 -0.02846103 0.004847943 0.9995833 -0.9978924 -0.001298189 -0.06487876 -0.9983362 0.002660632 -0.05760008 -0.9824321 -0.001296043 -0.1866161 -0.9805926 0.004864335 -0.1959963 -0.9376035 -0.005086183 -0.3476693 -0.933831 0.002984762 -0.3577021 -0.8925355 -0.00236392 -0.4509711 -0.8885613 0.002363264 -0.458752 -0.843628 -0.00236386 -0.5369229 -0.8338049 0.007378637 -0.55201 -0.7864308 -0.009761869 -0.6176013 -0.7216002 -0.007112503 -0.6922735 -0.7540056 0.009671807 -0.6567969 -0.6496914 -0.007112264 -0.7601649 -0.6801049 0.007111966 -0.7330804 -0.6043627 0.007112801 -0.7966777 -0.5714268 -0.007112503 -0.8206223 -0.5163784 0.008920848 -0.8563142 -0.4811465 -0.01024585 -0.8765805 -0.3617665 -0.01012438 -0.9322139 -0.3971763 0.01404058 -0.917635 -0.2638365 0.00248903 -0.9645642 -0.2689751 -0.001353323 -0.9631463 -0.9899006 -0.009832978 -0.1414224 -0.9664267 0.01265221 -0.2566306 -0.9434991 -0.009703397 -0.3312332 -0.8672398 0.01158559 -0.4977558 -0.8332422 -0.01263785 -0.5527637 -0.7012048 0.01169174 -0.7128641 -0.6474986 -0.01237118 -0.7619662 -0.5328412 0.01040369 -0.8461514 -0.4393697 -0.01070255 -0.8982425 -0.3681004 0.006111383 -0.9297661 -0.9999814 0.005689442 0.002243757 -0.9999707 0.006593286 0.003907322 -0.2010254 0.001325249 0.9795852 -0.235004 -0.01007866 0.9719421 -0.3688178 0.01205676 0.9294236 -0.4848853 -0.01291012 0.8744826 -0.5783687 0.01436638 0.815649 -0.6567255 -0.01085221 0.7540516 -0.7917721 0.006607651 0.610781 -0.7811524 -0.001762866 0.624338 -0.8953397 0.004978954 0.4453563 -0.9152205 -0.009548008 0.4028403 -0.9662091 0.01088732 0.2575294 -0.9827023 -0.01052123 0.1848932 7.08755e-4 4.94748e-4 0.9999997 0.005593478 -0.002944171 0.9999801 0.6020311 0.007140815 0.7984408 0.6143448 -0.001331329 0.7890366 0.4891131 -0.00987029 0.8721646 0.4453254 0.01427918 0.895255 0.3480902 -0.01434499 0.9373513 0.2848005 0.01188689 0.9585132 0.1538879 0.003478944 0.9880822 0.1781349 -0.009657859 0.9839587 -0.07307809 0.003752648 -0.9973192 -0.1028758 -0.01654833 -0.9945566 -0.2371053 0.01488894 -0.9713699 -0.3271654 -0.02525621 -0.9446296 -0.4175909 0.02409809 -0.9083155 -0.5823781 -0.007479488 -0.8128837 -0.5706061 -0.01873487 -0.8210102 -0.7148531 0.01622068 -0.6990867 -0.7505665 -0.01622879 -0.6605957 -0.8527246 0.005335032 -0.5223336 -0.8541306 0.007483839 -0.5200047 -0.9420726 0.004904747 -0.3353733 -0.9372421 -0.004903435 -0.348645 -0.9919538 0.01916873 -0.1251413 -0.986469 -0.004481971 -0.1638872 -0.9994285 -0.02864813 0.01795238 -0.9882521 0.03729265 0.1482135 -0.9619996 -0.02898341 0.2715081 -0.9216699 0.02174144 0.3873654 -0.8734657 -0.02525275 0.4862303 -0.8220042 0.02409648 0.5689715 -0.6994391 0.003578841 0.7146832 -0.7207818 -0.01482081 0.6930037 -0.5714924 0.004492044 0.8205951 -0.582386 -0.003576755 0.8129045 -0.4048376 -6.16339e-4 0.9143884 -0.4103035 -0.005340993 0.9119334 -0.2096111 0.007392823 0.9777569 -0.1968288 -0.002745926 0.9804341 0.01395702 0.01394599 0.9998054 -0.01516228 -0.007031321 0.9998604 0.2272311 0.005026698 0.9738279 0.207238 -0.0097422 0.978242 0.4177044 -0.002523839 0.9085795 0.414422 -0.005459487 0.9100685 0.6077795 0.01237124 0.7940096 0.6383376 -0.02437871 0.7693704 0.8182508 0.0254594 0.5742973 0.8428665 -0.01860046 0.5378013 0.9531834 0.01338189 0.3020966 0.9594495 -0.00789088 0.28177 0.9998426 0.007754623 0.01596289 0.9999749 -0.007041096 7.43273e-4 0.9727966 0.006132304 -0.2315796 0.9714381 0.001504242 -0.2372883 0.9065766 0.004237592 -0.4220203 0.9130224 -0.006356894 -0.4078601 0.8088666 0.004232823 -0.5879771 0.803709 -0.003364384 -0.595013 0.6515498 -0.009863257 -0.7585418 0.6324319 0.01110434 -0.7745364 0.458531 -0.002524435 -0.8886749 0.4418715 -0.01763415 -0.8969051 0.2744899 0.02122455 -0.9613558 0.1684452 -0.02907282 -0.9852823 0.1094354 0.008600056 -0.9939567 -0.003742754 -0.01719391 -0.9998453 -0.07127147 0.01916992 -0.9972727 -0.1832274 -0.01815748 -0.982903 -0.2691789 0.01833856 -0.9629157 -0.3969491 -0.01402831 -0.9177334 -0.4249098 0.004491567 -0.9052246 -0.603044 0.01915955 -0.7974779 -0.5714876 -0.004491925 -0.8205986 -0.6992452 -0.02322435 -0.7145047 -0.7964627 0.0237227 -0.6042223 -0.8222121 -0.007157266 -0.5691363 -0.9243385 0.006570816 -0.3815172 -0.9218866 9.31365e-4 -0.3874586 -0.9908461 0.02188199 -0.1332118 -0.9850199 -0.005665183 -0.1723475 -0.9882519 0.03729289 0.1482146 -0.9620003 -0.0289793 0.2715061 -0.9216702 0.02174985 0.3873642 -0.8852015 -0.01489037 0.4649695 -0.8221644 0.01320528 0.5690971 -0.7860234 -0.01823741 0.6179276 -0.6866847 0.02872419 0.7263877 -0.5963074 -0.03324824 0.8020675 -0.5007724 0.02466464 0.8652276 -0.3871532 -0.01793879 0.9218409 -0.3035795 0.01926928 0.9526113 -0.2208838 -0.01724952 0.9751476 -0.08445388 0.01399475 0.9963292 -0.02386695 -0.01741236 0.9995636 0.09581214 0.02127295 0.9951721 0.2072001 -0.02412199 0.9780012 0.2982885 0.01743751 0.9543165 0.4648291 0.01501417 0.8852732 0.4143695 -0.01783418 0.909934 0.656044 0.003903865 0.7547127 0.6384236 -0.01824325 0.769469 0.8137905 0.01052767 0.581063 0.8426716 -0.02850544 0.5376727 0.9133061 0.02735245 0.4063543 0.9587591 -0.03874158 0.2815673 0.985317 0.02650135 0.1686659 0.9997486 -0.0191316 -0.01169902 0.999975 -0.007038891 7.41446e-4 0.972796 0.006123661 -0.2315828 0.9648436 -0.01873737 -0.2621565 0.8954257 0.02865248 -0.4442882 0.8623151 -0.02174788 -0.505905 0.7450127 0.001653313 -0.6670484 0.736855 0.01328527 -0.6759203 0.5586339 -0.001920998 -0.8294121 0.5502939 -0.01003903 -0.8349107 0.3936151 0.01132625 -0.9192056 0.3668883 -0.006843268 -0.9302399 0.2018164 -0.0028041 -0.9794194 0.1762345 0.01667046 -0.9842071 -8.10825e-4 -0.0241366 -0.9997084 -0.05431222 0.0145201 -0.9984185 -0.2156177 -0.008862018 -0.9764378 -0.2371305 0.004486143 -0.9714676 -0.3975473 -0.004484772 -0.9175708 -0.409752 0.00358051 -0.91219 -0.5550965 0.004492402 -0.8317738 -0.5439453 -0.003575444 -0.8391131 -0.7032601 0.008850872 -0.7108775 -0.6874139 -0.004490971 -0.726252 -0.7980905 -0.01182138 -0.6024217 -0.8347647 0.02060544 -0.5502213 -0.89767 -0.02194303 -0.4401217 -0.9361487 0.01815539 -0.3511353 -0.9651829 -0.01306807 -0.2612499 -0.9858564 0.01866185 -0.16655 -0.9963246 -0.02588462 -0.08165359 -0.994616 0.03131639 0.09878528 -0.9858791 -0.01737743 0.1665548 -0.9362682 0.008586406 0.3511813 -0.937082 0.006580173 0.3490473 -0.8268278 0.005334317 0.5624299 -0.8349216 -0.006124138 0.5503348 -0.6931669 0.00491029 0.7207604 -0.7032767 -0.00490576 0.7108993 -0.5439447 0.003575146 0.8391135 -0.5550827 -0.004489123 0.8317832 -0.3975576 -3.04674e-4 0.9175773 -0.4023537 -0.003955841 0.9154759 -0.2096078 0.007392287 0.9777576 -0.1968309 -0.002745926 0.9804336 0.005661845 0.007970929 0.9999523 -0.01516222 -0.007031202 0.9998604 0.2008079 0.002447307 0.9796277 0.2072522 -0.003281891 0.9782821 0.4441316 0.0186904 0.8957667 0.4144092 -0.009078741 0.9100455 0.6640602 0.0142669 0.7475429 0.6384226 -0.0182479 0.7694697 0.8503041 0.002475678 0.5262858 0.8429567 -0.01162087 0.537856 0.9522804 0.002481579 0.3052146 0.9593205 -0.01814955 0.2817354 0.9966145 0.0267533 0.07774293 0.9995195 -0.03098976 7.41212e-4 0.9805107 0.02413189 -0.1949787 0.964698 -0.02555751 -0.2621157 0.9088767 0.02533233 -0.4162951 0.854667 -0.02551633 -0.5185494 0.8086943 0.02117192 -0.587848 0.6937757 -0.03303766 -0.719433 0.6322561 0.02637106 -0.7743105 0.453222 -0.0137661 -0.8912914 0.4686691 0.003613948 -0.8833665 0.2596889 -0.01110774 -0.9656285 0.2192806 0.02386683 -0.9753699 -0.1094233 -0.0143584 -0.9938915 -0.1720039 0.01205009 -0.9850226 -0.2801939 -0.01394408 -0.9598422 -0.3326552 0.0141614 -0.9429422 -0.5061046 0.004909157 -0.8624582 -0.4863801 -0.01086491 -0.8736799 -0.6604207 0.003579556 -0.7508872 -0.6503384 -0.004487574 -0.7596314 -0.7809591 0.009683132 -0.6245071 -0.7671047 -0.003572881 -0.641512 -0.8786075 -0.01653355 -0.4772585 -0.8966464 0.01050645 -0.4426227 -0.9622653 0.001068294 -0.2721112 -0.9629832 -0.001069068 -0.2695598 -0.9959 -0.01050436 -0.08984941 -0.999025 0.02830928 -0.03387689 -0.9906392 -0.02842664 0.1335148 -0.9710171 0.02525371 0.2376721 -0.9391038 -0.02175545 0.3429445 -0.8937928 0.02548021 0.4477559 -0.8346666 -0.02547454 0.5501661 -0.7609717 0.02527636 0.6482925 -0.7088258 -0.01506894 0.7052226 -0.5706573 0.01403313 0.8210685 -0.5757701 0.008583486 0.8175666 -0.387153 -0.01758897 0.9218477 -0.3190863 0.02623081 0.9473626 -0.2208797 -0.01724863 0.9751485 -0.08445429 0.01399517 0.9963291 -0.02386695 -0.01741254 0.9995636 0.09581166 0.02127283 0.9951722 0.2071983 -0.02412396 0.9780015 0.2982875 0.0174365 0.9543168 0.464831 0.0150159 0.885272 0.4143695 -0.01783519 0.909934 0.6560439 0.003903865 0.7547128 0.6384236 -0.01824486 0.7694691 0.8185726 0.01075267 0.5743024 0.8427267 -0.02617615 0.5377051 0.9222585 0.02198678 0.3859481 0.9590523 -0.0297892 0.2816582 0.9809931 0.02447712 0.1924932 0.9997088 -0.02412319 7.41241e-4 0.9992728 0.005734562 -0.03769814 0.9757343 0.00659734 -0.2188588 0.9714165 -0.007030904 -0.2372773 0.8983443 0.0178743 -0.4389281 0.9085284 -0.002537786 -0.4178155 0.7570495 -0.02279132 -0.65296 0.7368932 0.008703708 -0.6759532 0.558612 0.008729219 -0.8293833 0.5308206 -0.01604437 -0.8473323 0.3936043 0.01292049 -0.9191892 0.3394034 -0.01975965 -0.9404334 0.1925447 0.02308428 -0.9810167 0.09622645 -0.02249801 -0.9951053 0.01181191 0.01481115 -0.9998205 0.1979886 0.006641209 -0.9801818 0.1655666 0.0198391 -0.9859991 0.596996 -0.0160489 -0.8020838 0.6613318 0.01419156 -0.7499592 0.9044155 -0.009311616 -0.4265513 0.9011475 -0.00641793 -0.4334652 0.9971559 0.01190054 -0.07442158 0.9993594 -0.01474344 0.03260916 0.9575447 0.01710456 0.2877771 0.9182955 -0.01403546 0.3956471 0.7334384 -0.001717627 0.6797538 0.692409 0.01699745 0.721305 0.4784781 -0.01420736 0.8779847 0.3338747 0.01577353 0.9424855 0.1415494 -0.01185333 0.9898603 -0.02538734 0.01234865 0.9996015 -0.1568801 -0.01185882 0.9875465 -0.3810749 0.01185899 0.9244682 -0.5357292 -0.02008014 0.8441511 -0.6369279 0.01180559 0.7708331 -0.8863415 -1.16315e-4 0.4630321 -0.9007242 -0.01447343 0.4341503 -0.9997855 0.01255083 -0.01647889 -0.992969 -0.02315646 -0.1160879 -0.9111639 0.02177011 -0.4114686 -0.7874479 -0.01700872 -0.6161466 -0.7269513 0.00656861 -0.6866577 -0.4931405 -0.008838295 -0.8699048 -0.3876032 0.021048 -0.921586 -0.1658448 -0.02143096 -0.9859191 0.1979893 -0.003577888 -0.9801977 0.2304315 0.008526742 -0.9730512 0.570525 -0.002599537 -0.8212762 0.5970257 -0.01284915 -0.8021193 0.7973701 0.01591753 -0.6032807 0.9006243 -0.02043986 -0.4341179 0.9648444 0.02238821 -0.2618669 0.9989171 -0.03229802 0.03349167 0.9666455 0.02997732 0.2543579 0.8402802 -0.02087372 0.5417504 0.749085 0.02087318 0.662145 0.5284955 -0.02591681 0.8485404 0.3108199 0.02513277 0.9501366 0.1247215 -0.01816326 0.9920256 -0.09165501 0.01334822 0.9957014 -0.2622405 -0.0108658 0.9649415 -0.3814285 0.01007157 0.9243435 -0.5837973 -0.0171709 0.8117179 -0.6863599 0.01682382 0.7270674 -0.9043602 -0.01557439 0.4264858 -0.8974785 -0.009505927 0.4409561 -0.9970255 0.02170091 0.07395529 -0.9970254 -0.02170139 -0.07395547 -0.8899312 -0.005208611 -0.4560654 -0.9148703 0.01301842 -0.4035379 -0.6613613 0.008234262 -0.7500224 -0.6104336 -0.01390761 -0.7919455 -0.2623074 0.01729893 -0.9648293 -0.1906 -0.009081602 -0.9816259 0.09960693 -0.02354741 -0.9947482 0.2792357 0.02322638 -0.9599417 0.5764159 -0.02293258 -0.8168347 0.680093 0.01695376 -0.7329298 0.8697632 -0.01228344 -0.4933164 0.9215172 0.0149821 -0.3880486 0.9846249 -0.01618558 -0.173931 0.9997334 0.015899 0.01674616 0.9747869 -0.01753008 0.2224482 0.933537 0.01552206 0.358145 0.7716057 -0.01528549 0.6359175 0.7098389 0.012196 0.7042585 0.4415049 -0.01219731 0.897176 0.3727045 0.01028513 0.9278931 0.04218238 -0.007233798 0.9990838 -0.05065935 0.01836407 0.9985471 -0.3024591 -0.02312558 0.9528818 -0.5420997 0.0215519 0.8400378 -0.6613091 -0.01560068 0.7499513 -0.8448424 0.0193485 0.5346654 -0.8970109 -0.01185339 0.4418495 -0.9931905 -0.007043957 0.1162892 -0.9986135 0.01569604 0.05024623 -0.9478475 -0.01178425 -0.3185063 -0.9336586 0.00352776 -0.3581469 -0.680636 0.01660263 -0.7324337 -0.6550436 -2.2744e-4 -0.7555912 -0.3420929 -0.02159839 -0.9394178 -0.1657429 0.0251289 -0.9858488 0.133153 0.01660668 -0.9909564 0.3466403 -0.01566469 -0.9378674 0.5075212 0.01797634 -0.8614518 0.6424708 -0.0159471 -0.7661443 0.8444609 0.015392 -0.535396 0.8819848 -0.00794053 -0.4712111 0.9949842 -0.002410769 -0.1000029 0.9922481 0.005213677 -0.1241631 0.9729396 0.002181828 0.2310497 0.9692149 -0.002030253 0.246208 0.8396157 0.002368271 0.5431759 0.8308938 -0.002955257 0.5564232 0.4780638 -0.01335942 0.8782236 0.5142267 0.003304541 0.857648 0.09108531 0.01926207 0.9956568 -0.06590163 -0.02675306 0.9974675 -0.2871217 0.0158962 0.9577623 -0.5570064 -0.01281869 0.8304094 -0.5563619 -0.01252353 0.8308458 -0.811998 0.01608526 0.5834387 -0.8855379 -0.01574522 0.4643002 -0.9604261 0.01331233 0.2782168 -0.9930803 -0.01697462 0.1162046 -0.9930804 0.01697468 -0.1162028 -0.9604269 -0.01331317 -0.2782142 -0.8855365 0.01574581 -0.4643028 -0.8120012 -0.01608335 -0.5834341 -0.5702459 0.01118713 -0.8213979 -0.5237756 -0.007433056 -0.851824 -0.1978352 0.01045382 -0.9801796 -0.08578634 -0.01850104 -0.9961418 0 -1 1.13457e-5 0 -1 -1.08719e-5 0 -1 8.51191e-6 0 -1 -1.00682e-6 0 -1 4.59407e-6 0 -1 -4.32394e-6 0 -1 4.36251e-6 0 -1 2.66577e-6 0 -1 -1.09457e-5 0 -1 -1.56217e-5 -8.11155e-4 -0.9999992 -0.001016378 0 -1 1.43944e-5 1.71958e-4 -1 -4.17321e-4 -6.03124e-4 -0.9999993 -0.0010432 1.77925e-5 -0.9999998 -7.07539e-4 0.001313745 -0.9999991 2.8269e-4 -1.50615e-4 -1 -4.2315e-4 0 -1 9.71705e-7 0 -1 -1.10631e-5 0 -1 4.14771e-7 5.98976e-4 -0.9999998 8.77863e-6 0 -1 1.9803e-6 -1.12162e-4 -1 4.75274e-4 6.72129e-4 -0.9999998 8.04858e-5 0 -1 4.80605e-6 0 -1 -4.92203e-6 1.4507e-4 -0.9999999 5.28943e-4 0 -1 1.69788e-6 6.11529e-4 -0.9999998 3.14734e-4 0 -1 3.78426e-6 0 -1 6.67637e-6 4.69064e-4 -0.9999998 5.31273e-4 0 -1 5.95008e-6 0 -1 3.24549e-6 0 -1 1.15035e-5 6.09245e-4 -0.9999999 2.66014e-4 5.11155e-4 -0.9999998 5.02035e-4 0 -1 4.78803e-6 0 -1 -8.91476e-6 3.29815e-4 -0.9999998 5.89678e-4 0 -1 8.21472e-6 0 -1 -3.00715e-6 6.51563e-4 -0.9999999 -5.80397e-5 2.98578e-4 -0.9999999 4.20836e-4 7.05241e-4 -0.9999997 -3.33641e-4 2.83928e-4 -1 3.04409e-4 0 -1 -1.34611e-6 0 -1 2.30449e-5 0 -1 8.6452e-6 0 -1 2.04092e-5 0 -1 -1.21062e-6 0 -1 6.07503e-7 -6.46e-4 -0.9999999 1.62672e-4 -3.21402e-4 -1 3.4777e-4 -0.00146681 -0.9999988 -6.43004e-4 -5.64075e-4 -0.9999998 2.29527e-4 1.74852e-4 -0.9999997 7.38276e-4 -3.00719e-4 -1 2.23851e-4 -4.50075e-4 -1 -7.79592e-7 0 -1 -3.79183e-6 0 -1 -1.99782e-5 0 -1 5.46547e-6 1.01706e-4 -0.9999999 6.49824e-4 4.43912e-5 -1 1.12149e-4 2.37785e-5 -1 -2.29683e-5 1.18717e-5 -1 -2.98081e-5 2.95497e-6 -1 -3.07822e-5 5.21389e-5 -1 -1.08408e-5 -6.99138e-6 -1 -3.30506e-5 0 -1 3.06383e-5 0 -1 -9.95524e-7 2.81149e-5 -1 1.41739e-4 0 -1 1.90783e-6 -2.5332e-5 -1 -1.55835e-5 -7.752e-6 -1 -2.45028e-5 -1.57614e-5 -1 -1.23066e-5 0 -1 2.44216e-7 0 -1 -1.24514e-5 0 -1 1.19439e-6 -1.79952e-5 -1 7.47425e-5 0 -1 1.41366e-6 -4.10007e-5 -1 3.53496e-7 0 -1 2.10319e-6 0 -1 -1.5749e-6 0 0 1 1.07279e-5 -1.93717e-4 -1 -8.45214e-6 0 -1 0.9998735 5.84959e-4 0.01589906 0.9996556 -0.005449414 0.0256738 0.9557093 -0.004911363 0.2942714 0.9553248 -0.004148125 0.2955291 0.861261 0.01447498 0.5079567 0.8120501 -0.02313041 0.5831293 0.6856623 0.02122557 0.7276104 0.5837814 -0.02743905 0.8114472 0.4256057 0.03343725 0.9042908 0.2388325 -0.03962635 0.9702519 0.04939788 0.04322332 0.9978435 -0.1401357 -0.03628098 0.9894675 -0.3653241 0.02947652 0.9304136 -0.4407948 -0.01316487 0.8975114 -0.6743375 0.009852647 0.7383576 -0.6858091 2.19015e-4 0.7277815 -0.865649 -0.00521183 0.5006244 -0.8822998 0.01302772 0.4705078 -0.9728431 -0.01759588 0.2307961 -0.980333 0.002341508 0.1973368 -0.9991923 0.0210886 -0.03420776 -0.9872046 -0.03041255 -0.1565321 -0.9418457 0.03041398 -0.3346664 -0.8938732 -0.02108651 -0.4478238 -0.7665767 -0.002343714 -0.6421486 -0.7209683 0.03691065 -0.6919844 -0.5637051 -0.0289331 -0.8254694 -0.3728222 0.02127075 -0.927659 -0.3269598 -0.004131436 -0.9450292 -0.03258556 0.005151152 -0.9994557 -0.01678693 -0.006174147 -0.9998401 0.3566355 -0.003778696 -0.9342361 0.3423552 0.005649447 -0.9395536 0.5830901 -0.003883838 -0.8123983 0.5709763 0.003077805 -0.8209608 0.7924776 0.005156636 -0.6098793 0.7918066 0.005942165 -0.6107429 0.9502677 -0.01724809 -0.3109564 0.9647963 0.01466172 -0.2625893 0.00320363 0.0183826 -0.999826 -0.0106669 0 -0.9999431 0 1 -1.03157e-5 0 1 -1.00214e-5 -0.9999945 0 -0.003337383 -0.998774 0.041579 0.02686411 0 1 4.81547e-6 0 1 -7.69563e-6 0 1 7.3454e-6 0 1 -1.3854e-5 0 1 -4.27492e-6 0 1 1.21911e-5 -0.008336663 0.9999416 -0.006878614 8.29944e-4 0.9999873 -0.004982531 0 1 6.62054e-6 0 1 -1.44125e-6 0 1 -2.47109e-6 0 1 1.7937e-5 0 1 -6.43114e-6 0 1 1.91955e-5 0 1 -5.25778e-6 0 1 1.05986e-5 0 1 -1.92569e-5 0 1 4.8747e-6 0 1 4.50692e-6 0 1 -4.39789e-6 0 1 -2.65798e-6 0 1 5.38448e-6 0 1 1.07875e-5 0 1 -8.232e-6 0 1 4.76784e-6 0 1 -6.93911e-6 0 1 -1.5761e-5 0 1 5.1098e-6 0 1 -5.65775e-6 0 1 2.3932e-6 0 1 5.29302e-7 0 1 -3.72024e-5 -0.9871738 -0.001604974 -0.1596413 -0.9631361 0.003635287 -0.2689903 -0.8227283 -0.00506407 -0.5684124 -0.6328956 0.005262911 -0.7742194 -0.3913133 -0.004502058 -0.9202466 -0.1841709 0.003862857 -0.9828866 0.1823529 -0.004998266 -0.9832205 0.3445111 0.004164516 -0.938773 0.7438643 -0.002979159 -0.668324 0.7837784 0.001138567 -0.6210396 0.9895575 -0.001069366 -0.1441348 0.9972266 0.003164112 -0.07435923 0.9547287 -0.003543853 0.2974569 0.860716 0.003750026 0.5090716 0.774613 -0.002039909 0.6324322 0.5240963 0.002143502 0.8516564 0.4540929 -0.001197695 0.8909536 0.1184133 6.49496e-4 0.9929642 0.1437528 -7.62419e-4 0.9896134 -0.2334647 0.001616597 0.972364 -0.3231525 -0.002089738 0.9463446 -0.5636748 0.001809418 0.8259949 -0.672119 -0.002666354 0.7404384 -0.8310616 0.00292927 0.5561727 -0.9443162 -0.003195941 0.3290241 -0.9774302 0.001897692 0.2112508 0 1 4.78944e-5 0 1 1.17852e-5 0 1 -1.96932e-5 0 1 5.87689e-6 0 1 1.05444e-5 0 1 -2.90023e-6 0 1 5.26072e-6 0 1 -4.92596e-6 0 1 6.88622e-5 -0.9983427 -0.002358794 -0.05750113 -0.9703905 0.003065526 -0.2415223 -0.9193233 -0.002300441 -0.3934966 -0.7117692 0.002387642 -0.7024094 -0.6503685 -0.002592086 -0.7596145 -0.1844753 0.003965139 -0.9828292 -0.05300098 -0.004898548 -0.9985825 0.4104892 0.004060566 -0.9118564 0.5395336 -0.003300368 -0.8419576 0.8006374 0.003050088 -0.5991414 0.8799061 -0.003864586 -0.475132 0.9935087 0.004126548 -0.1136812 0.9921809 -0.005613088 0.124682 0.9477997 0.003144681 0.3188508 0.6976206 -0.001351475 0.7164661 0.6965031 -0.001472771 0.7175524 0.1486699 0.001102089 0.9888863 0.1604892 0.00205928 0.9870355 -0.3416875 -0.003306031 0.9398078 -0.4775844 0.004023551 0.8785767 -0.7155914 -0.002861618 0.6985133 -0.8263475 0.002420246 0.5631555 -0.9367409 -0.002363502 0.3500155 -0.9774279 0.002447962 0.2112554 0 1 -9.3247e-6 0 1 1.30141e-5 0 1 2.08415e-6 0 1 -1.3894e-6 -0.9991403 0.003988862 -0.04126703 -0.9710598 -0.004988729 -0.2387844 -0.8728233 0.003996491 -0.4880201 -0.6643454 -0.003010809 -0.7474198 -0.5602496 0.00316137 -0.8283179 -0.2736649 -0.003832936 -0.9618175 0.08872884 4.38154e-4 -0.9960557 0.02738445 0.003826141 -0.9996178 0.542692 -0.001598954 -0.8399302 0.5630049 -2.3563e-5 -0.8264536 0.853699 0.00216794 -0.5207621 0.8931462 -0.001997172 -0.4497622 0.9955582 -9.33566e-5 -0.09414893 0.9979484 0.001449882 -0.06400823 0.9404296 -0.001112997 0.3399868 0.9253262 0.001377999 0.3791699 0.5994619 -0.002552986 0.8003993 0.552697 0.001389145 0.8333811 0.1215121 4.25721e-4 0.9925899 0.05865079 -0.002801001 0.9982746 -0.2579062 0.002833962 0.9661659 -0.4106159 -0.002593696 0.9118048 -0.6318695 0.001738548 0.7750729 -0.7040297 -0.001498997 0.710169 -0.8838242 0.002589285 0.4678122 -0.9425814 -0.003989279 0.3339531 0 1 -2.44153e-5 0 1 7.78853e-6 0 1 2.99172e-6 0 1 2.27941e-5 -0.9908626 -0.00331211 -0.1348356 -0.9724828 0.001684963 -0.2329686 -0.8150785 -0.001088619 -0.5793495 -0.7902006 9.94195e-4 -0.6128476 -0.4534549 -0.001757383 -0.8912776 -0.424053 1.84935e-4 -0.9056373 -0.04102218 0.001827597 -0.9991566 0.08850061 -0.004128932 -0.9960676 0.3887829 0.003970861 -0.9213209 0.5808894 -0.003414511 -0.8139753 0.7660718 0.002630054 -0.6427496 0.8648423 -0.002937972 -0.5020351 0.9671494 0.004075109 -0.2541759 0.9999249 -0.00415349 -0.01153218 0.9569338 0.004775822 0.2902669 0.9138256 -0.001432418 0.4061047 0.6938146 -0.002641558 0.7201489 0.5868013 0.004822134 0.8097168 0.2332556 -0.004152119 0.9724066 0.08303582 0.003479897 0.9965405 -0.3257184 -0.003023087 0.945462 -0.4082385 0.001414775 0.9128743 -0.7036672 0.001462221 0.7105282 -0.7295828 -6.64252e-4 0.6838922 -0.9173456 -0.002541542 0.3980836 -0.9627071 0.003972291 0.270517 0 1 -5.90793e-6 0 1 -2.28972e-6 0 1 -1.47907e-6 0 1 9.11624e-7 -0.9934571 7.66063e-5 -0.1142068 -0.975668 -0.005744278 -0.2191783 -0.9253759 0.004488289 -0.3790243 -0.8312327 -0.004606425 -0.5559056 -0.7197631 0.004334509 -0.6942062 -0.6372218 -0.003448843 -0.7706729 -0.4038776 0.005417883 -0.914797 -0.3385612 -0.002383172 -0.9409413 -0.06042587 -0.002749502 -0.998169 0.04281079 0.007424771 -0.9990557 0.2252703 -0.004777312 -0.9742846 0.4768348 0.003583848 -0.8789857 0.4558201 7.30313e-4 -0.8900716 0.7100064 -6.24606e-4 -0.704195 0.7189639 5.21219e-4 -0.6950472 0.8876531 -5.57887e-4 -0.4605123 0.9024904 0.002423644 -0.4307033 0.9831178 -0.003280758 -0.1829444 0.9990614 0.004603683 -0.04307168 0.9981114 -0.00207442 0.06139487 0.9426862 0.002057731 0.3336744 0.9430342 0.002165794 0.3326886 0.8136194 -0.004253983 0.5813823 0.7229486 0.006311416 0.690873 0.5468116 -0.005858123 0.8372352 0.3910422 0.005874514 0.920354 0.1807927 -0.005865156 0.9835038 0.003871977 0.005883157 0.9999752 -0.2133513 -0.005873858 0.9769579 -0.3839208 0.005888104 0.9233474 -0.5743163 -0.005878269 0.8186125 -0.7117246 0.005896091 0.7024339 -0.8460301 -0.005885303 0.5331026 -0.9155412 0.003758668 0.4022068 -0.9889529 -0.002881288 0.1482022 -0.9825811 0.001283526 0.1858301 0 1 9.24997e-6 0 1 -3.82562e-6 0 1 1.71693e-6 0 1 -1.33798e-6 0 1 -5.3377e-6 0 1 6.72798e-6 0 1 6.70136e-6 0 1 3.67218e-6 0 1 5.67788e-6 0 1 -5.42639e-6 0 1 1.20998e-5 0 1 -1.79716e-6 0 1 6.01907e-6 0 1 5.98561e-6 0 1 -7.16762e-6 0.9981421 0.001705586 0.06090599 0.01002848 0.04706084 -0.9988417 0.9870337 -0.00234282 0.1604959 0.9220152 0.001837432 0.3871496 0.9374693 -0.002647697 0.3480583 0.817978 0.003748416 0.5752372 0.7243592 -0.005882382 0.6893978 0.5588657 0.005893111 0.8292374 0.4016742 -0.005875289 0.9157639 0.2020927 0.005435943 0.9793514 0.01660913 -0.00546658 0.9998472 -0.1690454 0.005907535 0.9855906 -0.3710604 -0.006454586 0.9285864 -0.5513565 0.005919873 0.8342489 -0.7010834 -0.005468785 0.7130584 -0.8224155 0.005913138 0.5688567 -0.9189162 -0.00596261 0.3944081 -0.9817433 0.005289375 0.190137 -0.9995297 -0.005479574 0.03017628 -0.984053 0.005272746 -0.1777973 -0.9457986 -0.003747105 -0.324732 -0.8599764 0.002153217 -0.5103293 -0.826337 -0.001881659 -0.5631729 -0.6965636 0.003223657 -0.7174879 -0.59812 -0.004933059 -0.8013915 -0.4038752 0.005885541 -0.9147952 -0.2954753 -0.00525695 -0.955336 0.04283958 0.004049122 -0.9990738 0.06063175 0.001603484 -0.9981589 0.3673803 -0.004230618 -0.9300612 0.4558133 0.004927933 -0.8900618 0.6767199 -0.003785848 -0.7362309 0.7189594 0.001437187 -0.6950507 0.9022551 -1.22896e-4 -0.4312027 0.8912948 0.002827048 -0.4534157 0.9821285 -0.004550278 -0.1881569 0.7391346 0.04748505 0.6718819 0.9968187 0.002095997 -0.07967555 0 1 3.7669e-6 0 1 -1.05591e-5 0 1 1.73769e-5 0 1 -1.45512e-5 0 1 7.72961e-6 0 1 2.32113e-6 0 1 -1.32812e-5 0 1 -1.00814e-5 0 1 8.0734e-6 0 1 5.54535e-6 0 1 2.09175e-6 0 1 -7.69744e-6 0 1 1.36228e-5 0 1 3.46904e-6 0.001638352 0.9980961 0.06165695 -2.34991e-5 0.9832448 0.1822904 -1.97707e-4 0.9816114 0.1908904 -0.002263426 0.9812639 0.1926555 2.12183e-4 0.9139443 0.4058395 -3.97918e-4 0.8987493 0.4384629 -0.001893877 0.8954444 0.4451695 5.22753e-4 0.7509719 0.660334 -0.003675699 0.7644222 0.6447055 2.52688e-5 0.7365994 0.6763293 -0.00233978 0.7394459 0.6732119 -5.6357e-4 0.5584243 0.8295554 4.02415e-4 0.5279629 0.8492674 6.59144e-4 0.4650415 0.8852886 -2.87378e-5 0.4992346 0.8664669 -1.12763e-4 0.4949016 0.8689491 -0.001544296 0.4688172 0.8832939 -3.06e-5 0.4237887 0.9057611 4.54806e-5 0.4206331 0.9072309 1.56001e-5 0.1938404 0.9810332 -2.86641e-5 0.189812 0.9818205 0.0151568 0.7998813 0.5999668 0.0589562 0.950246 0.3058703 -0.07006931 0.9927429 0.09773397 -0.02687889 0.9082167 0.4176363 0.002451419 0.5940377 0.8044335 -5.11634e-4 0.5774423 0.8164315 0.001559257 0.6543875 0.7561578 0.001670479 0.8153568 0.5789564 0.002348721 0.9419317 0.3357964 -0.9955766 1.38566e-4 -0.09395456 -0.9994998 0.006033778 0.0310465 -0.97079 -0.00372684 -0.2399021 -0.9375895 0.003275573 -0.3477287 -0.8183178 -0.001880526 -0.5747631 -0.8193234 -0.001687705 -0.5733292 -0.5596652 0.001666665 -0.8287172 -0.5348001 -0.001607775 -0.8449772 -0.1951681 0.001586437 -0.9807686 -0.1675009 -0.001527249 -0.9858708 0.2161857 0.001641929 -0.9763509 0.2176167 0.001458287 -0.9760332 0.5291265 -0.003506541 -0.8485357 0.6232345 0.005114078 -0.7820183 0.7490335 -0.003965497 -0.6625202 0.8695092 0.005260705 -0.4938888 0.9382744 -0.00580269 -0.3458434 0.9930103 0.006287515 -0.1178603 0.9989788 -0.006178319 0.04475814 0.9531524 0.004839003 0.3024516 0.9278507 -0.001042902 0.3729505 0.8200046 -0.001226127 0.5723556 0.7947698 0.001852869 0.6069081 0.6249833 -0.001654744 0.7806365 0.6078904 5.66493e-4 0.7940207 0.2486577 -5.14674e-5 0.9685915 0.268908 0.003054678 0.9631611 -0.04454314 -0.003877341 0.999 -0.1743206 0.004533946 0.9846785 -0.2808923 -0.002317905 0.9597365 -0.4945407 0.003008425 0.8691494 -0.5233159 -7.62753e-5 0.8521388 -0.7105149 -0.002764344 0.7036768 -0.793718 0.006770372 0.6082483 -0.8942451 -0.0051952 0.4475475 -0.9812889 0.003666818 0.1925066 -0.979945 0.002960503 0.1992464 -0.999987 -0.001018106 -0.005021989 0 1 -1.76013e-5 0 1 -8.12876e-6 0 1 7.60659e-6 0 1 2.95578e-6 0 1 7.15848e-6 0 1 1.75052e-6 0 1 -1.40924e-5 0 1 2.16394e-5 0 1 1.0119e-5 0 1 -1.2602e-5 0 1 -9.00097e-6 0 1 -1.34988e-5 0 1 2.42687e-5 0 1 -3.77145e-6 -0.001033484 0.9999537 -0.009565293 -9.79253e-5 0.9999923 0.003952383 0 1 -3.45797e-6 0 1 7.84946e-6 0 1 6.70972e-7 0 1 -5.0684e-6 0 1 1.04783e-5 -5.20337e-4 0.9999999 -1.7337e-4 -5.20178e-4 1 0 0 1 7.98256e-6 0 1 -4.08524e-6 0 1 -1.25174e-5 -8.34342e-5 1 1.78317e-4 2.17073e-5 1 3.65836e-5 0 1 -9.05999e-7 1.57939e-5 1 4.58291e-5 0 1 -2.67575e-6 0 1 -6.84722e-6 1.59332e-6 1 8.80437e-5 0 1 1.38264e-5 0 1 -4.43425e-6 0 1 -4.44429e-6 0 1 1.27685e-5 0 1 -1.40186e-5 0 1 2.9359e-6 -0.004789829 0.9999886 5.22843e-5 6.57966e-4 0.9999999 1.76003e-5 0 1 1.2778e-6 0 1 -2.10276e-5 0 1 0 0 1 5.09172e-6 0 1 1.19573e-7 -5.52467e-5 0.9999985 -0.001783251 0 1 2.39306e-7 0 1 -2.92853e-6 -1.95773e-4 0.9999966 0.002620339 0 1 -4.94246e-6 -8.28032e-6 1 2.80444e-5 -8.9809e-6 1 2.40666e-5 -9.49226e-6 1 0 -2.83689e-6 1 1.15301e-4 -1.00465e-5 1 5.91561e-6 1.02226e-5 1 -4.36118e-6 0 1 3.2898e-7 4.03149e-5 1 2.6965e-4 0.001068294 0.9999994 2.71084e-4 0 1 -1.52292e-6 0 1 3.57971e-6 0 1 0 0 1 1.7282e-7 0 1 -1.77139e-6 0 1 -5.0738e-6 -5.8685e-4 0.9999999 -1.88307e-5 -1.06163e-5 0.9999906 -0.00434482 8.06046e-5 0.9999988 -0.001579821 0.007703065 0.9999704 -4.95868e-5 0.02883374 0.9994121 -0.01855069 -0.01519429 0.9998846 3.2676e-4 0.9973075 0.001566112 0.07331687 0.9996901 0.006160438 -0.02412074 0.9767216 -0.002577006 0.2144958 0.9426217 0.003596186 0.3338438 0.8605821 -0.004291892 0.5092938 0.7947671 0.002971589 0.6069074 0.6078903 0.002477943 0.7940173 0.6554317 -0.002007603 0.755252 0.4044447 -0.004488885 0.9145514 0.2486484 0.006945788 0.9685689 0.101168 -0.005296945 0.9948554 -0.1743155 0.004453182 0.9846798 -0.2710866 -0.004733383 0.9625434 -0.4945407 0.005394101 0.8691377 -0.6134102 -0.005020976 0.7897486 -0.7938014 0.005076587 0.608156 -0.8350493 -0.00209707 0.5501711 -0.9763863 -1.70102e-4 0.2160323 -0.9807505 0.002295672 0.1952517 -0.9921969 -0.001295506 -0.1246746 -0.9828543 0.003260791 -0.1843557 -0.9262447 -0.004082143 -0.3769008 -0.8483578 0.004968166 -0.5294002 -0.749036 -0.003662168 -0.6625193 -0.6298235 0.003742098 -0.7767293 -0.5291318 -0.003650665 -0.8485319 -0.2959921 0.00395298 -0.9551822 -0.2176103 -0.003342211 -0.9760301 0.09688764 0.003508388 -0.9952892 0.1675009 -0.003461599 -0.9858659 0.4746586 0.003450214 -0.8801633 0.5347958 -0.003399908 -0.8449746 0.7784088 0.003387928 -0.6277487 0.8193216 -0.003338038 -0.5733245 0.9535622 0.002827405 -0.3011829 0.9707947 -0.002073705 -0.2399028 0.9995111 0.003578782 0.03106307 0.9990504 0.001184701 -0.04355484 0 1 1.7576e-5 0 1 -3.57262e-6 0 1 -7.15973e-6 0 1 -3.09494e-6 0 1 2.18097e-6 0 1 7.2109e-6 0 1 -1.12423e-5 0 1 8.70752e-6 0 1 -7.0571e-6 0 1 -7.07459e-6 0 1 4.05655e-6 0 1 -1.0974e-5 0 1 -6.16779e-6 0 1 -8.35105e-6 0 1 -5.67015e-6 0 1 -4.03934e-6 -0.03959542 0.9992156 -6.29811e-4 -0.1739281 0.9847582 6.89863e-4 -0.3422505 0.9396085 -5.95748e-4 -0.3974216 0.9176362 2.5994e-4 -0.549292 0.8356305 -1.71976e-4 -0.5832064 0.8123239 3.73685e-4 -0.7233126 0.6905205 -6.38914e-4 -0.7838515 0.6209482 5.7246e-4 -0.8719296 0.4896312 -3.14355e-4 -0.8991433 0.4376544 2.78428e-4 -0.9412017 0.3378453 -1.5566e-4 -0.9492537 0.3144512 -0.006155967 -0.9423629 0.3345926 -1.41462e-4 -0.9664418 0.2568857 1.30252e-5 -0.9701425 0.242536 -7.10686e-5 -0.9839367 0.1785178 -3.369e-4 -0.995546 0.09427773 2.48589e-4 -0.01087337 0.9999395 -0.001668214 -0.01683884 0.9998543 -0.002843379 -0.9999992 0.001146495 -6.58378e-4 -0.9999991 5.14823e-4 -0.001250028 -0.999961 0.008385181 -0.002771854 -0.9999994 0.001063168 4.38164e-4 -0.999997 0.002471387 -1.72478e-4 -0.9999355 0.01133555 7.72981e-4 -0.9999799 0.006350636 -1.72478e-4 -0.9999945 -6.01573e-4 0.003277659 -0.9999942 0.003417193 -1.83054e-4 -0.008336842 0.9999644 -0.001356184 -0.02365505 0.9997188 0.001666903 0.9999982 -0.001013338 0.001629889 0.9999965 -0.002684056 -4.47511e-6 0.9999977 -0.00212866 2.64486e-4 0.9999991 -0.001389563 2.20647e-6 0.9999991 -0.00138992 2.31832e-6 0.999997 2.34076e-4 -0.002492427 -0.09380167 0.004722476 -0.9955798 -0.3465942 -0.003986358 -0.9380068 -0.5215727 0.002496182 -0.8532034 -0.726989 -0.001948058 -0.6866464 -0.8173037 0.002788782 -0.5762005 -0.9388675 -0.004092574 -0.3442546 -0.9967373 0.004696071 -0.08057808 -0.9884651 -0.003328502 0.1514124 -0.9236902 0.002464711 0.3831323 -0.8472124 -0.002390503 0.5312491 -0.7079648 0.002520501 0.7062432 -0.5187537 -0.003272116 0.8549175 -0.4007889 0.002273321 0.9161676 -0.005780398 -0.001549839 0.9999821 0.05571335 0.00184226 0.9984452 0.4415044 -0.002751886 0.8972549 0.5626324 0.003116548 0.8267014 0.7554529 -0.00225073 0.6551991 0.8730269 0.003105759 0.4876623 0.9454464 -0.003189027 0.3257623 0.999616 0.003205716 -0.02752685 0.9947794 -5.29933e-4 -0.1020485 0.8958192 -0.001287162 -0.444417 0.8516635 0.003369152 -0.5240781 0.5817965 -0.002872049 -0.8133294 0.4462814 0.003902196 -0.8948843 0.1863742 -0.004124045 -0.9824702 0 1 6.20771e-5 0 1 -2.19025e-5 0 1 3.01125e-5 0 1 1.82692e-5 0 1 -4.77076e-5 0 1 1.55711e-5 0 1 3.49769e-5 0 1 -1.90899e-5 -0.09580039 -0.003971815 -0.9953927 -0.1843543 8.69533e-4 -0.9828595 -0.5848611 3.74358e-4 -0.8111335 -0.5765477 0.001054167 -0.8170629 -0.8530445 -0.003253936 -0.521828 -0.9478034 0.004958212 -0.3188169 -0.9843075 -0.001645803 -0.1764544 -0.9761273 5.95889e-6 0.2171995 -0.9626639 0.002766013 0.2706858 -0.8426984 -0.002742469 0.538379 -0.7216355 0.002989053 0.6922668 -0.5187593 -0.003272593 0.8549141 -0.4007805 0.00227344 0.9161713 -0.005798518 -0.00154972 0.9999821 0.04721701 0.001373827 0.9988837 0.4790198 -0.002364873 0.8778009 0.5351155 0.001579165 0.8447775 0.8744555 5.52602e-4 0.4851057 0.8935931 -0.002351224 0.4488719 0.9941811 0.001850306 -0.107706 0.9963642 0.003523528 -0.08512413 0.8958153 -0.003932058 -0.4444093 0.7447149 0.005136787 -0.6673629 0.5303134 -0.005714952 -0.8477824 0.3053338 0.004973351 -0.9522325 0 1 2.54629e-5 0 1 -8.71813e-6 0 1 -1.02053e-5 -0.2690048 -0.003683567 -0.9631319 -0.3526029 8.20487e-4 -0.9357727 -0.6744958 0.002791285 -0.7382735 -0.7847962 -0.005021691 -0.6197336 -0.934859 0.003899276 -0.3549978 -0.9907501 -0.003208041 -0.1356614 -0.9907211 0.003601431 0.1358628 -0.9662854 -0.0018422 0.2574669 -0.7884969 -5.71565e-4 0.6150386 -0.7682995 0.00134176 0.6400893 -0.4210253 -3.77298e-5 0.907049 -0.4088672 -8.44445e-4 0.9125934 0.02775377 9.64609e-5 0.9996148 0.0548489 0.001398503 0.9984937 0.3507159 -0.001720845 0.9364804 0.4462946 0.002090394 0.8948838 0.7590889 0.001236259 0.650986 0.7217069 -0.00148195 0.6921973 0.9581278 -0.00222975 0.2863324 0.9801027 0.002688765 0.1984727 0.9724025 -0.00228101 -0.2332985 0.9451134 0.003093481 -0.3267279 0.7195702 -0.004169106 -0.6944073 0.5840088 0.005223035 -0.8117306 0.2497938 -0.004476428 -0.9682887 0.05330324 0.003435611 -0.9985725 0 1 -3.50376e-5 0 1 -4.60075e-6 0 1 -2.08302e-5 -0.2442338 -0.003568291 -0.9697099 -0.3754374 0.002635776 -0.926844 -0.7045248 -0.001532018 -0.7096778 -0.6838449 2.01071e-4 -0.7296275 -0.930038 -7.30868e-4 -0.3674628 -0.9309295 -5.90814e-4 -0.3651986 -0.9998487 0.002246439 0.01724934 -0.9880048 -0.004084348 0.1543697 -0.8641199 0.004830896 0.5032628 -0.7942224 -0.001757144 0.6076248 -0.5465935 -0.002833127 0.8373934 -0.3996911 0.004884243 0.9166369 -0.1079518 -0.003317415 0.9941506 0.07165265 0.002508759 0.9974266 0.3268423 -0.002647101 0.9450752 0.4986137 0.004252851 0.866814 0.7390287 -0.00580281 0.673649 0.9063807 0.005337893 0.4224283 0.9862018 -0.00450921 0.1654866 0.9991554 0.002858936 -0.04099237 0.93596 -0.001776576 -0.3521019 0.916078 4.75203e-4 -0.4010001 0.6692541 0.001802682 -0.7430315 0.7018104 -7.09312e-4 -0.7123635 0.2497985 -0.002721309 -0.9682941 0.1386374 0.003669381 -0.9903365 0 1 -3.3074e-5 0 1 1.24827e-5 0 1 -2.36314e-5 0.09608459 -0.9953731 3.12243e-4 0.120834 -0.9926728 -1.22273e-5 0.2263298 -0.9740507 3.46219e-4 0.2697666 -0.9629257 -1.74389e-4 0.3843153 -0.9232019 4.04819e-4 0.4205535 -0.9072679 -1.64697e-4 0.5419803 -0.8403912 2.53605e-4 0.5681347 -0.8229356 -2.2806e-4 0.6665486 -0.7454616 1.87166e-4 0.6933264 -0.7206237 -3.18335e-4 0.7713432 -0.6364195 -1.63042e-6 0.7956102 -0.6058087 -4.9412e-4 0.8603745 -0.5096625 1.39072e-4 0.8705018 -0.4921653 -1.99655e-4 0.9341369 -0.3569152 -1.61257e-4 0.9380723 -0.3464395 -3.4425e-4 0.972334 -0.2335951 1.95492e-4 0.9787225 -0.205188 -2.91114e-4 0.9907689 -0.001644253 -0.135552 0.985692 0.001356244 -0.1685511 0.9304819 -0.001967966 -0.3663327 0.9094503 0.002650797 -0.4158043 0.801741 -0.002460181 -0.5976666 0.7614824 0.00212562 -0.648182 0.6538463 -0.00161904 -0.7566257 0.5821282 0.002750575 -0.8130924 0.4773883 -0.003578603 -0.8786853 0.3189449 0.003535866 -0.9477667 0.1928724 -0.003692567 -0.9812169 0.07981121 0.003045439 -0.9968054 -0.1454326 -0.003723442 -0.9893612 -0.1861301 3.13584e-4 -0.9825251 -0.422806 0.002967715 -0.9062154 -0.5076195 -0.006080567 -0.8615599 -0.7184594 0.006082355 -0.6955424 -0.8015881 -0.006061434 -0.597846 -0.9225762 0.004938364 -0.3857834 -0.9705422 -0.005535125 -0.2408679 -0.992547 0.003053545 -0.1218252 -0.9893671 -0.001357436 0.1454337 -0.9914101 4.5503e-4 0.1307895 -0.9100327 -0.001948773 0.4145319 -0.8915131 0.002512395 0.4529879 -0.7252368 0.003037989 0.6884929 -0.7046024 -9.56426e-4 0.7096017 -0.5410691 -0.003582715 0.8409706 -0.3959937 0.004401147 0.9182428 -0.3626312 6.20385e-4 0.9319326 -0.1076501 -0.002103507 0.9941866 -0.08109772 8.13374e-4 0.9967058 0.1211597 0.001139581 0.9926324 0.1564589 -0.002411544 0.9876816 0.3870645 0.001401305 0.9220517 0.3891774 0.001651883 0.9211614 0.5834775 -0.001868128 0.8121272 0.660878 0.005319893 0.7504746 0.7324008 -0.002916097 0.6808676 0.8754844 -0.001743555 0.4832434 0.9071193 0.006017982 0.4208305 0.9554692 -0.002212464 0.2950826 0.9932404 -7.89605e-4 0.1160734 0.9962903 0.002496719 0.08601993 -0.3211995 -0.00144428 -0.9470105 -0.4521703 0.005284786 -0.8919161 -0.5031166 -0.001580238 -0.8642172 -0.7272632 -0.002222478 -0.6863552 -0.7826932 0.006357848 -0.6223753 -0.8727348 -0.003925204 -0.4881789 -0.9618088 9.48644e-4 -0.2737208 -0.9719915 0.004941225 -0.2349639 -0.9986654 -0.003937542 -0.05149811 -0.9819865 0.003628134 0.1889161 -0.9852485 0.001200497 0.171126 -0.8525649 -0.001223564 0.52262 -0.8423158 0.001310646 0.5389828 -0.5872789 -0.00134474 0.8093836 -0.5699108 0.001434266 0.8217054 -0.2323457 -0.001468122 0.9726322 -0.2339317 -0.00168085 0.9722517 0.05325686 0.003384709 0.9985752 0.1226668 -0.00266242 0.9924443 0.3309173 1.20925e-4 0.9436599 0.3870186 0.005077838 0.9220579 0.5244297 -0.003849208 0.8514452 0.6812664 -9.13942e-4 0.7320351 0.7383428 0.007683992 0.674382 0.8555004 -0.005269169 0.5177753 0.9522688 0.003357112 0.3052425 0.9441247 -4.40327e-4 0.3295882 0.9984163 0.001521646 0.05623823 0.9995152 -0.001738429 0.03108769 0.9688618 -0.001994788 -0.2475943 0.9467867 0.007037401 -0.3217849 0.853154 -0.0055781 -0.5216294 0.7609683 0.006622314 -0.6487553 0.6788404 -0.003277182 -0.7342786 0.5346319 -0.001284837 -0.8450841 0.4778698 0.004697799 -0.8784181 0.3796035 -0.001339673 -0.9251483 0.1279045 -0.1512583 -0.9801844 0.4274805 -0.1356573 -0.8937883 0.5247657 -0.09977698 -0.8453789 0.2250086 -0.2333829 -0.9459935 0.2405854 -0.2308117 -0.9427856 0.308255 -0.2529057 -0.9170702 0.1444139 -0.3356859 -0.9308382 0.3869569 -0.218324 -0.895879 0.5654996 -0.1539865 -0.8102459 0.6830196 -0.09672224 -0.7239676 0.3263339 -0.3929806 -0.8596933 0.7185998 -0.1573304 -0.6773932 0.5085763 -0.3050093 -0.805183 0.5538164 -0.2763126 -0.7854546 0.1846206 -0.4585973 -0.8692548 0.6218172 -0.3013368 -0.722869 0.2153157 -0.4726148 -0.8545609 0.7125826 -0.1938146 -0.6742863 0.4150902 -0.4217556 -0.8061157 0.4561863 -0.4061518 -0.7917922 0.8138394 -0.08419871 -0.5749573 0.8404405 -0.118956 -0.5286864 0.6344249 -0.3809295 -0.6726052 0.2507196 -0.5710146 -0.7817174 0.3196849 -0.5780997 -0.7507346 0.1785467 -0.626239 -0.758911 0.8897503 -0.08585 -0.4483014 0.521896 -0.4736001 -0.7094559 0.6992895 -0.4124787 -0.5838285 0.3592572 -0.6088845 -0.707244 0.783169 -0.3335472 -0.5247788 0.7846166 -0.3297215 -0.5250339 0.4966768 -0.5756182 -0.6495968 0.8272592 -0.2715188 -0.4918534 0.6791638 -0.4925256 -0.5442014 0.1439473 -0.7366889 -0.6607335 0.9170177 -0.176609 -0.3576142 0.5326292 -0.6068001 -0.5899999 0.572719 -0.6012793 -0.5571858 0.1580981 -0.7499823 -0.6422863 0.8923354 -0.2503137 -0.3756071 0.312591 -0.7341144 -0.602796 0.9484407 -0.1415795 -0.2835763 0.8088366 -0.4236427 -0.4078115 0.8923414 -0.3241832 -0.3140577 0.9602261 -0.1999441 -0.1949056 0.3489414 -0.7636384 -0.5432276 0.4118511 -0.7482977 -0.5200281 0.122727 -0.8187742 -0.5608448 0.8563176 -0.3974598 -0.3297666 0.9327886 -0.2940127 -0.2084752 0.7446777 -0.5296724 -0.4060818 0.6160172 -0.6660807 -0.4205466 0.2861048 -0.8313062 -0.4765229 0.7300733 -0.5799104 -0.3615203 0.9808577 -0.1619539 -0.1081159 0.1763617 -0.8565479 -0.4849973 0.8361734 -0.4980252 -0.2297498 0.5588995 -0.7413729 -0.3714802 0.7688868 -0.5879191 -0.2513253 0.4968096 -0.7775941 -0.3853929 0.8665759 -0.468542 -0.1717987 0.9220195 -0.3607564 -0.1404815 0.1522155 -0.9051236 -0.3969657 0.1183882 -0.918384 -0.3775644 0.3326814 -0.8826539 -0.332032 0.7513465 -0.6262409 -0.2080891 0.4357061 -0.8378428 -0.328907 0.332208 -0.8826371 -0.3325502 0.6813124 -0.711444 -0.1722235 0.6213341 -0.7577946 -0.199227 0.1005874 -0.9584022 -0.2671096 0.4820508 -0.85848 -0.175041 0.3122388 -0.9304302 -0.191851 0.5534065 -0.8198385 -0.1469907 0.4176229 -0.8979888 -0.1385909 0.1899747 -0.96952 -0.1547275 0.2396147 -0.9595013 -0.1481295 0.1172339 -0.9896492 -0.08276861 0.8603209 -0.5033901 0.08029109 0.9156128 -0.3803201 0.1304216 0.9665019 -0.1956196 0.1661538 0.8821062 -0.4405845 0.1666553 0.9619916 -0.2045307 0.1809407 0.7863056 -0.6110874 0.09108114 0.8704729 -0.4440847 0.2122874 0.9382892 -0.2042745 0.2790795 0.678842 -0.7104281 0.1856489 0.7393594 -0.6502166 0.1748316 0.8718413 -0.3793256 0.3098464 0.922215 -0.2304785 0.3104824 0.7893908 -0.5482239 0.2762477 0.6339378 -0.7380913 0.2309637 0.5306999 -0.8303896 0.1697372 0.6222499 -0.7337942 0.2726742 0.3636534 -0.9205054 0.1429199 0.8609941 -0.2147821 0.46104 0.80354 -0.4137243 0.4279672 0.4223726 -0.8774602 0.2272994 0.73833 -0.530506 0.4164519 0.8031532 -0.3891096 0.4511527 0.2483794 -0.9581381 0.1424045 0.8427613 -0.2364669 0.4835668 0.6225848 -0.6845588 0.379167 0.72907 -0.5380011 0.4230979 0.4154655 -0.8718922 0.2592152 0.4414172 -0.8392645 0.3174685 0.08590042 -0.9789146 0.1853302 0.1610845 -0.9616789 0.2218684 0.5478252 -0.6953566 0.4651526 0.7722105 -0.232773 0.591192 0.6383011 -0.5301085 0.5581727 0.7300032 -0.3450326 0.5899557 0.2606699 -0.9033309 0.3406531 0.7502748 -0.1721317 0.6383248 0.4246177 -0.7984648 0.4267947 0.1786472 -0.9370635 0.2999954 0.533297 -0.6424136 0.5503628 0.5689186 -0.5857032 0.5773071 0.66896 -0.3966346 0.6286283 0.7098395 -0.1718549 0.6830768 0.3586688 -0.8023766 0.4770206 0.09976273 -0.9199826 0.3790509 0.2802914 -0.8336435 0.4758942 0.3962519 -0.6874058 0.6086524 0.206715 -0.8271937 0.5225128 0.5810356 -0.2925505 0.7594814 0.5749493 -0.3473391 0.740803 0.3707944 -0.6753708 0.637484 0.1744495 -0.8388174 0.5157061 0.6279397 -0.09528106 0.7724075 0.4577825 -0.5099015 0.7283102 0.5498024 -0.2152431 0.807086 0.4176089 -0.5472326 0.7253546 0.4762753 -0.4250675 0.7697269 0.2155939 -0.7174176 0.6624435 0.245146 -0.6904695 0.6805552 0.4667421 -0.1980444 0.8619341 0.3916002 -0.3783298 0.8387585 0.4225807 -0.2212653 0.8789011 0.2173529 -0.561952 0.7981025 0.3081763 -0.3984467 0.8638679 0.2289596 -0.5740173 0.7861816 0.349326 -0.1968876 0.9160823 0.1518874 -0.5630578 0.8123399 0.2348411 -0.2428053 0.9412201 0.2098224 -0.3183629 0.9244564 0.1455639 -0.3468669 0.9265498 0.1788604 -0.1577693 0.9711426 0.06793147 -0.4593083 0.8856756 -0.9249324 0.3464252 -0.156492 -0.9230536 0.3504602 -0.1585866 -0.9646647 0.2089 -0.1605706 -0.9611698 0.1249744 -0.2460367 -0.8865398 0.3663353 -0.28257 -0.8114551 0.463921 -0.3554123 -0.9083669 0.1855555 -0.3747519 -0.8778277 0.1663393 -0.4491657 -0.7886003 0.3774382 -0.4854379 -0.8177378 0.2408282 -0.5227876 -0.6525 0.4720206 -0.5928239 -0.7387977 0.1977165 -0.6442719 -0.6041292 0.3809249 -0.6999459 -0.6153326 0.3038392 -0.7273566 -0.4669209 0.4882004 -0.7373231 -0.5543864 0.2553452 -0.7921203 -0.4427886 0.2601202 -0.8580652 -0.3958495 0.3570172 -0.8460745 -0.4121866 0.2108757 -0.8863599 -0.2483043 0.4183223 -0.8736999 -0.2141951 0.2042505 -0.9551975 -0.1856248 0.3064979 -0.9335966 -0.2072882 0.1918109 -0.9592915 0 1 5.38074e-6 0 1 -8.7984e-6 0 1 2.23039e-5 0 1 -3.63274e-6 0 1 -5.43357e-6 0 1 -4.10289e-6 0 1 -6.02631e-6 0 1 1.7795e-5 0 1 1.00289e-5 0 1 -9.22067e-6 0 1 8.15836e-6 0 1 5.70252e-6 0 1 -3.61747e-6 0 1 1.09435e-5 0 1 -1.48297e-5 0 1 -1.71407e-6 0 1 1.36438e-5 0 1 6.57445e-6 0 1 -9.84853e-6 -0.2182777 0.1885632 0.9574961 -0.3388792 0.1394068 0.9304444 -0.5450625 0.06967061 0.8354956 -0.434528 0.2099577 0.8758444 -0.4374064 0.2438496 0.8655709 -0.6326448 0.1753409 0.7543316 -0.599469 0.3047452 0.740113 -0.6170598 0.2851941 0.7334177 -0.7687419 0.06366306 0.6363826 -0.7921238 0.2631054 0.550741 -0.7819397 0.2460867 0.5727231 -0.7695648 0.4317154 0.4705229 -0.8945439 0.1829519 0.4078235 -0.9084437 0.2611426 0.3263963 -0.9799747 0.1165826 0.1614252 -0.9371704 0.2801911 0.2078571 -0.9280769 0.333059 0.1665688 -0.9752156 6.58104e-4 0.221256 -0.9712011 -7.24041e-4 0.23826 -0.9199289 0.003984212 0.3920653 -0.8513398 -0.005064427 0.5245902 -0.7747198 0.007131814 0.6322645 -0.5413039 -0.001016497 0.8408265 -0.5653174 -0.005056321 0.8248581 -0.3526672 0.00477451 0.9357367 -0.1704393 -0.001712143 0.9853667 -0.2093045 -0.00284785 0.9778465 0.9961076 -0.003457486 -0.08807796 0.9719853 0.003225743 -0.2350196 0.9579974 -0.002077817 -0.2867694 0.9016831 -0.002096652 -0.4323925 0.870434 0.00353837 -0.4922726 0.8129177 -0.003240048 -0.5823696 0.7015588 0.003468871 -0.7126031 0.6818364 -1.74926e-4 -0.7315047 0.5342512 -0.005124568 -0.8453102 0.3615564 -0.00171566 -0.9323487 0.4208049 0.004558324 -0.9071398 0.2904528 -0.003831267 -0.9568817 0.1514195 -0.001059949 -0.988469 0.17553 7.11708e-4 -0.9844738 0.2114247 -0.005558609 0.9773785 0.3462373 0.00171113 0.9381454 0.337387 5.34683e-4 0.941366 0.4625926 -0.003181517 0.8865653 0.5548986 0.002129316 0.8319154 0.6221033 -0.004559218 0.782922 0.7567233 0.002833425 0.6537292 0.7922268 -0.003061413 0.6102191 0.8787595 -0.002886354 0.4772561 0.8954514 4.36647e-4 0.445159 0.9436052 -0.003555059 0.3310537 0.9744449 0.002842247 0.2246091 0.9924215 -0.004256725 0.1228069 -0.1380097 6.55711e-4 -0.9904307 -0.2118257 0.003678977 -0.9773005 -0.3226647 -0.002693355 -0.9465095 -0.4343072 0.005483329 -0.9007482 -0.60025 7.55093e-4 -0.7998123 -0.6394329 -0.003607988 -0.7688384 -0.7247611 0.004923462 -0.6889827 -0.8855058 -0.00437504 -0.4646077 -0.8909199 -0.002632021 -0.454153 -0.9712695 0.006560623 -0.2378917 -0.9926 -5.54177e-4 -0.1214284 -0.9906023 0.1367346 0.003296136 -0.9999984 9.37646e-6 0.001796782 -0.9999797 0.006356477 4.57412e-4 -0.9999358 0.01133036 4.38147e-4 -0.9999649 0.008384346 -1.0279e-4 -0.02365511 0.9997199 8.14283e-4 -0.01087331 0.9999396 -0.00158739 6.26048e-4 0.002815425 0.9999959 1.345e-4 -9.4687e-4 0.9999996 3.69764e-4 0.001151084 -0.9999993 5.08899e-4 -0.003747522 -0.9999929 -0.00521773 0.001151084 -0.9999858 -0.00462526 1.69744e-5 -0.9999893 4.50376e-4 -0.003103613 -0.9999951 -1.31236e-4 0.00235188 -0.9999973 -1.60743e-4 0.9994642 -0.03273123 -7.2024e-5 0.9993309 -0.03657698 0.001918613 0.9886853 -0.1499928 -0.002538859 0.9623522 -0.2717941 0.001411378 0.9330123 -0.359842 3.22959e-4 0.9562752 -0.2924681 -5.33077e-4 0.940993 -0.3384257 5.79343e-4 0.8203144 -0.5719125 4.73664e-4 0.8625028 -0.5060521 -6.04344e-4 0.8164305 -0.5774435 -9.63473e-4 0.805191 -0.5930147 0.002923369 0.7156047 -0.6984993 1.90605e-4 0.66082 -0.7505446 6.94765e-4 0.6917084 -0.7221767 -4.99147e-4 0.638673 -0.7694782 1.02978e-4 0.6268756 -0.7791193 -2.01888e-5 0.6191502 -0.7852727 -6.15537e-5 0.6063357 -0.7952089 4.52351e-5 0.6614939 -0.7499505 -1.74232e-4 0.6190566 -0.7853464 -1.88749e-4 0.4801052 -0.8772109 2.31012e-4 0.4395039 -0.8982407 -0.01421684 0.3412137 -0.9398784 -4.6635e-5 0.3202567 -0.9473308 -1.6231e-5 0.3084727 -0.9512333 8.43205e-5 0.2406491 -0.9706122 2.38664e-5 0.2139213 -0.9768509 4.74767e-5 0.1839482 -0.982936 1.30036e-4 0.1686582 -0.9856747 0.02196812 0.9582955 -0.2849337 0.006325304 0.8417502 -0.5398303 -9.65323e-4 0.6663347 -0.7456523 -0.004307746 0.7697902 -0.6382824 -0.01103907 0.8745801 -0.4847555 -0.05139964 0.976099 -0.2111612 -3.59267e-4 -0.9925191 0.1220898 2.75015e-4 -0.9792782 0.2025203 -2.18723e-4 -0.9631112 0.269104 2.14719e-4 -0.9205814 0.3905508 -3.15265e-4 -0.8975266 0.4409604 4.18321e-4 -0.8355292 0.549446 -2.61974e-4 -0.7718456 0.63581 4.42501e-4 -0.7247123 0.6890515 1.67163e-4 -0.6424291 0.7663453 -2.70674e-4 -0.6150488 0.788489 1.41258e-4 -0.4590801 0.888395 -1.52801e-4 -0.4822221 0.8760489 -3.00129e-4 -0.3442211 0.9388886 8.88639e-5 -0.2903969 0.9569063 -1.83978e-4 -0.1991526 0.9799685 3.08872e-4 -0.1498069 0.9887153 1.22208e-4 -1 1.14388e-4 1.07628e-4 -1 2.74247e-4 1.3215e-4 -1 4.94376e-5 3.82048e-5 -0.9999994 0.001157462 1.401e-4 -1 7.42711e-6 1.47713e-4 -1 -3.97027e-5 1.61876e-4 -1 -8.9444e-5 1.25873e-4 -1 4.1795e-5 3.38946e-5 -1 -3.23173e-5 1.96477e-5 -1 -5.59284e-5 -4.35498e-5 -1 4.80999e-7 -4.07963e-5 -1 3.18316e-5 -5.29758e-5 -1 -2.47369e-5 -4.90154e-5 -1 -2.35873e-5 -3.83827e-5 -1 8.09476e-5 -3.50133e-5 -1 6.32684e-5 -4.59571e-5 -1 6.7359e-6 -1.05306e-4 -1 -2.23878e-4 -1.61919e-4 -1 -1.68166e-4 -1.30041e-4 -1 -1.94238e-4 -1.04267e-4 -1 -2.22349e-4 -1.53794e-5 -1 -3.10825e-4 3.7567e-5 -0.9999994 0.001182854 0.03390169 0.999374 0.01011651 0 1 -9.74475e-6 0 1 -1.62515e-6 0 1 1.24402e-5 0 1 0 0 1 9.0803e-6 0 1 -4.86919e-6 0 1 -5.03923e-6 -5.45501e-4 0.007509887 0.9999718 -4.08475e-4 0.003751277 0.999993 0 0.007509946 0.9999719 -0.002496421 0 0.999997 0.9999998 0 -6.4179e-4 0.9999967 0.002582907 0 2.87984e-4 -9.30688e-4 -0.9999995 1.63821e-4 0 -1 0 -0.005561172 -0.9999846 -0.009213924 0 -0.9999576 -0.005856812 0.001809298 -0.9999813 5.72606e-5 -0.006000995 -0.999982 0 -1.86265e-6 1 0 5.32185e-7 1 -1.62316e-6 0 1 -0.9999819 0 -0.006022155 -0.9999929 -0.003792762 0 -0.9999884 0.001737833 -0.004516959 -0.9999977 -0.002084493 -5.21139e-4 -0.9911463 -0.005237817 0.1326712 -0.9419375 0.002276837 0.3357809 -0.943365 0.001743853 0.331752 -0.896035 -0.002966344 0.4439737 -0.8251004 0.001221239 0.5649849 -0.8096138 -0.001260161 0.5869618 -0.6676245 0.001394212 0.7444969 -0.6494956 -0.00193566 0.7603629 -0.4539744 -0.001836538 0.8910129 -0.4133574 0.003325581 0.9105628 -0.2705832 -0.003469467 0.9626904 -0.1755205 0.001356601 0.9844749 -0.1183962 -0.002232372 0.9929639 0.6156985 0.002368271 0.7879782 0.731496 0.001816987 0.6818434 0.6992171 -0.001751482 0.7149072 -0.6618728 -0.003828883 -0.7496065 -0.615843 4.0163e-4 -0.7878688 -0.7314575 -0.001019537 -0.6818863 -0.7234711 -0.001978039 -0.690352 1 7.26923e-7 0 0 1 -5.66844e-6 0 1 8.01806e-6 0 1 2.40936e-5 0 1 -1.89949e-5 0 1 3.72132e-6 0 1 2.4433e-5 0 1 -1.21522e-6 0 1 8.37307e-6 0 1 -3.29651e-6 0 1 -1.94207e-5 0 1 -4.70182e-6 0 1 -5.42238e-6 0 1 3.07518e-6 0 1 -6.81424e-6 0 1 -3.29899e-6 0 1 -5.29372e-6 0.9999988 0.00140661 -7.22541e-4 0.9998642 0.01157522 -0.01173943 -1.63801e-4 -0.001229405 0.9999993 -8.82544e-4 0.006009459 0.9999816 0 0.00270766 0.9999964 0.07230633 0.005993783 0.9973645 0.01671314 -0.009644269 0.9998138 8.56281e-6 0.002642154 0.9999966 0 1 -2.39504e-6 0 1 -2.81795e-6 0 1 2.40982e-5 0 1 -6.75546e-6 0 1 4.84515e-6 0 1 4.23672e-6 0 1 -6.19414e-6 0 1 5.54427e-6 0 1 -5.30972e-6 0 1 -6.79208e-7 0 1 5.58008e-6 0 1 -9.03681e-6 0 1 6.42753e-5 -0.08784347 -0.003735005 -0.9961273 -0.2964287 4.3232e-4 -0.9550549 -0.3130694 0.002748191 -0.9497263 -0.4922477 -0.004733204 -0.8704423 -0.5683066 0.001839816 -0.822815 -0.6531813 -0.00409013 -0.7571907 -0.7331317 0.002984702 -0.6800803 -0.8113522 -0.003498613 -0.5845472 -0.8635964 0.001109659 -0.5041825 -0.8881727 -0.002167105 -0.4595047 -0.9626412 -0.001999914 -0.2707728 -0.9548148 0.001426935 -0.2971981 -0.9892269 -0.004384636 -0.1463252 0 -2.48353e-6 -1 0 3.7253e-6 -1 -8.76506e-6 0 -1 0.9999925 0.00387305 0 0.9999926 0.003870725 0 0.9999967 0.002581715 0 0.9999994 0.001106262 2.76602e-4 0.9999893 0.003441512 0.003081738 0.9999946 0.003310859 0 0.9999967 0.001847863 0.001773655 0.9999981 0.00192517 4.81222e-4 -0.921586 -0.002126336 0.3881684 -0.9328548 4.72416e-4 0.3602522 -0.8081136 0.004367947 0.5890104 -0.7595741 -0.00399816 0.6504086 -0.5565372 0.001506745 0.8308213 -0.5609598 9.223e-4 0.8278427 -0.3333653 -6.90214e-4 0.9427975 -0.3132157 9.68062e-4 0.9496815 -0.08094543 -0.001607716 0.9967172 -0.0332058 0.003260254 0.9994432 0.3018608 -0.004083514 0.9533433 0.3656396 0.004262626 0.9307469 0.6321304 -0.003454864 0.7748544 0.6728408 0.001285314 0.7397862 0.7443394 6.25877e-4 0.6678013 0.8125694 -9.48652e-4 0.5828638 0.8463959 0.007628202 0.5324999 0.927561 -0.01067501 0.3735194 0.9854542 0.01186704 0.1695269 0.9996314 -0.01094496 0.02484887 0.9847117 0.00960505 -0.1739273 0.9629772 -0.005227029 -0.2695325 0.889736 -0.004699766 -0.4564512 0.8469219 0.009933412 -0.5316247 0.736441 -0.008406102 -0.6764496 0.7243574 -0.005499422 -0.6894029 0.5495644 0.007880508 -0.8354144 0.5037223 0.001185774 -0.8638648 0.3209812 -0.002943933 -0.947081 -2.97561e-5 -0.990868 -0.1348356 1.38286e-4 -0.993935 -0.1099693 -5.92895e-5 -0.960888 -0.2769375 1.96906e-4 -0.967047 -0.2545983 9.38799e-5 -0.9046954 -0.4260591 -7.37205e-6 -0.9002347 -0.435405 -3.00909e-6 -0.8308898 -0.5564371 2.49071e-5 -0.8323142 -0.5543041 1.54026e-4 -0.7399838 -0.6726248 -1.07245e-4 -0.7252401 -0.6884962 4.59156e-6 -0.6199092 -0.7846736 -1.40432e-4 -0.6099363 -0.7924506 -9.77619e-7 -0.5000898 -0.8659737 -2.35954e-5 -0.4983969 -0.866949 9.24464e-5 -0.3471728 -0.9378013 -8.15066e-6 -0.3396328 -0.9405581 -1.78198e-4 -0.2000479 -0.9797862 2.72786e-4 -0.1585011 -0.9873588 -0.9433429 -0.1343913 -0.3033864 -0.9837125 -0.1583325 -0.08509236 -0.9572935 -0.2557006 -0.1349313 -0.9343011 -0.2326135 -0.2701343 -0.893743 -0.1159256 -0.4333415 -0.9522607 -0.263491 -0.1541821 -0.784219 -0.1158311 -0.6095768 -0.8995146 -0.2826249 -0.3331618 -0.8455716 -0.2314146 -0.4810988 -0.8595498 -0.2700232 -0.4338915 -0.8794556 -0.4494943 -0.1565656 -0.7786041 -0.2265397 -0.585197 -0.786674 -0.2444036 -0.5669313 -0.6677976 -0.08666121 -0.7392808 -0.8398448 -0.4484872 -0.3058105 -0.8379344 -0.4888501 -0.2426756 -0.6248978 -0.2239495 -0.7478966 -0.7920045 -0.4438366 -0.4192113 -0.6204128 -0.2278769 -0.75044 -0.7023485 -0.4300292 -0.5672578 -0.7320356 -0.4810439 -0.4824113 -0.4727733 -0.1328695 -0.8711093 -0.760039 -0.6072461 -0.2315018 -0.6327946 -0.4462898 -0.6327689 -0.7434293 -0.6236371 -0.2416396 -0.5632791 -0.3473257 -0.749721 -0.695422 -0.6400564 -0.3266742 -0.6732175 -0.5971053 -0.4361692 -0.6679703 -0.7252344 -0.1668853 -0.3943862 -0.1983527 -0.8972824 -0.4953984 -0.3722256 -0.784875 -0.3871983 -0.2601064 -0.8845463 -0.5652652 -0.6518185 -0.5055769 -0.2926369 -0.1300619 -0.9473372 -0.5276261 -0.5866053 -0.6144144 -0.6103863 -0.7693482 -0.1884993 -0.433402 -0.4429114 -0.7848517 -0.5381731 -0.6491575 -0.537554 -0.3063672 -0.3263455 -0.8942247 -0.4440841 -0.5832119 -0.6801862 -0.5645075 -0.7723662 -0.2911733 -0.5430529 -0.8324128 -0.1103743 -0.5101829 -0.7959381 -0.3258775 -0.1795674 -0.2040353 -0.962354 -0.3030197 -0.4519012 -0.8390259 -0.190147 -0.2891632 -0.9382051 -0.5191189 -0.7958824 -0.3115877 -0.1094127 -0.1667629 -0.9799078 -0.4092827 -0.7287915 -0.5489541 -0.4658129 -0.8691502 -0.1661216 -0.1496093 -0.3384034 -0.9290319 -0.3733178 -0.6337219 -0.6775178 -0.2452472 -0.494962 -0.8335865 -0.3541088 -0.6860995 -0.6355112 -0.2369233 -0.5821375 -0.7778068 -0.3735188 -0.7909522 -0.4846425 -0.174022 -0.4636263 -0.8687733 -0.3920384 -0.8318666 -0.3928154 -0.3714416 -0.917114 -0.1446835 -0.1834191 -0.6334164 -0.7517588 -0.3421964 -0.867065 -0.3620774 -0.3007696 -0.9227541 -0.2409622 -0.3081392 -0.930644 -0.1973626 -0.1859718 -0.7395662 -0.6468821 -0.1954363 -0.7298904 -0.6550303 -0.183644 -0.8216959 -0.5395283 -0.1804457 -0.8242483 -0.5367068 -0.1651277 -0.8932911 -0.4180478 -0.1712636 -0.9768753 -0.1279979 -0.1150905 -0.9224674 -0.3685215 -0.1545074 -0.9110983 -0.3821356 -0.1067174 -0.9795118 -0.1707867 -0.07053369 -0.9577544 -0.278804 0.0203315 0.9997933 2.82442e-4 0.2185152 0.9758335 -3.63042e-4 0.2667733 0.9637592 4.70859e-4 0.4559466 0.8900071 -4.63735e-4 0.5280565 0.8492091 6.00114e-4 0.6401783 0.7682262 -6.52434e-4 0.7607616 0.6490305 0.001199305 0.853842 0.5205306 -0.001385033 0.954052 0.2996391 0.001165568 0.9778706 0.2092108 -3.94766e-4 0.9995878 0.02870845 0 0.999467 0.03264856 7.33866e-5 0.1563218 0.1033616 -0.982283 0.2698894 0.1866157 -0.9446346 0.06197893 0.398167 -0.9152168 0.3351886 0.1290621 -0.9332693 0.2667345 0.2342277 -0.9348744 0.4806234 0.1645749 -0.8613457 0.407039 0.404376 -0.8190236 0.5124555 0.2722706 -0.8144066 0.6454077 0.2518851 -0.7211123 0.7066175 0.3089352 -0.6365932 0.7909468 0.2149217 -0.5728978 0.8734719 0.2040899 -0.4420342 0.8753736 0.2081431 -0.4363458 0.9555516 0.1467435 -0.2557103 -0.1277212 -0.1701284 0.9771099 -0.2935845 -0.1264923 0.9475272 -0.2225646 -0.2159217 0.9507065 -0.4409656 -0.1155357 0.8900567 -0.2288556 -0.2658838 0.936446 -0.4776154 -0.1715128 0.8616652 -0.1857838 -0.3514153 0.9176011 -0.6535875 -0.08325988 0.7522575 -0.6316608 -0.142793 0.7619809 -0.4624058 -0.2962164 0.8357253 -0.2003113 -0.4420996 0.8743132 -0.4221101 -0.3258234 0.8459682 -0.1759398 -0.472428 0.86363 -0.6447435 -0.2411981 0.7253478 -0.5449073 -0.3252292 0.7728533 -0.7947148 -0.1186103 0.5952814 -0.6750053 -0.2580665 0.6912088 -0.3609344 -0.4558494 0.8135895 -0.8004568 -0.1592467 0.577849 -0.7408413 -0.2406584 0.6270866 -0.1762322 -0.6112157 0.7715942 -0.388686 -0.5216625 0.7594679 -0.5463175 -0.4627538 0.6981377 -0.8489699 -0.1845004 0.4951865 -0.1818723 -0.6152325 0.7670799 -0.4511614 -0.5267443 0.7204123 -0.6704984 -0.4293797 0.605033 -0.3012115 -0.606621 0.735719 -0.6000732 -0.4770152 0.6421594 -0.7370285 -0.423397 0.5268055 -0.8628789 -0.2328918 0.4485549 -0.1753441 -0.7242065 0.6669179 -0.74118 -0.4264298 0.5184689 -0.4796777 -0.6229155 0.617969 -0.329262 -0.6971596 0.636832 -0.9521348 -0.1045588 0.2872399 -0.8073791 -0.3725242 0.4575639 -0.06888324 -0.7769495 0.6257834 -0.5733343 -0.5822898 0.5763909 -0.9139502 -0.236995 0.329437 -0.2810844 -0.73725 0.6143729 -0.4409518 -0.6689294 0.5984104 -0.7114575 -0.5325643 0.4584797 -0.9819994 -0.09782862 0.1615763 -0.9142847 -0.3011265 0.2709364 -0.6378255 -0.6150346 0.4635852 -0.1284354 -0.8471686 0.5155676 -0.8552477 -0.4066359 0.3212456 -0.2758882 -0.8101531 0.5172405 -0.4717434 -0.7467303 0.4688839 -0.6198667 -0.6577295 0.427969 -0.9313971 -0.3042466 0.1998335 -0.9740542 -0.2014277 0.1031768 -0.05127155 -0.8929452 0.447236 -0.5811702 -0.6977376 0.418812 -0.2499927 -0.8301674 0.4983233 -0.4285563 -0.787555 0.4428278 -0.8113755 -0.5175126 0.2717546 -0.8050755 -0.5517266 0.2178327 -0.896668 -0.4329059 0.09262424 -0.7127325 -0.6631999 0.2284259 -0.2695017 -0.8997355 0.3432859 -0.7944924 -0.5701725 0.2090104 -0.4184769 -0.841884 0.3407472 -0.5461391 -0.7916109 0.2740153 -0.3597535 -0.8799747 0.3101968 -0.1899716 -0.9318623 0.3091014 -0.6669402 -0.7212674 0.1869875 -0.5797514 -0.7890376 0.2032439 -0.1501073 -0.9583659 0.2429046 -0.5535297 -0.8198955 0.1462066 -0.1575677 -0.9700362 0.1849387 -0.3749202 -0.9203553 0.1112709 -0.4000356 -0.9031814 0.1556756 -0.0842089 -0.989641 0.1162735 -0.2684344 -0.9581373 0.09957814 -0.1101185 -0.9939185 1.73008e-4 -0.1741178 -0.9847247 -5.06655e-4 -0.2587814 -0.9659358 4.29221e-4 -0.3617593 -0.9322714 -5.80657e-4 -0.4290118 -0.9032989 3.64249e-4 -0.5681508 -0.8229245 2.1366e-5 -0.5598387 -0.8286016 -1.63202e-4 -0.6968891 -0.717179 3.92626e-5 -0.6938707 -0.7200996 -2.71827e-5 -0.7892315 -0.6140958 -7.34903e-5 -0.7903162 -0.6126992 -4.78334e-5 -0.8754092 -0.4833824 -4.86036e-4 -0.8999028 -0.4360904 5.62752e-4 -0.9587005 -0.2844173 -4.13762e-4 -0.977847 -0.20932 6.34282e-4 -0.9910494 -0.1334958 -2.46515e-4 -0.9993485 -0.03609371 0 -0.9992679 -0.03825879 -6.31689e-5 0.9659134 6.0161e-4 -0.2588649 0.9612182 -0.001085698 -0.2757869 0.8834934 0.002888858 -0.4684349 0.8314328 -0.003245711 -0.5556159 0.7848893 0.003150165 -0.6196282 0.6635375 0.004500687 -0.7481296 0.589502 -0.002034485 -0.8077644 0.5255743 0.002595901 -0.8507438 0.3604797 3.00351e-4 -0.932767 0.3332701 -0.002433836 -0.9428282 0.1498777 0.004120707 -0.988696 0.9998328 0.001473784 -0.01823359 0.9999883 -0.0032624 -0.003584682 -0.917477 5.25807e-4 0.3977886 -0.9218996 0.001637041 0.3874255 -0.8516756 -0.002743363 0.5240623 -0.7652516 0.005328118 0.6437093 -0.70679 -0.003458678 0.7074149 -0.4794611 0.00253272 0.8775595 -0.4559539 -9.4841e-4 0.890003 -0.1738637 -0.001459062 0.9847686 -0.1959916 8.36316e-4 0.9806053 0.05755263 -0.001236915 0.9983417 0.02760022 0.001482546 0.999618 0.3092976 1.97573e-4 0.9509653 0.3034327 -6.0564e-4 0.9528527 0.5876176 0.001927793 0.8091365 0.5994152 -3.86856e-5 0.8004384 0.7889051 -0.002290666 0.6145108 0.8475061 0.00521785 0.53076 0.9020983 -0.002536952 0.4315232 0.9798238 6.78481e-4 0.1998624 0.9822768 0.001926481 0.1874268 0.9982509 -0.00222975 -0.05908006 0.9928188 0.003354012 -0.1195815 0.9111506 -0.003910899 -0.4120551 0.8803468 0.004023373 -0.4743134 0.6833996 -0.004049062 -0.7300333 0.6286783 0.004158496 -0.7776545 0.3432942 -0.004396796 -0.9392178 0.3110487 -2.77916e-4 -0.9503939 0.04951441 0.004077315 -0.9987651 -0.04532665 -0.004360377 -0.9989628 -0.291563 0.002018272 -0.9565495 -0.3082785 0.003865718 -0.9512884 -0.4970531 -0.00360769 -0.8677127 -0.6522882 0.003221511 -0.7579643 -0.649628 0.002776026 -0.7602471 -0.8381235 -0.003370761 -0.5454701 -0.8809767 0.005480647 -0.473128 -0.9430682 -0.002098977 -0.3325929 -0.9999879 0.002464652 0.004266023 -0.999961 0 0.008838355 0 1.86264e-6 -1 -4.87581e-6 0 -1 0 -5.32185e-7 -1 0.9999824 0.003730237 -0.004634797 0.9999874 0.002581954 -0.004304528 -0.9756193 -0.01317638 -0.219074 -0.9674393 0.008665382 -0.2529551 -0.9058717 0.001206099 -0.4235508 -0.8901261 -0.01884907 -0.4553244 -0.8140271 0.01844978 -0.5805339 -0.73418 -0.0152263 -0.6787841 -0.7072365 0.003568589 -0.7069681 -0.5844272 -0.003254711 -0.8114397 -0.5795504 4.86061e-4 -0.8149363 -0.9999427 0.00219959 -0.01048082 -0.9999543 0.003530263 -0.008888244 0 -1 2.52819e-6 0 -1 -3.27022e-6 0 -1 -8.891e-6 -2.47159e-5 -1 -4.20314e-4 9.36034e-5 -1 -4.89446e-4 0 -1 9.19796e-6 0 -1 -4.34699e-6 -3.4459e-5 -1 -4.27767e-4 0 -1 3.76648e-6 -1.57984e-4 -1 -3.78502e-4 0 -1 -4.78876e-6 -3.10752e-4 -1 -3.37156e-4 0 -1 -2.51206e-6 -4.77454e-4 -0.9999999 -3.01542e-4 -8.95302e-4 -0.9999995 -2.44699e-4 0 -1 -2.57102e-6 0 -1 -8.19283e-6 0 -1 -6.49464e-7 0 -1 -4.73767e-6 0 -1 -3.4882e-6 0 -1 7.04094e-6 0 -1 6.9685e-6 0 -1 -9.53869e-7 0 -1 -6.22138e-6 0 -1 3.96587e-6 0 -1 -6.93567e-6 0 -1 -7.01843e-6 0 -1 -4.48624e-6 0 -1 1.06488e-5 0 -1 4.45494e-5 0 -1 -1.35871e-7 0 -1 -3.64833e-6 0 -1 -7.56585e-7 0 -1 -2.1627e-6 -9.00856e-5 -1 3.72612e-5 -1.72327e-4 -1 3.58776e-5 -8.56056e-5 -1 5.0188e-5 -6.07611e-5 -1 5.9505e-5 -4.14767e-5 -1 7.23314e-5 -0.002540767 -0.9999969 -6.21019e-5 -3.64729e-5 -1 9.12722e-6 -4.11921e-4 -1 -3.89485e-6 -0.002466917 -0.999997 -6.22663e-5 0 -1 -1.38387e-7 -0.9898325 -0.01103997 0.1418097 -0.9793072 0.01279574 0.2019745 -0.9487715 -0.008889853 0.3158379 -0.9307093 0.008892357 0.3656518 -0.8836591 -0.01183444 0.4679813 -0.8490478 0.01182973 0.5281836 -0.7680509 -0.01360917 0.6402443 -0.7449731 0.006343245 0.6670644 -0.5904926 2.70797e-4 0.8070431 -0.5891179 -0.001143634 0.8080464 -0.9800351 -0.02083271 0.1977304 -0.9515774 0.02889984 0.306048 -0.8906906 -0.02470153 0.4539387 -0.8255258 0.01996827 0.564011 -0.7443196 -0.01850807 0.6675672 -0.6839796 0.01218748 0.7293993 -0.7223207 0.01444709 -0.6914073 -0.6906874 -0.004781901 -0.7231377 -0.8121399 -0.01537811 -0.5832599 -0.886977 0.01630401 -0.4615256 -0.9010735 -6.6797e-5 -0.4336665 -0.9756892 -0.005581736 -0.2190881 -0.980226 0.006696522 -0.1977683 -0.999992 -0.0039438 -7.27963e-4 -0.9999076 0.01337707 0.002468109 6.37992e-4 0.9999995 -7.31519e-4 7.72696e-4 0.9999996 -6.45471e-4 4.89582e-4 0.9999995 -8.95627e-4 0.001124024 0.9999992 -5.29505e-4 5.47482e-4 0.9999996 -7.76749e-4 0 1 -1.06039e-5 0.002165317 0.9999976 -3.96296e-4 0 1 5.73394e-6 0 1 -6.914e-6 0 1 -3.85318e-6 0 1 -7.15168e-6 0 1 4.26639e-6 0 1 -4.82139e-6 0 1 4.85874e-6 0 1 -6.15328e-6 0 1 3.51491e-6 0 1 -3.95732e-6 0 1 -8.84701e-6 0 1 -2.78358e-7 0 1 -4.23287e-7 0 1 1.76803e-7 0 1 4.97194e-6 0 1 0 0 1 1.59748e-7 0 1 2.12102e-7 0 1 5.69619e-6 0 1 -1.70053e-6 0 1 -1.00896e-6 0 1 3.54277e-6 0 1 -7.41979e-6 0 1 1.01899e-5 0 1 -7.6576e-6 4.0028e-4 1 3.85738e-5 1.15432e-4 1 4.92311e-5 6.77233e-5 1 5.39557e-5 4.48724e-5 1 5.62586e-5 2.71914e-5 1 6.32506e-5 1.23833e-5 1 7.63218e-5 -1.57809e-6 1 7.77396e-5 -2.29322e-5 1 9.93838e-5 -5.3304e-5 1 1.21945e-4 -8.51117e-5 1 1.56104e-4 0.004251539 0.999991 -4.5299e-5 0.008522689 0.9999638 -1.13534e-6 -0.9830232 -0.03049117 0.1809304 -0.9776765 0.01478403 0.2095951 -0.9175806 -6.03111e-4 0.3975496 -0.9039615 -0.04372376 0.4253728 -0.8335643 0.05178195 0.5499902 -0.7667654 -0.0408858 0.6406242 -0.6912009 0.03139013 0.7219807 -0.6568719 -0.01710021 0.7538084 -0.5271962 0.03064012 0.8491911 -0.4788686 -0.03638678 0.8771322 -0.3484749 0.0325039 0.9367544 -0.2712902 -0.04980838 0.9612081 -0.1395692 0.06590646 0.9880167 0.007704734 -0.08288836 0.9965291 0.1409156 0.08288967 0.9865456 0.2932352 -0.07443863 0.953138 0.4133296 0.06024014 0.9085868 0.5340093 -0.06053996 0.8433085 0.624111 0.07088655 0.7781135 0.7402977 -0.06959587 0.6686671 0.827698 0.06286841 0.5576413 0.8683272 -0.03517568 0.4947431 0.9505649 0.04140418 0.3077534 0.9592571 -0.003508508 0.2825129 0.9935947 -0.02835506 0.1093885 0.9973064 0.06798374 0.02753436 0.99654 -0.03969782 -0.07302182 0.9699909 7.33137e-4 -0.2431405 0.9653408 0.02914667 -0.2593601 0.8902058 -0.03078347 -0.4545174 0.8881961 -0.02227258 -0.4589246 0.7969742 0.04902809 -0.6020203 0.7253157 -0.06640613 -0.6852061 0.6497214 0.04050976 -0.7590923 0.5085078 0.01542508 -0.8609193 0.541251 -0.02425217 -0.8405113 0.3792829 -0.02595227 -0.9249168 0.3435193 0.02017199 -0.938929 0.1834271 0.003051161 -0.9830286 0.1644356 -0.02424335 -0.9860899 0.001663982 0.01960742 -0.9998064 -0.03485101 -0.01818889 -0.999227 -0.1638497 0.01819658 -0.9863176 -0.1997556 -0.01961213 -0.9796495 -0.3485711 0.02193886 -0.9370256 -0.3913793 -0.03485196 -0.9195693 -0.5411314 0.05162429 -0.839352 -0.5986714 -0.04398494 -0.7997862 -0.7479119 0.02011495 -0.6634932 -0.7420917 0.003886818 -0.6702871 -0.8605177 0.003902852 -0.5094056 -0.8711978 -0.02472102 -0.4903092 -0.9351038 0.03205269 -0.3529216 -0.9587211 -0.04269301 -0.2811249 -0.9839755 0.03310465 -0.175204 -0.9974439 -0.03666621 -0.06132936 -0.9995849 0.02856677 -0.003744006 0 1 7.01238e-6 0 1 6.89445e-6 0 1 -3.47936e-6 0 1 1.37408e-5 0 1 -1.57832e-5 0 1 -6.41857e-6 0 1 1.11156e-5 0 1 -3.20659e-6 0 1 -1.65335e-6 0 1 3.46031e-6 0 1 -5.375e-6 0 1 8.38785e-6 0 1 9.01318e-6 0 1 1.73262e-6 0 1 2.98373e-6 0 1 -3.5277e-6 0 1 2.44814e-6 0 1 -2.54276e-6 0 1 5.55071e-6 0 1 4.71666e-6 0 1 6.89888e-6 0.1731775 -0.01254993 -0.9848107 0.1984326 0.006021916 -0.9800961 0.5076827 -5.71781e-4 -0.861544 0.4972993 0.008561789 -0.8675369 0.7181117 -0.01649111 -0.6957325 0.7833388 0.02583885 -0.6210579 0.8549751 -0.01589953 -0.5184256 0.9460049 0.01837593 -0.3236312 0.9570531 -0.002332329 -0.2899035 0.9986394 -0.0113815 -0.05089223 0.9985418 0.03056222 0.04450094 0.984749 -0.02015268 0.1728103 0.9146621 0.01369512 0.4039872 0.9012898 -0.003995358 0.4331985 0.7759776 0.003476083 0.6307511 0.7500422 -0.01438546 0.6612337 0.6160627 0.02082741 0.7874218 0.5003077 -0.02646321 0.8654432 0.3568761 0.02938765 0.9336894 0.2314977 -0.02206408 0.9725853 -0.01610249 0.01250219 0.9997922 0.01610249 -0.01250231 0.9997922 -0.2315064 0.02206462 0.9725832 -0.3568639 -0.0293864 0.9336941 -0.4860092 0.02066838 0.8737093 -0.6161238 -0.01573008 0.7874922 -0.6869111 0.01192015 0.7266438 -0.7916563 -0.01653629 0.6107431 -0.8417425 0.02329963 0.5393762 -0.9499828 -0.02625918 0.3111966 -0.9801682 0.03286111 0.1954237 -0.9985236 -0.01901054 0.05088508 -0.9849124 0.008265793 -0.1728562 -0.9809834 0.02158069 -0.1928882 -0.897301 -0.02536857 -0.4406896 -0.8440499 0.02458286 -0.5357009 -0.7276427 -0.0196827 -0.6856739 -0.6732864 0.01115119 -0.7392976 -0.4847022 -0.006216645 -0.8746572 -0.493292 2.34662e-4 -0.8698638 -0.1984419 -0.006026387 -0.9800942 -0.1731752 0.01255035 -0.9848111 -0.9960026 0.04072582 0.07950019 -0.9865276 -0.04203629 0.1581028 -0.9600467 0.03655952 0.2774413 -0.9262571 -0.05046403 0.3734985 -0.8899347 0.03935164 0.4543873 -0.7890776 -0.01598525 0.6140856 -0.7966043 0.009938776 0.6044196 -0.6536819 -0.04026007 0.7556977 -0.5709558 0.0711959 0.817888 -0.5129322 -0.0245198 0.8580789 -0.3059769 0.01180899 0.9519658 -0.3096441 0.004826486 0.9508404 -0.09030175 -0.01154226 0.9958476 -0.09475004 -0.01939988 0.9953121 0.1051507 0.04397636 0.9934835 0.1764082 -0.0546897 0.9827967 0.3441996 0.04295545 0.9379134 0.4080346 -0.04742151 0.9117341 0.5465975 0.05061101 0.8358647 0.6395204 -0.05098944 0.7670813 0.6895437 0.02319663 0.7238726 0.8102092 -0.0208733 0.5857691 0.8255637 0.02275311 0.56385 0.9283193 -0.03108274 0.3704825 0.9466086 0.04777419 0.3188259 0.9842897 -0.04701268 0.1701871 0.9960352 0.05543297 0.06957799 0.9978157 -0.04180371 -0.05114942 0.9874939 0.03116065 -0.1545479 0.9700664 -0.03802669 -0.2398445 0.9404106 0.05062317 -0.3362519 0.8501067 0.02266269 -0.5261227 0.8768987 -0.04602921 -0.4784666 0.7368829 0.004976689 -0.6760021 0.7473606 -0.01869434 -0.6641557 0.5791304 0.00496608 -0.8152199 0.5660721 -0.01868236 -0.8241441 0.4163251 0.02265107 -0.9089336 0.3899407 -0.01367706 -0.9207384 0.2261734 -0.005613207 -0.9740709 0.1923569 0.04578751 -0.9802563 0.01925051 -0.05217278 -0.9984526 -0.1045363 0.06392735 -0.9924643 -0.1680204 -0.023391 -0.9855061 -0.3855005 0.004953205 -0.9226945 -0.3859852 0.006004512 -0.9224855 -0.5867688 0.004970729 -0.8097394 -0.605647 -0.02958244 -0.7951834 -0.7237907 0.03737336 -0.6890068 -0.7788708 -0.05790984 -0.6245053 -0.865889 0.05791676 -0.4968721 -0.9168858 -0.07260906 -0.3924899 -0.9554892 0.04969036 -0.2908118 -0.9926834 -0.0075562 -0.1205109 -0.9941766 -0.04822885 -0.09636831 -0.003040134 -6.93897e-4 -0.9999952 -9.48471e-7 0 -1 -1.03114e-6 0 -1 -0.002019166 0.001534163 -0.9999968 -6.95879e-6 0 -1 6.9003e-6 0 -1 -2.22648e-6 0 -1 1.08162e-5 0 -1 -1.70024e-7 0 -1 0 0 -1 -2.90304e-6 0 -1 3.44757e-6 0 -1 -2.18418e-6 0 -1 -4.82803e-6 0 -1 -7.48884e-6 0 -1 1.59269e-5 0 -1 0.003712713 -0.002266764 -0.9999907 0.001902878 0.001345932 -0.9999973 0 1 7.58366e-6 0 1 -5.93619e-6 0 1 -6.55936e-6 0 1 6.49581e-6 -2.34685e-4 1 -2.86303e-4 -2.12951e-4 1 -4.14352e-4 -1.48872e-4 0.9999999 -5.01967e-4 0 1 -5.67843e-6 0 1 3.40637e-6 -2.8146e-4 1 -3.43811e-4 0 1 1.58756e-5 -3.75241e-4 1 -3.09575e-4 0 1 -7.53259e-6 -0.01350992 0.9999078 0.001389503 0 1 -1.41477e-6 0 1 1.79e-6 0 1 -2.35436e-6 0 1 6.79805e-6 0 1 -8.84893e-6 0 1 2.98704e-5 0 1 3.96917e-6 0 1 8.24991e-6 0 1 -8.2143e-6 0 1 -4.7956e-6 0 1 5.40106e-6 0 1 3.89437e-6 0 1 4.39116e-6 0 1 -1.34066e-5 0 1 -1.84575e-5 0 1 1.51433e-5 0 1 0 3.41951e-4 0.9999998 7.04779e-4 1.37688e-4 0.9999999 5.14528e-4 2.74949e-5 1 4.31557e-4 -5.12465e-5 1 3.70855e-4 -1.19617e-4 1 3.48475e-4 -1.89396e-4 1 3.22895e-4 -2.72404e-4 1 3.06128e-4 0.004441142 0.9999899 8.42746e-4 3.64011e-4 0.9999998 7.01782e-4 -0.02570879 0.9996695 -2.12238e-4 -0.01524925 0.9998838 0 0.9979937 -0.02063351 -0.05985832 0.9798497 0.01281309 -0.1993252 0.9595459 -0.01490283 -0.2811577 0.9264912 0.01870471 -0.3758515 0.8706744 -0.02280277 -0.4913312 0.8030333 0.01927584 -0.5956224 0.7531437 -0.01257663 -0.6577358 0.6649914 0.011105 -0.7467685 0.5996083 -0.01663482 -0.8001208 0.5486845 0.001773416 -0.8360276 0.9998837 0.01518821 0.001449465 0.9830645 0.0035699 0.183225 0.9804867 -0.005519688 0.1965084 0.9038543 0.005630731 0.4278035 0.889919 -0.01602756 0.4558369 0.792944 0.01864075 0.6090095 0.7251847 -0.02286827 0.6881746 0.6649952 0.01165652 0.7467567 0.5528441 -0.003470361 0.8332775 0.5569531 2.78263e-4 0.8305439 0.7125609 0.002656877 0.7016053 0.7203785 -0.003626704 0.6935717 0.854308 0.003997385 0.5197519 0.8618795 -0.005413353 0.5070842 0.9700658 0.005700111 0.2427752 0.9727114 -0.002012908 0.2320099 0.9781857 -0.01807403 -0.2069449 0.9516831 0.0212956 -0.3063428 0.9171299 -0.01238584 -0.398396 0.8320557 0.01398962 -0.5545157 0.8174071 -0.001349747 -0.5760589 0.6685028 -0.00986278 -0.7436444 0.6174138 0.02260541 -0.7863137 2.37872e-4 -1 -2.92229e-4 4.58139e-4 -0.9999999 -2.64474e-4 1.28263e-4 -1 -3.16952e-4 0.001094222 -0.9999994 -2.22019e-4 4.90501e-5 -1 -3.44358e-4 -6.16225e-5 -1 -3.84908e-4 2.83738e-5 -1 -3.43631e-4 0 -1 1.84805e-6 0 -1 4.85045e-6 0 -1 -1.12742e-6 0 -1 7.76805e-6 0 -1 -3.98712e-6 0 -1 4.4056e-6 0 -1 -9.9936e-6 0 -1 1.06605e-6 0 -1 -3.01865e-6 0 -1 4.36929e-6 0 -1 -1.15189e-5 0 -1 -7.84335e-6 0 -1 2.99351e-6 0 -1 -7.91365e-6 0 -1 4.26189e-6 0 -1 -9.65661e-6 2.87621e-5 -1 7.99877e-5 5.36532e-5 -1 6.687e-5 9.48323e-5 -1 5.38003e-5 1.66554e-4 -1 4.61025e-5 0 -1 2.52155e-6 8.43767e-5 -1 3.44291e-5 0 -1 1.64896e-6 0 -1 -1.30122e-6 0 -1 8.02644e-6 0 -1 -4.84294e-6 0 -1 6.15619e-6 0 -1 3.84968e-6 0 -1 -4.88929e-6 0 -1 6.63346e-6 0.005011439 -0.9999876 -3.90415e-5 7.39328e-5 -1 9.00992e-6 2.36757e-5 -1 9.6547e-6 0.001110851 -0.9999995 -1.4579e-5 0.001131355 -0.9999994 -1.19116e-5 0.9999997 -6.92672e-4 3.04759e-4 0.9999165 0.01275116 -0.002132654 -0.9995572 -0.001845777 0.02970224 -0.9986265 -0.02759146 0.04454046 -0.9732149 0.0215798 0.2288823 -0.9646502 -0.02131044 0.2626709 -0.9087184 0.02127933 0.416867 -0.893903 -0.02101999 0.4477675 -0.8083075 0.02099639 0.5883861 -0.7880371 -0.02073264 0.6152787 -0.6759433 0.02069938 0.7366629 -0.6512064 -0.02044606 0.7586252 -0.5168712 0.02041447 0.8558198 -0.4887984 -0.02015405 0.872164 -0.3373883 0.02013367 0.9411503 -0.3071643 -0.01986712 0.9514491 -0.1445946 0.01983433 0.9892923 -0.1134752 -0.01958739 0.9933478 0.05395257 0.01955682 0.9983521 0.08470332 -0.01930528 0.9962192 0.2503595 0.01928406 0.9679609 0.2795572 -0.01901006 0.9599409 0.43688 0.01897716 0.8993196 0.4633981 -0.01871848 0.8859525 0.606135 0.01868927 0.7951422 0.6290696 -0.01843273 0.7771304 0.7514283 0.01838952 0.6595585 0.7700021 -0.0181517 0.6377831 0.8714847 0.02005338 0.4900126 0.8843165 -0.01942586 0.4664838 0.9652085 0.02280491 0.2604855 0.9665591 0.01405018 0.2560589 0.9974914 -0.04473757 0.0548585 0.9984229 0.05537652 -0.009235262 0.9774554 -0.01545125 -0.2105759 0.9803199 -0.04751312 -0.1916133 0.9272217 0.04314118 -0.37202 0.8881376 -0.05130511 -0.456705 0.8405651 0.03514701 -0.5405693 0.7696432 -0.03534287 -0.6374955 0.7173329 0.03548628 -0.6958264 0.6287747 -0.03542405 -0.7767803 0.5655336 0.03555828 -0.8239584 0.463203 -0.03551304 -0.8855406 0.3913955 0.03564018 -0.9195321 0.2794162 -0.03557652 -0.9595109 0.2018036 0.03572815 -0.9787741 0.08467221 -0.0356599 -0.9957706 0.004226565 0.03581881 -0.9993494 -0.1134018 -0.03574085 -0.9929062 -0.1935344 0.035892 -0.9804368 -0.3070191 -0.03582602 -0.9510289 -0.3836331 0.03595644 -0.9227854 -0.4885707 -0.03588032 -0.8717862 -0.5585691 0.03603905 -0.8286747 -0.6509239 -0.03595185 -0.7582912 -0.7114472 0.03612744 -0.7018103 -0.7876962 -0.03602987 -0.6150094 -0.836217 0.03620439 -0.5472024 -0.8935155 -0.03610765 -0.4475783 -0.9279413 0.03625303 -0.3709594 -0.9693645 -0.05050253 -0.2403789 -0.98336 0.03676205 -0.1779093 0 1 6.07187e-6 0 1 -9.36628e-6 0 1 -6.0254e-6 0 1 -1.51786e-6 0 1 4.68218e-6 0 1 -3.01692e-6 0 1 -1.21081e-5 0 1 -2.85681e-6 0 1 -6.16352e-6 0 1 5.59358e-7 0 1 6.00795e-6 0 1 5.7316e-6 0 1 -1.21093e-5 0 1 6.56538e-6 0 1 -4.1846e-6 0 1 6.05151e-6 0 1 1.71455e-6 0 1 -2.99643e-6 0 1 6.90787e-6 0 1 3.04592e-6 -2.69136e-6 1 -4.37403e-6 -4.4454e-6 1 0 0 1 -2.11215e-6 0 1 3.01109e-6 -3.43073e-6 1 6.63808e-6 0 1 -2.68517e-6 0 1 2.99169e-6 -0.224012 0.9745855 -0.001354098 -0.2316548 0.9727981 2.62628e-4 -0.3104501 0.9505896 4.13694e-4 -0.2578078 0.9661962 -1.74131e-5 -0.2659353 0.963991 -1.91849e-5 -0.3157724 0.9488341 0.001293361 -0.3100306 0.9507259 0.001136362 -0.365024 0.9309981 1.45152e-4 -0.4981707 0.867079 -3.52377e-4 -0.5754607 0.8178294 3.47155e-4 -0.7690576 0.6391795 -4.3082e-4 -0.8127048 0.5826756 3.07968e-4 -0.2204293 0.9754015 -0.001686632 -0.1325479 0.9911741 -0.002273023 0.008613526 0.006687581 -0.9999406 0.3570291 -0.005211293 -0.9340788 0.3502113 -5.01645e-5 -0.9366708 0.6339927 -0.01188063 -0.7732478 0.6108894 0.004394054 -0.7917038 0.7989726 0.01729273 -0.6011188 0.8558263 -0.03149437 -0.5163038 0.942878 0.03377145 -0.3314222 0.9877508 -0.03513562 -0.1520325 0.999563 0.02626234 -0.01357311 0.9817038 -0.02109515 0.1892423 0.9623193 0.01307398 0.2716078 0.8976528 -0.01014518 0.4405866 0.8654077 0.01729935 0.5007699 0.7498138 -0.02875506 0.6610238 0.6422135 0.03227061 0.7658463 0.5003077 -0.02646523 0.8654431 0.3568692 0.02938663 0.933692 0.2315053 -0.02206474 0.9725835 -0.01610267 0.01250231 0.9997922 0.01610249 -0.01250219 0.9997922 -0.2315049 0.0220645 0.9725835 -0.3568724 -0.02938568 0.9336909 -0.5003089 0.02646392 0.8654426 -0.6160593 -0.02082818 0.7874244 -0.7813038 0.004841089 0.6241321 -0.7661996 0.01912683 0.6423181 -0.921083 -0.01512598 0.3890724 -0.9451925 0.01939934 0.3259369 -0.9909511 -0.01636618 0.1332224 -0.9977953 0.01115292 0.06542301 -0.9901695 7.16838e-4 -0.1398718 -0.9886559 -0.004992127 -0.1501156 -0.9342274 -0.004238486 -0.356653 -0.927428 0.004238367 -0.373978 -0.8171295 -0.004393339 -0.5764374 -0.8209772 -7.09033e-4 -0.5709606 -0.6295 0.004660964 -0.7769865 -0.6373823 0.0108307 -0.7704717 -0.4718705 -0.0150026 -0.8815403 -0.3568721 0.02938216 -0.9336912 -0.2314806 -0.02206617 -0.9725893 0.0161032 0.0125072 -0.9997922 0.1986306 -0.9800743 5.74521e-4 0.390207 -0.9207268 -8.24831e-4 0.5008653 -0.8655251 4.16285e-4 0.7521626 -0.6589776 -1.77549e-4 0.7457539 -0.6662216 -5.533e-5 0.8762814 -0.4817993 5.36531e-4 0.8856534 -0.4643469 -3.7318e-6 0.7908648 -0.6119904 -7.54355e-4 0.7530156 -0.6580023 8.22702e-4 0.6618299 -0.7496538 -6.5968e-4 0.6054825 -0.7958584 6.89358e-4 0.5287314 -0.8487889 -6.9128e-4 0.4459694 -0.895048 6.77338e-4 0.351666 -0.9361252 -8.14558e-4 0.2996364 -0.9540535 4.00718e-4 0.1642354 -0.9864212 1.38458e-4 0.1386 -0.9903483 -4.64968e-4 0.03733789 -0.9993028 2.97808e-4 -0.9994004 0.01779872 0.02969765 -0.9734205 0.006616711 0.2289297 -0.9682609 -0.0250197 0.2486867 -0.908717 0.02128845 0.4168698 -0.8939035 -0.02101635 0.4477665 -0.8083022 0.02100634 0.5883929 -0.7880403 -0.02071857 0.6152749 -0.6759556 0.02070611 0.7366514 -0.6511968 -0.02044761 0.7586335 -0.516901 0.02041816 0.8558016 -0.4887874 -0.02016419 0.8721699 -0.3374092 0.02014261 0.9411426 -0.3071397 -0.01987838 0.9514569 -0.1445889 0.01984578 0.9892928 -0.113451 -0.01958823 0.9933505 0.05394822 0.0195558 0.9983522 0.08471858 -0.0193032 0.9962179 0.2503586 0.01926505 0.9679616 0.2795471 -0.01901227 0.9599438 0.4368641 0.01897752 0.8993273 0.4634062 -0.01873576 0.885948 0.606113 0.01869845 0.7951588 0.6290634 -0.01844191 0.7771352 0.7514232 0.01838833 0.6595643 0.7699968 -0.01815408 0.6377895 0.8714826 0.0200442 0.4900165 0.8841469 -0.01884424 0.466829 0.9652259 0.02202177 0.2604882 0.9730591 -0.04466116 0.2261893 0.9984926 0.05410546 -0.009236752 0.9955793 -0.05738812 -0.07435506 0.9769862 0.03461462 -0.2104753 0.946401 -0.05015408 -0.3190764 0.9278256 0.02369487 -0.3722612 0.8408803 0.02221411 -0.5407651 0.8141328 -0.04669231 -0.5787986 0.7173714 0.03400593 -0.6958607 0.6665829 -0.03384822 -0.744662 0.5655773 0.03388923 -0.8239987 0.5065992 -0.0337314 -0.8615217 0.3914275 0.03377437 -0.919589 0.3267055 -0.03360974 -0.9445284 0.201809 0.03365021 -0.9788467 0.1339714 -0.03347969 -0.9904195 0.004220247 0.03351593 -0.9994294 -0.06401431 -0.03335422 -0.9973915 -0.1935458 0.03339678 -0.9805227 -0.2594766 -0.03320723 -0.9651783 -0.3836846 0.03325754 -0.9228652 -0.4447482 -0.03307038 -0.8950449 -0.5586374 0.03311514 -0.8287506 -0.6125626 -0.03294527 -0.7897353 -0.7115305 0.03299009 -0.7018804 -0.7563049 -0.03278571 -0.6533975 -0.8363191 0.0328384 -0.5472589 -0.8703172 -0.03263503 -0.491409 -0.9280558 0.03267443 -0.3710051 -0.9546008 -0.04946446 -0.293753 -0.982617 0.05348098 -0.1777742 -0.9982562 -0.05568116 -0.01960098 0.9710152 0.005176305 -0.2389619 0.9716203 0.007143259 -0.2364382 0.9134298 -0.01525551 -0.4067104 0.8743848 0.01958382 -0.4848378 0.8121364 -0.01957547 -0.5831393 0.7525103 0.01868718 -0.6583154 0.6274727 -0.01452541 -0.7785032 0.6097189 -4.77686e-4 -0.7926176 0.4119584 -0.00666815 -0.9111782 0.428272 0.006057024 -0.9036297 0.1885691 7.41172e-5 -0.98206 0.1834433 0.003573715 -0.9830238 0.9999833 -0.002550005 -0.005186498 0.9999772 -9.57811e-4 -0.006705939 0.9706121 0.01305174 0.2402957 0.9803878 -0.01162075 0.1967349 0.9033002 -0.01860862 0.4286054 0.8516033 0.02322953 0.5236719 0.8010171 -0.01101601 0.5985401 0.6935783 0.00771296 0.72034 0.6833923 -3.54621e-4 0.7300513 0.6823184 0 0.7310552 0.6823178 1.59478e-6 0.7310557 0.6823186 -1.55218e-6 0.7310549 0.6823189 0 0.7310548 0.6823185 1.38088e-6 0.7310551 0.6823169 0 0.7310565 0.682319 -1.26076e-6 0.7310547 0.6823198 1.79141e-6 0.7310539 0.6823203 1.38001e-6 0.7310534 0.6823169 2.12838e-6 0.7310566 0.6823198 0 0.7310538 0.6823152 8.0527e-7 0.7310582 0.6823133 0 0.73106 0.6823204 3.64146e-6 0.7310532 0.682317 2.47214e-6 0.7310565 0.6834597 0.001443445 0.7299869 0.6830818 0.004411578 0.7303286 -0.9779837 0.002260684 -0.2086696 -0.9776066 0.001143276 -0.210438 -0.9243672 -0.005008518 -0.3814712 -0.9169889 0.005548238 -0.3988745 -0.8215686 -4.69452e-4 -0.5701097 -0.8181782 -0.004139244 -0.57495 -0.700172 0.003477275 -0.7139657 -0.6907392 -0.00277251 -0.7230988 -0.5744715 0.002770483 -0.81852 -0.5636739 -0.003481388 -0.8259902 -0.4042968 0.004136502 -0.9146186 -0.3911347 -0.004748046 -0.9203213 -0.187222 0.004696369 -0.9823064 -0.1768923 -0.001734018 -0.9842287 -0.9999985 8.41318e-4 -0.001543283 -0.9999746 0.005018591 -0.005085289 -0.9863296 -0.002457857 0.164767 -0.9826603 0.006536483 0.1852998 -0.9376497 -0.009559094 0.3474501 -0.9107421 0.01771891 0.4125956 -0.846148 -0.02008479 0.5325695 -0.7787407 0.01630008 0.6271343 -0.6889846 -0.003949284 0.7247653 -0.6802688 -0.003100693 0.7329562 -0.6823174 -2.68937e-7 0.7310562 -0.6823193 1.69796e-6 0.7310543 -0.6823164 -4.44095e-7 0.731057 -0.6823183 0 0.7310552 -0.6823207 0 0.7310531 -0.6823178 0 0.7310557 -0.6823175 -7.41577e-7 0.731056 -0.6823175 0 0.731056 -0.6823182 0 0.7310554 -0.6823142 0 0.7310591 -0.6823147 -3.80403e-6 0.7310586 -0.6823198 0 0.7310539 -0.682321 0 0.7310527 -0.6823149 -1.74296e-6 0.7310584 -0.6823213 0 0.7310525 -0.6839668 -0.01144307 0.7294234 -0.6825565 2.80637e-4 0.7308328 0 1 7.82558e-6 0 1 1.18825e-5 0 1 -1.97892e-6 0 1 2.28029e-6 0 1 -3.79188e-6 0 1 -4.84759e-6 0 1 3.12182e-6 0 1 3.2971e-6 0 1 -4.6746e-6 0 1 3.0083e-6 0 1 9.77351e-6 0 1 -5.26378e-7 0 1 4.83874e-6 0 1 -1.17092e-5 0 1 1.36043e-5 0 1 -3.75979e-6 0 1 -5.01668e-6 0 1 6.95246e-6 0 1 7.64409e-6 0 1 -3.01659e-6 -5.30542e-7 1 -9.75972e-6 0 1 3.04257e-6 -4.55443e-6 1 1.19953e-5 0 1 3.0181e-6 -4.82762e-6 1 0 0 1 7.53361e-7 0 1 5.39507e-6 0 1 -6.02395e-6 0 1 -6.04998e-6 0 1 -1.20505e-5 0 1 -3.26334e-6 0 1 -1.20177e-5 0 1 -1.17358e-6 0 1 1.21349e-5 0 1 -3.83972e-6 0 1 5.99776e-6 0 1 7.66701e-6 0 1 6.96263e-6 0 1 -3.02463e-6 0.08839249 0.0200423 0.9958841 0.0419175 -0.008844852 0.999082 0.3112989 -0.02382898 0.9500133 0.4481154 0.02638244 0.8935863 0.5293422 -0.01115435 0.8483352 0.7048544 0.005604624 0.7093299 0.6915612 -0.005594193 0.7222962 0.8440866 0.01239854 0.5360636 0.8703875 -0.01374381 0.4921755 0.9645895 0.003516256 0.2637321 0.9650945 0.00458014 0.2618624 0.9999672 0.007514297 0.003042101 0.9997652 -0.003844082 0.02132666 0.9435294 -0.01056927 -0.3311202 0.9318583 0.01312339 -0.3625851 0.7989842 -0.01141947 -0.6012436 0.7587619 0.01914918 -0.6510866 0.6208449 -0.02150243 -0.7836386 0.502101 0.02953279 -0.8643046 0.3875976 -0.02020901 -0.9216073 0.1874735 0.001401484 -0.9822687 0.1702181 0.01254564 -0.9853266 -0.08041399 0.001404881 -0.9967606 -0.06904453 0.008051574 -0.9975811 -0.2763177 -0.01433038 -0.9609595 -0.3856504 0.02877604 -0.9221962 -0.509368 -0.02507549 -0.8601835 -0.679386 0.01646214 -0.7335965 -0.7406218 -0.02181226 -0.6715681 -0.843843 0.02711594 -0.5359048 -0.9245684 -0.02552461 -0.3801603 -0.9644678 0.01631337 -0.2636963 -0.9911609 -0.01631557 -0.1316578 -0.9994213 0.01893585 -0.02825736 -0.9652333 0.02371221 0.2603123 -0.9841454 -0.01728391 0.1765201 -0.8841281 -0.03511399 0.4659234 -0.7983157 0.04151022 0.600807 -0.6401928 -0.03575801 0.7673817 -0.5450118 0.02325379 0.8381059 -0.3179718 -0.02121526 0.9478628 -0.2653365 0.01291251 0.9640694 0.1332942 -0.01444214 0.9909713 0.2034923 0.02216285 0.9788258 0.4342034 -0.02504324 0.9004667 0.5277528 0.02247279 0.8491008 0.6498118 -0.01444268 0.759958 0.7548616 0.02025288 0.6555715 0.8026068 -0.01451152 0.5963318 0.9304375 -0.01350265 0.366202 0.9398679 0.00663191 0.3414738 0.9929735 0.01936268 0.1167421 0.9994989 -0.03065907 0.007878065 0.9798909 0.02826738 -0.197522 0.9475234 -0.02263087 -0.3188846 0.865933 0.02360403 -0.499603 0.8257203 -0.01512819 -0.5638769 0.6294943 0.006040036 -0.7769817 0.6304047 0.005200386 -0.7762492 0.3876696 -0.004124343 -0.9217892 0.3739463 0.003269553 -0.9274446 0.1414726 0.004761099 -0.9899308 0.1563224 -0.00351721 -0.9876999 -0.1414729 -0.004761099 -0.9899308 -0.1563214 0.003517508 -0.9877 -0.3663185 -0.003023266 -0.9304847 -0.379826 0.003468334 -0.9250515 -0.6033799 0.005034148 -0.7974382 -0.5910494 -0.00425136 -0.8066242 -0.8305601 0.01445376 -0.5567414 -0.8122248 -0.00503683 -0.5833228 -0.9452763 -0.02145785 -0.3255646 -0.9644991 0.01422548 -0.2637028 -0.9999437 0.005919456 -0.008812069 -0.9995383 -0.01693409 0.02522921 -0.9454922 -7.97816e-4 0.3256436 -0.9422941 0.006037056 0.3347319 -0.8072658 0.005394041 0.5901635 -0.8066568 0.004693031 0.5910015 -0.6162767 -0.01889914 0.787303 -0.5712125 0.0119937 0.8207145 -0.3763606 0.005322515 0.9264581 -0.3491687 -0.01064527 0.9369995 -0.1232894 -0.001787304 0.9923692 -0.09405523 0.01333588 0.9954777 0.2526621 0.9675545 4.56831e-4 0.3660724 0.9305862 -7.07454e-4 0.5873205 0.8093542 6.61941e-4 0.7106986 0.7034965 -5.46385e-4 0.8347833 0.5505787 4.23348e-4 0.9035941 0.4283896 -4.54659e-4 -0.2051432 -0.9787318 5.87013e-4 -0.3759548 -0.9266377 -7.79931e-4 -0.5269839 -0.8498751 5.3478e-4 -0.7086228 -0.7055875 -4.31646e-4 -0.7588255 -0.6512941 1.87143e-4 -0.8824144 -0.4704733 -1.29674e-4 -0.87159 -0.4902352 6.13695e-4 -0.7654232 -0.6435273 -3.3135e-4 -0.768352 -0.6400275 -1.72147e-4 -0.6321048 -0.7748829 3.1327e-4 -0.6165028 -0.7873527 -2.94167e-4 -0.4409516 -0.8975307 -6.61432e-4 -0.4748718 -0.8800551 2.4209e-4 -0.3325387 -0.9430893 8.63129e-4 -0.2119542 -0.9772791 -0.001079618 -0.171754 -0.9851399 -2.09302e-5 -0.06956511 -0.9975773 5.74408e-4 -1.62335e-5 -1 -2.92235e-5 -2.18314e-4 -1 2.24555e-4 1.02666e-5 -1 -2.39555e-5 -6.43272e-5 -1 0 -1.3569e-6 -1 -2.76855e-5 -4.12936e-5 -1 0 -3.07942e-5 -1 -2.98247e-5 -1.28814e-4 -1 1.36268e-4 0 -1 1.27867e-5 0 -1 2.62107e-6 0 -1 -1.96883e-6 0 -1 1.32261e-6 0 -1 7.22411e-7 0 -1 1.45203e-5 0 -1 -5.35598e-6 0 -1 -4.03303e-6 0 -1 8.2562e-7 0 -1 -8.75891e-6 -4.46564e-5 -1 4.67297e-5 -7.55573e-5 -1 2.69e-5 -2.02663e-5 -1 6.53286e-5 -2.67761e-4 -1 -1.32701e-4 7.08709e-6 -1 7.71047e-5 0 -1 -4.58403e-6 0 -1 1.08375e-6 0 -1 3.71697e-7 0 -1 9.63746e-6 0 -1 -1.01804e-5 -4.07674e-4 -1 -1.15604e-4 -5.33702e-4 -0.9999999 -9.06395e-5 0 -1 2.80419e-6 -2.60231e-4 -1 -1.61913e-4 -8.28434e-4 -0.9999997 4.66516e-5 0 -1 9.73279e-7 0 -1 -9.82188e-7 0 -1 2.41373e-5 0 -1 9.82917e-7 -1.17381e-4 -1 -9.56894e-5 -2.30698e-7 -1 -2.71238e-5 5.25936e-5 -1 -1.23392e-4 0 -1 -2.92147e-5 0 -1 -2.95414e-6 -9.61132e-7 -1 -1.16032e-4 0 -1 1.2006e-5 0 -1 -2.08712e-5 0 -1 4.40662e-7 0 -1 7.52106e-6 -5.30081e-5 -1 -1.09803e-4 -1.12646e-4 -1 -9.71112e-5 0 -1 2.24075e-5 0 -1 2.22013e-6 0 -1 -1.2328e-5 0 -1 -4.09397e-6 0 -1 1.66918e-5 0 -1 1.0401e-5 0 -1 -2.49517e-6 0 -1 -7.31078e-6 0 -1 -6.91347e-6 0 -1 -3.69451e-6 0 -1 8.10918e-7 1.41811e-4 -1 5.18163e-5 1.01858e-4 -1 -8.17594e-6 7.92222e-5 -1 -3.09016e-5 5.99552e-5 -1 -5.27431e-5 2.40237e-7 -1 -1.14563e-4 2.7737e-4 -1 2.97855e-4 0 -1 -2.70883e-6 0 -1 4.26502e-6 0 -1 -7.71504e-7 0 -1 -4.29132e-7 0 -1 -1.51057e-6 0 -1 1.18785e-6 0 -1 -9.62721e-6 0 -1 1.33997e-6 1.87654e-5 -1 -7.94177e-6 0 -1 2.03008e-6 0 -1 6.30309e-7 2.11563e-7 -1 -6.20045e-6 9.92126e-7 -1 5.89289e-6 0 -1 -6.05063e-7 2.16578e-6 -1 0 0 -1 -1.66883e-6 0 -1 6.674e-6 0 -1 3.25019e-6 0 -1 -1.71006e-6 0 -1 1.09706e-6 3.39035e-4 -1 4.57803e-5 1.07585e-4 -1 -3.32867e-5 1.73004e-4 -1 -1.39007e-5 0.95 0.31225 -4.5684e-5 0.9260895 0.3773035 7.4959e-4 0.9066277 0.4219316 -1.7759e-4 0.813728 0.581246 2.53961e-4 0.8177964 0.5755074 4.68263e-4 0.7104029 0.7037949 -7.72396e-4 0.6375605 0.7704001 7.32335e-4 0.5650832 0.8250338 -5.19042e-4 0.4858711 0.8740304 5.18226e-4 0.4034625 0.9149962 -4.7125e-4 0.3207862 0.9471517 3.80666e-4 0.2700662 0.9628418 -2.22539e-4 0.1643228 0.9864066 3.26001e-4 0.143935 0.9895872 -1.70086e-5 0.05119138 0.9986888 -3.08134e-4 -0.9457188 0.324986 -8.22451e-5 -0.9416999 0.3364539 2.04698e-4 -0.8704342 0.4922847 -2.8393e-4 -0.8588234 0.5122717 2.51977e-4 -0.7696157 0.6385075 -2.0897e-4 -0.7558075 0.6547938 2.20982e-4 -0.6343867 0.7730159 -2.4246e-4 -0.6177123 0.7864043 2.39985e-4 -0.4622659 0.8867414 -2.60901e-4 -0.4361779 0.8998603 4.73922e-4 -0.2593421 0.9657853 -5.73853e-4 -0.1237888 0.9923086 -2.32314e-4 -0.1928341 0.9812313 5.75688e-4 -0.004616498 0.9999894 0 -0.01362967 0.9999071 2.26453e-4 -3.94288e-4 0.9999999 4.12005e-4 3.65356e-7 1 -8.36586e-6 1.98536e-7 1 -2.56019e-6 -1.71439e-4 1 -1.11961e-4 -2.81192e-4 1 2.96676e-5 0 1 1.83576e-6 1.61695e-4 1 1.9305e-4 -1.6375e-4 1 -1.95503e-4 -1.75712e-7 1 -7.67342e-6 -2.10592e-4 1 -6.0842e-5 -6.71622e-4 0.9999994 9.08025e-4 -1.73745e-4 1 -1.3894e-4 0 1 -5.76027e-6 0 1 1.86656e-5 0 1 -2.46558e-6 0 1 1.53721e-5 0 1 2.76145e-6 0 1 1.80146e-6 7.16236e-5 1 -4.65513e-5 3.53312e-5 1 -6.01381e-5 1.35605e-4 1 -1.59913e-5 3.41657e-4 1 1.61995e-4 -3.60111e-6 1 -8.20162e-5 0 1 -6.13197e-6 0 1 7.32004e-7 0 1 1.79507e-5 0 1 -1.29429e-5 3.2859e-4 1 6.16383e-5 3.09625e-4 1 6.95471e-5 8.18531e-4 0.9999997 -1.10135e-4 0 1 -6.57531e-6 0 1 -2.20057e-6 0 1 4.96908e-7 0 1 1.22246e-5 1.33934e-5 1 4.44392e-5 0 1 2.53347e-5 -7.84953e-7 1 4.37003e-5 0 1 -1.74443e-5 1.73157e-5 1 4.61643e-5 0 1 1.08862e-5 4.17564e-5 1 4.17838e-5 0 1 7.92852e-6 0 1 -2.55475e-6 0 1 1.64191e-5 0 1 -1.03815e-5 0 1 -2.03562e-6 0 1 -1.62008e-6 -1.70157e-5 1 1.27015e-5 -2.39879e-5 1 1.32299e-5 -3.61621e-5 1 0 1.33572e-5 1 4.43016e-5 -9.40417e-5 1 -1.00489e-4 0 1 -1.44135e-5 0 1 8.37906e-6 0 1 1.04719e-6 0 1 -7.81615e-6 0 1 1.60578e-5 0 1 -1.11252e-5 0 1 -6.81644e-7 -2.74863e-4 1 1.29199e-4 0 1 1.2126e-6 3.24078e-6 1 -5.34309e-5 0 1 -1.9722e-5 -2.25267e-5 1 -3.99455e-5 -4.70431e-5 1 -2.73404e-5 -9.72313e-5 1 -1.5791e-5 0 1 -7.11091e-7 0 1 2.09055e-6 0 1 -4.73234e-6 0 1 2.26815e-6 -0.00125432 0.9999992 -1.78742e-4 -4.3399e-4 1 1.13905e-4 0.5679619 0.001554429 -0.8230534 0.5747471 0.01046639 -0.8182643 0.6888856 -0.01288992 -0.7247555 0.7519728 0.02033245 -0.6588807 0.7846322 -0.00853002 -0.6199029 0.8962684 0.008397996 -0.4434328 0.9036667 -0.005226552 -0.4282048 0.9725454 5.63192e-4 -0.2327127 0.9711623 0.004904806 -0.2383691 0.9990257 -0.006502091 -0.0436517 0.9997459 0.008164167 -0.02101153 0.9901482 -0.006131231 0.1398893 0.9862062 0.009155094 0.1652685 0.9479386 -0.01300847 0.3181876 0.9264357 0.01684343 0.3760763 0.8798664 -0.01711219 0.4749131 0.8276611 0.02460426 0.5606886 0.7626307 -0.01842743 0.6465716 0.5574733 9.96233e-4 -0.8301944 0.5547043 3.33345e-6 -0.8320477 0.5547002 1.44069e-6 -0.8320503 0.5547013 0 -0.8320496 0.5547026 -1.8582e-6 -0.8320487 0.5546962 0 -0.832053 0.5571811 0.002538919 -0.8303872 0.5546922 -1.30657e-6 -0.8320556 0.5547019 -2.15787e-6 -0.8320493 0.5547052 2.7609e-6 -0.832047 0.554405 -1.24317e-4 -0.832247 0.5540825 -8.92729e-4 -0.8324612 0.5547028 -1.3958e-6 -0.8320486 0.5546985 2.01528e-6 -0.8320515 0.5547067 -2.39063e-6 -0.832046 0.5547003 0 -0.8320503 0.9804789 0.02037107 -0.1955667 0.9598683 -0.01774382 -0.2798894 0.8885753 0.01116061 -0.4585952 0.8970803 -8.04959e-4 -0.4418669 0.7693966 0.005202233 -0.6387503 0.7574193 -0.006572782 -0.6528958 1.90067e-4 -1 -2.29055e-4 2.66978e-4 -1 -2.0761e-4 4.91454e-4 -0.9999999 -5.18921e-5 4.62912e-4 -0.9999999 -1.65164e-4 0 -1 -2.88474e-6 0 -1 3.65353e-6 0 -1 -5.7345e-6 0 -1 3.13854e-6 0 -1 -9.01823e-6 0 -1 5.09413e-6 6.94082e-5 -1 3.23457e-4 1.59596e-4 -1 2.86733e-4 2.59262e-4 -1 2.6612e-4 4.47194e-4 -1 2.39253e-4 8.18527e-4 -0.9999997 2.12012e-4 0 -1 1.62904e-6 0 -1 -9.4176e-7 0 -1 -1.10231e-6 0 -1 1.17154e-5 0 -1 -1.1853e-5 1.07049e-4 -1 3.03465e-4 0 -1 -1.63612e-6 0.003538548 -0.9999938 6.88772e-5 0.00134176 -0.9999992 -8.47817e-5 0.9999105 -0.01336091 -7.96896e-4 0.9999307 -0.01176482 5.40745e-4 0.8936489 -0.4487669 1.5311e-4 0.8925924 -0.4508645 -1.48785e-5 0.8165633 -0.5772557 5.10962e-4 0.8231471 -0.567828 -5.43674e-4 0.7069243 -0.7072893 6.53829e-5 0.7177059 -0.696344 0.001847803 0.6292738 -0.7771809 -0.002074718 0.5557275 -0.8313623 0.001938521 0.4462539 -0.8949064 4.53641e-4 0.4799275 -0.877305 -0.002365052 0.3211033 -0.9470425 0.001780807 0.2677719 -0.9634792 -0.002462148 0.1732615 -0.9848743 0.001794934 0.104239 -0.9945514 -0.001407921 0.0247513 -0.9996924 0.001626491 -0.9426852 0.3336834 5.37137e-5 -0.9443178 0.3290345 4.80544e-4 -0.889892 0.4561664 -0.002128362 -0.8509895 0.5251787 0.002113103 -0.8072806 0.5901665 -0.00126326 -0.7302225 0.6832077 0.001557648 -0.7065889 0.707624 -6.73649e-4 -0.5882852 0.8086533 -6.24824e-4 -0.5509465 0.8345373 0.002349197 -0.4696013 0.8828774 -0.001568973 -0.3056846 0.9521307 -0.001997351 -0.3534404 0.9354565 0.001086711 -0.2071292 0.9783116 0.00200653 -0.09478127 0.9954981 4.15598e-4 -0.05883306 0.9982661 -0.001924395 -0.6606431 0.02026909 -0.7504265 -0.7156507 -0.01733899 -0.6982432 -0.8106433 0.01144218 -0.5854285 -0.8353202 -0.01287251 -0.5496131 -0.902345 0.01420068 -0.4307806 -0.9382534 -0.01639378 -0.3455603 -0.9515983 0.00368303 -0.3073226 -0.9924318 0.01568979 -0.1217908 -0.9876905 -0.003993034 -0.1563701 -0.9998334 -0.01777607 -0.00418359 -0.9924376 0.01530742 0.1217923 -0.9879698 -0.004081666 0.1545933 -0.9424207 0.005091667 0.3343909 -0.943347 0.007353365 0.3317264 -0.871735 -0.01435297 0.4897674 -0.8360707 0.01612842 0.5483847 -0.7894955 -0.01223164 0.6136344 -0.7136777 0.01502394 0.7003132 -0.555727 -5.72354e-4 -0.8313647 -0.5547015 1.57174e-6 -0.8320495 -0.5546975 -2.3413e-6 -0.8320521 -0.5547 1.08254e-6 -0.8320506 -0.5547003 4.9017e-7 -0.8320503 -0.555484 7.6419e-4 -0.8315269 -0.5546987 0 -0.8320513 -0.5547022 0 -0.832049 -0.5547025 2.25943e-6 -0.8320487 -0.5547031 1.45829e-6 -0.8320484 -0.5546982 0 -0.8320516 -0.5547004 1.23724e-6 -0.8320502 -0.5546993 -2.01901e-6 -0.8320509 -0.5547002 1.65844e-6 -0.8320503 -0.5547027 -2.92203e-6 -0.8320487 -0.5565735 -0.008427619 -0.8307557 -0.5632687 0.00411731 -0.8262637 -0.9725916 0.002022624 -0.2325112 -0.9699337 -0.005731105 -0.243302 -0.8571659 0.00574851 -0.5150085 -0.8492605 -0.004858553 -0.5279517 -0.7008165 0.003924012 -0.7133309 -0.6932806 -0.001451075 -0.7206663 2.01621e-4 1 -2.10244e-4 1.45443e-4 1 -2.30842e-4 3.40383e-4 1 -1.82585e-4 8.33523e-5 1 -2.66282e-4 9.00204e-4 0.9999997 -1.36366e-4 -1.04114e-6 1 -3.33164e-4 -4.7662e-5 1 -3.91779e-4 0 1 7.28347e-6 0 1 3.15919e-5 0.001775801 0.9999982 6.94308e-4 0.001240134 0.9999989 9.42058e-4 0.003128886 0.9999951 4.39499e-4 0.002059936 0.9999979 -1.85355e-4 0 1 2.49578e-6 0 1 1.17084e-5 0 1 -8.85101e-6 0 1 -7.04115e-6 0 1 4.17714e-6 0 1 -1.14124e-6 0 1 9.67214e-6 0 1 1.25295e-5 0 1 4.77106e-6 0 1 2.98578e-6 0 1 -1.11395e-5 0.006245374 0.9999805 1.14577e-4 -0.9999765 6.51401e-4 0.006836414 -0.9999655 -0.001095294 0.00823456 0.9455038 0.3256112 -1.71352e-5 0.9423543 0.3346161 7.46172e-4 0.8413036 0.540562 -0.001122951 0.8357578 0.5490983 3.32233e-5 0.7002666 0.7138813 4.23452e-4 0.6894168 0.7243646 -6.91808e-4 0.5664518 0.8240948 5.67052e-4 0.5558147 0.8313062 -2.6732e-4 0.4091063 0.9124868 -1.2902e-4 0.4034224 0.9150138 4.05431e-4 0.2287077 0.9734952 -6.94781e-5 0.226207 0.9740793 -2.45436e-4 0.0918709 0.9957709 1.14964e-4 0.07562464 0.9971362 -6.92093e-4 -0.8826915 -0.4699518 -0.001113116 -0.890294 -0.4553862 1.19154e-4 -0.8156729 -0.5785076 0.002591729 -0.7731469 -0.6342215 -0.002643406 -0.6948955 -0.7191081 0.001977562 -0.6509131 -0.7591506 -0.001585483 -0.5610546 -0.8277769 0.00184977 -0.5215293 -0.853232 -0.001568198 -0.3675991 -0.9299832 -0.001513004 -0.3972984 -0.9176888 0.001164019 -0.2126169 -0.9771357 3.3992e-4 -0.2267622 -0.9739485 0.001776635 -0.09403538 -0.995568 -0.001309275 -0.01376867 -0.9999052 1.86056e-4 -0.03561896 -0.9993647 0.001221656 0 -1 4.62691e-6 0 -1 -1.15227e-5 0 -1 4.07591e-6 0 -1 -6.22254e-6 0 -1 3.98009e-6 0 -1 2.03128e-6 0 -1 -1.19096e-6 0 -1 -5.71001e-6 0 -1 -3.68e-6 0 -1 3.19124e-6 0 -1 -2.78393e-6 0 -1 -6.78873e-6 0 -1 -1.13333e-6 0 -1 6.52894e-6 -0.00296998 -0.9999956 5.08006e-5 -0.0012542 -0.9999985 -0.001295685 0 -1 -8.92734e-6 0 -1 4.51314e-6 -0.001788318 -0.9999979 -0.00102365 0 -1 -9.72785e-6 -0.003113627 -0.9999951 -5.95547e-4 -5.88235e-4 -0.9999999 2.34506e-4 -3.37016e-4 -1 2.84144e-4 -1.86037e-4 -1 3.26139e-4 -9.41605e-5 -1 3.68923e-4 -1.16724e-5 -1 4.10025e-4 -1.62923e-4 -1 3.16802e-4 -0.004546225 -0.9999897 -2.562e-4 -0.001444339 -0.9999989 1.1532e-4 0 1 1.89594e-5 0 1 -6.35243e-5 1.34148e-4 0.9999997 -8.5081e-4 1.49326e-5 0.9999998 -7.26091e-4 -1.07147e-4 0.9999998 -6.35262e-4 -2.14559e-4 0.9999998 -5.66319e-4 -3.24152e-4 0.9999999 -5.17304e-4 -4.54579e-4 0.9999999 -4.79912e-4 -6.39447e-4 0.9999997 -4.52929e-4 0 1 -3.00299e-6 0 1 9.50335e-6 0 1 4.69348e-6 0 1 -1.21399e-5 0 1 9.54037e-6 0 1 -7.84406e-6 0 1 1.06401e-5 -0.001081764 0.9999994 2.1871e-4 -6.90624e-4 0.9999996 6.04176e-4 0.00146532 0.9999982 0.001293778 -0.01198142 0.9999282 2.85931e-4 -0.05802267 0.9983124 -0.002427101 -0.164473 0.9863801 0.00170052 -0.2117681 0.9773173 0.002300262 -0.211372 0.9774031 0.00227952 -0.2496846 0.9683272 4.4082e-4 -0.3701308 0.9289757 -0.002710998 -0.5131178 0.8583164 0.001783788 -0.7573952 0.6529568 -2.42355e-4 -0.7691079 0.6391178 -0.001161396 -0.3462404 -0.9381453 9.32852e-4 -0.3959123 -0.9182872 -0.001452922 -0.7003022 -0.7138453 0.001313149 -0.7399474 -0.6726644 -7.85654e-4 0.05813443 -0.006146967 -0.9982899 0.4634403 0.004067063 -0.8861189 0.4996781 -0.005778491 -0.8661919 0.7663171 0.007673919 -0.6424167 0.8259769 -0.01014786 -0.5636127 0.9505936 0.009022474 -0.3103071 0.9875081 -0.01482605 -0.1568694 0.9981546 0.01569193 0.05866211 0.9341288 -0.01277148 0.3567075 0.8738902 0.01350206 0.4859359 0.7333901 -0.01231312 0.6796965 0.4710947 -0.0018 0.8820808 0.5214682 0.01033669 0.8532083 0.04127204 -0.009929418 0.9990986 0.09111839 0.001955211 0.9958382 -0.3267807 0.01551425 0.9449729 -0.492245 -0.02000713 0.8702268 -0.7099646 0.01472407 0.7040835 -0.853024 -0.01363259 0.5216938 -0.934105 0.01492702 0.3566863 -0.993045 -0.01538121 0.1167271 -0.9888351 0.01049333 -0.1486443 -0.976841 -0.001453697 -0.2139617 -0.844672 0.001979172 -0.5352807 -0.8441724 0.001759767 -0.5360689 -0.5909268 -0.005414962 -0.8067072 -0.5069603 0.01309818 -0.86187 -0.3030784 -0.01096045 -0.9529026 -0.02457791 0.01237732 -0.9996214 0.2138236 -0.006894171 -0.976848 0.2950476 0.006118476 -0.955463 0.5426765 -0.007362306 -0.8399095 0.590958 0.004300594 -0.8066909 0.8401961 0.002406299 -0.5422775 0.8697975 -0.009579598 -0.4933159 0.9691858 0.008441686 -0.2461863 0.9982186 -0.01482844 -0.05779087 0.9949127 0.01208317 0.1000138 0.8698065 -0.008327722 0.4933228 0.8902229 0.005650579 0.4554902 0.6105395 -0.009512722 0.7919287 0.514233 0.01542651 0.8575118 0.2393141 -0.01227116 0.9708647 0.04980254 0.01191443 0.9986881 -0.09085577 -0.007309556 0.9958373 -0.3735157 0.008152961 0.9275881 -0.4337399 -0.005623817 0.9010207 -0.7442442 0.003770053 0.6678969 -0.7818401 -0.009248197 0.6234104 -0.9453541 0.01390683 0.3257488 -0.9886041 -0.01894581 0.1493416 -0.99102 0.01682847 -0.132651 -0.9480949 -0.01195788 -0.3177627 -0.8399141 0.008602678 -0.5426514 -0.7820005 -0.006392776 -0.6232452 -0.5626643 0.009505808 -0.8266309 -0.5003898 -0.005912482 -0.8657802 -0.1575461 -0.002470374 -0.9875086 -0.1079667 0.008946239 -0.9941143 0.03297758 -0.006017029 -0.999438 0.4483265 -0.003267705 -0.893864 0.4188514 0.003571629 -0.9080479 0.7104963 0.004425227 -0.7036871 0.7607521 -0.0100401 -0.648965 0.9308601 0.01256096 -0.36516 0.9765183 -0.01350897 -0.2150105 0.9998304 0.00881344 -0.01617646 0.9709501 -0.01133149 0.2390142 0.9503272 0.004716336 0.3112174 0.7496734 0.00262618 0.6618028 0.7164002 -0.00904119 0.6976311 0.4407762 0.009065747 0.8975713 0.3657615 -0.006921231 0.9306829 -0.01679807 0.002461493 0.9998559 0.008309304 -0.004723489 0.9999544 -0.3891123 0.0110237 0.9211244 -0.4849398 -0.01291555 0.8744522 -0.7712267 0.007015049 0.6365221 -0.8019195 -0.003373026 0.5974228 -0.9581279 0.004960417 0.2862976 -0.9729763 -0.007060647 0.2307976 -0.9921969 0.006741642 -0.1244988 -0.9767073 -0.01099938 -0.2142941 -0.8806743 0.01185363 -0.473574 -0.7662024 -0.01404249 -0.6424459 -0.665929 0.007680952 -0.7459757 -0.4039337 -0.003870785 -0.9147802 -0.4008244 -0.004678428 -0.916143 -0.01612198 0.005687117 -0.999854 0.07462984 -0.01528447 -0.9970942 0.3180826 0.01630377 -0.9479228 0.4849572 -0.01129913 -0.8744649 0.655721 0.008880674 -0.7549512 0.7656415 -0.007972478 -0.6432182 0.8784055 0.008457243 -0.4778414 0.9367511 -0.01077145 -0.3498308 0.9971251 0.01671439 -0.07390761 0.9949218 -0.01715749 0.09917914 0.8859648 0.01445263 0.4635272 0.8445461 -0.006542384 0.535443 0.4780874 -0.01049721 0.8782495 0.5286258 0.004269003 0.8488442 0.1071939 0.01607489 0.9941083 -0.05746221 -0.01857262 0.998175 -0.3806253 0.01377159 0.9246268 -0.5214425 -0.01471102 0.8531597 -0.7389163 0.01691102 0.6735849 -0.8738347 -0.01817542 0.4858833 -0.9710344 0.01942414 0.2381496 -0.9995003 -0.01952546 0.02485668 -0.9422358 0.02144551 -0.3342632 -0.8823121 -0.01415622 -0.4704519 -0.6172053 0.008015513 -0.7867615 -0.5840616 -0.001858949 -0.8117073 -0.2393997 0.01423472 -0.9708167 -0.1973374 0.002090632 -0.9803334 0.3717284 -0.01160436 -0.9282691 0.328791 0.004350423 -0.9443927 0.6336191 0.01365846 -0.7735246 0.735348 -0.01603209 -0.6775001 0.8125168 0.009175956 -0.5828658 0.9331929 -0.01362752 -0.3591174 0.9601362 0.01007026 -0.2793515 0.9999913 -0.004149794 3.96133e-4 0.999993 0.00348252 -0.001365661 0.2308167 0.001599073 0.9729959 0.2364544 1.09268e-5 0.9716426 0.5492446 0.006776988 0.8356343 0.5280534 -0.002895653 0.8492063 0.8405556 -0.003319859 0.5417152 0.8356361 -0.006776988 0.5492416 0.9547913 0.007330179 0.2971868 0.9726169 -0.008261919 0.2322675 -0.001465976 -0.001139163 0.9999983 -0.002891898 0.005934298 0.9999783 -0.3487102 0.001285254 -0.9372297 -0.3514208 2.61766e-4 -0.9362176 -0.6347857 -0.002477765 -0.7726844 -0.6341612 -0.002748489 -0.7731961 -0.8179715 0.00830686 -0.575199 -0.8697806 -0.01404863 -0.4932388 -0.9496433 0.01325827 -0.3130525 -0.9811931 -0.009434938 -0.1927982 1.0048e-4 -0.002937674 -0.9999957 -5.88299e-4 5.05523e-4 -0.9999998 -0.3622746 -0.008003532 0.9320371 -0.4279354 0.01182681 0.903732 -0.5964136 -0.010374 0.8026103 -0.7068046 0.01610422 0.7072255 -0.8270103 -0.01478284 0.5619925 -0.9189819 0.01531463 0.3940023 -0.9522637 -0.008396506 0.3051613 -0.9999824 0.005802333 0.001346826 -0.9999877 0.004827141 0.001120626 0.230597 -0.9730487 -0.001144409 0.2958132 -0.9552453 0.001035988 0.5477455 -0.836645 -4.13605e-4 0.5588569 -0.8292638 -8.84108e-4 0.7584969 -0.6516758 0.001065194 0.8050926 -0.5931487 -8.20309e-4 0.3153787 0.9489656 8.33078e-4 0.2855036 0.9583776 -1.94924e-4 0.5545094 0.8321769 -0.001110613 0.6214969 0.7834156 0.001262664 0.8352526 0.5498666 1.92349e-4 0.8183397 0.5747344 -7.81875e-4 -0.6777378 -0.009111762 0.7352472 -0.6571977 0.004016518 0.7537077 -0.6049131 -0.002541184 0.7962875 -0.6006156 1.81513e-4 0.799538 -0.538977 -6.71963e-4 0.8423203 -0.5441733 -0.00582093 0.8389527 -0.5051612 0.00350672 0.8630179 -0.4482043 -0.003017961 0.8939261 -0.4647158 4.22526e-4 0.8854598 -0.4352006 -4.82223e-4 0.9003334 -0.4112626 4.58699e-4 0.9115168 -0.3865199 -0.001300692 0.9222801 -0.3811573 -2.07672e-4 0.9245102 -0.3372696 -4.19335e-4 0.9414081 -0.3482162 8.14807e-4 0.9374139 -0.3207205 -2.63025e-5 0.9471739 -0.3008292 0.01335114 0.9535846 -0.2865295 0.005086839 0.9580579 -0.2547067 -0.005162239 0.9670046 -0.1800947 -0.01579111 0.9835225 -0.1351446 0.0253638 0.9905012 0.6865622 0.008937418 0.7270162 0.6312927 -0.01071918 0.7754706 0.6163356 0.001975238 0.7874812 0.5577925 0.003620564 0.8299726 0.5343307 -0.005726754 0.8452562 0.4911226 0.003650009 0.8710829 0.454165 -0.003645837 0.8909102 0.4365219 1.63708e-4 0.8996937 0.4192954 7.27541e-4 0.9078496 0.3923941 -0.001976966 0.9197952 0.387912 -7.73206e-4 0.9216961 0.3604823 0.001113593 0.9327655 0.3366169 -0.001036942 0.9416412 0.3136497 7.36671e-4 0.9495385 0.2874763 0.008241117 0.9577523 0.2745193 0.001346766 0.9615806 0.1824626 -0.01913028 0.9830268 0.1365582 0.02427971 0.9903345 -0.7071127 0.002346873 0.7070969 -0.7055355 -5.51573e-4 0.7086744 -0.7086488 5.44582e-4 0.7055613 -0.7063023 0.003008067 0.7079041 -0.6382954 -0.02355307 0.7694312 -0.5892271 0.0283904 0.8074686 -0.4630405 0.003491044 0.8863304 -0.4881267 -0.02518266 0.8724095 -0.3509947 0.01368492 0.9362775 -0.324762 -0.01368474 0.9456968 -0.1795026 0.02436208 0.9834558 -0.2083502 -0.003643453 0.9780476 -0.0890429 -0.01884073 0.9958497 0.00973314 0.005532979 0.9999374 -0.001421809 -0.009633898 0.9999526 0.705248 -0.003497004 0.7089521 0.7089132 -1.47085e-4 0.7052958 0.7081775 -8.74822e-5 0.7060345 0.7069128 0.00129491 0.7072996 0.6553249 -0.01573348 0.7551834 0.6373811 0.007730126 0.7705099 0.5003868 -0.009362041 0.8657515 0.5035629 -0.01433867 0.8638396 0.3879435 0.0216301 0.9214293 0.3190072 -0.03530704 0.9470944 0.2392925 0.02478867 0.9706311 0.1306399 -0.005316793 0.9914157 0.1229987 -0.01421868 0.992305 -8.56201e-4 -0.004744946 0.9999884 -0.009873807 -0.01303851 0.9998663 2.26186e-4 0.009943723 0.9999505 -4.57437e-4 0.003699421 0.9999932 -0.02035003 -0.003408193 0.9997872 -0.0551998 0.04504513 0.9974588 -0.2145317 -0.06013423 0.9748641 -0.403539 -0.02067965 0.9147288 -0.3480448 0.05010634 0.936138 -0.547774 0.02066117 0.8363712 -0.5762888 -0.02048689 0.8169894 -0.7024691 0.02049386 0.7114192 -0.7263274 -0.0203194 0.6870485 -0.8293879 0.02030634 0.558304 -0.8477498 -0.0201379 0.5300139 -0.9234905 0.02011615 0.3830937 -0.935756 -0.01995944 0.3520829 -0.9810487 0.01994508 0.1927324 -0.9868746 -0.01975464 0.1602756 -0.9990921 -0.01959031 -0.03783196 -0.9997914 0.01974576 -0.005240559 -0.9789808 0.01957303 -0.2030114 -0.971931 -0.01941961 -0.2344632 -0.9194381 0.01940208 -0.3927562 -0.9064608 -0.01924026 -0.4218513 -0.8235188 0.01922011 -0.5669634 -0.8052603 -0.01905703 -0.5926152 -0.6950129 0.0190283 -0.7187455 -0.6723082 -0.01886385 -0.740031 -0.5128426 -0.01870149 -0.8582789 -0.5390189 0.01885014 -0.8420828 -0.3331669 -0.01851201 -0.9426862 -0.3616999 0.01868838 -0.9321073 -0.1403703 -0.01833361 -0.9899293 -0.1700548 0.01848959 -0.9852612 0.05796766 -0.01815903 -0.9981533 0.02829927 0.01831227 -0.9994319 0.2540365 -0.01797431 -0.9670276 0.2255441 0.01815056 -0.9740639 0.4400715 -0.01779592 -0.8977864 0.4138619 0.01795005 -0.9101627 0.6087818 -0.0176301 -0.793142 0.5858089 0.01777648 -0.8102543 0.7534888 -0.01744133 -0.6572294 0.7345868 0.0176084 -0.6782863 0.8684902 -0.01734858 -0.4954028 0.8542511 0.0174005 -0.5195694 0.9397428 0.0167272 -0.3414729 0.9480129 -0.01368886 -0.3179375 0.9884997 0.01317012 -0.1506489 0.9928355 -0.03658878 -0.1137505 0.9947831 0.06698721 0.07693707 0.9843373 -0.07076621 0.1614691 0.9163613 -0.0147584 0.4000802 0.9299801 0.03891438 0.3655447 0.8160422 -0.01292711 0.5778478 0.827746 0.01352751 0.56094 0.7007988 0.01280397 0.713244 0.6869214 -0.01218497 0.7266297 0.5311433 -0.0114144 0.8472051 0.5462868 0.01205581 0.8375114 0.3547722 -0.01059412 0.9348928 0.3702642 0.01126796 0.9288582 0.166825 -0.004213035 0.9859776 0.177482 0.01069122 0.984066 0 1 -8.19343e-6 0 1 -1.36421e-5 0 1 1.51887e-5 0 1 3.37259e-6 0 1 -2.55978e-6 0 1 3.77891e-6 0 1 -2.41616e-6 0 1 6.77296e-6 0 1 7.62782e-6 0 1 -6.68777e-6 0 1 1.77745e-5 0 1 -6.52962e-6 0 1 -5.00651e-6 0 1 -4.9867e-6 0 1 -6.76187e-6 0 1 7.52774e-6 0 1 -3.38581e-6 0 1 6.79653e-6 0 1 -3.38713e-6 -0.1574068 0.07843184 0.9844144 -0.2992626 -0.07201194 0.9514495 -0.4183534 0.07370185 0.9052892 -0.5314058 -0.0582664 0.8451113 -0.6911137 0.0357415 0.7218617 -0.6761615 -0.01231497 0.7366505 -0.8405299 0.04901254 0.5395436 -0.8783286 -0.09065639 0.4693831 -0.9603377 0.08041882 0.2669916 -0.9855109 -0.08083003 0.1491135 -0.9983384 0.05547112 0.01560384 -0.9893554 -0.04059219 -0.1397439 -0.9768371 0.04356807 -0.2095023 -0.9291914 -0.06521993 -0.3637993 -0.8786795 0.07138729 -0.4720448 -0.7961685 -0.05953454 -0.6021391 -0.7469406 0.03073394 -0.6641802 -0.617576 -0.01271909 -0.7864085 -0.6157408 -0.0165984 -0.787774 -0.4044176 -0.01272207 -0.9144861 -0.4180614 0.01271808 -0.9083298 -0.14952 -0.01716512 -0.9886097 -0.1647269 0.01451027 -0.9862325 0.1414527 0.01623809 -0.9898118 0.1646762 -0.02803814 -0.9859491 0.3737445 0.03429096 -0.9268977 0.43252 -0.06423914 -0.8993331 0.603081 0.0673806 -0.7948291 0.6844972 -0.05558204 -0.7268936 0.7660443 0.04202365 -0.6414127 0.8339327 -0.04921823 -0.5496671 0.899512 0.0627709 -0.4323635 0.9381417 -0.05034381 -0.3425723 0.9844325 0.03238266 -0.1727545 0.9916164 -0.03239554 -0.1250903 0.9967848 0.05417376 0.05903786 0.9887192 -0.05415171 0.1396501 0.9341724 -0.01184189 0.3566256 0.9444162 0.03619873 0.3267534 0.8267936 -0.01032429 0.5624108 0.8348799 0.01185113 0.5503047 0.6806967 -0.01407551 0.7324302 0.6915148 0.01116168 0.7222762 0.4640892 0.03884124 0.8849365 0.4556325 0.01682317 0.8900091 0.2553315 -0.0586397 0.9650738 0.1399094 0.08214479 0.986751 0.003090739 -0.07662993 0.9970549 0 1 -7.81223e-6 0 1 3.45638e-6 0 1 -4.10558e-6 0 1 4.95648e-6 0 1 -4.95917e-6 0 1 3.75563e-6 0 1 1.3618e-6 0 1 -6.03415e-6 0 1 -3.86919e-6 0 1 -3.40127e-6 0 1 1.42607e-5 0 1 -5.44381e-6 0 1 -7.50573e-6 0 1 -1.77902e-6 0 1 4.42495e-6 0 1 -1.5057e-5 0 1 2.51422e-6 0 1 -1.37132e-5 0.9979953 0.004328846 -0.06314039 0.9990819 -0.00884211 -0.04192167 0.9398582 0.005029499 -0.3415278 0.9450047 -0.00425148 -0.3270293 0.8017268 -0.004763543 -0.5976718 0.7926629 0.003520429 -0.60965 0.6419766 -0.003026783 -0.7667184 0.6307338 0.003473699 -0.7759915 0.4348228 0.003020763 -0.900511 0.4479023 -0.003470778 -0.8940758 0.2315832 0.003470599 -0.972809 0.2457366 -0.003022372 -0.969332 -0.005061924 -0.008400917 -0.999952 -0.01162755 -0.004331171 -0.9999231 -0.2497977 0.01787292 -0.9681332 -0.3286993 -0.02018654 -0.9442189 -0.5026022 0.01345068 -0.8644132 -0.5658891 -0.01434516 -0.8243566 -0.694099 0.01810747 -0.7196519 -0.7716242 -0.0201652 -0.635759 -0.8686401 0.02252113 -0.4949317 -0.9058413 -0.01300936 -0.4234176 -0.9795618 -5.3945e-4 -0.2011433 -0.982239 0.007834017 -0.1874706 -0.9960516 -0.002311408 0.08874678 -0.9952911 -0.007639646 0.09662961 -0.9057225 0.01042997 0.423743 -0.9032375 0.005946934 0.4291001 -0.7436407 -0.01891523 0.6683119 -0.6926351 0.02145379 0.7209692 -0.4641592 0.007957041 0.8857161 -0.4995236 -0.01216119 0.866215 -0.2618459 -0.01064562 0.965051 -0.1682199 0.02699232 0.9853799 -0.04877191 -0.01954913 0.9986186 0.211516 0.001621723 0.9773733 0.2151538 0.004522025 0.9765697 0.4826683 0.01215803 0.8757188 0.5288886 -0.01522558 0.8485547 0.6978139 0.01229983 0.7161736 0.7222995 -0.005374789 0.6915596 0.8747624 -2.57662e-4 0.4845523 0.8806205 0.005876183 0.4737861 0.9583386 -0.007616519 0.2855336 0.9683828 0.01175916 0.2491915 0.9941248 -0.02627676 -0.1050018 0.9821022 0.02217668 -0.1870391 0.9137363 -0.01439923 -0.4060527 0.8794689 0.01848739 -0.4755972 0.7743902 -0.02478384 -0.6322228 0.6927576 0.02240681 -0.7208223 0.535113 -0.01595938 -0.8446297 0.5007032 0.004123151 -0.8656094 0.2474851 0.003989219 -0.9688835 0.2621976 -0.004391491 -0.9650043 -0.01162755 -0.004331111 -0.9999231 -0.3286993 -0.0201869 -0.9442189 -0.5026036 0.01344954 -0.8644125 -0.5726835 -0.01741653 -0.8195916 -0.6940507 0.02173906 -0.7195979 -0.7972409 -0.02220886 -0.6032526 -0.8686147 0.02391415 -0.4949106 -0.9337946 -0.02722424 -0.3567725 -0.9819357 0.02602624 -0.187417 -0.9985698 -0.02063208 -0.04932248 -0.9965897 0.01859813 0.08039385 -0.9699148 -0.02747732 0.2418892 -0.9285525 0.02981966 0.3700016 -0.8100844 -0.02667313 0.5857064 -0.7661225 0.01783728 0.6424471 -0.5399645 -0.01941698 0.8414638 -0.4933903 0.01344609 0.8697041 -0.2700479 -0.007260441 0.9628195 -0.2477741 0.00302565 0.9688132 -0.02826958 0.006130516 0.9995816 -0.04876679 -0.003022789 0.9988057 0.2441411 0.01572299 0.9696123 0.1931709 -0.009214639 0.9811219 0.4586496 -0.02085536 0.8883726 0.5112997 0.01107966 0.859331 0.7036663 0.007404446 0.7104921 0.7293586 -0.01477825 0.683972 0.8836649 0.004755675 0.468096 0.885688 0.007223427 0.4642246 0.9717325 -0.009640395 0.235888 0.9825991 0.02009934 0.1846482 -0.1803077 -0.01141643 0.9835441 -0.2465098 0.01473605 0.9690282 -0.374188 -0.01358526 0.9272534 -0.4504774 0.01515501 0.8926593 -0.5749018 -0.01515567 0.818082 -0.6536003 0.01910662 0.7565987 -0.7289364 -0.01557034 0.6844044 -0.8362804 0.01210165 0.5481687 -0.8529758 -0.003955662 0.5219355 -0.9522874 0.004847645 0.3051642 -0.9555461 -0.002753973 0.2948294 0.180305 0.01141655 0.9835445 0.2465137 -0.01473623 0.9690273 0.3895793 0.01708918 0.9208344 0.4504833 -0.01425743 0.8926711 0.6414353 0.005222499 0.7671594 0.6399765 0.004004597 0.768384 0.7988558 -0.004006981 0.6015093 0.8027304 1.0775e-4 0.5963423 0.9468318 -0.02367115 0.3208571 0.9296478 0.006123542 0.3683985 0.9854292 0.01919132 0.1689996 0.9981892 -0.03781795 0.04677927 0.9791684 -0.1193776 0.1642507 0.9421293 -0.2055722 0.2648257 0.9653166 -0.1690679 0.1989467 0.888006 -0.2748335 0.3686624 0.8225645 -0.3453761 0.4517778 0.7652752 -0.3837225 0.5168279 0.6335715 -0.4682442 0.6159014 0.6546739 -0.4603368 0.5995767 0.4723414 -0.5267003 0.7067393 0.3502081 -0.5673918 0.7452657 0.6213935 -0.5008745 0.6024906 0.2081161 -0.5842388 0.7844443 0.9864948 -0.0218113 0.1623339 0.9593856 0.01719766 0.2815734 0.8883537 -0.01458275 0.4589284 0.8395524 0.01292419 0.543125 0.690052 -0.01206892 0.7236592 0.6423155 0.01128178 0.7663573 0.4389606 -0.01179867 0.8984288 0.3648427 0.01202714 0.9309915 0.192559 -0.01146507 0.9812185 0.08799964 0.01581507 0.995995 -0.1215029 -0.02133965 0.9923617 -0.2330793 0.01611745 0.9723242 -0.4737896 -0.008392632 0.8805982 -0.4629337 -0.003010213 0.8863878 -0.6686305 0.002315223 0.7435913 -0.6917738 -0.007082402 0.7220796 -0.8125191 0.00985068 0.5828515 -0.8697767 -0.01420027 0.4932413 -0.9378507 0.01791018 0.3465768 -0.9809158 -0.02565205 0.1927335 -0.9995769 0.02582442 -0.01338446 -0.9810241 -0.02094161 -0.1927517 -0.9453325 0.0150358 -0.3257613 -0.8656264 -0.01638436 -0.5004223 -0.7987613 0.01950746 -0.6013318 -0.6611862 -0.01870977 -0.7499886 -0.5399882 0.01734602 -0.8414939 -0.415696 -0.01767367 -0.909332 -0.2461494 0.02256816 -0.9689692 -0.06135773 -0.02180284 -0.9978777 0.09170538 0.0195474 -0.9955943 0.2704812 -0.02151793 -0.9624848 0.4214298 0.02208429 -0.9065921 0.6145381 -0.02352482 -0.7885363 0.6941766 0.0175212 -0.7195914 0.8726939 -0.01365357 -0.4880767 0.9032671 0.01225483 -0.4289038 0.9811503 -0.01418119 -0.1927252 0.9950913 0.02129763 -0.09664291 0.9809325 0.02504104 0.1927291 0.9339151 -0.01959401 0.3569576 0.8613764 0.01959413 0.5075892 0.771462 -0.02134823 0.6359173 0.6341611 0.01747524 0.7730035 0.5218616 -0.01513904 0.852896 0.4086927 0.01342189 0.9125735 0.2227843 -0.01915866 0.9746796 0.1212474 0.01488918 0.9925107 -0.1318566 0.009427547 0.9912241 -0.1662049 -0.009427249 0.9860463 -0.4030439 -0.01440048 0.9150674 -0.5023724 0.01968568 0.8644273 -0.6355982 -0.01300638 0.7719106 -0.7418896 0.0092839 0.6704578 -0.7966099 -0.008900165 0.6044283 -0.8805546 0.01323592 0.4737601 -0.9241207 -0.01084232 0.381947 -0.98156 0.005080461 0.1910872 -0.980777 0.003440439 0.1951017 -0.9971479 -2.97841e-4 -0.07547175 -0.9972579 2.93799e-4 -0.0740053 -0.9427169 -0.003362059 -0.333577 -0.9414814 -0.001969695 -0.3370593 -0.8383808 0.008814215 -0.5450138 -0.8137591 -0.007743775 -0.5811508 -0.6447886 -0.007744312 -0.7643218 -0.5813162 0.02068161 -0.8134149 -0.4292382 -0.0148642 -0.9030691 -0.2781664 0.01157695 -0.9604632 -0.168424 -0.01396775 -0.9856158 -0.02131813 0.01892155 -0.9995937 0.1683969 -0.02162116 -0.9854822 0.3310891 0.01830065 -0.943422 0.449395 -0.0163052 -0.8931844 0.6230975 0.02299648 -0.7818061 0.7459282 -0.02888745 -0.6653997 0.8612858 0.02442264 -0.5075337 0.9440059 -0.01955658 -0.3293486 0.9810338 0.0205124 -0.1927483 0.9996777 -0.02538847 -3.13579e-4 0.9866951 -0.008336961 0.1623681 0.991097 0.003588914 0.1330932 0.9200242 0.01098871 0.3917074 0.8883413 -0.01532864 0.4589282 0.7238301 0.01172381 0.6898787 0.6900864 -0.007907152 0.7236838 0.4810252 0.007619321 0.8766738 0.4389774 -0.007448434 0.8984673 0.1925598 -0.008413434 0.9812492 0.2412332 0.007446825 0.9704386 -0.07764363 0.01077234 0.996923 -0.1215249 -0.009507954 0.9925429 -0.4661357 0.007458567 0.8846818 -0.4629117 0.009432017 0.8863542 -0.6917105 -0.01439845 0.7220314 -0.7713798 0.02144396 0.6360137 -0.8697238 -0.01772046 0.4932206 -0.9487056 0.02106279 0.3154589 -0.9809914 -0.02250176 0.1927428 -0.9973241 0.02413052 -0.06901103 -0.9810411 -0.02011132 -0.1927538 -0.9201697 0.01440483 -0.3912549 -0.8656333 -0.01586836 -0.5004269 -0.7760506 0.01759946 -0.630425 -0.6611923 -0.01767688 -0.7500083 -0.5351184 0.01592063 -0.844627 -0.4405841 -0.0108838 -0.8976454 -0.2462032 0.01120287 -0.9691535 -0.194949 -0.007351577 -0.9807859 0.1047541 1.89141e-4 -0.9944981 0.09172075 0.006053805 -0.9957664 0.3877296 -0.003689587 -0.9217659 0.4215139 0.01017779 -0.9067649 0.6340965 -0.01383584 -0.7731302 0.6759545 0.007732331 -0.7369029 0.8461644 0.007736623 -0.532866 0.8726877 -0.01380145 -0.4880837 0.9749865 0.009603798 -0.2220571 0.9812404 -0.003827989 -0.1927507 0.9988279 0.01930636 0.04438853 0.9849461 -0.009842813 0.1725815 0.9217985 0.003225982 0.387656 0.9275498 0.009346544 0.3735828 0.7875499 -0.009679019 0.6161749 0.7438678 0.01102399 0.6682359 0.6241069 -0.00897479 0.7812874 0.5535091 0.01140546 0.832765 0.3680321 -0.01595932 0.9296761 0.2679613 0.0214076 0.9631919 0.00267744 -0.0261746 0.9996539 -0.1354062 0.02781748 0.9903997 -0.3776531 -0.02279603 0.9256665 -0.502372 0.01968753 0.8644274 -0.6355971 -0.01300525 0.7719116 -0.762426 0.01400661 0.6469237 -0.7966392 -0.004740118 0.6044368 -0.9241679 -0.001916825 0.3819818 -0.9378188 0.01037931 0.3469702 -0.98153 -0.009367108 0.191079 -0.9967274 0.0129435 0.0797947 -0.9971794 -0.01259326 -0.07399231 -0.9806449 0.01468366 -0.1952437 -0.9426016 -0.01588112 -0.3335421 -0.8674633 0.01600694 -0.4972436 -0.8137348 -0.01109749 -0.5811305 -0.644791 -0.007240831 -0.7643248 -0.6881778 0.009228587 -0.7254834 -0.4461231 0.009602129 -0.8949202 -0.4292863 0.00164622 -0.903167 -0.1684176 -0.01488244 -0.9856034 -0.06089246 0.02730917 -0.9977708 0.1683963 -0.02162063 -0.9854823 0.3310907 0.01830035 -0.9434216 0.4493957 -0.0163058 -0.8931841 0.5963104 0.01657408 -0.8025829 0.7292289 -0.01250177 -0.6841557 0.7709213 0.006910145 -0.636893 0.9032594 -0.01334685 -0.4288873 0.9384897 0.0222485 -0.3445896 0.9955382 -0.02083545 -0.09203052 0.02268135 0.004931628 -0.9997307 0.01806455 0.002083957 -0.9998347 -0.9780498 0.002019345 -0.2083622 -0.9748994 -0.003320693 -0.2226217 -0.9030176 0.006442546 -0.4295554 -0.9092029 4.25382e-4 -0.4163532 -0.7869048 -0.009186327 -0.6170061 -0.7515387 0.01122617 -0.6595937 -0.6082443 -0.01122635 -0.7936705 -0.5702984 0.006105303 -0.821415 -0.3949491 8.71671e-4 -0.9187027 -0.3760462 -0.006603717 -0.9265775 -0.2052904 0.006870329 -0.978677 -0.1627851 -0.007782936 -0.9866309 -0.999997 0.002454221 -3.47916e-4 -0.9999979 0.002064704 -3.19028e-4 0.1739497 -0.01098453 -0.9846933 0.2574174 0.0122382 -0.9662229 0.3951037 -0.01066458 -0.9185746 0.4520309 0.007004201 -0.8919748 0.6047407 -0.005509555 -0.7964034 0.629 0.00585103 -0.7773833 0.7787351 -0.009137034 -0.6272864 0.8072906 0.008100569 -0.5900986 0.9092958 -0.003421723 -0.4161365 0.9069143 -0.005509614 -0.4212792 0.9698951 0.008219242 -0.2433847 0.9780884 -0.004961729 -0.2081309 1 4.852e-4 2.41979e-4 0.9999884 -0.004821896 -1.51671e-4 0 -1 5.68616e-6 0 -1 3.01245e-6 0 -1 -1.51231e-6 0 -1 1.32294e-6 0 -1 -2.41892e-6 0 -1 2.33178e-6 0 -1 -6.02144e-6 0 -1 -2.67531e-6 0 -1 5.93268e-6 0 -1 -3.81668e-6 0 -1 2.4272e-6 0 -1 -2.40185e-6 0 -1 2.25157e-6 0 -1 -3.64812e-6 0 -1 1.52397e-6 0 -1 1.93749e-6 0 -1 -3.73729e-6 0 -1 -1.35019e-6 0 -1 6.54649e-6 0 -1 -1.34809e-6 0 -1 4.05584e-6 -0.9995797 -0.02897942 8.1021e-4 -0.9909654 0.02527272 0.1317151 -0.9744219 -0.02346158 0.2234987 -0.9278014 0.02617514 0.3721553 -0.8966857 -0.02115893 0.4421621 -0.8175185 0.01400196 0.5757321 -0.7742196 -0.02295529 0.6325006 -0.7006782 0.02557849 0.7130188 -0.5236507 0.01223576 0.8518453 -0.5609346 -0.0252555 0.827475 -0.298052 0.005463778 0.9545341 -0.3153045 -0.009323716 0.9489448 -0.07551121 0.01879268 0.9969679 -0.1126052 -0.004590988 0.9936293 0.06904488 -0.02606201 0.9972731 0.1889786 0.0270884 0.9816076 0.2976662 -0.02834391 0.9542492 0.4103255 0.03271114 0.9113523 0.5429307 -0.03271281 0.8391402 0.648324 0.03384739 0.7606118 0.7220135 -0.02862584 0.6912866 0.8392132 0.03131639 0.5429001 0.8821001 -0.0288555 0.4701776 0.9524963 0.02886122 0.3031798 0.9693081 -0.0139876 0.2454511 0.9978646 -0.006464779 0.06499695 0.9993718 0.02443927 0.02566373 0.9858329 -0.02245175 -0.1662212 0.9750301 0.01653176 -0.2214568 0.9177687 -0.01086181 -0.396967 0.9121947 -0.001159369 -0.4097557 0.8317756 0.006096124 -0.5550786 0.8205909 -0.006092786 -0.5714837 0.7146879 0.001158952 -0.6994426 0.7109011 0.004907727 -0.7032749 0.5503097 0.01085829 -0.8348901 0.5691294 -0.004908382 -0.8222334 0.3798058 -0.01773452 -0.9248962 0.3429968 0.01329857 -0.9392425 0.1335682 0.001283288 -0.9910389 0.107234 -0.02253752 -0.9939785 -0.1154062 0.02734595 -0.9929419 -0.1665616 -0.01433944 -0.9859268 -0.3511869 -0.006459951 -0.9362832 -0.3798107 0.01773434 -0.9248943 -0.5691322 0.004908084 -0.8222314 -0.5503082 -0.01085823 -0.834891 -0.7324718 0.007282674 -0.6807584 -0.7222971 -0.005766093 -0.6915588 -0.8855758 0.005773723 -0.4644592 -0.8785765 -0.007284283 -0.4775463 -0.9620504 -0.01540809 -0.2724366 -0.965075 -0.00577718 -0.2619102 -0.9945964 0.02454519 -0.1008734 0 -1 -5.91944e-6 0 -1 3.00416e-6 0 -1 1.48555e-6 0 -1 -3.36007e-7 0 -1 4.80844e-6 0 -1 -3.56195e-6 0 -1 6.73328e-7 0 -1 -2.17921e-6 0 -1 -1.91699e-6 0 -1 2.40895e-6 0 -1 2.97682e-6 0 -1 -5.36368e-6 0 -1 2.64172e-6 0 -1 -6.0302e-6 0 -1 -6.06956e-6 0 -1 2.40158e-6 0 -1 -7.76244e-6 0 -1 -4.06003e-6 0 -1 2.98546e-6 0 -1 -1.56587e-6 0 -1 4.25009e-6 0 -1 -3.7652e-7 0 -1 -2.78873e-6 0 -1 -3.30089e-6 0 -1 -7.23018e-6 0 -1 2.81091e-6 0 -1 6.68896e-7 0 -1 1.45452e-6 0 -1 -4.40698e-6 0 -1 8.30865e-6 -0.9999322 -0.006091654 0.009920835 -0.9803074 0.007280051 0.1973438 -0.9815264 0.001868784 0.1913178 -0.8978789 -0.009689927 0.440136 -0.8970124 -0.007752656 0.4419375 -0.802988 0.0150659 0.5958048 -0.7528692 -0.02653622 0.657635 -0.6764631 0.02185148 0.7361523 -0.5165202 0.01145964 0.8561983 -0.5540441 -0.02188217 0.8321997 -0.2980497 0.005465626 0.9545347 -0.3153045 -0.009323596 0.9489448 -0.07551223 0.01879251 0.9969678 -0.1126005 -0.004589021 0.9936298 0.06904524 -0.02606213 0.9972731 0.1889816 0.02708929 0.9816069 0.2743881 -0.016312 0.9614807 0.4104912 0.01712495 0.9117038 0.4426274 -0.007983028 0.8966701 0.6370382 4.84465e-4 0.7708323 0.6422016 0.007039487 0.7665035 0.8061882 0.003956794 0.5916461 0.7979215 -0.005677342 0.6027348 0.9003664 0.00567919 0.4350958 0.894269 -0.003959238 0.4475126 0.9781218 0.02188366 0.2068793 0.969386 -0.00568211 0.2454764 0.9975499 -0.02592039 0.06497997 0.9967725 0.03124248 -0.07394963 0.9857439 -0.02617347 -0.1662044 0.9487337 0.02274703 -0.3152571 0.9176282 -0.02060592 -0.3969056 0.8629519 0.02147775 -0.5048295 0.8204742 -0.01759958 -0.5714127 0.7089582 0.01097548 -0.7051651 0.7242615 -0.008903145 -0.689468 0.5916981 0.01506775 -0.8060189 0.5413438 -0.01686739 -0.8406323 0.4353454 0.01119285 -0.9001941 0.3717566 -0.01804715 -0.9281549 0.2720254 0.02573907 -0.9619458 0.1314282 -0.02286493 -0.991062 0.05958902 0.01394379 -0.9981256 -0.05958861 -0.01394367 -0.9981256 -0.1230028 0.01853328 -0.9922333 -0.2875164 -0.02244532 -0.9575127 -0.3409903 0.01653546 -0.9399214 -0.5274521 0.004907369 -0.8495706 -0.5080067 -0.01086556 -0.8612846 -0.6853202 0.004908442 -0.7282254 -0.674965 -0.004905998 -0.7378335 -0.8030688 -0.004488587 -0.5958694 -0.8109537 0.003578007 -0.5850995 -0.8965956 -0.006673991 -0.4428001 -0.8979111 -0.004337966 -0.4401556 -0.9665546 0.01967036 -0.2557054 -0.9800722 -0.02305787 -0.1972988 -0.999535 0.0159592 -0.02598464 0 -1 -3.45457e-6 0 -1 7.6052e-6 0 -1 6.83382e-6 0 -1 -2.70709e-6 0 -1 -3.57862e-6 0 -1 -1.34145e-6 0 -1 -6.24189e-6 0 -1 -2.59428e-6 0 -1 -5.39887e-6 0 -1 1.71739e-6 0 -1 6.09067e-6 0 -1 5.32308e-6 0 -1 -3.47085e-6 0 -1 -2.42265e-6 0 -1 -2.44396e-6 0 -1 -9.70015e-7 0 -1 1.9319e-6 0 -1 2.2406e-6 0 -1 -1.34959e-6 0 -1 -5.40351e-6 0 -1 -6.17867e-7 0 -1 4.44913e-6 0 -1 5.53655e-6 0 -1 -4.69365e-6 -0.9995797 -0.0289793 8.10207e-4 -0.9909654 0.0252729 0.1317159 -0.974421 -0.02346628 0.223502 -0.9278027 0.0261752 0.3721519 -0.8890951 -0.03125298 0.4566545 -0.7984026 0.03885596 0.600869 -0.7305406 -0.03364413 0.68204 -0.5858919 0.02073913 0.8101239 -0.5400753 -0.02073603 0.8413612 -0.391864 0.02644741 0.9196429 -0.2321897 0.004492104 0.9726603 -0.2756396 -0.02270495 0.9609929 -0.02574574 0.007283568 0.9996421 -0.04058223 -0.005772769 0.9991596 0.2436665 0.01113981 0.9697951 0.2233149 -0.007283687 0.9747191 0.4202779 -0.0113793 0.9073241 0.48307 0.02656286 0.8751788 0.5645729 -0.02048081 0.825129 0.7075673 0.005904197 0.7066214 0.7108708 0.01020008 0.7032487 0.8483508 0.01085758 0.5293233 0.8361598 -0.004909873 0.5484639 0.9251915 -0.01415365 0.3792366 0.9446819 0.01394706 0.3276913 0.9769573 -0.01394385 0.2129787 0.9896168 0.02286738 0.1419005 0.9996679 -0.025738 -0.001328468 0.9931179 0.02165019 -0.1151006 0.9829705 -0.01399314 -0.1832304 0.9462147 0.01871657 -0.3229978 0.917631 -0.02060121 -0.3968995 0.8629493 0.02147364 -0.5048344 0.8204813 -0.01759529 -0.5714025 0.7146512 0.0096457 -0.6994146 0.7182619 0.005462408 -0.6957514 0.550337 0.006125748 -0.8349202 0.5624392 -0.005337357 -0.8268214 0.3566656 -0.006123542 -0.934212 0.3430239 0.005339443 -0.9393116 0.1398645 -0.005772709 -0.9901539 0.125152 0.007287919 -0.9921109 -0.1251556 -0.007283806 -0.9921105 -0.1398596 0.005773186 -0.9901546 -0.3566727 0.006121575 -0.9342095 -0.3430275 -0.005338668 -0.9393102 -0.5624385 0.00533384 -0.8268219 -0.5503318 -0.006124258 -0.8349237 -0.7324717 0.007283449 -0.6807585 -0.7222973 -0.005766153 -0.6915587 -0.8855774 0.005769789 -0.4644558 -0.8785772 -0.007272481 -0.477545 -0.9620499 -0.01540857 -0.2724382 -0.9650752 -0.005773365 -0.2619097 -0.9945966 0.02454501 -0.1008726 0 -1 -1.48474e-6 0 -1 6.86859e-6 0 -1 -1.35487e-6 0 -1 -1.38301e-6 0 -1 -2.96733e-6 0 -1 3.7441e-7 0 -1 4.00474e-7 0 -1 -1.52236e-6 0 -1 2.43789e-6 0 -1 -3.46988e-6 0 -1 1.72789e-6 0 -1 1.71347e-6 0 -1 -3.01198e-6 0 -1 -3.47409e-6 0 -1 6.06361e-7 0 -1 1.51583e-6 0 -1 -2.17607e-6 0 -1 -2.69501e-6 0 -1 6.25659e-6 0 -1 -2.17058e-6 0 -1 -5.3988e-6 0 -1 9.31415e-6 0 -1 9.24791e-6 0 -1 -2.15684e-6 -0.999535 -0.01596087 0.02598488 -0.9800724 0.02305835 0.197298 -0.9665547 -0.01966822 0.2557051 -0.890188 0.007040083 0.4555391 -0.8893541 0.00879091 0.4571347 -0.7504398 -0.01150441 0.6608387 -0.7476049 -0.007181286 0.6641049 -0.5911222 0.023238 0.8062472 -0.5188187 -0.03605365 0.8541238 -0.3972973 0.02427017 0.917369 -0.232192 0.004490792 0.9726596 -0.2675954 -0.01763391 0.96337 -0.02574592 0.007283449 0.9996421 -0.04058223 -0.00577265 0.9991596 0.2436664 0.01113981 0.9697952 0.2233076 -0.00728172 0.9747209 0.4202776 -0.01137804 0.9073243 0.4612011 0.01314932 0.8871982 0.5646495 -0.012241 0.82524 0.6274203 0.02232354 0.7783609 0.7219154 -0.0330066 0.6911937 0.8009849 0.02863734 0.5979995 0.9003711 0.005682766 0.4350858 0.8822563 -0.02187818 0.4702608 0.9782595 0.01404184 0.206909 0.9732116 -0.006580352 0.2298171 0.9997803 -0.01879 -0.009300172 0.9969199 0.0260871 -0.07396024 0.9779734 -0.01929122 -0.2078363 0.9488461 0.01668715 -0.3152978 0.9271613 -0.01421773 -0.3743928 0.862928 0.02253854 -0.5048241 0.81105 -0.03332501 -0.5840269 0.7179376 0.03051424 -0.6954385 0.6226534 -0.02492105 -0.7821009 0.5502312 0.02060562 -0.8347581 0.440109 -0.02194356 -0.8976762 0.3429526 0.02175283 -0.9391009 0.2456657 -0.02174609 -0.9691107 0.1251025 0.02898675 -0.9917203 0.02358388 -0.02454155 -0.9994206 -0.1506906 0.01540732 -0.988461 -0.1398636 0.005772411 -0.990154 -0.3566808 -1.90022e-4 -0.9342264 -0.3507307 -0.00577569 -0.9364587 -0.5694789 0.008601784 -0.821961 -0.5843886 -0.007813036 -0.8114364 -0.7600817 0.02187407 -0.6494594 -0.7397695 3.04309e-4 -0.6728603 -0.8407052 -0.0232231 -0.5409951 -0.907451 0.02100449 -0.4196326 -0.9282127 -0.01096886 -0.3718885 -0.9764186 0.01097053 -0.2156069 -0.9834964 -0.01097255 -0.1805948 -0.9997803 0.01097357 -0.01786398 0.9784675 0.001319646 0.2063969 0.9763088 -0.002409934 0.2163687 0.9156485 0.002429366 0.4019728 0.9167133 0.003407716 0.3995313 0.8403132 -0.006856799 0.5420578 0.8019508 0.009570837 0.5973137 0.7194911 -0.009570062 0.6944357 0.6594939 0.01067614 0.7516341 0.531176 -0.01313376 0.8471598 0.4738732 0.008951306 0.8805476 0.2870735 -0.003513574 0.9579022 0.2891415 -0.00262618 0.9572829 0.08408814 0.002550005 0.9964551 0.09351217 0.006322562 0.9955981 -0.9953057 -0.005533456 0.0966224 -0.9841582 0.00980246 0.1770216 -0.9551946 -0.009375751 0.29583 -0.9288738 0.009380877 0.3702776 -0.8761674 -0.009984076 0.4819039 -0.8219949 0.009896934 0.5694089 -0.7616004 -0.009896039 0.6479715 -0.6971164 0.0083431 0.7169094 -0.5837829 -0.008156895 0.8118689 -0.5724688 -0.003034651 0.819921 -0.4029299 0.008950471 0.9151872 -0.3413586 -0.01313489 0.9398414 -0.1812834 0.0115537 0.983363 -0.09228235 -0.0131976 0.9956455 -0.9999319 0.01107609 0.003694176 -0.9999401 0.01036244 0.003529727 0.04862952 0.01399284 0.9987189 0.1494539 -0.01413172 0.9886677 0.2384651 0.0117858 0.9710795 0.3511396 -0.01355522 0.9362251 0.419665 0.01238888 0.9075945 0.5506117 -0.01028698 0.8346982 0.591739 0.01028698 0.806064 0.6932532 -0.009789228 0.7206277 0.7571459 0.01043015 0.6531626 0.786458 -0.00508964 0.6176227 0.9787916 -0.007070004 0.2047365 0.9673293 0.00900191 0.2533631 0.9137685 -0.009032487 0.406135 0.8903879 0.008409917 0.4551249 -0.06252926 -0.01013207 0.9979917 -0.1494539 0.01413208 0.9886677 -0.2239222 -0.007514536 0.9745781 -0.3355117 -7.4595e-4 0.9420357 -0.3468179 0.004844367 0.93792 -0.4815856 0.003928601 0.8763903 -0.5116115 -0.01028686 0.8591554 -0.6325932 0.0120626 0.7743903 -0.6942828 -0.01531445 0.7195393 -0.75673 0.01003229 0.6536507 -0.989773 -0.01227301 0.1421231 -0.9391697 -0.006243407 0.343397 -0.9571355 0.01277053 0.2893589 -0.8420412 -0.007157266 0.5393658 -0.8613744 0.004032492 0.5079548 0.1989325 0.5863134 -0.7852787 0.2122324 0.5875881 -0.7808313 0.4008512 0.5495278 -0.7330332 0.3839407 0.5483491 -0.7429017 0.5521757 0.503902 -0.6642175 0.6585223 0.4500001 -0.6031984 0.6413291 0.4546129 -0.618081 0.6967366 0.4296671 -0.5744078 0.8076212 0.3460544 -0.4774875 0.7970233 0.3520575 -0.4907233 0.9008546 0.2619249 -0.3462029 0.9370028 0.2021784 -0.2848678 0.9627061 0.1655544 -0.2139831 0.978702 0.1274127 -0.1609614 -0.07252919 -0.9973661 -7.25971e-4 -0.0728513 -0.9973426 -7.47055e-4 -0.2151263 -0.9765856 0.001101851 -0.2325643 -0.9725811 -2.88777e-4 -0.3143216 -0.9493138 -0.002293527 -0.4109622 -0.9116516 0.001245021 -0.4564483 -0.8897478 -0.001999616 -0.5449976 -0.8384371 9.61394e-4 -0.6110889 -0.7915582 -0.00247389 -0.6871456 -0.7265184 0.001397967 -0.7316502 -0.6816771 -0.002145707 -0.8459678 -0.533234 2.87253e-5 -0.8282521 -0.560348 0.002943277 -0.9188337 -0.3946447 -2.26686e-4 -0.9382809 -0.3458572 0.003446102 -0.9743757 -0.2249084 -0.002885818 -0.9900273 -0.1408556 0.002416431 -0.002703785 -0.9641131 0.2654782 0.004484117 -0.9728704 0.2313075 -0.001064181 -0.9601501 0.279483 -0.001876592 -0.8923278 0.4513842 -1.84476e-4 -0.9027526 0.4301601 -0.002077758 -0.7947046 0.606993 -2.23203e-4 -0.8206608 0.5714157 7.69856e-4 -0.719955 0.6940203 -2.3048e-4 -0.7015661 0.7126044 0.3407716 -0.9398952 0.02172029 0.2524021 -0.9672256 0.02771317 0.2502205 -0.9678223 0.0266447 0.2625729 -0.9644939 0.02841132 0.7108142 -0.4980915 0.4966367 0.4967916 -0.8504394 0.1730635 0.5614385 -0.7647144 0.3162262 0.6264507 -0.4906623 0.6056484 0.1662246 -0.9841301 0.06210756 0.3766652 -0.9189169 0.1171119 0.3573556 -0.9267895 0.1155776 0.5372379 -0.7214235 0.4369482 0.5587521 -0.6680995 0.4913647 0.2782171 -0.9437084 0.1789128 0.4577178 -0.5794509 0.6743376 0.0468313 -0.9986411 0.0228669 0.3683381 -0.9067864 0.2050991 0.4935043 -0.7794798 0.3858302 0.2564724 -0.9536878 0.1571678 0.3242754 -0.7365006 0.5936433 0.492302 -0.6414535 0.5883674 0.2726988 -0.9226905 0.2725397 0.1380584 -0.9827723 0.1228764 0.4122548 -0.7253917 0.5512285 0.2809788 -0.9168322 0.2836719 0.1728332 -0.9644494 0.1999149 0.2799427 -0.8830029 0.3767467 0.1172853 -0.9871546 0.1084904 0.9676544 -0.1780114 0.1787648 0.8782575 -0.4336218 0.2015835 0.9157186 -0.3001416 0.2671599 0.9064657 -0.3995038 0.1368086 0.7397581 -0.6581063 0.1401932 0.4643293 -0.8784903 0.1124864 0.6025019 -0.792572 0.09392148 0.7542949 -0.5815199 0.3047525 0.7185379 -0.6069697 0.3395455 0.6857399 -0.6669509 0.2914403 0.6531108 -0.5989987 0.4633 0.6972903 -0.5521106 0.4571216 0.5282306 -0.7813435 0.3323774 0.4473786 -0.7666407 0.4605588 0.1485671 -0.9492767 0.2771311 0.2001214 -0.9305281 0.306707 0.0694015 -0.9856695 0.1537505 0.06424629 -0.9903854 0.122513 -0.007268309 -0.9639903 0.265838 0.004643559 -0.9966148 0.08208239 0.08451408 -0.9341816 0.3466442 0.931258 -0.350072 0.1010362 0.8149937 -0.5738639 0.08040934 0.8208361 -0.5665308 0.07260239 0.8198851 -0.5328949 0.2093119 0.7149277 -0.683597 0.1468796 0.8121663 -0.4439784 0.3785089 0.8069427 -0.461448 0.368659 0.7357965 -0.6166878 0.2798209 0.5525674 -0.8139261 0.1794257 0.5889416 -0.7782071 0.2180399 0.4453206 -0.8656533 0.2287665 0.2581213 -0.7044109 0.6611949 0.9636898 -0.2423726 0.1120612 0.6842717 -0.7277325 0.04666543 0.1819769 -0.7429622 0.6441209 0.1482926 -0.6821634 0.7160046 0.2618828 -0.8074408 0.5286368 0.2349699 -0.825043 0.5139 0.1055595 -0.8577982 0.5030305 0.1315537 -0.7957673 0.5911413 0.094913 -0.8252422 0.5567468 0.4983035 -0.8653677 0.05322003 0.5954746 -0.8030662 0.02224624 0.07811653 -0.9969424 0.001983821 0.2315798 -0.9728152 -0.001163005 0.2514986 -0.9678511 -0.00358361 0.4235562 -0.9058677 0.002005755 0.4801682 -0.8771656 -0.004351198 0.6212069 -0.7836459 -0.001101374 0.5596134 -0.8287519 0.001813232 0.6839222 -0.7295519 0.002125263 0.7184628 -0.6955628 -0.001919567 0.8243256 -0.566116 -2.87792e-4 0.8157453 -0.5784078 -0.002037405 0.9299827 -0.3676021 -9.93773e-4 0.9250136 -0.3799337 5.15529e-4 0.9877918 -0.1557629 0.002318024 0.9771975 -0.2123171 -0.002601087 -0.9941763 -0.0418756 -0.09929716 -0.9652045 0.1000242 -0.2416105 -0.9781528 -0.06559103 -0.1972689 -0.9007953 -0.2314745 -0.3674066 -0.8316324 0.239252 -0.5011447 -0.8459405 0.1052463 -0.5227885 -0.8457037 -0.4042243 -0.3484077 -0.8339222 0.2358961 -0.4989258 -0.7582928 0.2501554 -0.6020086 -0.3474234 -0.9369992 -0.03646349 -0.1939272 -0.9802843 -0.03788137 -0.6273389 -0.7202394 -0.296144 -0.6190983 -0.7429881 -0.2543343 -0.6691934 -0.7306109 -0.1356021 -0.2961935 -0.9522967 -0.07348841 -0.3266535 -0.930743 -0.1643624 -0.337716 -0.9336888 -0.1190512 -0.1606129 -0.9842696 -0.07359993 -0.9845075 -0.1319347 -0.1154919 -0.9766558 -0.2051189 -0.06379461 -0.9576718 -0.1915949 -0.2148401 -0.950479 -0.2509111 -0.1833942 -0.9159591 -0.2085379 -0.3428276 -0.8678225 0.2617439 -0.4223439 -0.869402 -0.4161621 -0.2663629 -0.9005367 -0.2297328 -0.3691295 -0.9164029 0.02161461 -0.3996731 -0.7875387 0.06556707 -0.6127674 -0.9167619 0.02221733 -0.3988158 -0.8364467 -0.5194997 -0.1745775 -0.5612373 -0.8238449 -0.07932454 -0.7805737 -0.5354704 -0.3224535 -0.8792003 -0.3630362 -0.3085638 -0.7513661 -0.6225932 -0.2186933 -0.4619267 -0.8803945 -0.1073749 -0.5339389 -0.8282839 -0.1698682 -0.04611307 -0.9988033 -0.01629865 -0.2602125 -0.962637 -0.07496404 -0.1916872 -0.9792879 -0.06520086 -0.3155944 -0.9405881 -0.1252765 -0.5053214 -0.8382527 -0.2048966 -0.4230759 -0.8837461 -0.1999998 -0.931187 -0.3471431 -0.1112774 -0.9166349 -0.3932721 -0.07153749 -0.8619692 -0.463715 -0.2048847 -0.9678286 -0.08811676 -0.2356762 -0.9305258 0.10948 -0.3494794 -0.6645346 -0.7367494 -0.1248766 -0.6892602 -0.7152499 -0.1154906 -0.5044499 -0.8624327 -0.04171586 -0.4021447 -0.9134533 -0.062312 -0.7950574 -0.5959247 -0.1129489 -0.760074 0.3405818 -0.5534361 -0.6132833 0.3928851 -0.6852189 -0.650576 0.3463089 -0.6758854 -0.4967755 0.40759 -0.7662144 -0.4384167 0.5177614 -0.7346524 -0.4860021 0.3664225 -0.7934335 -0.2505134 0.4873169 -0.8365198 -0.2572261 0.4308357 -0.8649945 -0.2858556 0.4034096 -0.8692222 -0.1350914 0.403321 -0.9050318 0.7665984 0.2909631 -0.5724225 0.2716916 0.4429537 -0.8543862 0.2469744 0.4337854 -0.8665068 0.2189157 0.478381 -0.8504278 0.273001 0.5437185 -0.7936251 0.3195469 0.362243 -0.8755969 0.4696251 0.4445239 -0.7627913 0.4725937 0.4130573 -0.7784851 0.4805718 0.4033073 -0.7787131 0.6426099 0.348559 -0.6823189 0.5651389 0.445015 -0.6946796 0 -1 5.06782e-6 0 -1 5.05998e-6 0 -1 1.50572e-6 0 -1 8.46114e-6 0 -1 -7.69787e-6 0 -1 -7.66901e-6 0 -1 6.84838e-6 0 -1 3.61392e-6 0 -1 -6.22794e-6 0 -1 3.55829e-6 0 -1 1.87823e-5 0 -1 -1.17095e-5 0 -1 3.84223e-6 0 -1 1.33075e-5 0 -1 -3.67448e-6 0.999575 -0.007982015 -0.02803772 0.8910436 0.008870303 -0.4538311 0.8122804 -0.006130695 -0.5832349 0.5030938 -0.003458857 -0.864225 0.4554877 0.003820419 -0.8902339 0.05781328 0.005496323 -0.9983124 -0.09991884 -0.009500324 -0.9949503 -0.4853898 0.009870767 -0.8742422 -0.667779 -0.01018965 -0.7442899 -0.8778216 0.007946848 -0.4789219 -0.9755819 -0.008920788 -0.2194548 -0.999436 0.006836533 -0.0328803 -0.9173165 -0.006621479 0.3981038 -0.8745421 0.003661692 0.4849359 -0.5705965 -0.001778542 0.8212288 -0.5746841 -0.002299547 0.8183722 -0.1977639 0.003685593 0.9802428 -0.09922748 -0.00576657 0.9950482 0.3337201 0.005114972 0.9426584 0.4290285 -0.005234241 0.9032759 0.7661417 0.00618726 0.6426421 0.8460118 -0.007202029 0.5331157 0.9928707 0.007110655 0.118985 0.8093927 0.04799431 0.5853035 0.6063857 0.01698899 0.7949892 0.6295713 -0.04263746 0.7757719 0.2849516 -0.01907515 0.9583522 0.2848041 -0.01872676 0.9584028 -0.02441769 0.042988 0.9987772 -0.1060591 -0.08710896 0.9905371 -0.3378497 0.1016595 0.9356938 -0.4777554 -0.121845 0.8700021 -0.683242 0.1167165 0.7208034 -0.777673 -0.1035276 0.6200862 -0.9130174 0.1035542 0.3945578 -0.955483 -0.09035199 0.2808715 -0.9961219 0.08791303 0.003550648 -0.9949618 -0.06445419 -0.0767908 -0.9131568 0.04949021 -0.4045932 -0.9080131 0.01930564 -0.4184968 -0.7716013 -0.04623597 -0.634424 -0.6800422 0.1278334 -0.7219428 -0.5510944 -0.07938539 -0.8306582 -0.3730395 0.004930436 -0.9278025 -0.4162787 0.003009378 -0.9092321 -0.3315319 -0.005594491 -0.9434275 -0.1709218 0.008896052 -0.9852445 -0.008360147 -0.01198166 -0.9998934 0.1976478 0.01297724 -0.9801872 0.3701295 -0.01298934 -0.9288895 0.5600297 0.01298272 -0.8283708 0.6997241 -0.01299566 -0.7142951 0.8359522 0.0129854 -0.5486488 0.9210586 -0.01299911 -0.389207 0.9827979 0.01299011 -0.1842269 0.999291 -0.008305907 -0.03672492 0.9844366 -0.002678155 0.1757194 0.9772515 0.005660355 0.2120084 0.9160609 0.003974974 0.4010195 0.8972071 -0.001164913 0.4416085 0.866988 -0.06413292 0.4941851 -1.53672e-5 -1.21152e-5 -1 0 -3.34865e-5 -1 -0.00284636 -0.0055058 -0.9999808 1.33805e-4 -2.90764e-4 -1 4.03547e-6 -4.74663e-5 -1 -5.33871e-6 -1.17235e-4 -1 0 -1 -3.58952e-6 0 -1 8.17187e-6 0 -1 -7.15779e-6 0 -1 -6.25022e-6 0 -1 -2.02564e-6 0 -1 3.9675e-6 0 -1 -1.32866e-5 0 -1 6.72893e-6 0 -1 -2.02913e-5 0 -1 -2.47878e-6 0 -1 5.22111e-6 0.9969688 0.001583099 -0.07778769 0.9889417 -0.004613339 -0.1482328 0.8896868 0.003951251 -0.4565542 0.8277971 -0.004577517 -0.561009 0.5945417 0.005660235 -0.8040449 0.4805755 -0.005901813 -0.8769336 0.08573096 0.005923748 -0.9963008 -0.01960027 -0.0050655 -0.9997951 -0.4928569 0.005286812 -0.8700944 -0.5658785 -0.005159378 -0.8244726 -0.9148292 0.005367577 -0.4038056 -0.9480184 -0.006470978 -0.3181496 -0.9786148 0.006678223 0.2055934 -0.9397779 -0.008375704 0.3416834 -0.7627563 0.006465911 0.6466539 -0.5838604 -0.006509065 0.8118281 -0.45831 0.004102528 0.888783 -0.09922772 -0.005167305 0.9950514 -0.01998025 0.002366602 0.9997977 0.3652008 9.30133e-4 0.9309284 0.4520004 -0.008069097 0.8919813 0.7272574 0.009069263 0.6863049 0.9065778 -0.009875297 0.4219232 0.9570479 0.003006279 0.2899143 0.6149299 0.08744055 -0.7837191 0.8075484 -0.09374332 -0.582304 0.8581509 0.07747721 -0.5075179 0.973345 -0.07738947 -0.2158944 0.9877119 0.07677614 -0.1361275 0.9809855 -0.07668161 0.1782903 0.9635506 0.07611143 0.2564711 0.8352074 -0.07599008 0.5446599 0.789416 0.0754351 0.6092061 0.5588026 -0.07530158 0.825875 0.4924213 0.07472389 0.8671435 0.1949712 -0.07460671 0.9779673 0.118718 0.07404571 0.9901633 -0.207544 -0.07775038 0.975131 -0.2736716 0.06353807 0.9597222 -0.5971121 -0.04778456 0.8007334 -0.6182415 0.00975275 0.7859277 -0.8262886 0.008970022 0.5631756 -0.8892813 -4.9167e-4 0.4573606 -0.855576 -0.05910426 0.5142923 -0.907521 0.003596901 0.4199914 -0.9844489 0.002525269 0.1756539 -0.9782145 -0.003959894 0.2075591 -0.9851679 -0.002862751 -0.1715699 -0.9810685 0.00274831 -0.193642 -0.8418142 -0.002704143 -0.5397606 -0.8302295 0.002589821 -0.5574158 -0.567031 -0.002545356 -0.8236926 -0.5506413 0.002429366 -0.8347384 -0.2037006 -0.002384662 -0.9790304 -0.1856623 0.002260982 -0.982611 0.1775771 -0.002051055 -0.9841048 0.1751071 -0.002617359 -0.984546 0.4008091 0.0039801 -0.916153 0.4368942 -5.94492e-4 -0.8995127 0.50321 -0.08104026 -0.8603559 -0.9999931 -0.003738641 -1.58199e-5 -0.9999995 -0.001062035 -2.84803e-4 0 -1 5.30935e-6 0 -1 -2.36125e-6 0 -1 2.11047e-6 0 -1 6.41622e-6 0 -1 7.59503e-6 0 -1 3.61404e-6 0 -1 -9.50557e-6 0 -1 7.283e-6 0 -1 -8.43162e-6 0 -1 -3.32941e-6 0 -1 7.81995e-6 0 -1 1.10629e-5 0 -1 9.319e-7 0 -1 4.11506e-6 0.9959999 0.007236778 -0.08906126 0.9818427 -0.001841306 -0.1896882 0.8230131 -0.003432273 -0.568012 0.7404308 0.01019787 -0.6720553 0.4156109 -0.01137608 -0.9094715 0.1746118 0.01087367 -0.9845774 -0.2056303 -0.008031606 -0.9785969 -0.3232595 0.00262022 -0.9463068 -0.6535405 -2.63918e-4 -0.7568916 -0.6989246 -0.006326496 -0.7151674 -0.9125725 0.008010327 -0.4088368 -0.9860745 -0.008457124 -0.1660892 -0.9992123 0.006385326 0.03916579 -0.9296964 -0.007713377 0.3682462 -0.8564486 0.005490541 0.5162031 -0.5991685 -0.003302752 0.8006162 -0.6017132 -0.002965271 0.7987069 -0.2085303 0.004451453 0.9780058 -0.08526337 -0.007855355 0.9963276 0.3177416 0.007727205 0.9481459 0.496812 -0.007210969 0.8678283 0.6798137 0.004431247 0.7333714 0.8398102 -0.004064381 0.5428649 0.9069609 0.00462377 0.4211896 0.9847162 -0.005261063 0.1740877 0.4585549 -0.09894752 0.8831403 0.3993154 0.00349462 0.9168071 0.4012857 0.003145337 0.9159476 0.06092745 -6.2738e-4 0.998142 0.05446451 -0.002409279 0.9985128 -0.3291459 0.002323746 0.9442762 -0.3469077 -0.002442419 0.9378961 -0.6682092 0.002487123 0.7439693 -0.6831189 -0.002600133 0.7303026 -0.903627 0.002646327 0.428312 -0.9126708 -0.002763211 0.4086864 -0.9989281 0.002806603 0.04620552 -0.9994987 -8.28367e-4 0.03164941 -0.9423646 0.005443394 -0.3345438 -0.9529327 -0.001122117 -0.3031798 -0.8680079 -0.002934336 -0.4965419 -0.8442117 -0.02332746 -0.5355021 -0.8022511 0.04225057 -0.5954897 -0.6965491 -0.07579517 -0.7134945 -0.5633716 0.07966971 -0.8223536 -0.4180663 -0.09324771 -0.9036181 -0.3131624 0.06109511 -0.9477325 -0.01290708 -0.02676373 -0.9995585 -0.01903223 -0.01226466 -0.9997437 0.3470444 -0.005707144 -0.9378313 0.3356017 -0.03275674 -0.9414343 0.5965155 0.06329739 -0.8001017 0.6736812 -0.1036437 -0.7317183 0.8437564 0.1036105 -0.5266308 0.9046141 -0.1040266 -0.4133425 0.9817361 0.1039961 -0.1593082 0.9940685 -0.1044378 -0.03034383 0.9669112 0.1044078 0.23277 0.9280692 -0.1048142 0.3573538 0.8229717 0.07852935 0.5626285 0.7305709 -0.06945455 0.6792955 0.6392303 0.06920856 0.7658949 0 -1 0 0 -1 1.14814e-5 0 -1 -1.59386e-5 0 -1 1.57143e-7 0 -1 -1.00437e-5 0 -1 -4.18525e-6 0 -1 -1.08007e-5 0 -1 1.22522e-5 0 -1 1.83881e-7 0 -1 2.01661e-7 0 -1 -2.7854e-7 0 -1 2.93278e-7 0 -1 -8.10348e-6 0 -1 -1.02476e-5 0 -1 3.00798e-6 0 -1 1.5971e-7 0 -1 1.24602e-5 0 -1 9.51148e-6 0 -1 -2.93422e-7 0 -1 -2.54794e-5 0 -1 0 0.9999995 -8.9638e-4 6.92231e-4 0.9999693 -0.007835626 -5.54742e-6 -9.25221e-4 -0.001184642 0.9999989 6.22022e-5 -0.01100206 0.9999396 0 -1 1.17909e-5 0 -1 4.50312e-6 0 -1 -2.27906e-6 0 -1 -7.69709e-6 0 -1 1.9051e-6 0 -1 -3.87475e-6 0 -1 3.54295e-6 0 -1 9.27158e-6 0 -1 -1.02323e-5 0 -1 -9.29983e-6 0 -1 4.43048e-6 0 -1 -2.22585e-6 0 -1 -2.02469e-6 0 -1 -1.55802e-5 0 -1 1.43055e-5 0 -1 7.44457e-6 0.9184693 0.002630233 -0.3954837 0.8562201 -0.09920883 -0.5069957 0.9407165 0.007432043 -0.3391129 0.9657387 -0.005903124 -0.2594493 0.9992899 0.007241308 0.03697603 0.994687 -0.007269501 0.102689 0.9079028 0.007275879 0.4191179 0.8781423 -0.007306873 0.4783439 0.6824145 0.006948351 0.7309325 0.6257523 -0.008286118 0.7799779 0.3863078 0.008801341 0.922328 0.2925698 -0.008163928 0.9562094 0.02563625 0.008431553 0.9996359 -0.02491229 -0.002657175 0.9996861 -0.331509 -0.00405097 0.9434434 -0.3777998 0.004727542 0.9258753 -0.4722419 4.50986e-4 0.881469 -0.5524782 -0.03477406 0.8328018 -0.6106423 0.05659359 0.7898818 -0.7764918 -0.05636978 0.6276009 -0.8407083 0.09132021 0.5337324 -0.924763 -0.1152911 0.3626587 -0.9788415 0.1378284 0.1512375 -0.9881485 -0.136239 -0.07072186 -0.9716888 0.09669923 -0.2155698 -0.8658797 -0.09186065 -0.4917458 -0.8195808 0.07656461 -0.567825 -0.6240237 -0.06452655 -0.7787367 -0.5586949 0.05308306 -0.8276728 -0.3611808 -0.05715316 -0.9307427 -0.2997314 0.04660636 -0.9528846 0.01664125 -0.01615631 -0.999731 0.01663601 -0.01612621 -0.9997316 0.3398262 0.01604688 -0.9403513 0.3394889 0.01682728 -0.9404596 0.6357088 -0.051584 -0.7702035 0.702309 0.1430384 -0.6973537 0.9818443 -0.001791775 -0.1896805 0.9669919 0.003134548 -0.2547883 0.8230205 -0.004749476 -0.567992 0.755608 0.004453778 -0.655009 0.379989 0.001088738 -0.9249905 0.4156324 -0.00361979 -0.9095255 -0.2139074 -0.001178741 -0.9768533 -0.2106434 -0.001637041 -0.9775616 -0.6407119 0.002965152 -0.7677758 -0.727907 -0.008153617 -0.6856275 -0.9090881 0.008010089 -0.4165272 -0.9949673 -0.007678031 -0.09990578 -0.9999952 0.002132475 -0.00227493 -0.8849607 -0.001545906 0.4656633 -0.8771111 2.40505e-4 0.4802874 -0.605898 2.43645e-4 0.7955424 -0.5812734 -0.002535045 0.8137044 -0.2085316 0.004451453 0.9780055 -0.08526402 -0.007855355 0.9963275 0.3337509 0.008361697 0.9426243 0.4968016 -0.007350325 0.867833 0.7661577 0.006683409 0.6426181 0.8398224 -0.003919959 0.5428472 0.9847296 6.10785e-4 0.1740899 0.9874093 0.002168297 0.1581713 0.9999949 0.001380741 0.002914309 0.9999938 0.002258896 0.002723097 -0.08870238 -0.7545163 0.6502593 -0.2372524 -0.7008453 0.6727014 -0.2340818 -0.6951621 0.679673 -0.2015591 -0.8272725 0.5243988 -0.1009446 -0.8843726 0.455736 -0.3929054 -0.636573 0.6636267 -0.3856198 -0.7411158 0.5495861 -0.1591656 -0.9192786 0.3599907 -0.1618492 -0.8683311 0.4688348 -0.04515153 -0.9711532 0.2341427 -0.00660789 -0.9990465 0.04315924 -0.08605897 -0.9588137 0.2706847 -0.09622895 -0.967109 0.2354573 -0.4830984 -0.5918035 0.6452786 -0.04966884 -0.996205 0.07147413 -0.4536196 -0.7104756 0.5380091 -0.5335758 -0.6565783 0.5331059 -0.3049793 -0.8768345 0.3716839 -0.3104938 -0.8538298 0.4178139 -0.6803298 -0.592986 0.4307193 -0.8192704 -0.3416084 0.4605429 -0.4477009 -0.8291077 0.3348797 -0.1821257 -0.9586569 0.2186488 -0.1981048 -0.9454041 0.2587773 -0.5610094 -0.7162892 0.4149679 -0.6791825 -0.6054985 0.4148287 -0.2995459 -0.9159983 0.2668697 -0.04523932 -0.9972826 0.05814629 -0.2119023 -0.9659413 0.1485089 -0.7856827 -0.5203495 0.334573 -0.1347516 -0.9839342 0.1171141 -0.6767516 -0.6620035 0.3221161 -0.6386697 -0.714967 0.2844699 -0.386005 -0.903118 0.1880908 -0.5394945 -0.8058846 0.2439174 -0.556452 -0.7881369 0.2630618 -0.3941349 -0.8978197 0.1964122 -0.1563883 -0.9774782 0.1417009 -0.4477136 -0.8707477 0.2033499 -0.1587768 -0.984413 0.07563734 -0.4443577 -0.8344426 0.3259627 -0.8306264 -0.4253197 0.3593924 -0.9128727 -0.3026991 0.2739283 -0.7814769 -0.5580918 0.2789757 -0.8523508 -0.5110701 0.1109297 -0.8375677 -0.532615 0.121663 -0.06749314 -0.9974125 0.02476102 -0.9091511 -0.3419139 0.2377796 -0.8316297 -0.5024777 0.2364496 -0.9109414 -0.3869749 0.1429558 -0.9597249 -0.2543631 0.1192797 -0.4940601 -0.8549168 0.1581835 -0.2850762 -0.955235 0.0791065 -0.3445066 -0.9300435 0.1278058 -0.7396668 -0.6637393 0.1110997 -0.6971653 -0.7127888 0.07676386 -0.5508784 -0.8304679 0.0828014 -0.5734138 -0.8139448 0.09322398 -0.9585592 -0.261518 0.113016 -0.6175293 -0.7698897 0.1610198 -0.7111076 -0.6759417 0.193465 -0.6764558 -0.7066627 0.2074499 -0.4677118 -0.8726484 0.1404661 -0.5020048 -0.8607296 0.08447343 -0.3938906 -0.9163931 0.07123196 -0.3096379 -0.9506717 0.0186491 -0.1831369 -0.9829283 0.01768726 0.9965912 -0.006557106 0.08223825 0.9936111 0.009289979 0.1124752 0.9841498 -0.00812608 0.1771527 0.9768733 0.007862567 0.2136746 0.9617193 -0.007983088 0.2739204 0.95135 0.007716536 0.3080156 0.9298084 -0.007829546 0.367961 0.9167295 0.007557809 0.3994373 0.8887312 -0.007661044 0.4583646 0.8733415 0.007383644 0.4870525 0.8389022 -0.007477998 0.5442309 0.8215955 0.007200777 0.5700255 0.7808123 -0.007285594 0.6247232 0.7619818 0.007006764 0.6475607 0.7150336 -0.007081329 0.6990543 0.6950673 0.006799459 0.7189126 0.6422182 -0.006868541 0.7664912 0.621498 0.00657761 0.7833882 0.5630815 -0.00663793 0.8263748 0.5419812 0.006345272 0.8403668 0.4783975 -0.006398737 0.8781202 0.4572688 0.006097435 0.8893076 0.3890049 -0.006146311 0.9212153 0.3681814 0.005836486 0.9297357 0.295772 -0.005876004 0.9552405 0.2717161 0.007731735 0.9623464 0.1993033 -0.007248342 0.979911 0.1966243 -0.005857348 0.9804615 0.09978544 0.006011784 0.9949909 0.09833431 0.004750609 0.9951421 6.94839e-4 -0.01300442 0.9999153 -0.09867721 -0.005666553 0.9951034 -0.06162577 0.01733851 0.9979488 -0.1721287 7.10498e-4 0.9850742 -0.1981494 -0.007059693 0.9801465 -0.2280104 0.005186796 0.9736449 -0.2943492 -0.006275773 0.9556774 -0.3165295 0.006047129 0.9485635 -0.3877318 -0.006077945 0.9217522 -0.4081256 0.005846202 0.9129071 -0.4772844 -0.005877792 0.8787292 -0.4957861 0.005639016 0.8684265 -0.5621368 -0.005663096 0.8270249 -0.5786462 0.005418837 0.8155607 -0.6414402 -0.005440413 0.7671537 -0.6559109 0.005188226 0.7548206 -0.714416 -0.005208194 0.6997019 -0.7268382 0.004945814 0.686791 -0.7803373 -0.004962503 0.6253394 -0.7907382 0.004693686 0.6121367 -0.8385621 -0.004701375 0.5447859 -0.8469982 0.004425764 0.5315776 -0.888503 -0.004429638 0.4588495 -0.8950749 0.004143297 0.4458967 -0.9296732 -0.004142463 0.3683621 -0.934507 0.003848135 0.355924 -0.9616571 -0.003839373 0.2742281 -0.9649187 0.00353384 0.2625253 -0.9841377 -0.003521263 0.1773718 -0.9879965 0.01101076 0.1540834 -0.9965932 -0.01339513 0.08137977 0.9999586 -0.008692502 -0.002730727 0.999973 -0.007271647 -0.001072406 0.00972718 0.598066 -0.801388 0.007213711 0.5991629 -0.8005948 -0.01376372 0.4011076 -0.9159276 0.01290005 0.4556385 -0.8900715 0.0086295 0.4301331 -0.9027243 -0.003794908 0.4525262 -0.8917431 0.7130389 0.4187896 -0.5623086 0.7115985 0.4199116 -0.5632954 0.6137713 0.4748666 -0.6307033 0.6074253 0.4789324 -0.6337651 0.4679953 0.5290911 -0.707844 0.4155619 0.5506913 -0.7239113 0.2364059 0.571955 -0.7854807 0.2320902 0.5724374 -0.7864156 0.4133709 0.556019 -0.7210877 0.1274623 0.6230454 -0.7717304 -0.01986962 0.5793378 -0.8148454 -0.1863765 0.6102771 -0.7699518 -0.2184407 0.5909591 -0.7765637 -0.2568107 0.5801196 -0.7729874 -0.3715896 0.5521371 -0.7463684 -0.488685 0.528434 -0.6942222 -0.5450257 0.500135 -0.6729131 -0.6438211 0.4631395 -0.6090946 -0.6961957 0.430783 -0.5742279 -0.7050214 0.42261 -0.5695136 0 0.6013334 -0.7989983 -0.003742754 0.6018791 -0.7985786 -0.9999989 5.57757e-4 -0.001383185 -1 6.3579e-5 4.37983e-4 -0.9999369 -0.011096 0.001759052 -0.9999983 -0.001612961 9.38779e-4 -0.001856863 0.9972348 0.07429295 0.009450316 0.9988209 0.04761976 1.2648e-4 0.9988182 0.04860359 7.28723e-4 0.9999346 0.01141303 -0.009760439 0.9876095 -0.1566281 0.01076287 0.9577422 -0.2874267 -0.00969249 0.8639005 -0.5035694 0.005670309 0.817927 -0.5752943 0.007790684 -0.5982096 0.8013018 0 -0.6006318 0.7995257 1 -7.19311e-5 1.3489e-5 0.9999998 -6.37212e-4 2.07186e-4 0.9999912 -0.001702845 0.003850877 1 -5.4873e-7 0 1 -7.7181e-7 0 1 2.64191e-7 0 1 -3.95538e-7 0 1 1.53006e-6 0 0.9469283 5.8895e-4 0.3214446 0.9432038 -0.001446902 0.3322117 0.7469552 0.001637578 0.6648724 0.738411 -0.001102983 0.6743501 0.275652 0.003269612 -0.9612519 0.2650222 -0.001769185 -0.9642408 0.1567898 0.001737773 -0.9876305 0.1468477 -0.003009378 -0.9891546 0.4347482 -0.003849744 -0.9005439 0.4473124 0.00387603 -0.8943695 0.6034882 -0.003882348 -0.7973625 0.6146286 0.003883004 -0.7888071 0.7434762 -0.003548741 -0.6687532 0.7522786 0.002828061 -0.6588391 0.8356989 -0.002302348 -0.5491831 0.8504176 0.007378876 -0.5260568 0.9000782 -0.01015955 -0.43561 0.9345394 0.01393944 -0.3555865 0.9625794 -0.01458805 -0.2706071 0.9848214 0.01309025 -0.1730766 0.998104 -0.01450324 -0.05981868 0.9999124 0.00753355 -0.0108934 0.9853467 -0.001539289 0.1705563 0.9852253 -0.001994311 0.171252 0.9380037 -0.001540839 0.3466219 0.9302697 0.008095622 0.3667873 0.8817577 -0.009093403 0.471615 0.851314 0.009094834 0.5245779 0.7952278 -0.005654692 0.6062846 0.7716012 0.005656599 0.6360816 0.7032734 -0.009417712 0.7108572 0.6432188 0.01646292 0.7655055 0.563049 -0.01661872 0.8262565 0.4231956 -2.08087e-4 0.9060384 0.4516245 0.01519238 0.8920788 0 -1 1.01786e-5 0 -1 -5.27038e-6 0 -1 -9.66798e-6 0 -1 6.52147e-6 0 -1 1.07615e-5 0 -1 -1.48337e-5 0 -1 -8.29845e-6 0 -1 6.48494e-6 0 -1 -3.20496e-6 0 -1 1.02492e-5 0 -1 2.05958e-7 0 -1 -7.43897e-7 0 -1 -2.32861e-6 0 -1 5.24593e-7 0 -1 1.44771e-6 3.20589e-6 -1 -2.20036e-5 1.53328e-6 -1 0 0 -1 -9.0436e-6 1.68274e-6 -1 0 0 -1 5.90704e-6 0 -1 1.55344e-6 0 -1 6.11745e-6 0 -1 -2.02335e-6 0 -1 8.27604e-6 0 -1 -2.3453e-6 0 -1 -1.96645e-6 0 -1 1.14639e-5 0 -1 -5.58374e-6 0 -1 9.76553e-6 0 -1 1.59232e-5 -0.003914058 -0.9999764 0.005663931 -7.56151e-5 -1 -5.34235e-5 -6.17989e-5 -1 -7.75227e-5 -4.11457e-5 -1 -1.37477e-4 8.24133e-7 -1 -1.90849e-5 -8.15239e-5 -1 7.87583e-6 -1.82435e-5 -1 -2.26114e-5 -1.86709e-5 -1 -5.60488e-6 0 -1 -2.76053e-7 0 -1 2.55799e-6 0 -1 -3.37537e-6 0 -1 -3.87757e-7 0 -1 8.00964e-6 0 -1 7.10737e-6 0 -1 -3.08305e-6 0 -1 -3.8083e-7 -1.75325e-5 -1 2.30514e-5 2.45217e-5 -1 3.82852e-5 -0.003956437 -0.999992 -7.42136e-4 0 -1 -3.02537e-6 0.001023471 -0.9999975 0.001987934 -0.001949667 -0.9999948 0.00257951 7.63054e-4 -0.9999979 0.00192815 0 -1 2.17843e-6 0 -1 3.01315e-6 0 -1 -2.0914e-6 0 -1 1.24681e-5 0.002562284 -0.9999866 0.004500031 0 -1 -1.3323e-6 0 -1 -4.74482e-6 0 -1 -6.85655e-6 0.002620041 -0.9999888 0.003940463 0 -1 -4.04259e-6 0 -1 5.42311e-7 8.54594e-5 -1 -4.32395e-5 6.97322e-5 -1 -8.39377e-5 0 -1 1.99801e-7 4.51672e-5 -1 -1.60891e-4 0 -1 0 0 -1 -2.43174e-7 0 -1 2.10231e-7 0 -1 0 0 -1 -1.24206e-6 0 -1 0 0 -1 -7.29607e-5 0 -1 -1.985e-6 0 -1 -6.88642e-6 -1.57707e-4 -0.9999992 -0.001317501 -2.80374e-4 -0.999999 -0.001401007 0 -1 1.89833e-6 0 -1 2.14838e-6 0 -1 1.00063e-5 0 -1 -4.70667e-6 0 -1 -3.35066e-6 8.53467e-4 -0.9999862 0.005198717 0 -1 1.56312e-6 0 -1 -4.69162e-6 -0.00177747 -0.9999842 0.005329787 0.003057181 -0.9999953 1.9447e-4 0 -1 -2.40571e-6 0 -1 6.36224e-6 -1.75514e-6 -1 4.88131e-6 0 -1 -2.90007e-6 0 -1 3.27201e-6 -2.34394e-6 -1 4.02478e-6 0 -1 -4.66527e-6 0 -1 3.92506e-6 0 -1 2.58491e-6 0 -1 -8.18486e-7 5.83407e-4 -0.9999997 -7.31028e-4 0 -1 -5.95394e-6 5.66426e-4 -0.9999999 1.3155e-5 3.11627e-4 -0.9999969 0.002501904 1.38971e-6 -1 1.57672e-6 0 -1 -2.31705e-6 0 -1 -4.99403e-6 0 -1 -1.73069e-6 0 -1 7.06664e-6 0 -1 -6.39182e-6 0 -1 -3.77614e-7 0 -1 -5.05366e-6 0 -1 5.00716e-6 0 -1 9.01375e-7 0 -1 2.94856e-6 0 -1 -3.87281e-7 0 -1 -6.42153e-6 0 -1 -6.43815e-6 0 -1 1.63482e-6 0 -1 -4.7138e-6 0 -1 7.74678e-7 0 -1 -1.93288e-7 0 -1 1.6942e-6 0 -1 -1.4761e-6 0 -1 -7.86359e-7 0 -1 1.9444e-6 0 -1 2.59117e-6 0 -1 3.56158e-6 0 -1 -3.34358e-6 0 -1 -9.8211e-6 0 -1 3.28705e-6 0 -1 0 0 -1 -4.22345e-6 0 -1 -3.57444e-6 0 -1 9.91942e-7 0 -1 -4.97857e-7 0 -1 2.21248e-7 0 -1 -5.02065e-6 0 -1 3.82714e-6 0 -1 6.93349e-6 0 -1 5.71605e-6 1.80685e-6 -1 4.16446e-7 0.01810306 5.18321e-4 -0.9998361 1 2.15189e-4 -6.88607e-5 0.999989 -0.004079401 -0.002309441 0.1294156 0.009489715 -0.9915452 0.08957177 -0.004586696 -0.9959699 0.2162197 -0.01027643 -0.9762907 0.2996178 0.009023547 -0.9540166 0.3347035 -0.006337821 -0.9423022 0.4374701 0.009196043 -0.899186 0.4835909 -0.007519304 -0.8752619 0.5374649 0.005872011 -0.8432657 0.5868017 -0.008077919 -0.8096904 0.6428413 0.008074402 -0.7659569 0.7001368 -0.01000666 -0.7139387 0.7262532 0.005081415 -0.6874086 0.8097202 -4.62452e-4 -0.586816 0.821522 -0.01076954 -0.5700752 0.8714856 0.01027345 -0.4903134 0.93074 0.007523596 -0.3656042 0.9134912 -0.01070392 -0.406718 0.9726319 0.005693733 -0.2322822 0.9629688 -0.006287753 -0.2695397 0.99258 0.00536549 -0.1214751 0.9880394 -0.006225943 -0.1540767 -2.91712e-4 -0.0014714 -0.9999989 1.71133e-4 0.002973139 -0.9999957 0 1 1.58093e-6 0 1 -7.34495e-6 0 1 -6.93841e-6 0 1 -1.83195e-6 0 1 2.355e-6 0 1 -1.66311e-6 0 1 1.87072e-6 0 1 -1.95338e-6 0 1 5.42831e-6 0 1 -7.21284e-6 0 1 9.96716e-6 0 1 -3.9569e-6 0 1 4.00757e-6 0 1 0 0 1 8.37417e-7 0 1 -2.62225e-6 0 1 1.59505e-6 0 1 -2.65501e-6 0 1 8.86038e-6 0 1 -5.12002e-6 0 1 7.64817e-6 0 1 3.12945e-6 0 1 8.10524e-6 0 1 -2.65851e-6 0 1 -2.05513e-6 0 1 7.80793e-6 0 1 -5.34538e-6 0 1 1.8018e-6 0 1 -6.06492e-6 0 1 8.82981e-6 0 1 6.62322e-7 0 1 2.00526e-6 0 1 -5.34553e-6 0 1 4.6942e-6 0 1 3.42847e-7 0 1 -1.0922e-5 0 1 5.97323e-7 0 1 5.8829e-7 0 1 -1.16367e-6 0 1 4.45339e-6 0 1 -4.76457e-7 0 1 -2.56338e-6 0 1 1.41715e-5 0 1 -5.76081e-7 2.11281e-6 1 -2.79268e-7 -2.41608e-6 1 1.19348e-6 0 1 2.04951e-5 0 1 7.51639e-5 0 1 -5.05131e-7 0 1 -8.01301e-6 0 1 -5.54776e-7 0 1 1.78588e-5 0 1 1.88432e-6 0 1 -3.03375e-5 0 1 8.38672e-7 0 1 -1.91032e-5 0 1 -1.07656e-5 0 1 2.5715e-6 0 1 -3.35492e-6 0 1 2.83192e-6 0 1 4.37318e-6 0 1 4.86591e-6 0 1 -1.09577e-5 0 1 3.41218e-5 0 1 6.57171e-6 0 1 8.37818e-7 0 1 -2.91024e-6 0 1 0 0 1 1.23396e-6 0 1 -8.23369e-6 0 1 -8.12282e-6 0 1 -1.97897e-5 0 1 5.31616e-6 0 1 1.79173e-6 0 1 -2.4511e-5 0 1 -2.15443e-6 0 1 4.59506e-6 0 1 -2.37071e-5 0 1 3.61287e-6 0 1 2.05212e-5 0 1 5.70171e-6 0 1 -2.80786e-6 0 1 4.99023e-7 0 1 1.83458e-6 0 1 -4.35803e-7 0 1 -1.08146e-6 0 1 1.65208e-6 0 1 2.46316e-6 0 1 4.64253e-6 0 1 1.89926e-6 0 1 -1.29791e-5 0 1 -2.27494e-5 0 1 1.4796e-6 0 1 2.37791e-5 0 1 -1.75857e-5 0 1 5.08006e-6 0 1 1.94222e-6 0 1 -3.92348e-6 0 1 -1.81421e-6 0 1 -1.04945e-6 0 1 3.244e-6 0 1 5.97872e-6 -0.9522724 -0.007568776 -0.3051559 -0.9057668 0.009696722 -0.4236655 -0.8317385 -0.006747305 -0.5551267 -0.677112 0.009536027 -0.7358183 -0.6090881 -0.006706655 -0.7930744 -0.306039 0.002540171 -0.9520156 -0.3103244 0.001533389 -0.9506295 -0.999983 0.005432784 -0.002145051 -0.9999985 8.21721e-4 -0.001553952 -0.985326 -0.006118237 -0.1705736 -0.9880564 0.001921832 -0.1540806 -0.9629696 0.006683647 -0.2695273 -0.9504216 -0.006684899 -0.3108925 -0.9135279 0.006273984 -0.4067278 -0.9086412 4.49421e-4 -0.4175775 -0.8368417 -0.00566715 -0.5474157 -0.8259924 0.005666673 -0.5636529 -0.7335098 -4.49935e-4 -0.6796787 -0.7315453 -0.001863181 -0.6817904 -0.6450745 0.001863956 -0.7641175 -0.6361862 -0.003803014 -0.7715263 -0.4943311 -0.003327488 -0.8692674 -0.5056998 0.004174828 -0.8626994 -0.3626351 0.001425623 -0.9319301 -0.3656204 0.002983987 -0.9307593 -0.2536376 -0.004377663 -0.9672895 -0.2174947 0.01041215 -0.976006 -0.1117269 -0.01297706 -0.9936543 -0.02051907 0.02016603 -0.9995861 0.759188 0.2524949 -0.5998999 0.8527871 0.1852658 -0.4882936 0.7950163 0.1411519 -0.5899368 0.8989491 0.1093167 -0.4241941 0.9397611 0.03685468 -0.3398395 0.8839074 -0.3081777 -0.3517586 0.966263 -0.1039394 -0.2356533 0.8112336 -0.5019953 -0.2998348 0.9910469 0.06353873 -0.1174261 0.6025347 -0.6708027 -0.432407 0.8482915 -0.4569182 -0.2676332 0.5722427 -0.7901408 -0.2195816 0.1698422 -0.9822809 -0.07923394 0.3062841 -0.9355148 -0.1760745 0.2935414 -0.9494951 -0.1108722 0.4248648 -0.8960264 -0.1289451 0.3349937 -0.9384956 -0.08369779 0.667826 -0.7439791 0.02244198 0.2120127 -0.9767061 -0.03310513 0.9450869 0.01581424 -0.3264365 0.8261489 -0.01208448 -0.5633223 0.916818 -0.06958818 -0.3931949 0.9723746 0.04022765 -0.2299339 0.9499152 0.09152227 -0.298806 0.8666577 -0.3341454 -0.3704743 0.9452616 -0.1775966 -0.2737518 0.8581272 -0.424671 -0.2885694 0.9152656 -0.3865935 -0.1132885 0.9790745 -0.1626464 -0.1223086 0.9794218 -0.1585208 -0.1249171 0.914699 -0.3882921 -0.1120495 0.7947467 -0.5913432 -0.1367142 0.436729 -0.866452 -0.2419276 0.4443011 -0.8870969 -0.1251224 0.5840984 -0.8009955 -0.1312834 0.7129903 -0.6953655 -0.090065 0.8181096 -0.5622081 -0.1209083 0.1177193 -0.9915285 -0.05489486 0.1802451 -0.9805248 -0.07799333 0.6327607 -0.7661463 -0.1124001 0.5964084 -0.7984266 -0.08253455 0.4327741 -0.8991815 -0.06464654 0.4167009 -0.9075696 -0.05174791 0.1643469 -0.9846802 -0.0582683 0.05048441 -0.9986496 -0.01225966 0.2278184 -0.9725625 -0.04712861 0.9232791 -0.3160042 -0.2183966 0.7901818 -0.5487403 -0.2729412 0.6839756 -0.6928642 -0.2282905 0.6390339 -0.7347835 -0.2274398 5.72882e-5 -0.8989821 -0.4379855 -2.53898e-5 -0.9000206 -0.4358475 7.05867e-4 -0.7606505 -0.6491613 -0.001779973 -0.7015383 -0.7126296 0.004553496 -0.5821571 -0.8130636 8.14211e-4 -0.6117167 -0.7910766 -0.004500865 -0.7378268 -0.6749752 0.002057015 -0.4950571 -0.8688581 -0.006572365 -0.410445 -0.9118617 0.00308007 -0.5055364 -0.8627998 0.002792775 -0.3102787 -0.9506415 -0.00374943 -0.2538409 -0.9672387 0.005259573 -0.1652299 -0.9862411 2.45311e-4 -0.086286 -0.9962705 -0.005484342 -0.02667069 -0.9996293 -0.005691349 0.06866395 -0.9976237 0.005812823 0.1794983 -0.9837412 0.00676316 0.2110879 -0.9774437 -0.006612658 0.3608633 -0.9325953 0.002918064 0.455295 -0.8903359 -0.004433512 0.3957675 -0.9183401 0.00483644 0.5390936 -0.842232 1.85185e-4 0.5811117 -0.8138238 -0.00112611 0.6617376 -0.7497347 -0.004722774 0.6858977 -0.7276826 0.003784 0.8160442 -0.5779772 -0.002620995 0.7857257 -0.6185696 -0.004876136 0.7762795 -0.6303703 0.005075514 0.8834972 -0.4684089 0.001894295 0.950222 -0.3115682 -0.005519807 0.9551605 -0.2960371 0.006293237 0.979115 -0.2032102 -0.006785988 0.9991207 -0.04137432 -7.16523e-4 0.9959428 0.08998608 0.003058075 0.996701 0.08110517 -0.001851856 0.8548665 -0.5188447 -4.35714e-4 0.9449009 -0.3273565 0.001008391 0.9955127 -0.09462308 -0.001376092 0.9966231 -0.08210128 -0.001656889 0.9953882 0.0959149 0.001234173 0.997308 0.07331609 0.001009285 -0.6016354 0.7987702 0.00374037 -0.6038548 0.7970856 -0.9969482 -0.0462709 0.06287676 -0.9707304 -0.1448349 0.1915862 -0.9620899 -0.1673575 0.2153478 -0.8972639 -0.2631098 0.3545291 -0.8604766 -0.3098719 0.404425 -0.8156147 -0.3473111 0.4627611 -0.6558245 -0.4563579 0.6013582 -0.6537739 -0.4570617 0.6030544 -0.4814741 -0.5243218 0.7023315 -0.3914887 -0.5568369 0.7325772 -0.2900092 -0.5740531 0.76574 -0.1577316 -0.5941346 0.7887489 -0.1403805 -0.5970064 0.7898586 -0.9999973 -0.002061545 0.001095592 -0.9999785 -0.005696177 -0.003278672 -0.970418 0.1467722 -0.191695 -0.9802137 0.116109 -0.1603118 -0.9218416 0.2319482 -0.3104966 -0.9129426 0.2404068 -0.3297583 -0.7184329 0.411884 -0.5605407 -0.7999445 0.3585307 -0.4811908 -0.7923084 0.3621495 -0.4910144 -0.6782152 0.4445127 -0.5851776 -0.5917312 0.4813603 -0.6466425 -0.5806735 0.4825608 -0.6557084 -0.4062783 0.5513802 -0.7286411 -0.3132742 0.5603024 -0.7667598 -0.2697173 0.5778244 -0.7703062 -0.05226719 0.5986816 -0.7992801 -0.005296409 0.5929112 -0.8052505 -0.01241213 0.5961266 -0.8027945 0 -1 -3.34694e-5 0 -1 -1.90189e-6 0 -1 7.23509e-6 0 -1 -1.28275e-5 0 -1 1.49201e-5 0 -1 8.21881e-6 0 -1 -9.26929e-6 0 -1 3.10031e-6 0 -1 -6.81579e-6 0 -1 9.21366e-6 0 -1 -6.57518e-6 0 -1 -5.49664e-7 0 -1 -5.62573e-7 0 -1 6.30001e-6 0 -1 2.4889e-5 0 -1 7.58686e-6 -0.01837277 -0.5097318 -0.8601372 -0.008816838 -0.935976 -0.3519536 -0.1014792 -0.5081382 -0.8552763 -0.1269139 -0.7309356 -0.6705417 -0.1025934 -0.8828303 -0.4583506 -0.2623235 -0.5096721 -0.8194028 -0.1235329 -0.7415826 -0.6593898 -0.2745237 -0.4786641 -0.8339769 -0.1268293 -0.9163703 -0.3797103 -0.430491 -0.4901027 -0.7579425 -0.2394919 -0.8654515 -0.4400424 -0.2020558 -0.8993139 -0.3878248 -0.362492 -0.6232668 -0.6929199 -0.4914743 -0.6179879 -0.6136319 -0.4588943 -0.6591868 -0.5957255 -0.2710757 -0.9137532 -0.3026106 -0.6487668 -0.3679342 -0.6661278 -0.4452356 -0.8014987 -0.3992056 -0.5340747 -0.7306064 -0.4254159 -0.6997584 -0.543577 -0.4635324 -0.739264 -0.4750881 -0.4772633 -0.4011711 -0.8873731 -0.2272245 -0.7208496 -0.6124267 -0.3245142 -0.6372551 -0.7191897 -0.2768973 -0.8099798 -0.5009869 -0.3048689 -0.3931444 -0.9086669 -0.1405777 -0.7404184 -0.6332175 -0.225425 -0.8469701 -0.5101475 -0.1496376 -0.8104822 -0.5724409 -0.1242181 -0.3475118 -0.9353299 -0.06628417 -0.8575501 -0.5139476 -0.0215817 -0.8126114 -0.5813493 -0.04118132 -0.5470458 -0.8366082 -0.02877241 -0.4624414 -0.8865829 -0.01089578 -0.7566007 -0.648005 0.08743667 -0.8087176 -0.5759704 0.1193071 -0.3423299 -0.9380449 0.0536859 -0.6990301 -0.6952294 0.1673713 -0.6598142 -0.7288307 0.1828963 -0.8202284 -0.4658114 0.3320321 -0.6592964 -0.7131058 0.2383453 -0.1851379 -0.9789363 0.08606767 -0.6903591 -0.6388698 0.3394848 -0.5851214 -0.770661 0.2524178 -0.7708363 -0.3972769 0.4979786 -0.6008285 -0.6694649 0.4368317 -0.1782656 -0.9799515 0.08897507 -0.6053884 -0.5954364 0.528167 -0.4622112 -0.7818742 0.4183704 -0.6163339 -0.4149866 0.6692674 -0.2815859 -0.9117327 0.2990866 -0.5070958 -0.5862212 0.6318216 -0.4833706 -0.388669 0.784404 -0.401292 -0.6399529 0.6553054 -0.2303374 -0.8781932 0.4191915 -0.3648038 -0.5948225 0.7163131 -0.2741439 -0.4594635 0.8448305 -0.2707312 -0.5857231 0.7639589 -0.08137923 -0.9552349 0.2844359 -0.1628471 -0.680709 0.7142242 -0.09985929 -0.3707501 0.9233485 -0.05406081 -0.5762704 0.8154692 -0.06336092 -0.7614392 0.6451324 -0.07962405 -0.6617803 0.7454575 0.05672454 -0.8607094 0.5059265 0.07320404 -0.5020004 0.8617638 0.04214531 -0.6393608 0.7677509 0.1278241 -0.7516767 0.6470265 0.2109438 -0.4938443 0.8435761 0.1311867 -0.6900764 0.7117477 0.3187976 -0.405429 0.8567353 0.3033266 -0.6671984 0.680323 0.2428316 -0.7704302 0.5894662 0.3900244 -0.5519991 0.7370061 0.5083327 -0.3441109 0.7894211 0.238174 -0.8870822 0.3954218 0.5221067 -0.5497434 0.6520636 0.6137537 -0.3934215 0.6844896 0.4824013 -0.7049497 0.5199375 0.3634359 -0.8348559 0.4134367 0.5978184 -0.5225281 0.6079289 0.6848236 -0.5241206 0.5062749 0.6745621 -0.5394424 0.5039524 0.2951188 -0.9370753 0.1865335 0.7962754 -0.3925371 0.4602828 0.6533054 -0.6898006 0.3120373 0.7299092 -0.6369221 0.2481189 0.5845283 -0.7598592 0.2845011 0.6252045 -0.7170714 0.308104 0.8520331 -0.4745163 0.2210742 0.3689015 -0.9228109 0.111049 0.8077789 -0.5584012 0.1888955 0.5625913 -0.8236562 0.07128375 0.894862 -0.4332792 0.1071969 0.4510667 -0.8916652 0.03836935 0.8176921 -0.5745258 0.03605377 0.8799291 -0.4732037 -0.04246294 0.8537742 -0.517958 -0.05281388 0.3485127 -0.9371166 -0.01874542 0.8168005 -0.5531699 -0.1638298 0.8461531 -0.4942095 -0.1994542 0.5899034 -0.795319 -0.139577 0.5620596 -0.8157159 -0.1367365 0.7455662 -0.6178103 -0.2498833 0.6430861 -0.7547687 -0.129478 0.7546367 -0.5571095 -0.3466306 0.5957515 -0.7366535 -0.3200342 0.591425 -0.7414681 -0.3169254 0.8105195 -0.2817414 -0.5134977 0.617309 -0.6399424 -0.4576062 0.6449516 -0.524739 -0.5555955 0.3762457 -0.8945259 -0.2413764 0.6668346 -0.4221025 -0.6141344 0.3177146 -0.8940473 -0.3158114 0.5494616 -0.4797962 -0.6840232 0.5678836 -0.4388163 -0.6963824 0.3911595 -0.7981929 -0.4581294 0.4425275 -0.7457408 -0.4980363 0.2414034 0.9152914 -0.3224375 0.3597248 -0.7417814 -0.5660022 0.4974058 -0.2334769 -0.8355093 0.2486296 -0.8431055 -0.4768192 0.3647814 -0.5460821 -0.7541412 0.2376641 -0.7893989 -0.5660082 0.2787629 -0.4318124 -0.857805 0.2132194 -0.5902583 -0.7785454 0.1105694 -0.9120543 -0.3948817 0.05355495 -0.8541486 -0.5172641 0.1120513 -0.498129 -0.8598325 0.06330591 -0.6173153 -0.7841646 0.05281186 -0.8120664 -0.5811705 -0.1239538 -4.72671e-4 0.9922879 -0.09196233 2.47745e-4 0.9957625 -0.2475295 -7.32208e-4 0.9688801 -0.1847659 -2.74799e-5 0.9827826 -0.330291 4.01318e-5 0.9438791 -0.3447927 -2.25973e-4 0.9386789 -0.4680249 2.6693e-4 0.8837152 -0.4651478 3.56111e-4 0.885233 -0.5731753 -2.22091e-4 0.8194327 -0.6211625 0.001145303 0.783681 -0.7173311 -5.87732e-4 0.6967322 -0.7552732 5.08019e-4 0.65541 -0.8201795 -3.48928e-4 0.5721064 -0.820092 -3.44396e-4 0.5722317 -0.8995677 3.37361e-4 0.4367812 -0.9080789 -3.12327e-4 0.4187993 -0.9492881 -6.10147e-4 0.3144072 -0.9658388 4.36546e-4 0.2591435 -0.987706 -9.91495e-4 0.15632 -0.9959348 1.61732e-4 0.09007829 -0.9999682 -7.6573e-4 -0.00793451 -0.9987289 1.94034e-4 -0.05040335 -0.9886333 1.79623e-4 -0.1503475 -0.9844782 -4.07271e-4 -0.1755068 -0.9562977 5.61272e-4 -0.2923943 -0.9382752 -3.96728e-4 -0.3458895 -0.911163 6.56455e-5 -0.412046 -0.8989956 -4.38363e-4 -0.4379575 -0.8249019 2.85049e-4 -0.5652759 -0.8288082 5.09731e-4 -0.5595326 -0.7660995 -4.49717e-4 -0.6427219 -0.7159492 4.29952e-4 -0.6981524 -0.6620182 -9.08989e-4 -0.7494872 -0.5963382 -1.0568e-5 -0.8027334 -0.5511803 -5.80917e-4 -0.8343861 -0.4789475 4.44565e-4 -0.8778434 -0.4459937 -3.57106e-4 -0.8950361 -0.3356767 7.83977e-4 -0.9419769 -0.3088024 -1.31632e-4 -0.9511262 -0.1699856 -2.17303e-4 -0.9854466 -0.1250708 7.81496e-4 -0.9921476 -0.02777814 -5.79286e-4 -0.999614 0.07478386 3.31314e-4 -0.9971997 0.091264 -1.24704e-4 -0.9958267 0.2752599 -2.62442e-4 -0.9613699 0.2662994 8.00326e-5 -0.9638904 0.4607916 1.01739e-4 -0.8875085 0.4606924 1.059e-4 -0.8875598 0.6176433 1.61737e-4 -0.7864584 0.6309865 -4.34195e-4 -0.7757938 0.7584147 5.44874e-4 -0.6517722 0.7888841 -7.79343e-4 -0.6145416 0.8377512 4.00182e-4 -0.5460519 0.9033159 -5.98242e-4 -0.4289757 0.8985775 -2.50411e-4 -0.4388149 0.9583816 -2.57781e-5 -0.2854906 0.9595492 -1.13933e-4 -0.2815414 0.985197 1.78798e-4 -0.1714261 0.9889391 -2.27422e-4 -0.1483221 0.9979627 1.25816e-4 -0.06380069 0.9993366 -3.63419e-4 -0.03641968 0.998157 5.80328e-4 0.06068122 0.9893718 -5.25289e-4 0.1454065 0.9822668 3.55443e-4 0.1874883 0.9537903 -6.84397e-4 0.3004727 0.9305622 1.08653e-4 0.3661339 0.9159777 -5.65889e-4 0.4012287 0.8701969 3.87187e-4 0.492704 0.8462217 -3.36965e-4 0.5328308 0.7929549 4.8454e-4 0.6092802 0.7655301 -2.45661e-4 0.6434002 0.6840173 3.43927e-4 0.7294658 0.7171255 -0.0011518 0.6969431 0.6107561 5.70274e-4 0.7918186 0.5419132 -9.46745e-4 0.840434 0.4721634 5.30208e-4 0.8815109 0.389307 1.92375e-4 0.9211081 0.367568 -5.33687e-4 0.9299965 0.2456512 -2.95763e-4 0.9693583 0.2393482 -4.80364e-4 0.9709337 0.07524305 6.78815e-5 0.9971652 0.06832045 -1.74568e-4 0.9976635 -0.001038849 -0.9999989 -0.001128494 0.006433069 -0.9999737 -0.003373146 -0.001207113 -0.9999977 -0.001828312 4.4557e-4 -0.999995 -0.003131926 1.97224e-4 -1 1.55983e-4 -0.00235033 -0.999991 0.003543734 -4.40483e-4 -0.9999997 8.07713e-4 -0.001140177 -0.9999977 0.00182259 -2.47246e-4 -0.9999997 7.77303e-4 -0.001486957 -0.9999977 0.001522541 -8.74319e-4 -0.9999993 8.1861e-4 5.29408e-4 -0.9999986 0.001620829 -6.38149e-4 -0.9999991 0.001233875 -8.20627e-5 -0.9999994 0.001151919 7.13346e-4 -0.999998 -0.001909434 -5.11835e-4 -0.9999979 0.002063572 0.00153619 -0.9999975 0.00163567 -0.005562245 -0.9999734 -0.004727244 0.004142045 -0.9999914 3.40865e-4 0.001117706 -0.9999989 -0.00104314 -0.001307666 -0.9999992 9.95983e-5 -7.24018e-5 -0.9999978 -0.002140998 9.74355e-4 -0.9999994 5.91499e-4 5.34217e-4 -0.9999993 0.00110656 -0.001811683 -0.9999983 5.52174e-4 -0.001222252 -0.9999865 -0.005050301 0.001050472 -0.9999971 -0.002141654 0.001904547 -0.9999845 0.005252122 -9.00863e-4 -0.9999992 9.58589e-4 -4.34099e-4 -0.9999996 8.91709e-4 -0.003204047 -0.9999933 0.001767337 -0.003343224 -0.9999929 0.001759052 -0.004198551 -0.9999895 0.001903235 4.20545e-5 -0.9999993 -0.001211941 -9.49435e-4 -0.9999995 -3.51755e-4 0.001266896 -0.999996 0.002535164 0.006135523 -0.9999737 -0.003885567 5.07599e-4 -0.9999999 -2.58094e-4 -0.002239823 -0.9999961 0.001701593 0.001305699 -0.9999978 -0.001653552 -1.58402e-4 -0.9999997 8.60579e-4 0.001094639 -0.9999983 -0.001488208 -0.01908767 0.5175828 0.8554204 0.007341504 0.9512169 0.3084356 -0.1172937 0.1514195 0.9814858 -0.1304084 0.7330495 0.6675568 -0.1120005 0.8357768 0.5375249 -0.121798 0.7542297 0.6452153 -0.2072203 0.4637401 0.8613971 -0.3504109 0.3377116 0.8735921 -0.2612084 0.6037217 0.7531868 -0.2198136 0.8321227 0.5091698 -0.3836786 0.5359619 0.7520211 -0.3555297 0.7829456 0.510485 -0.375881 0.7659053 0.5216346 -0.5111463 0.5281775 0.6780547 -0.4313133 0.6569113 0.6184144 -0.6008881 0.4900903 0.6314625 -0.4429658 0.789305 0.425181 -0.07454359 -0.993541 0.08555531 -0.7090624 0.3399032 0.6178158 -0.57419 0.6919116 0.4376807 -0.6794783 0.5739327 0.4570673 -0.3363963 0.8993474 0.2793063 -0.7933464 0.4394982 0.4212399 -0.7594131 0.5347127 0.3706403 -0.2773317 0.9443658 0.1768061 -0.8758504 0.3809314 0.2962727 -0.8519726 0.4447496 0.276298 -0.6469547 0.7306465 0.2181868 -0.5571234 0.8117958 0.1749315 -0.8727684 0.4680967 0.1384231 -0.8660943 0.4814733 0.134403 -0.4602494 0.8866003 0.04593968 -0.8344123 0.5510208 -0.011505 -0.8541492 0.5200108 -0.004249572 -0.6435104 0.7654095 -0.006541252 -0.7549483 0.6557148 0.009549617 -0.9725368 0.1452871 -0.1818355 -0.5882751 0.8054738 -0.0717262 -0.7653999 0.6009877 -0.230167 -0.4552197 0.8845692 -0.1015495 -0.7534053 0.6134796 -0.2366926 -0.8120514 0.4574879 -0.3623223 -0.5145509 0.8293082 -0.2179117 -0.347921 0.9220087 -0.1698563 -0.7482466 0.5480197 -0.3739005 -0.7504945 0.4380278 -0.4948635 -0.7314993 0.4731582 -0.4909482 -0.3472088 0.9049594 -0.2459568 -0.6099461 0.5915511 -0.5272886 -0.4013555 0.8638874 -0.3043227 -0.5718927 0.5234753 -0.6315951 -0.5931646 0.4908361 -0.6381502 -0.2839812 0.9165524 -0.2815786 -0.3485693 0.8121438 -0.467891 -0.5165868 0.3823769 -0.766111 -0.3213616 0.8368575 -0.4431661 -0.4935585 0.4378227 -0.7514728 -0.3940739 0.5220266 -0.756435 -0.2551047 0.7733275 -0.5804191 -0.3731848 0.3547604 -0.8572505 -0.1366779 0.9040544 -0.4049749 -0.2208479 0.5937358 -0.7737597 -0.1832128 0.5424675 -0.819855 -0.07828587 0.9243706 -0.3733772 -0.1481037 0.6213501 -0.7694085 -0.06959348 0.8306854 -0.5523756 -0.02427005 0.572753 -0.8193687 -0.04071408 0.5304582 -0.8467328 -0.027309 0.9066973 -0.4208969 0.07743322 0.4504023 -0.8894616 0.08386439 0.4881657 -0.8687123 0.03724622 0.7259865 -0.6866996 0.05936557 0.9092401 -0.4120172 0.2063065 0.3196846 -0.9247915 0.1516998 0.8288328 -0.5385383 0.2297576 0.580296 -0.7813246 0.1343189 0.8521762 -0.5057216 0.3788729 0.534061 -0.7558004 0.3810768 0.4919613 -0.7827865 0.202821 0.9081522 -0.3662285 0.5195977 0.5196979 -0.6781833 0.4001635 0.6732296 -0.6217967 0.3744993 0.7310366 -0.5703822 0.5159977 0.5631442 -0.6454572 0.6534674 0.2873911 -0.7002761 0.3863149 0.8253062 -0.4118622 0.4763199 0.7506055 -0.4579418 0.6696811 0.5526058 -0.4961394 0.7222105 0.4592769 -0.5171816 0.4351607 0.8559439 -0.2792762 0.7870177 0.4606354 -0.4103882 0.7066224 0.6124848 -0.3543264 0.8580985 0.3813543 -0.3438547 0.8795286 0.1533421 -0.4504618 0.5591643 0.7843255 -0.2686426 0.8903537 0.3837352 -0.244985 0.5723329 0.7869327 -0.2305907 0.8434708 0.5106995 -0.1665635 0.2889917 0.953643 -0.08395826 0.820595 0.5530032 -0.1442611 0.8758416 0.4820725 -0.02253484 0.8334324 0.5513831 -0.03697574 0.5818455 0.8130683 -0.01938587 0.6384793 0.769113 -0.02845394 0.8355625 0.535075 0.1246209 0.8212239 0.5584033 0.1173762 0.4337924 0.8981189 0.0721575 0.6945363 0.7011125 0.1614335 0.9445012 0.1531091 0.2906463 0.7178114 0.6366637 0.281791 0.403117 0.9041427 0.1415017 0.7765725 0.5285679 0.3428574 0.5742159 0.7616288 0.3003295 0.7523241 0.437581 0.4924746 0.7446975 0.4621617 0.4814895 0.3095426 0.9264633 0.2141246 0.6299474 0.5932737 0.5011913 0.3284493 0.8820316 0.3378486 0.6155064 0.4554133 0.6432345 0.6186138 0.438319 0.6520686 0.4465004 0.7867602 0.4261994 0.5342824 0.3147979 0.7845028 0.3251404 0.8217077 0.4680603 0.4823042 0.4591168 0.7460526 0.3652647 0.7153289 0.5957233 0.349951 0.352369 0.8679691 0.3390274 0.5182907 0.7851338 0.1721602 0.8528096 0.4930282 0.2411041 0.4191047 0.8753401 0.1865127 0.5957298 0.7812293 0.1917719 0.6120037 0.7672517 0.1853803 0.6364951 0.748671 0.03076928 0.6489835 0.76018 0.2984948 0.4432171 0.8452571 0.1064398 -0.8555612 0.5066416 0.002744019 0.9999962 4.86244e-4 0.0030514 0.9999946 0.001261413 -0.002822637 0.9999943 -0.00185281 -0.003540873 0.9999899 -0.002794981 -0.003823697 0.9999901 -0.002300143 0.003695487 0.9999915 0.001855194 0.004169106 0.9999914 8.52705e-5 0.00285381 0.9999957 -6.5993e-4 -0.001426935 0.9999983 0.001222789 -0.005153417 0.9999867 -1.4439e-4 5.13275e-4 0.9999793 -0.006424129 8.96488e-4 0.9999993 8.0787e-4 0.001586914 0.9999983 9.39574e-4 1.17016e-4 0.9999994 0.001096189 5.48912e-4 0.9999946 0.003260195 6.49399e-4 0.9999973 0.00226432 -0.002645373 0.9999958 -0.001250267 0.006398916 0.9999791 9.72265e-4 -4.49882e-4 0.9999916 0.004086554 0.001313686 0.9999879 -0.004740655 -0.005859792 0.9999806 0.002150475 0.002281367 0.9999794 -0.00599569 3.26453e-4 0.9999994 -0.001080513 -5.12976e-4 0.9999995 9.39118e-4 4.63129e-4 0.9999988 -0.001476764 0.001196026 0.9999994 1.91822e-4 0.001136779 0.9999994 1.87169e-4 -0.001258432 0.9999988 0.001026809 0.001612603 0.9999974 -0.001600325 0.002453088 0.9999576 -0.008884251 -0.001945912 0.9999954 0.00234586 -0.001188576 0.9999991 6.69593e-4 -0.001943111 0.9999917 0.00358355 -0.003879368 0.9999918 -0.001246094 -0.001298904 0.9999977 0.00170952 0.005075395 0.9999869 7.42671e-4 -5.71305e-4 0.9999964 0.002676546 -0.001764535 0.9999976 0.00135976 0.001420021 0.9999876 0.004787445 -0.001192629 0.9999992 -5.07277e-4 -0.001345932 0.9999951 0.002860069 -0.003029882 0.9999939 -0.001756191 -0.9949764 -0.01450693 -0.0990538 -0.9794395 0.01170879 -0.2013983 -0.904112 -0.008109211 -0.4272189 -0.9082312 -0.003634929 -0.4184529 -0.7327061 0.003281295 -0.6805372 -0.7221409 -0.002773642 -0.6917406 -0.5346948 0.002263724 -0.8450423 -0.5223254 -0.00197035 -0.852744 -0.325446 0.002291202 -0.9455579 -0.3112177 -0.003101348 -0.9503336 -0.007877349 0.003636956 -0.9999625 0.007877349 -0.003636956 -0.9999625 0.3424468 0.003817915 -0.9395295 0.3171921 0.01706123 -0.9482079 0.5061296 -0.01482146 -0.8623301 0.6741807 0.0187183 -0.7383292 0.7212279 -0.007057487 -0.692662 0.8974896 -0.004014492 -0.4410176 0.9008366 -1.53822e-4 -0.4341585 0.9853003 0.01200014 -0.1704093 0.9969671 -0.02015107 -0.07517009 0.9937913 0.01403272 0.1103722 0.9649715 -0.01102161 0.2621232 0.9468516 0.004665076 0.321637 0.8304291 0.01028233 0.5570294 0.8548898 -0.005872905 0.5187764 0.6447545 -0.01559156 0.7642307 0.5744993 0.01914346 0.8182812 0.3449378 -0.01681816 0.9384749 0.244126 0.01716858 0.9695916 0.02522826 -0.0187236 0.9995064 -0.07781529 0.01455068 0.9968616 -0.3272774 -0.00649482 0.9449061 -0.3336305 -0.009146153 0.9426597 -0.5292931 0.01036226 0.8483757 -0.5963541 -0.01035869 0.8026548 -0.7407271 0.007136881 0.6717683 -0.7584588 -9.13546e-4 0.6517204 -0.9033104 0.008483409 0.4289039 -0.8924543 -9.15705e-4 0.4511369 -0.984157 -0.0128377 0.1768339 -0.9961621 0.01560485 0.08612644 0.9811612 0.00129944 0.193187 0.9755899 -0.008629322 0.2194306 0.904088 0.0110957 0.4272023 0.8705837 -0.01002252 0.4919184 0.7335987 0.002873599 0.6795769 0.7270558 0.006707668 0.6865457 0.4992944 0.002883672 0.8664277 0.5220507 -0.005908131 0.8528941 0.2937443 -3.4209e-4 0.955884 0.2875887 -0.002430677 0.957751 0.04081386 0.0027709 0.999163 0.02543407 -0.003279268 0.9996712 -0.2872231 0.003637075 0.9578568 -0.2861016 0.004175186 0.9581902 -0.5349658 -0.008961677 0.8448262 -0.5841301 0.01079684 0.8115883 -0.7492688 -0.007627904 0.6622222 -0.7786461 0.005901277 0.6274357 -0.9007226 -0.00754112 0.4343292 -0.9235275 0.01237761 0.3833326 -0.9894881 -0.01350826 0.1439821 -0.9995134 0.01812696 0.0253877 -0.9962233 -0.01012569 -0.08623605 -0.9514827 0.008462846 -0.3075858 -0.9365676 -0.006130039 -0.3504335 -0.827606 0.007825553 -0.5612549 -0.8196825 0.002349555 -0.5728135 -0.6531751 -0.01489216 -0.7570605 -0.5657333 0.02332556 -0.8242584 -0.3547562 -0.02058362 -0.9347323 -0.2416033 0.01786851 -0.9702106 -0.01364207 -0.01652336 -0.9997704 0.06968295 0.009430527 -0.9975247 0.3036166 -0.004737854 -0.9527825 0.2893053 0.001309752 -0.9572361 0.5727558 0.01494336 -0.8195899 0.5262678 -0.00490576 -0.8503047 0.7475014 -0.01754623 -0.6640286 0.8192126 0.01169139 -0.5733708 0.8995738 -0.009965598 -0.4366552 0.9242225 0.006145715 -0.3818051 0.9938355 0.001295864 -0.1108571 0.9918865 -0.005826592 -0.126993 0.8831133 0.4678561 -0.03494989 0.7976172 0.602865 -0.01899248 0.3174223 0.948159 -0.01541429 0.9279773 0.3575419 -0.1049858 0.6567977 0.7510791 -0.06705987 0.4303953 0.9011206 -0.05236101 0.8093175 0.5661727 -0.1563766 0.03168064 0.9994913 -0.003678977 0.9055932 0.3528363 -0.2353882 0.8087472 0.5665708 -0.1578783 0.5852491 0.7956478 -0.1562956 0.4074305 0.9092447 -0.08529013 0.8950154 0.3277354 -0.3025509 0.8634544 0.3953917 -0.3132284 0.2171638 0.9743471 -0.05905729 0.5996811 0.7701001 -0.2175514 0.5356969 0.8148494 -0.2214713 0.8409503 0.3477631 -0.4145641 0.2896958 0.9495705 -0.1199686 0.7239944 0.5611486 -0.4011788 0.5745722 0.7656384 -0.2892486 0.7038505 0.5537815 -0.4448826 0.1486361 0.9848935 -0.08883714 0.7614303 0.3458049 -0.5483091 0.3875305 0.8876102 -0.2489346 0.2383149 0.9580796 -0.1590268 0.527647 0.7573027 -0.3848134 0.7005102 0.4127152 -0.5821955 0.6987379 0.3537784 -0.6217767 0.5227053 0.7439984 -0.4162278 0.4200434 0.8204019 -0.3879491 0.6570953 0.3924853 -0.6435691 0.3083536 0.9100505 -0.2769952 0.6511836 0.2734329 -0.7079509 0.4286603 0.7761319 -0.4624604 0.4507975 0.7409808 -0.497724 0.5280403 0.4871312 -0.6956125 0.4462272 0.6974205 -0.5607904 0.5193625 0.4107148 -0.7493838 0.1642402 0.9626114 -0.2154166 0.1248126 0.9803891 -0.1525096 0.4546718 0.4860795 -0.7463246 0.330884 0.7587016 -0.5611487 0.3075512 0.8103941 -0.498672 0.4402981 0.3599219 -0.8225532 0.2086058 0.9162333 -0.3420528 0.1641082 0.9400824 -0.2988539 0.3606298 0.2864764 -0.8876246 0.3667615 0.4239794 -0.8280868 0.2794644 0.6691566 -0.6885705 0.2531498 0.7007964 -0.666933 0.2505414 0.4137581 -0.8752332 0.1758095 0.8620897 -0.4752815 0.2241661 0.6233944 -0.7490855 0.2356914 0.2930426 -0.9265936 0.02386718 0.9973444 -0.06880819 0.08500045 0.9415051 -0.3261027 0.12045 0.7699132 -0.6266781 0.08848518 0.8850066 -0.4570927 0.1429439 0.3274946 -0.9339777 0.0845732 0.5847908 -0.8067634 0.05108177 0.5964205 -0.8010451 -0.009897232 0.4011274 -0.9159689 -0.01050251 0.848793 -0.528621 0.007901072 0.9237457 -0.382925 -0.01235455 0.847413 -0.5307907 -0.08678692 0.4947964 -0.8646645 -0.072604 0.6823073 -0.7274515 -0.126367 0.4050335 -0.9055271 -0.006718099 0.9982499 -0.05875432 -0.1255649 0.8475289 -0.5156822 -0.0816906 0.9131754 -0.3992962 -0.1961676 0.4663372 -0.8625821 -0.2089156 0.6048732 -0.7684288 -0.1031168 0.8715589 -0.4793246 -0.3273851 0.4183992 -0.8472079 -0.2622021 0.5772761 -0.7733061 -0.255128 0.7544738 -0.6047141 -0.2017748 0.8690975 -0.4516156 -0.4074313 0.3989286 -0.8214961 -0.3914106 0.4263036 -0.8155141 -0.1948354 0.8930351 -0.4056201 -0.4645619 0.4908339 -0.7370648 -0.2385517 0.8719817 -0.4274823 -0.5241049 0.3681446 -0.7679737 -0.4680207 0.4880653 -0.736715 -0.4054985 0.7516146 -0.520237 -0.2691744 0.8802453 -0.3907856 -0.5889295 0.3891976 -0.7082989 -0.58091 0.4683814 -0.6657046 -0.4369341 0.7277667 -0.528625 -0.6637974 0.3919854 -0.6369619 -0.1198162 0.9839329 -0.1323643 -0.3717764 0.8633774 -0.3411185 -0.6680149 0.4597736 -0.5851192 -0.3993947 0.8464827 -0.3520666 -0.7188813 0.3961497 -0.571205 -0.7260366 0.4183804 -0.5457368 -0.7995399 0.3023151 -0.5189813 -0.6032323 0.6956173 -0.3901634 -0.4364824 0.8425759 -0.3155136 -0.7836735 0.4352452 -0.44319 -0.6520226 0.6560761 -0.3800407 -0.8513679 0.306878 -0.4254393 -0.2828004 0.9453471 -0.1623051 -0.5602248 0.7831735 -0.2697917 -0.314567 0.9345322 -0.1664248 -0.8313871 0.4535499 -0.3210732 -0.6373007 0.7298324 -0.2473714 -0.9059258 0.301891 -0.296918 -0.5910357 0.7816025 -0.1994354 -0.4522268 0.8823755 -0.1300175 -0.2447715 0.9651765 -0.09231019 -0.871176 0.4487847 -0.1991103 -0.9256845 0.3427222 -0.1601552 -0.4494878 0.88646 -0.1102249 -0.8819436 0.4381041 -0.1738979 -0.6359943 0.7670719 -0.08433389 -0.6154744 0.7866362 -0.04893803 -0.5199489 0.8539293 -0.02139836 -0.9187738 0.394012 -0.02468854 -0.9137588 0.4052562 -0.02850115 -0.235596 0.9714062 -0.02940106 -0.5180448 0.8550726 0.02192068 -0.9054984 0.4190241 0.06701946 -0.8992846 0.4317045 0.07013326 -0.6241272 0.7789425 0.0609411 -0.9006066 0.3910019 0.1898037 -0.8259385 0.5232657 0.2098063 -0.1554526 0.987321 0.03212314 -0.5887475 0.7996541 0.1180245 -0.8916409 0.3229954 0.3172548 -0.38515 0.9168071 0.1054714 -0.8267675 0.4995543 0.2586527 -0.5517717 0.7982679 0.2414883 -0.8765519 0.2821698 0.3899194 -0.5581594 0.7994762 0.222027 -0.7575407 0.5231845 0.3903974 -0.7243037 0.5416672 0.426592 -0.4220989 0.8785054 0.2237427 -0.3269635 0.9248458 0.194307 -0.7293519 0.5176315 0.4473292 -0.7134729 0.4601199 0.5284376 -0.698929 0.5266398 0.4838892 -0.36607 0.888083 0.2780315 -0.699691 0.3463034 0.6249052 -0.3475878 0.8945613 0.2809677 -0.6838924 0.4538375 0.5712466 -0.4887782 0.7287358 0.4796251 -0.6042523 0.4420957 0.6628956 -0.4783584 0.7052458 0.5232605 -0.6150624 0.3442177 0.7093748 -0.1566115 0.9753766 0.155285 -0.4207112 0.7567931 0.5002664 -0.578415 0.3012214 0.7580909 -0.3097596 0.8659484 0.3926607 -0.5140965 0.4176569 0.7491779 -0.4798356 0.5201833 0.7065176 -0.5056513 0.2408695 0.8284316 -0.2474859 0.8928182 0.3763331 -0.3511409 0.6908965 0.6319511 -0.04526907 0.9954545 0.0837922 -0.4251549 0.3049969 0.8521857 -0.2777325 0.8140164 0.5101394 -0.3767177 0.4571549 0.8056631 -0.2029162 0.8692631 0.4507848 -0.3125842 0.3378204 0.8877886 -0.3159227 0.4802014 0.8182907 -0.2564538 0.6285315 0.7342885 -0.1304542 0.9351899 0.329244 -0.2029252 0.4399861 0.8747764 -0.194684 0.667678 0.7185431 -0.1366618 0.7948662 0.5911949 -0.1887502 0.3840247 0.9038243 -0.08865052 0.9400031 0.3294469 -0.05459505 0.9691399 0.2403898 -0.08538419 0.3638014 0.9275549 -0.1036468 0.4474 0.8883078 -0.06983882 0.7004087 0.710317 -0.03232204 0.7590193 0.6502655 -0.02566003 0.3511505 0.9359675 -0.00691092 0.9009677 0.4338313 0.02698671 0.6096711 0.792195 0.0119304 0.9290022 0.369882 0.09737503 0.5172255 0.8502917 0.06419253 0.6196957 0.7822126 0.0724197 0.8389875 0.5393101 0.2115122 0.2300364 0.9499189 0.1679793 0.4763017 0.8630874 0.1019208 0.8487061 0.5189509 0.195495 0.641431 0.7418545 0.2848312 0.3879408 0.8765689 0.0948686 0.9332936 0.3463568 0.2236921 0.6142852 0.7567137 0.3135263 0.32945 0.8905976 0.359579 0.4953114 0.7908032 0.2625581 0.7344028 0.625872 0.2509493 0.7700577 0.5865455 0.1704418 0.8861259 0.4309647 0.4037497 0.4165776 0.8145242 0.01607912 0.999019 0.04126173 0.08562284 0.9836306 0.1585552 0.5036354 0.3042432 0.8085714 0.4609887 0.4125401 0.7856847 0.2964339 0.8242411 0.4824455 0.1560365 0.9558667 0.2489407 0.3801078 0.7347841 0.5617923 0.5689195 0.3026136 0.7646932 0.5658915 0.3779023 0.7327733 0.4113668 0.7170295 0.5627133 0.4169223 0.7592366 0.4997354 0.3952085 0.797174 0.4564251 0.6158307 0.4214304 0.6656944 0.6213701 0.4131922 0.6657112 0.2104278 0.9452208 0.2495552 0.4255396 0.8023782 0.4184558 0.7078943 0.3486503 0.6142709 0.6512513 0.4583621 0.6047943 0.5599123 0.6641232 0.4954177 0.1273332 0.9849485 0.1168873 0.7697157 0.3422958 0.5388613 0.287193 0.9300079 0.2293586 0.7570565 0.3717248 0.5372952 0.6436576 0.6207666 0.4476091 0.554968 0.7215076 0.4140499 0.3660984 0.8925935 0.2631516 0.6445626 0.6705701 0.3672533 0.5173797 0.8107385 0.2739007 0.8409117 0.3189046 0.437227 0.3826197 0.8945729 0.2309577 0.8180125 0.4001199 0.4132306 0.5303636 0.8121529 0.2431504 0.7911302 0.5267042 0.3109595 0.4062582 0.9024348 0.1434072 0.8190558 0.4993703 0.2824481 0.1672889 0.9832903 0.07179713 0.7823765 0.5762177 0.2363476 0.4234296 0.8945294 0.1432641 0.8072347 0.5583164 0.1914551 0.9222859 0.3523435 0.1588799 0.9758605 0.2169312 0.02524441 0.5259988 0.8483712 0.0599296 0.8915017 0.4462829 0.07782262 0.4216719 0.904341 0.06603258 0.7443564 0.6667309 0.03746348 0.5302661 0.8458938 0.05728799 0.9945701 -0.009593129 -0.1036261 0.9919345 0.00783348 -0.1265096 0.9782791 -0.007848441 -0.2071436 0.9775924 -0.005749642 -0.2104286 0.9511101 -0.00966835 -0.3087007 0.9452763 0.001703262 -0.3262664 0.9190664 -0.0216704 -0.3935065 0.8753281 -0.006287217 -0.4834888 0.8881574 0.01106208 -0.4594063 0.8051002 0.02187496 -0.5927354 0.8236153 -0.01506793 -0.5669487 0.751825 0.009962499 -0.6592875 0.7150626 -0.02087819 -0.6987487 0.6520346 -0.00884515 -0.7581377 0.6696589 0.004671216 -0.7426542 0.5494731 0.00596714 -0.8354901 0.5680918 -0.01616752 -0.8228064 0.4893456 -0.005122303 -0.872075 0.4784854 0.004568517 -0.8780837 0.3873956 -5.22495e-4 -0.9219135 0.3777827 0.006949424 -0.9258682 0.2991089 -0.01361972 -0.9541218 0.2518845 0.0141052 -0.9676546 0.1916152 -0.01435989 -0.9813652 0.1270316 0.009074032 -0.9918572 0.1032086 -0.004367291 -0.9946502 -0.001050233 0.01345139 -0.999909 0.004688382 0.008058428 -0.9999566 -0.1061111 -0.01062899 -0.9942975 -0.1433793 0.01881182 -0.989489 -0.255352 -0.00807017 -0.9668145 -0.2601046 -0.003470957 -0.9655743 -0.328575 0.0134207 -0.9443826 -0.3742803 -0.01246863 -0.9272319 -0.444458 0.01773428 -0.8956242 -0.4865452 -0.01236844 -0.8735679 -0.5347445 -0.005099296 -0.8449985 -0.5579448 0.0167098 -0.82971 -0.6476911 -0.006525576 -0.7618752 -0.6464905 -0.00805813 -0.7628794 -0.7154523 0.009925484 -0.6985911 -0.7493519 -0.01992994 -0.6618721 -0.7817242 0.01019209 -0.6235411 -0.8351723 -0.004592359 -0.5499693 -0.8403877 0.002969324 -0.5419778 -0.8951018 -0.001207768 -0.4458604 -0.8953778 -6.34164e-4 -0.4453069 -0.9436725 -0.005297482 -0.3308386 -0.9489987 0.009671211 -0.3151318 -0.9763479 -0.01756292 -0.2154914 -0.9921907 -0.01556771 -0.1237553 -0.9858089 0.01014441 -0.1675646 -0.9994781 -0.001465976 -0.03227365 -0.9997507 -0.0112251 -0.0193001 -0.9965282 0.002456009 0.08322018 -0.9953075 -0.008022248 0.09642988 -0.975937 -0.00382477 0.2180193 -0.9764105 -0.006390273 0.2158284 -0.951529 0.01150709 0.3073439 -0.9339228 -0.02165746 0.3568183 -0.9035352 0.01076644 0.4283786 -0.8866941 -0.009088575 0.4622673 -0.8589259 0.01442384 0.5118967 -0.8141588 -0.004500031 0.5806249 -0.8114911 -0.001390337 0.5843631 -0.7534394 -0.005520939 0.6574943 -0.7419815 0.007612228 0.6703772 -0.6808692 -0.005393683 0.7323852 -0.6772873 -0.002291142 0.735715 -0.6057105 -3.0522e-4 0.7956851 -0.6036855 -0.002297759 0.7972193 -0.5230156 -0.001207888 0.8523224 -0.5237406 -0.001916825 0.8518757 -0.427109 -0.001914978 0.9041981 -0.4276915 -0.002578079 0.9039211 -0.3345222 0.01724499 0.9422302 -0.2995961 -0.01252591 0.9539839 -0.2589786 -0.01644361 0.9657432 -0.2057755 0.01395291 0.9784998 -0.1434274 -0.01145356 0.9895946 -0.1048117 0.01110768 0.9944301 -0.01031303 -0.009164512 0.9999048 0.01805168 0.01455605 0.9997312 0.09804266 0.01586288 0.9950559 0.09506362 0.01360607 0.9953783 0.1979619 0.01485335 0.9800972 0.2026247 0.009651005 0.979209 0.2810455 -0.02250677 0.9594305 0.3723513 -0.01152771 0.9280204 0.3457553 0.003432512 0.9383185 0.4730884 -0.01295578 0.8809198 0.4302484 0.006520509 0.902687 0.5156851 0.008697926 0.8567341 0.5748246 -0.01871347 0.8180626 0.609498 0.009689867 0.7927284 0.6748341 0.002417147 0.7379655 0.6822101 -0.006797015 0.7311246 0.7440303 0.005692064 0.6681216 0.7488122 -4.18062e-4 0.6627822 0.8149955 -3.68846e-4 0.5794674 0.8170747 0.002458572 0.5765268 0.8734782 -0.01538032 0.4866203 0.9084021 -0.01256906 0.4179089 0.8926931 0.00812745 0.4505922 0.9484385 0.02342933 0.3160939 0.9629028 -0.01357495 0.2695071 0.9915056 -0.01660329 0.129 0.9829561 0.02406889 0.182258 0.9998813 -0.003784358 0.01493453 0.9996907 0.005262792 0.02430933 0.8667778 -0.4981973 0.02226632 0.4634777 -0.8852902 0.03807753 0.9133638 -0.3857466 0.1302541 0.8544032 -0.5125665 0.08526843 0.03643631 -0.9993289 0.003747224 0.6137828 -0.7828473 0.102083 0.5740118 -0.8137254 0.09144145 0.8739302 -0.4484791 0.1873831 0.7109013 -0.6824393 0.169988 0.9337354 -0.2384334 0.2669977 0.6914809 -0.6939017 0.2008847 0.8779278 -0.3753653 0.2972267 0.2873878 -0.9541072 0.08418923 0.5472441 -0.810563 0.2085949 0.4778208 -0.8584953 0.1862069 0.8583119 -0.3687427 0.3568329 0.7386195 -0.5762739 0.3497853 0.3445007 -0.9201232 0.1862593 0.7841165 -0.3993186 0.4750854 0.7086564 -0.5764752 0.4067954 0.5950616 -0.709656 0.3772137 0.07812529 -0.9955865 0.05199968 0.7794629 -0.2592262 0.5702977 0.4615023 -0.8367664 0.2946822 0.7372111 -0.3419641 0.5827353 0.6213287 -0.6062763 0.4963666 0.7280086 -0.2618094 0.6336082 0.5202879 -0.7083189 0.4770587 0.3225687 -0.9044528 0.2791321 0.3131545 -0.9098509 0.2722237 0.6339359 -0.4352917 0.6392546 0.5417869 -0.6505382 0.5322284 0.6374235 -0.3332259 0.6947315 0.5513294 -0.43874 0.7096077 0.2023845 -0.9504851 0.235836 0.4422506 -0.6766486 0.5886943 0.426738 -0.7169712 0.5512232 0.5520458 -0.2694384 0.7890807 0.2539496 -0.906534 0.3372028 0.4712508 -0.4160824 0.7776877 0.409952 -0.6421969 0.6477057 0.4522342 -0.3462931 0.8219279 0.2953633 -0.7730658 0.5613642 0.2017725 -0.9173336 0.3432012 0.3629499 -0.4899534 0.792599 0.2930383 -0.7462252 0.5977262 0.3512424 -0.4384176 0.8272961 0.05815649 -0.9892701 0.1340245 0.2429444 -0.5483083 0.8002101 0.1757024 -0.7928569 0.5835296 0.1678125 -0.8332149 0.52687 0.1061196 -0.9282759 0.3564302 0.2342434 -0.4736113 0.8490126 0.1389869 -0.3985788 0.9065417 0.1430277 -0.4795745 0.8657664 0.1033803 -0.6681022 0.7368528 0.09831738 -0.2701059 0.9577978 0.05186736 -0.9484719 0.3125874 0.08320224 -0.706192 0.7031148 0.05303227 -0.8134266 0.579245 -0.005534172 -0.3756086 0.9267619 -1.49446e-5 -0.3395429 0.9405906 1.15379e-4 -0.5129545 0.8584158 0.007741272 -0.9913132 0.1312943 -0.002625167 -0.8486719 0.5289131 -0.01409673 -0.907322 0.4202001 -0.03263598 -0.6782246 0.7341296 -0.1325622 -0.3733758 0.9181601 -0.1342687 -0.3674598 0.9202963 -0.1025953 -0.621762 0.7764576 -0.1274716 -0.7503006 0.6486911 -0.08499813 -0.8999778 0.4275693 -0.2020105 -0.3802775 0.9025414 -0.2220567 -0.5768776 0.7860682 -0.08295959 -0.9330861 0.3499544 -0.3146781 -0.3854403 0.8674177 -0.1129642 -0.927717 0.3557812 -0.2569381 -0.574395 0.7772086 -0.2610929 -0.6649777 0.6997393 -0.3931208 -0.3962466 0.8297258 -0.4365811 -0.2767416 0.8560439 -0.1165134 -0.9493976 0.2916656 -0.3057891 -0.6821164 0.6642367 -0.2802125 -0.7970186 0.5350162 -0.4969351 -0.3230873 0.8054007 -0.4815707 -0.3590738 0.7994722 -0.2956139 -0.7955355 0.5289006 -0.3781387 -0.7246804 0.5760639 -0.5644659 -0.3407504 0.7518428 -0.5635302 -0.3794553 0.7337898 -0.3963519 -0.7501577 0.5293095 -0.4130067 -0.7330117 0.5404807 -0.1915442 -0.9496132 0.248084 -0.6277774 -0.3727158 0.6833583 -0.6177656 -0.4632384 0.6354337 -0.1464979 -0.9731982 0.1772667 -0.4993023 -0.6852084 0.5302704 -0.6898723 -0.3787178 0.6169676 -0.4150129 -0.8325858 0.3668314 -0.2978274 -0.9175041 0.2636004 -0.7714912 -0.3443772 0.534982 -0.6859384 -0.5119336 0.5171195 -0.5922276 -0.6807385 0.4311169 -0.19064 -0.9729858 0.1302121 -0.5799869 -0.724171 0.3730838 -0.794409 -0.4091708 0.4488803 -0.2575654 -0.9532359 0.1581184 -0.6424661 -0.6726873 0.3670548 -0.8363785 -0.3209832 0.444343 -0.6149669 -0.7315237 0.2944296 -0.848976 -0.4171187 0.3244256 -0.8339516 -0.4447455 0.3266901 -0.3463538 -0.9252539 0.15474 -0.6884041 -0.6675013 0.2837989 -0.3144595 -0.9417552 0.1192156 -0.5540947 -0.8140348 0.1741448 -0.8929841 -0.4009172 0.2045601 -0.8675335 -0.4499995 0.2118638 -0.1522769 -0.9873097 0.045071 -0.6376043 -0.7557579 0.1493009 -0.6026206 -0.7907371 0.1076266 -0.8535106 -0.5140777 0.08511084 -0.4283879 -0.9019288 0.05484801 -0.8490343 -0.5208177 0.08882457 -0.8208942 -0.5709165 0.01368463 -0.3946436 -0.9186883 0.01638203 -0.8726981 -0.4879066 -0.01858264 -0.5842909 -0.8115149 -0.006916761 -0.1956753 -0.9806252 -0.009249866 -0.8482691 -0.519817 -0.1011434 -0.814844 -0.5683568 -0.1140172 -0.621088 -0.7794618 -0.081788 -0.483766 -0.8710575 -0.08502644 -0.8918611 -0.3968448 -0.2170209 -0.8518844 -0.487754 -0.190759 -0.8872838 -0.3470658 -0.3037648 -0.6220134 -0.7561928 -0.2031551 -0.4746429 -0.8672436 -0.1503419 -0.475764 -0.8665074 -0.1510415 -0.7806372 -0.5391748 -0.3160635 -0.7774627 -0.5379704 -0.3257908 -0.8482794 -0.3033781 -0.434032 -0.6189919 -0.7155701 -0.3237417 -0.4928613 -0.8282871 -0.2665116 -0.3964279 -0.8965674 -0.1975144 -0.7721595 -0.4251713 -0.4722279 -0.7689245 -0.3926994 -0.5045219 -0.1260033 -0.9887809 -0.08022212 -0.7297886 -0.4474346 -0.5169245 -0.446411 -0.8278955 -0.3395677 -0.7094823 -0.3397029 -0.6174439 -0.4014256 -0.8560699 -0.3255792 -0.6373152 -0.4745955 -0.6071149 -0.4144224 -0.8235092 -0.3874107 -0.6102295 -0.2907888 -0.7369273 -0.5930802 -0.4311875 -0.6799508 -0.4555667 -0.6825816 -0.5714381 -0.3594155 -0.8510979 -0.3826916 -0.2025293 -0.9460062 -0.2530891 -0.5309433 -0.358395 -0.7678883 -0.4650115 -0.5109212 -0.7229965 -0.418546 -0.6831958 -0.5983836 -0.2742975 -0.8562383 -0.4377408 -0.4449338 -0.4967555 -0.745163 -0.4408069 -0.3253521 -0.8365617 -0.2858143 -0.7436566 -0.6043882 -0.2323092 -0.8623881 -0.4497991 -0.3724517 -0.3588147 -0.8558807 -0.2886881 -0.5905073 -0.7536314 -0.1089889 -0.9585071 -0.2634114 -0.2732957 -0.5977259 -0.7536799 -0.1475206 -0.8108178 -0.5664029 -0.2233209 -0.3373772 -0.9144968 -0.1813595 -0.4142728 -0.8919008 -0.134602 -0.6185009 -0.7741699 -0.1168454 -0.8116357 -0.572359 -0.07769739 -0.8706235 -0.4857755 -0.1072595 -0.2593769 -0.9598016 -0.04995512 -0.448275 -0.8924988 -0.04892021 -0.5305269 -0.8462553 -0.01610779 -0.9868075 -0.1610944 -0.002544045 -0.2979946 -0.9545642 0.001364171 -0.7473764 -0.6643995 0.001479983 -0.8051432 -0.5930787 0.01376098 -0.8570397 -0.5150668 0.08177876 -0.4094152 -0.9086757 0.08758568 -0.4596304 -0.8837808 0.06923902 -0.884725 -0.4609421 0.1972797 -0.3574718 -0.9128497 0.1467128 -0.516947 -0.8433511 0.1467877 -0.6690965 -0.728535 0.06887578 -0.9490529 -0.3074977 0.2717092 -0.3546242 -0.8946596 0.278813 -0.413587 -0.8667233 0.2284804 -0.6620216 -0.7138096 0.2253223 -0.7661725 -0.6018384 0.1964976 -0.8281039 -0.5250073 0.3737457 -0.3263943 -0.8682056 0.3919465 -0.4182637 -0.8194106 0.3687868 -0.5709471 -0.7334955 0.3861292 -0.6246936 -0.678721 0.5376515 -0.3301421 -0.7758461 0.16402 -0.9428302 -0.2901184 0.3277235 -0.8127657 -0.4816735 0.5597292 -0.468236 -0.6837093 0.341553 -0.8063198 -0.4828976 0.5520892 -0.4773331 -0.6836305 0.3349198 -0.8599835 -0.3850419 0.6688838 -0.4003108 -0.6263753 0.5882544 -0.5440868 -0.5982696 0.4475678 -0.7806367 -0.4362219 0.7099145 -0.4324562 -0.5558806 0.1192755 -0.986983 -0.1078798 0.4308585 -0.8339365 -0.3448346 0.4283878 -0.8366647 -0.3412859 0.7568062 -0.3568903 -0.5476073 0.7597553 -0.4252458 -0.4918718 0.04192608 -0.9985712 -0.03313255 0.4766683 -0.8211857 -0.3137539 0.7929552 -0.3881022 -0.4696794 0.4487635 -0.8569251 -0.2535562 0.7365843 -0.5760139 -0.354474 0.4976255 -0.8291901 -0.2545834 0.7969447 -0.4987221 -0.340816 0.4365294 -0.885057 -0.1616055 0.8047699 -0.5392696 -0.24806 0.788147 -0.5715496 -0.2283759 0.5898935 -0.789901 -0.1675773 0.8558272 -0.480282 -0.1920654 0.2140423 -0.9744433 -0.06816184 0.5092758 -0.8556061 -0.09260863 0.8129433 -0.5732987 -0.1022343 0.5148866 -0.8532081 -0.08323323 0.8364247 -0.5415525 -0.08434969 0.8017973 -0.5973911 -0.01565337 0.5712484 -0.8207525 -0.006395518 0.4403101 -0.8968226 -0.04285341 0.1285366 -0.9917028 0.002025127 6.1865e-4 -0.9999997 5.84649e-4 -1.52536e-4 -0.9999982 0.001931786 0.001593291 -0.9999988 3.6436e-5 8.15106e-4 -0.9999988 0.001417219 0.001531422 -0.9999986 7.15619e-4 0.001290857 -0.9999989 8.06772e-4 2.26959e-4 -0.9999998 7.40281e-4 0.001757681 -0.9999985 3.48578e-4 0.002278804 -0.9999974 -7.70385e-5 3.26954e-5 -0.9999997 8.03244e-4 -0.002120912 -0.9999942 0.002703964 0.003279566 -0.9999895 0.003251492 0.002176344 -0.9999977 -2.4684e-4 0.002114355 -0.9999958 -0.002015352 -2.218e-4 -0.9999998 7.48492e-4 0.002839624 -0.9999954 -0.001177191 -0.008611977 -0.9999629 3.88048e-4 0.002612471 -0.9999949 -0.001822173 0.002610504 -0.9999951 -0.001794934 0.002417743 -0.9999842 0.005093991 -0.003080785 -0.9999862 0.004280388 -7.69758e-4 -0.9999995 6.24782e-4 0.001573503 -0.9999963 -0.002246677 -8.59052e-4 -0.9999995 5.73106e-4 8.04427e-4 -0.9999938 -0.003446161 -9.17086e-4 -0.9999995 3.73653e-4 5.8907e-4 -0.9999982 -0.00184971 0.002853393 -0.9999918 -0.002886056 -0.001113057 -0.9999994 2.05331e-4 1.25266e-4 -0.9999985 -0.00179547 -0.001102924 -0.9999995 2.18705e-5 -0.002140223 -0.9999963 -0.001716673 -0.005382835 -0.9999789 -0.003662467 -0.001487314 -0.9999811 -0.005978643 0.00364536 -0.9999761 -0.005891799 -0.002849459 -0.999996 2.91881e-4 -0.002008378 -0.9999978 -6.55813e-4 -0.001849293 -0.9999976 -0.001251637 -0.001082599 -0.9999982 -0.001578629 -0.001956641 -0.9999963 -0.001927495 -0.002438902 -0.9999961 -0.001398622 0.9601291 -0.2718327 0.06526231 0.7126044 -0.700372 0.04091525 0.6176862 -0.7849103 0.04878252 0.8926402 -0.4374134 0.1089186 0.1232278 -0.9923536 0.00702244 0.9323519 -0.3150411 0.1773958 0.8933716 -0.4277948 0.1374002 0.6956093 -0.7050984 0.1377103 0.5307189 -0.8431922 0.08581703 0.4313967 -0.8985093 0.08110553 0.8377687 -0.4723717 0.2738773 0.8782491 -0.3775768 0.2934524 0.839358 -0.4775727 0.2596198 0.3750163 -0.919819 0.1153076 0.5939614 -0.7667372 0.243565 0.4673154 -0.8651463 0.1820392 0.8618854 -0.3158323 0.3967412 0.7855601 -0.4727175 0.3992912 0.6566017 -0.6820766 0.3219404 0.7839159 -0.3687258 0.4995169 0.5249592 -0.7823761 0.3351201 0.6801415 -0.5365021 0.4995729 0.2050105 -0.970264 0.1286799 0.6171781 -0.6428695 0.4536629 0.7111835 -0.3989244 0.5788587 0.2548257 -0.9516826 0.1713594 0.4801772 -0.7745246 0.4117543 0.6581079 -0.3826514 0.648438 0.3091886 -0.9120194 0.269487 0.6255332 -0.4458218 0.6402743 0.2618028 -0.9303671 0.2566643 0.5114983 -0.6625293 0.5471971 0.5013212 -0.681653 0.5329412 0.3402934 -0.8600848 0.3800716 0.5682812 -0.333462 0.7522364 0.5712872 -0.2981816 0.7646691 0.4814805 -0.5974413 0.6412804 0.09000605 -0.9904976 0.1039882 0.4118474 -0.6885068 0.5969424 0.5075632 -0.2720625 0.817534 0.2738848 -0.8652722 0.4198707 0.2624062 -0.8865304 0.3810601 0.4343633 -0.4368606 0.7877065 0.2480292 -0.8759155 0.4138278 0.3937332 -0.3939884 0.8305103 0.3944847 -0.4520005 0.8000484 0.2989975 -0.692572 0.6564637 0.1128313 -0.9623902 0.2471324 0.2247517 -0.7542973 0.616865 0.1488363 -0.8846983 0.4417653 0.2837309 -0.4162387 0.8638531 0.238566 -0.5491002 0.8009839 0.168303 -0.3421193 0.9244612 0.1842631 -0.5516092 0.8134953 0.08298152 -0.9129485 0.3995488 0.0532149 -0.9465953 0.3180028 0.1168328 -0.7046282 0.6998922 0.06984853 -0.4134772 0.9078314 0.08120948 -0.6750576 0.7332819 0.05588948 -0.3703313 0.927217 0.01050263 -0.8363439 0.5481047 -0.05145651 -0.3626444 0.930506 -0.03610247 -0.4281539 0.9029844 -0.04803109 -0.6669114 0.7435874 -0.01165527 -0.8360998 0.5484537 -0.1483117 -0.2785903 0.9488894 -0.1197011 -0.6594913 0.7421205 -0.04325205 -0.9412674 0.3348807 -0.1825554 -0.4865406 0.8543722 -0.0914216 -0.8903706 0.4459622 -0.2081235 -0.4901497 0.8464265 -0.2815666 -0.288829 0.91504 -0.2086077 -0.7226483 0.6589858 -0.1368781 -0.8641775 0.4842124 -0.3430069 -0.4493114 0.8249033 -0.1286997 -0.9383083 0.320958 -0.2727834 -0.6742289 0.6862978 -0.3816434 -0.3854236 0.8401174 -0.2728601 -0.7767292 0.5676611 -0.1947153 -0.8934702 0.4047185 -0.4114826 -0.5913509 0.6935318 -0.4287497 -0.5797928 0.6928305 -0.4286158 -0.5799983 0.6927413 -0.5346766 -0.4401318 0.721391 -0.1837396 -0.945017 0.2705227 -0.2863559 -0.8823537 0.3734332 -0.2991933 -0.8769205 0.3761567 -0.6372609 -0.3882307 0.6657143 -0.5715111 -0.5274718 0.6286086 -0.5220778 -0.6452917 0.5577038 -0.2519128 -0.9397892 0.2309463 -0.5125775 -0.7180132 0.4708731 -0.7163977 -0.3545026 0.6009179 -0.2639356 -0.9323183 0.2472259 -0.6193938 -0.6231419 0.4775411 -0.0406174 -0.9985966 0.03398948 -0.6157699 -0.6485362 0.4474688 -0.354643 -0.9021475 0.2456792 -0.7913548 -0.3769538 0.4813142 -0.3290455 -0.9198297 0.2136409 -0.684535 -0.5819156 0.4390742 -0.8541234 -0.285762 0.4345268 -0.63286 -0.7032379 0.3239518 -0.5071534 -0.8250006 0.2493384 -0.3946826 -0.8949924 0.2078806 -0.7764527 -0.5270656 0.3454317 -0.7871438 -0.5475525 0.2838855 -0.8155968 -0.5064179 0.2798981 -0.5256724 -0.8309791 0.1820502 -0.4527162 -0.8810411 0.1371663 -0.2195696 -0.971774 0.08628171 -0.890074 -0.4042518 0.210592 -0.8441295 -0.4899511 0.2177006 -0.6743884 -0.726215 0.1334626 -0.4587172 -0.8789716 0.1303359 -0.9203517 -0.3499335 0.1746405 -0.8589708 -0.5033115 0.09405702 -0.6806899 -0.7255213 0.1013913 -0.5405223 -0.8398689 0.04955929 -0.8842267 -0.4627828 0.06305122 -0.3033545 -0.9520957 0.0386002 -0.8349993 -0.5500206 0.01592999 -0.1849472 -0.9826112 0.01642805 -0.6697784 -0.7425593 0.001651287 -0.9165433 -0.3951532 -0.06166261 -0.6147391 -0.7878777 -0.03666949 -0.8187955 -0.5615322 -0.1193966 -0.4097981 -0.9108343 -0.04946374 -0.8816948 -0.4389603 -0.1729977 -0.8188065 -0.5610179 -0.1217158 -0.3910245 -0.9186381 -0.05660372 -0.5792995 -0.8035976 -0.1365394 -0.8663923 -0.4315186 -0.251309 -0.8476842 -0.4643658 -0.2565075 -0.1556739 -0.9871 -0.03740745 -0.5806063 -0.8016187 -0.1424918 -0.8321878 -0.4769954 -0.2827346 -0.4401829 -0.8841712 -0.1564619 -0.741943 -0.5997865 -0.2996277 -0.904734 -0.1204162 -0.4086031 -0.4662154 -0.8648526 -0.1862072 -0.7945846 -0.446478 -0.4114522 -0.7391802 -0.5694763 -0.3595963 -0.5167838 -0.8086273 -0.28117 -0.4280345 -0.8764386 -0.2205494 -0.7725327 -0.4004284 -0.4927985 -0.7703472 -0.4094187 -0.4888167 -0.301396 -0.9381386 -0.1704592 -0.6048202 -0.6883982 -0.4003755 -0.7317819 -0.3936057 -0.5563901 -0.6423741 -0.5523665 -0.5312691 -0.5291352 -0.7345077 -0.4248699 -0.2680432 -0.9400628 -0.2107961 -0.3983874 -0.846882 -0.3522478 -0.6350179 -0.4537613 -0.6251823 -0.3907443 -0.8448106 -0.3655324 -0.5266811 -0.6118858 -0.5900872 -0.5334916 -0.4665568 -0.7054868 -0.2513011 -0.9217628 -0.2952985 -0.5041155 -0.5978507 -0.6232513 -0.3180145 -0.8316981 -0.4551319 -0.5133547 -0.39323 -0.7627825 -0.4696804 -0.4365284 -0.7673614 -0.3260458 -0.7560275 -0.5675534 -0.2996583 -0.8320919 -0.4667205 -0.451147 -0.2906038 -0.8438103 -0.3407084 -0.4461515 -0.8275667 -0.2589192 -0.7375821 -0.6236453 -0.2562217 -0.7633523 -0.5929954 -0.3280267 -0.3538075 -0.8759102 -0.09772258 -0.9711109 -0.2177015 -0.04727935 -0.9904199 -0.1297422 -0.2486593 -0.4131291 -0.8760668 -0.07875335 -0.9380781 -0.3373539 -0.1793457 -0.6230434 -0.761349 -0.1788733 -0.7488446 -0.6381506 -0.1022819 -0.5903557 -0.8006364 -0.1240599 -0.5563192 -0.8216558 -0.03983455 -0.8335214 -0.5510494 0.004181742 -0.3328335 -0.9429764 -0.01556468 -0.4621747 -0.8866523 0.01573663 -0.7019963 -0.7120068 -0.01588106 -0.8493258 -0.5276302 9.17372e-4 -0.9032244 -0.4291677 0.06795459 -0.3337101 -0.9402233 0.02698379 -0.9281158 -0.3713127 0.1075648 -0.6374924 -0.7629111 0.1031259 -0.6309924 -0.7689043 0.09781348 -0.7791129 -0.6192057 0.1840898 -0.4826639 -0.8562397 0.02596443 -0.9887715 -0.1471631 0.2830764 -0.4391666 -0.8526434 0.2369498 -0.5241816 -0.8179784 0.150379 -0.8363348 -0.5271911 0.1453161 -0.8764039 -0.4591291 0.3647618 -0.3755899 -0.8519865 0.338149 -0.4417278 -0.8309826 0.2965535 -0.7058115 -0.6433398 0.1882742 -0.8699029 -0.4558749 0.4544283 -0.3284635 -0.8280137 0.1576457 -0.9405336 -0.3009058 0.4568266 -0.4577109 -0.7627649 0.4054173 -0.6229563 -0.6690009 0.3832632 -0.7228901 -0.5749254 0.3245955 -0.8257049 -0.4613559 0.5747787 -0.2644336 -0.774406 0.344517 -0.8028654 -0.486534 0.5694165 -0.4438562 -0.6919223 0.03642618 -0.9982054 -0.04753017 0.6353772 -0.4022945 -0.659132 0.5974446 -0.4823393 -0.6406316 0.1195883 -0.9838762 -0.13299 0.5092291 -0.6792641 -0.5284754 0.4608628 -0.7417775 -0.4872081 0.7398412 -0.2866002 -0.6086833 0.3028229 -0.9110944 -0.2796522 0.7108119 -0.4755311 -0.5182824 0.581217 -0.6846334 -0.4398454 0.4473788 -0.8365542 -0.3162741 0.7717424 -0.3903413 -0.5020434 0.4695941 -0.8440392 -0.2589965 0.4185788 -0.8698941 -0.260914 0.7951189 -0.452269 -0.4040283 0.7802929 -0.4751989 -0.4066067 0.4350023 -0.8797088 -0.1920561 0.8295783 -0.443219 -0.3396421 0.7689704 -0.5848243 -0.2581956 0.5174002 -0.8346241 -0.1889442 0.8192452 -0.5297495 -0.2195519 0.7932421 -0.5834919 -0.1740814 0.1189764 -0.992232 -0.03633856 0.4134745 -0.9051829 -0.09840017 0.3565681 -0.9312499 -0.07505363 0.8323724 -0.5397694 -0.1257185 0.9358221 -0.3524723 -5.13008e-4 0.4010484 -0.9151693 -0.04031521 0.8094249 -0.5868451 -0.02107626 0.7671567 -0.6383335 -0.06325364 0.3538838 -0.9350592 -0.02075284 0.99866 -0.02354693 -0.04608678 0.9918753 -0.005529105 -0.1270942 0.9920487 -0.007256925 -0.1256451 0.9648624 -0.01740527 -0.2621787 0.976205 0.009437382 -0.2166444 0.9352798 -0.006375491 -0.3538519 0.9444788 0.004459798 -0.3285422 0.8903268 -0.007493674 -0.4552604 0.9120481 0.01460897 -0.409823 0.8655858 0.009714007 -0.5006665 0.84042 -0.009714782 -0.5418485 0.8088293 0.01234877 -0.5879139 0.7756698 -0.007789075 -0.6310909 0.7406901 0.02483618 -0.6713877 0.6831418 0.002268373 -0.7302823 0.6857616 2.12328e-4 -0.7278262 0.5989636 -0.00644797 -0.8007503 0.5959448 -0.002636492 -0.8030211 0.4855518 -0.001051366 -0.8742073 0.4837506 9.83074e-4 -0.8752054 0.3877388 0.002672731 -0.9217654 0.3794983 0.009812116 -0.9251404 0.289839 -0.0135883 -0.956979 0.1915113 -0.01714688 -0.9813407 0.2502384 0.006855428 -0.96816 0.1172387 -0.008530437 -0.9930672 0.1455568 0.001382172 -0.989349 -0.01836973 -0.02021676 -0.9996269 0.04536473 0.01745766 -0.998818 -0.1508397 -0.0217188 -0.9883196 -0.1005229 0.01533746 -0.9948165 -0.2325208 -0.0063892 -0.9725704 -0.2479274 0.008728504 -0.9687393 -0.3470018 0.005347311 -0.9378493 -0.3388391 -0.002301275 -0.9408416 -0.4703034 -0.01323348 -0.8824056 -0.4290376 0.01484799 -0.9031647 -0.5655068 -0.01108241 -0.8246693 -0.5195483 0.01098084 -0.8543705 -0.6466393 -0.01126158 -0.762713 -0.6151273 0.01101583 -0.7883509 -0.7093254 -0.004941582 -0.7048639 -0.7130252 -4.24529e-5 -0.7011384 -0.7723122 0.002600431 -0.6352379 -0.7798902 0.01168864 -0.6258072 -0.8425526 -0.01721507 -0.538339 -0.8637481 0.0112521 -0.5037984 -0.9114702 -0.01192617 -0.4111934 -0.9140827 -0.005270481 -0.4054936 -0.9615285 0.004393815 -0.2746703 -0.9616283 0.00477606 -0.2743139 -0.9856308 0.00518918 -0.1688346 -0.985806 0.005909144 -0.1677845 -0.997466 -0.01542186 -0.06945359 -0.9993725 0.01217031 -0.03326553 -0.9972943 -0.006535112 0.07322257 -0.9978905 0.003147542 0.06484496 -0.9863923 -0.01777052 0.1634458 -0.9738538 0.02050381 0.2262488 -0.9635828 0.002183079 0.2674014 -0.9513352 0.009709596 0.3080052 -0.9379782 -0.01176482 0.3464949 -0.9108965 0.004253029 0.412613 -0.8976143 -0.01237446 0.4406082 -0.8704115 0.009562134 0.492232 -0.8319697 -0.02140712 0.5544081 -0.8074909 -0.005322992 0.5898562 -0.7836976 -0.02117919 0.6207814 -0.7458925 0.01323336 0.6659349 -0.6797059 -0.005710065 0.7334626 -0.6805489 -0.006584346 0.7326732 -0.5983845 0.005612015 0.8011894 -0.5882562 -0.002923429 0.8086693 -0.4974501 -0.01209712 0.8674083 -0.5351848 0.0159893 0.8445838 -0.4356354 -0.01290702 0.9000308 -0.4253394 -0.001692473 0.9050325 -0.3034116 -0.002824544 0.9528555 -0.2940133 -0.01258623 0.9557185 -0.1852467 0.009953498 0.9826416 -0.1605248 -0.009988069 0.9869813 -0.04742282 0.01253306 0.9987963 -0.05905497 0.001182436 0.9982541 0.02580779 0.01632475 0.9995337 0.05915576 -0.009457588 0.998204 0.1430527 0.01136553 0.9896499 0.1997011 -0.01111453 0.9797939 0.2346575 0.007480502 0.9720494 0.2949256 -0.01842629 0.9553426 0.3542999 0.01479411 0.9350149 0.4241147 -0.003241598 0.9056027 0.4210903 1.11703e-4 0.9070188 0.5169286 0.01395547 0.8559148 0.5331348 -0.00106728 0.8460297 0.6138742 0.006967365 0.7893732 0.6020291 -0.006568372 0.7984471 0.68154 0.01534932 0.7316199 0.7117474 -0.01629805 0.7022464 0.7827659 0.007944464 0.6222656 0.7767097 -0.001239061 0.6298575 0.8410887 -0.002740681 0.5408903 0.8458516 0.005771815 0.533387 0.8850945 0.01921492 0.4650146 0.9051985 -0.01637864 0.4246733 0.9490809 0.008761405 0.3149109 0.9429956 -0.01375961 0.3325208 0.9620807 0.01824879 0.2721539 0.982881 0.006998479 0.1841085 0.9830171 0.007631182 0.1833553 0.9970358 -0.01053446 0.07621556 0.9993541 0.01954489 0.03015977 0.9168544 0.3991328 -0.008442103 0.7245198 0.6888287 -0.02421122 0.9459207 0.3093208 -0.09774798 0.2926704 0.9560508 -0.01764118 0.767964 0.6251896 -0.139174 0.7968068 0.5924672 -0.1186664 0.5476927 0.8284203 -0.1172717 0.8850989 0.4110076 -0.2183412 0.5229984 0.8409742 -0.1386907 0.848812 0.4550886 -0.2690962 0.8044281 0.5271853 -0.2738087 0.4131594 0.900573 -0.1351576 0.1532996 0.9864008 -0.05926823 0.8079072 0.4522491 -0.3778316 0.7684127 0.5553896 -0.3179382 0.5445225 0.8012653 -0.2479299 0.7655155 0.4587338 -0.4511647 0.7614691 0.4760226 -0.4399628 0.490688 0.8285525 -0.2696781 0.3922736 0.8872022 -0.2428865 0.7230766 0.4674201 -0.5086048 0.7012691 0.5000855 -0.5080711 0.344624 0.9141945 -0.2132666 0.4544028 0.8272108 -0.3305155 0.6516235 0.5044462 -0.5664988 0.5817953 0.6035267 -0.5452246 0.422518 0.8311147 -0.3615618 0.08818954 0.9930365 -0.07811123 0.2207743 0.9492785 -0.2238957 0.5463454 0.5788421 -0.6053501 0.5773354 0.4428423 -0.6859844 0.5546153 0.3575267 -0.7513831 0.5177355 0.4096673 -0.7510811 0.3145662 0.8547818 -0.4127908 0.3448992 0.7464779 -0.5690478 0.2840513 0.8558906 -0.4321646 0.4669131 0.2936853 -0.8341111 0.1891677 0.9285986 -0.3192496 0.3863688 0.4649537 -0.7965786 0.3400932 0.6355602 -0.6931089 0.3621063 0.3005396 -0.8823577 0.2157723 0.7920998 -0.570982 0.1537073 0.9342203 -0.3218799 0.2526729 0.4597246 -0.8513577 0.1983381 0.7348616 -0.648568 0.1974812 0.7808562 -0.5926762 0.2374657 0.383075 -0.8926721 0.01760429 0.9973424 -0.07070016 0.1361756 0.4552305 -0.8798986 0.1336064 0.4633917 -0.8760237 0.1108829 0.7428839 -0.6601732 0.07982593 0.8042531 -0.5889014 0.0434488 0.9704787 -0.2372409 0.03409743 0.980016 -0.195975 0.0289371 0.4318974 -0.9014585 0.04213482 0.4803016 -0.8760909 0.03405594 0.7612837 -0.647524 -0.05216556 0.4365891 -0.8981474 -0.01777857 0.8421263 -0.5389873 -0.09348464 0.3060578 -0.9474118 -0.01755893 0.9429566 -0.3324523 -0.06145447 0.7506802 -0.6578015 -0.0266366 0.9637166 -0.2655956 -0.1719991 0.478296 -0.8611906 -0.07301682 0.8705942 -0.4865534 -0.1314709 0.7453527 -0.6535785 -0.1053524 0.8788237 -0.4653705 -0.2099626 0.4166625 -0.8844818 -0.2555828 0.5431775 -0.7997723 -0.3011744 0.5336778 -0.7902418 -0.1252657 0.9287594 -0.3488763 -0.3113074 0.5646243 -0.7643868 -0.2858548 0.6806473 -0.6745417 -0.4033525 0.4064151 -0.8198376 -0.1115195 0.95174 -0.2859272 -0.4963318 0.341577 -0.7981103 -0.4580831 0.4276015 -0.7793054 -0.3737688 0.7157592 -0.5899032 -0.3036051 0.792514 -0.5289098 -0.185319 0.9264708 -0.3275803 -0.1635227 0.9551748 -0.2467827 -0.3971969 0.7271252 -0.5599319 -0.5597497 0.3534075 -0.7495222 -0.5315579 0.5358874 -0.6559504 -0.2702662 0.8984925 -0.3459298 -0.5588006 0.547728 -0.6226847 -0.6223718 0.4527918 -0.6384615 -0.3729387 0.8557083 -0.3587202 -0.3185456 0.8925976 -0.3190586 -0.77309 0.2218539 -0.5942329 -0.6319574 0.576465 -0.5179944 -0.6449766 0.5599795 -0.5200272 -0.44333 0.8148775 -0.3734074 -0.0966255 0.9921947 -0.07882517 -0.4182469 0.8598916 -0.2926709 -0.7867642 0.3709245 -0.4933733 -0.6750385 0.6052493 -0.4218962 -0.6552655 0.6283352 -0.4193115 -0.8285256 0.2731862 -0.488789 -0.3272048 0.9208511 -0.2120621 -0.8526953 0.3567207 -0.3816559 -0.3453208 0.9208201 -0.1812287 -0.8352579 0.4118216 -0.3643451 -0.6662216 0.6718001 -0.3237801 -0.5441806 0.8035396 -0.2412298 -0.8445313 0.4436024 -0.2999733 -0.1385676 0.9890943 -0.04991787 -0.5990814 0.7772084 -0.1924804 -0.5444368 0.8188659 -0.1817888 -0.8934714 0.3577896 -0.2714692 -0.3744225 0.9214979 -0.1031964 -0.8267706 0.5346868 -0.174816 -0.8413984 0.5222167 -0.1390627 -0.4611824 0.8851704 -0.06151646 -0.827964 0.5465265 -0.1256371 -0.5906155 0.8044729 -0.06322175 -0.8924065 0.450087 -0.03213107 -0.8804881 0.4734842 -0.02352827 -0.6701048 0.7422639 0.002019703 -0.9345422 0.3433366 0.09354549 -0.1648537 0.9863047 0.005144774 -0.6222537 0.7822648 0.02936184 -0.922623 0.371983 0.1019584 -0.3227158 0.9459932 0.03084737 -0.7484965 0.6555693 0.09990912 -0.7189335 0.6826764 0.1307201 -0.938153 0.2856072 0.1956973 -0.8143165 0.5432384 0.2044032 -0.4505457 0.8866389 0.1043081 -0.8662565 0.3923819 0.309251 -0.7905332 0.5627326 0.2416389 -0.6559647 0.7188 0.2302976 -0.4106777 0.9031181 0.125386 -0.3032387 0.9467014 0.1086411 -0.8437215 0.3855124 0.3735163 -0.7957357 0.473165 0.3780471 -0.6625141 0.6920055 0.2867115 -0.8188692 0.2984249 0.4903018 -0.4569196 0.8551829 0.2447181 -0.7747108 0.4649274 0.4285624 -0.6235147 0.6809349 0.3841319 -0.4515699 0.854049 0.2582346 -0.7888053 0.2608886 0.556528 -0.3036072 0.9285851 0.21343 -0.6824129 0.4823668 0.549213 -0.626661 0.6137232 0.4802497 -0.3539026 0.8875244 0.2950482 -0.674959 0.4378628 0.5938912 -0.6136835 0.4999995 0.6110589 -0.3484454 0.8650929 0.3608326 -0.6120765 0.4189594 0.6706978 -0.3259186 0.8920072 0.3132095 -0.5643313 0.4444097 0.6957228 -0.4311225 0.6588597 0.6164715 -0.3118643 0.8672019 0.3882031 -0.4625151 0.3713229 0.8051081 -0.4201354 0.6439351 0.6394012 -0.1328882 0.9693594 0.2065987 -0.4006868 0.304205 0.8642392 -0.4024403 0.3830772 0.8314409 -0.3166611 0.6604311 0.68085 -0.2990222 0.7476249 0.5929948 -0.1906095 0.8951312 0.4029992 -0.2784692 0.3630304 0.8891928 -0.2771664 0.3401314 0.8986042 -0.1434131 0.9194 0.3662463 -0.2251191 0.6517192 0.7242814 -0.2238133 0.6409349 0.7342412 -0.06887316 0.9715656 0.2265321 -0.1895108 0.2551367 0.9481513 -0.1407709 0.7144257 0.6854047 -0.07921248 0.8611032 0.5022218 -0.1157237 0.5027651 0.8566419 -0.08622068 0.4997778 0.8618516 -0.0519154 0.573928 0.8172586 -0.02276355 0.8673245 0.4972223 -0.02449798 0.8758928 0.4818835 -0.001518905 0.9739198 0.2268875 0.05610853 0.415207 0.9079951 0.03784078 0.4947775 0.8681955 0.04631835 0.7807864 0.6230789 0.1012717 0.4006721 0.9106075 0.08104252 0.8072062 0.5846798 0.1473552 0.5228851 0.83957 0.1455351 0.6202652 0.7707728 0.2380684 0.2577287 0.9364292 0.0800541 0.9059059 0.4158436 0.05371004 0.9583673 0.2804417 0.2857937 0.4249292 0.858928 0.0394985 0.9876935 0.1513326 0.1981756 0.6655779 0.7195363 0.1770052 0.7980999 0.575939 0.2917222 0.4200103 0.8593543 0.3355025 0.558048 0.7589603 0.2044703 0.8291522 0.520287 0.1850937 0.8812122 0.4349777 0.42016 0.3721542 0.8276273 0.3578068 0.5328825 0.7668186 0.4816007 0.3260772 0.8134707 0.2086473 0.9034355 0.3745273 0.355612 0.7202746 0.5956045 0.2577681 0.8640766 0.4323509 0.4704422 0.5578755 0.6837098 0.07232856 0.992078 0.1027123 0.5345043 0.498294 0.6826481 0.4929291 0.5610995 0.6649725 0.3544775 0.8155998 0.4573214 0.648554 0.3466497 0.6776517 0.5909608 0.4734048 0.653187 0.3239706 0.8755481 0.3584114 0.5021899 0.7156916 0.485377 0.3803798 0.8424066 0.3816573 0.6958752 0.3879215 0.6043796 0.5959842 0.6215256 0.5084378 0.7429271 0.2716351 0.6117792 0.5735994 0.716006 0.3978935 0.7755912 0.3571357 0.5204925 0.3522599 0.897651 0.2648313 0.3331722 0.9070608 0.2573661 0.6585239 0.6307396 0.4105044 0.6639462 0.6305747 0.4019341 0.8428782 0.35799 0.4017455 0.2465109 0.9621197 0.1164397 0.5373232 0.8088004 0.2390097 0.8426665 0.4150502 0.3429967 0.7974839 0.5260386 0.2954707 0.404612 0.898947 0.1678798 0.8103414 0.5254358 0.2593534 0.7637283 0.6150006 0.1961978 0.558341 0.8201208 0.1251294 0.4413216 0.8905562 0.110204 0.8920563 0.4305212 0.137431 0.2318646 0.9718455 0.04189395 0.8742392 0.4728522 0.110076 0.6573047 0.7503244 0.07045489 0.9482856 0.3166186 0.02252 0.5607501 0.8278895 0.01258963 0.3981852 0.9173019 0.002421498 -0.001513123 0.9999978 0.00149548 -0.001583099 0.9999979 0.001350045 -0.001855611 0.9999976 0.001151442 -0.00124967 0.9999979 0.001687169 -0.001377284 0.9999981 0.001447916 -0.001910984 0.9999978 9.68164e-4 -6.03176e-4 0.9999984 0.001700341 -0.001955687 0.9999977 9.16555e-4 9.44397e-4 0.9999934 0.003513872 -0.001970946 0.999998 3.4762e-4 -0.001719236 0.9999983 8.23476e-4 -0.004413008 0.999986 0.002921342 1.40639e-5 0.9999999 5.54005e-4 -0.001220226 0.9999993 -1.22813e-4 0.001565039 0.9999986 6.7231e-4 6.07401e-4 0.9999985 0.001658618 -0.001221418 0.9999992 -4.88293e-4 -0.001160323 0.9999992 -5.37872e-4 0.001144468 0.9999983 0.001517415 0.001181006 0.9999983 0.001394093 -6.80583e-4 0.9999982 -0.001835465 -0.001601219 0.9999976 -0.001535952 -0.002380371 0.9999969 -7.42617e-4 0.003497123 0.9999938 -6.07277e-4 -6.58581e-4 0.9999992 -0.001074254 0.00264883 0.9999952 0.001606285 0.002712309 0.9999951 0.00156188 -4.04455e-4 0.9999992 -0.001232981 4.66478e-4 0.9999969 -0.002461016 0.002364754 0.99999 0.003824353 6.75425e-4 0.9999998 1.81859e-4 -0.002723097 0.9999955 -0.001272559 3.1805e-6 1 -4.02907e-4 0.003569841 0.9999936 -2.68407e-4 5.81487e-4 0.999992 -0.003973662 4.41908e-4 0.9999998 -5.30708e-4 2.57246e-4 0.9999997 -7.69568e-4 0.003950297 0.9999884 0.002794563 3.99598e-4 0.9999998 -6.78304e-4 2.00517e-4 1 -9.75129e-5 0.004360675 0.9999905 3.30348e-5 -5.7137e-4 0.9999974 -0.00222069 0.001838147 0.9999969 -0.001764476 0.9904501 0.04534751 -0.1302012 0.9770762 -0.03803896 -0.2094644 0.9643319 0.02474522 -0.2635372 0.9106245 -0.03109943 -0.4120632 0.9293005 0.01747488 -0.3689111 0.8822445 0.04184412 -0.4689282 0.817162 0.03243798 -0.5754946 0.7912722 -0.02301251 -0.6110309 0.747341 0.03508013 -0.663514 0.6481549 -0.007677555 -0.7614699 0.6436257 0.002332568 -0.765337 0.5259683 0.02684634 -0.8500804 0.4621624 -0.0501036 -0.8853788 0.421474 0.02474451 -0.9065029 0.2550786 0.05915045 -0.9651094 0.1808363 -0.06124889 -0.9816042 0.1139667 0.01907199 -0.9933016 -0.0672869 -0.05155551 -0.9964008 -8.34218e-4 0.0343483 -0.9994096 -0.1366475 0.0421651 -0.989722 -0.254619 0.06220388 -0.9650388 -0.3391209 -0.01341855 -0.9406472 -0.3794052 -0.09609228 -0.9202272 -0.4448568 0.01984679 -0.8953819 -0.5464181 0.07172256 -0.8344359 -0.6509115 -0.02228385 -0.7588266 -0.6612374 -0.05046737 -0.7484773 -0.7259687 0.03114372 -0.6870223 -0.8424914 -0.07547134 -0.5333971 -0.8183211 0.01362013 -0.5746001 -0.9032744 0.0743243 -0.4225769 -0.950577 0.03723257 -0.3082482 -0.9701086 -0.07893544 -0.2294744 -0.9842944 0.02134019 -0.1752411 -0.9981448 0.05876874 0.01591402 -0.994305 -0.05408364 0.09182953 -0.9834929 0.0448578 0.1752985 -0.9501227 -0.008366644 0.3117644 -0.9453051 0.014611 0.3258601 -0.8613455 0.00281018 0.5080119 -0.8666544 -0.02407765 0.4983277 -0.8024269 0.06332677 0.5933808 -0.6792297 -0.03958612 0.7328574 -0.6917631 -0.09459078 0.7159025 -0.6088595 0.0489543 0.7917662 -0.508132 0.07296228 0.8581833 -0.4154759 -0.05932724 0.9076674 -0.4400656 -0.002291321 0.8979627 -0.2955662 0.04590749 0.9542186 -0.1955054 -0.0305503 0.9802266 -0.1440383 0.03675138 0.9888895 0.003309309 -0.03567916 0.9993578 -0.05402082 0.03608304 0.9978877 0.09726434 0.05059319 0.9939719 0.2414661 -0.0559526 0.968795 0.1819333 0.02851688 0.9828973 0.3065574 0.0318526 0.9513191 0.3897847 0.05191659 0.9194415 0.4947446 -0.04242831 0.8680021 0.4894301 -0.0310868 0.8714883 0.5879054 0.06445789 0.8063576 0.6916521 0.02870911 0.72166 0.7288395 -0.04572057 0.6831564 0.7719903 0.02747201 0.6350404 0.8367264 0.03682053 0.546382 0.8699088 -0.04052156 0.4915455 0.9110417 0.07005363 0.4063197 0.9476001 0.04563432 0.3161829 0.9682614 -0.05687296 0.2433833 0.9845569 0.0371654 0.1710747 0.9997546 -0.002965211 0.02195179 0.9997491 -0.01751625 0.01396161 0.9989755 -0.04385596 -0.01117366 0.9902446 0.02103036 -0.1377438 0.9886036 0.0370686 -0.1459073 0.9504101 -0.06926959 -0.3031874 0.896206 -0.01928776 -0.4432188 0.9179642 0.04121446 -0.3945164 0.8322607 0.001921474 -0.5543813 0.8218664 0.02725338 -0.5690282 0.7532368 -0.06080579 -0.6549328 0.677958 -0.0220173 -0.7347709 0.605883 -0.02926242 -0.7950155 0.6496443 0.0263828 -0.7597804 0.4692299 0.003004074 -0.883071 0.4644114 0.01366531 -0.8855142 0.3065577 -0.03906202 -0.9510502 0.2310067 0.04602986 -0.9718627 0.2015034 -7.9533e-4 -0.9794875 0.06729364 -0.05344265 -0.9963009 -0.04805338 0.02191925 -0.9986043 -0.04907661 0.02416038 -0.9985027 -0.1946285 -0.04972618 -0.9796158 -0.2933863 0.04990756 -0.9546905 -0.334983 -0.01491451 -0.9421061 -0.4680591 -0.02162718 -0.8834325 -0.4917696 0.02411842 -0.8703914 -0.6004063 -0.04969727 -0.7981495 -0.6807484 0.01600944 -0.7323425 -0.6793427 0.01211893 -0.7337211 -0.7801036 -0.03096747 -0.6248835 -0.8158248 0.0231899 -0.5778341 -0.8457102 -0.03260189 -0.5326458 -0.8817155 -0.0398308 -0.4700971 -0.9258519 -0.01167136 -0.3777065 -0.9141873 0.02063345 -0.4047666 -0.9580329 -0.03962171 -0.2839069 -0.9842365 -0.0138511 -0.1763139 -0.9779139 0.02763092 -0.2071735 -0.9944654 -0.04368823 -0.09555107 -0.9995071 0.01313304 0.02851527 -0.999711 0.002861499 0.02387171 -0.9793115 -0.01402455 0.2018718 -0.9686205 0.03700244 0.2457748 -0.9502953 -0.04313719 0.3083474 -0.889941 -0.02463752 0.4554098 -0.8543882 0.08944755 0.5118788 -0.8090234 -0.04635602 0.5859457 -0.7545841 -0.07337588 0.6520881 -0.6641409 0.0184623 0.7473795 -0.6484953 0.06031638 0.7588254 -0.5327471 -0.055426 0.8444576 -0.4460085 -0.005031287 0.8950147 -0.4291859 0.02445554 0.9028851 -0.3398908 -0.04424923 0.9394235 -0.218853 0.01328212 0.9756675 -0.2026091 -0.01120781 0.9791955 -0.08731848 -0.02848041 0.9957733 -0.02936327 0.0439468 0.9986023 0.07626289 -0.06463366 0.9949907 0.1949251 -0.02954947 0.9803729 0.2565197 0.0853368 0.9627644 0.3420995 -0.04400885 0.9386326 0.474632 -0.0423277 0.8791661 0.5709332 -0.009789109 0.8209381 0.537747 0.04538863 0.8418838 0.7176288 0.01856601 0.6961783 0.7240442 -0.005041003 0.6897353 0.8058851 -0.06636786 0.5883405 0.8668097 -0.01226639 0.4984884 0.882359 0.04801517 0.4681211 0.9307798 -0.04340875 0.3629941 0.9720335 -0.02626895 0.2333684 0.9610369 0.02396637 0.2753793 0.9943677 -0.01406425 0.1050482 0.9966664 0.01802831 0.07956975 0.5184004 -0.855138 -3.53932e-4 0.4405299 -0.8977266 -0.00451976 0.8231384 -0.5646644 0.05997633 0.7112216 -0.6994423 0.07031613 0.935352 -0.3328058 0.119821 0.7105697 -0.7000489 0.0708695 0.9227635 -0.3213212 0.2127443 0.1886008 -0.9816087 0.02956604 0.4463186 -0.8883504 0.1078575 0.8144358 -0.5286536 0.2392066 0.4082097 -0.9070094 0.1034352 0.7370997 -0.6488966 0.1887254 0.8110339 -0.520994 0.2660628 0.8913846 -0.2812258 0.3554514 0.6257269 -0.7296177 0.2759055 0.4183469 -0.8902255 0.180235 0.3438042 -0.92399 0.1674553 0.8117875 -0.3744502 0.4480941 0.7586985 -0.4787368 0.4418006 0.6851021 -0.6202657 0.381976 0.4535207 -0.8357484 0.3095865 0.7333627 -0.4458408 0.5132303 0.6523869 -0.5573695 0.5135471 0.5492284 -0.6998055 0.45675 0.4445774 -0.8358954 0.3219158 0.6882596 -0.2326219 0.6871578 0.4901174 -0.7184028 0.4936418 0.6287105 -0.3809211 0.6779545 0.2218112 -0.9541174 0.2011467 0.492535 -0.70157 0.5149844 0.1246436 -0.9838207 0.1286894 0.5424721 -0.3897858 0.7441714 0.4111408 -0.7404489 0.5316942 0.3896869 -0.7615827 0.5178185 0.5408936 -0.3671666 0.7567185 0.2351061 -0.9098301 0.3419565 0.4355243 -0.314168 0.843574 0.4322599 -0.4665271 0.7716891 0.370669 -0.625342 0.6866965 0.1810986 -0.922906 0.3397762 0.3037952 -0.7108935 0.6343019 0.3344436 -0.3021152 0.892678 0.3001757 -0.4105377 0.8610188 0.2547449 -0.6427513 0.7224791 0.09509503 -0.9699586 0.2239137 0.2039154 -0.7125086 0.6713792 0.2009894 -0.2875776 0.9364307 0.1228587 -0.8604187 0.4945557 0.1370406 -0.5267524 0.8388992 0.08055162 -0.8692399 0.4877845 0.09262675 -0.5767095 0.8116813 0.05271762 -0.4105765 0.910301 0.06609964 -0.5411078 0.8383514 0.02603977 -0.9332821 0.3581992 -0.03172415 -0.700549 0.7128989 -0.03189909 -0.829442 0.5576813 -0.07502931 -0.3546224 0.9319944 -0.09432017 -0.4944964 0.8640469 -0.07356226 -0.8665604 0.4936212 -0.1984221 -0.3897478 0.8992916 -0.15727 -0.4899664 0.8574376 -0.1410468 -0.8081406 0.5718519 -0.2952706 -0.4123294 0.8618583 -0.3070174 -0.5248662 0.7938866 -0.1701663 -0.8511345 0.496602 -0.1839224 -0.838369 0.5131376 -0.03993374 -0.9892442 0.1407172 -0.3744991 -0.4727423 0.7976624 -0.4085083 -0.5874558 0.6985819 -0.2611464 -0.8423287 0.4714713 -0.4900159 -0.4940627 0.7181828 -0.2421772 -0.8896408 0.3871559 -0.4958788 -0.503431 0.7075745 -0.3541042 -0.8420879 0.4068146 -0.6311007 -0.3404046 0.6970199 -0.3489103 -0.8213611 0.4512511 -0.6339549 -0.369853 0.679198 -0.2022514 -0.958069 0.2029734 -0.4639828 -0.7427751 0.4827062 -0.6820251 -0.359439 0.636903 -0.6370218 -0.5823498 0.5050465 -0.4787812 -0.7655238 0.4298161 -0.3348467 -0.8999038 0.279376 -0.7730445 -0.3537646 0.5265483 -0.6651941 -0.5628415 0.4906386 -0.8320474 -0.3251495 0.4494163 -0.3489385 -0.9079225 0.232204 -0.8691495 -0.228219 0.4387428 -0.5872036 -0.7364481 0.3359112 -0.6040444 -0.7249746 0.3309718 -0.8701225 -0.3418608 0.3549905 -0.6063491 -0.7517042 0.2593873 -0.1777272 -0.9800118 0.0893861 -0.6560012 -0.7085117 0.2601417 -0.9135947 -0.2577785 0.3144757 -0.3452362 -0.92925 0.1315543 -0.8233134 -0.5242621 0.217496 -0.7130814 -0.6657158 0.2198576 -0.8998458 -0.4067147 0.157673 -0.8587347 -0.4858371 0.1629018 -0.7445037 -0.658741 0.1085109 -0.5223894 -0.847162 0.0970878 -0.4020923 -0.9130187 0.06869137 -0.3613549 -0.9301067 0.06575781 -0.9503222 -0.3085758 0.04085236 -0.8648049 -0.5020971 0.003333449 -0.7797988 -0.6257093 0.02004903 -0.06104439 -0.9981299 0.003220975 -0.5474089 -0.8367884 -0.01134139 -0.8754845 -0.4757187 -0.08496296 -0.4992706 -0.86556 -0.03917688 -0.863615 -0.4947695 -0.09681224 -0.5382673 -0.8401752 -0.06613665 -0.8822922 -0.4429101 -0.1593461 -0.8522913 -0.4875888 -0.1893585 -0.5208907 -0.8442407 -0.1262164 -0.8713204 -0.4215204 -0.2512398 -0.5474703 -0.8283452 -0.1188294 -0.7951197 -0.5289799 -0.2965892 -0.6022341 -0.7697474 -0.2116673 -0.2074859 -0.9754766 -0.0734511 -0.8122498 -0.4703654 -0.3449737 -0.4483836 -0.8685225 -0.2112366 -0.7891966 -0.4790031 -0.3843497 -0.6801182 -0.6180519 -0.3942731 -0.48633 -0.8308808 -0.2704082 -0.711728 -0.4974219 -0.4959987 -0.7029644 -0.4973478 -0.5084154 -0.7305166 -0.3268942 -0.5995713 -0.317552 -0.9171519 -0.2408176 -0.4861298 -0.7642824 -0.4237338 -0.3819178 -0.8594124 -0.3399254 -0.6498564 -0.3649215 -0.6667225 -0.5860018 -0.4949381 -0.6415903 -0.5641409 -0.5191435 -0.6420554 -0.3982267 -0.7731165 -0.4936664 -0.5382065 -0.3986671 -0.742562 -0.3315193 -0.8709822 -0.3626088 -0.5147954 -0.4291589 -0.7421647 -0.4182345 -0.6386785 -0.6458868 -0.1279661 -0.9756075 -0.1783674 -0.3696437 -0.7649419 -0.5274727 -0.4577764 -0.2450534 -0.8546284 -0.236015 -0.8833857 -0.4048786 -0.3662795 -0.4995439 -0.7850447 -0.3479521 -0.6330212 -0.6915298 -0.2299131 -0.840174 -0.4911698 -0.281427 -0.4700432 -0.8365753 -0.2847568 -0.3447409 -0.8944649 -0.2287765 -0.8407863 -0.4906524 -0.286131 -0.4790456 -0.829846 -0.1159178 -0.9262019 -0.3587661 -0.2056311 -0.2469461 -0.9469602 -0.1438848 -0.725211 -0.6733248 -0.1148516 -0.9177173 -0.3802685 -0.1262726 -0.4789025 -0.8687391 -0.1135682 -0.695032 -0.7099527 -0.05871289 -0.7749133 -0.6293348 -0.05252158 -0.3360733 -0.9403703 -0.04178118 -0.9178085 -0.3948191 0.01325756 -0.5223684 -0.8526169 -0.02198308 -0.7462909 -0.6652569 0.08514744 -0.3728978 -0.9239574 0.05615204 -0.5011106 -0.8635597 0.09553736 -0.6804363 -0.726553 0.03287076 -0.8268128 -0.5615159 0.01013714 -0.9846634 -0.1741707 0.03026473 -0.9618275 -0.271978 0.1737472 -0.3294086 -0.9280635 0.194451 -0.4949072 -0.8469097 0.1142943 -0.6798996 -0.7243435 0.2944823 -0.4201712 -0.8583335 0.1300862 -0.8728282 -0.4703708 0.2384092 -0.5040867 -0.8300951 0.1374998 -0.8708976 -0.4718381 0.3302478 -0.4644273 -0.8217322 0.1543381 -0.89105 -0.4268604 0.27824 -0.7592568 -0.5883126 0.4471978 -0.2956137 -0.8441722 0.4562952 -0.3629415 -0.8124458 0.07987177 -0.9841278 -0.1584704 0.3490158 -0.7361331 -0.5799105 0.3501384 -0.7454516 -0.5671905 0.5489321 -0.3420927 -0.7626574 0.2414223 -0.9062154 -0.347115 0.5055578 -0.5895831 -0.6299231 0.5109239 -0.5979188 -0.6176163 0.5956085 -0.5115365 -0.619339 0.2990086 -0.8954914 -0.3296801 0.6930035 -0.4176024 -0.5876687 0.2946538 -0.9025169 -0.3140739 0.6261799 -0.5418251 -0.5606463 0.5421084 -0.711205 -0.4475556 0.1504741 -0.9802168 -0.1285796 0.5292274 -0.7629389 -0.371272 0.8062332 -0.2855159 -0.5181398 0.797884 -0.370015 -0.4758886 0.3534994 -0.9075325 -0.2267665 0.6753121 -0.6180242 -0.4024919 0.8573011 -0.2817895 -0.4308474 0.8433658 -0.3805249 -0.3793879 0.6892754 -0.665663 -0.2859934 0.3380868 -0.9285722 -0.1531369 0.707036 -0.6377639 -0.3055443 0.9327177 -0.2022213 -0.2985705 0.0657438 -0.9976165 -0.02095931 0.4605873 -0.8689931 -0.1808601 0.8773109 -0.4124685 -0.2453476 0.7994254 -0.5475226 -0.2472614 0.5297895 -0.8416064 -0.1049858 0.54282 -0.8297579 -0.1298015 0.8790535 -0.4505151 -0.1558888 0.7193428 -0.6854647 -0.1126243 0.9344187 -0.3320593 -0.1288352 0.3340948 -0.94097 -0.05437219 0.9195341 -0.3916807 -0.03229999 0.8677312 -0.4969253 -0.0103929 0.7126914 -0.6996848 -0.05012196 0.006620585 -0.9999743 0.002768993 0.001348674 -0.9999973 0.001921057 0.006607711 -0.9999684 0.004431486 3.39967e-4 -0.9999924 0.003892242 0.005720138 -0.9999718 0.004879832 0.005602598 -0.9999825 0.001901149 0.001069128 -0.9999905 0.004242718 0.004224956 -0.9999856 0.003321528 9.21528e-4 -0.9999997 9.78126e-5 -7.2921e-4 -0.9999828 0.005840539 -4.70434e-4 -0.9999818 0.006017982 -0.003179252 -0.9999701 0.007055938 8.93025e-4 -0.9999997 -1.58661e-4 -0.002762973 -0.9999643 0.007984936 0.003097832 -0.9999916 -0.00268191 0.004455566 -0.9999877 -0.002191603 -0.00442487 -0.9999652 0.007089793 0.004452049 -0.9999876 -0.002224683 -0.006968975 -0.9999458 0.007737517 -0.002435088 -0.9999482 0.009894251 0.001785039 -0.9999966 -0.001948416 -0.001899302 -0.9999967 0.001726746 9.8078e-4 -0.9999924 -0.003784358 -0.002497613 -0.9999962 0.001185476 0.001476824 -0.9999907 -0.004056811 -0.003383219 -0.9999936 0.001139163 0.001316249 -0.9999904 -0.004176676 -0.003765165 -0.9999929 3.2969e-4 -0.007340252 -0.9999724 -0.001201272 -1.61006e-5 -0.999998 -0.002039611 -0.007188081 -0.9999731 -0.0014804 -0.00788027 -0.9999635 -0.003315389 -6.71066e-4 -0.999998 -0.00193715 -0.007115721 -0.9999548 -0.006317138 -0.007436394 -0.9999662 -0.003516972 -0.00470364 -0.9999613 -0.007449924 -0.007484197 -0.9999666 -0.003289997 -0.003016054 -0.9999709 -0.007024586 -0.004189133 -0.9999837 -0.003890156 0.8945044 0.4426402 -0.06270217 0.7930305 0.6077147 -0.04225623 0.6645663 0.7451568 -0.05561459 0.9281852 0.3521862 -0.1201547 0.8895975 0.4298786 -0.1543397 0.7650682 0.6238779 -0.1595218 0.2330042 0.9722667 -0.02016782 0.642322 0.758985 -0.1066034 0.9304319 0.260971 -0.2572755 0.4062927 0.9088886 -0.09406322 0.8563422 0.4256333 -0.2924287 0.7664474 0.5935953 -0.2453628 0.8690903 0.368264 -0.3302479 0.3783633 0.9186584 -0.1136143 0.5462715 0.8062872 -0.2269111 0.5464799 0.8069364 -0.2240833 0.8011472 0.4418109 -0.4036909 0.7477158 0.5327227 -0.3963932 0.4221028 0.8773116 -0.2283718 0.678282 0.5895054 -0.4386535 0.5241491 0.7778089 -0.3468159 0.7030158 0.5003247 -0.5054147 0.1595777 0.9810459 -0.1099279 0.6680137 0.4154642 -0.6173712 0.6456835 0.528131 -0.5515165 0.4814167 0.757934 -0.4401979 0.3991234 0.852937 -0.3364507 0.2814927 0.9273309 -0.2466163 0.2334935 0.9400939 -0.2484036 0.4369814 0.7480213 -0.4995111 0.5896263 0.4206266 -0.6895028 0.5909585 0.3872787 -0.7076604 0.3680943 0.8114314 -0.4539667 0.3274676 0.8060861 -0.4929403 0.480816 0.4317094 -0.7631795 0.4744234 0.4438896 -0.7601872 0.06232744 0.9936079 -0.09412008 0.3922302 0.3332281 -0.8573882 0.3902339 0.4684088 -0.7926605 0.2283999 0.8785715 -0.4194587 0.1814477 0.9188664 -0.350373 0.3205044 0.6264893 -0.7104845 0.2619271 0.3957368 -0.8802196 0.2404554 0.6271069 -0.7408901 0.2440251 0.3041976 -0.9208234 0.1381057 0.8036295 -0.5788839 0.1151979 0.9092179 -0.4000653 0.1242325 0.4597116 -0.8793358 0.1110078 0.5043756 -0.8563193 0.1289067 0.7932146 -0.5951418 0.07813489 0.5203402 -0.850377 -0.002985239 0.3179563 -0.9481008 0.01652491 0.8886898 -0.4582111 0.002931296 0.718324 -0.6957026 0.01246416 0.9944508 -0.1044625 -0.08509528 0.5581533 -0.8253629 6.21396e-4 0.9412353 -0.3377512 -0.07563203 0.5588886 -0.8257866 -0.1471271 0.2927867 -0.9447908 -0.04686421 0.9372328 -0.3455409 -0.1263983 0.7301248 -0.6715216 -0.1232567 0.7714753 -0.6242063 -0.2267058 0.2906925 -0.9295711 -0.2499932 0.4805881 -0.8405585 -0.04676139 0.975166 -0.2164828 -0.32641 0.4169622 -0.8482918 -0.2939356 0.5027908 -0.8128982 -0.2723827 0.6619503 -0.6983047 -0.1871936 0.8243197 -0.5342804 -0.1513797 0.9098576 -0.3863203 -0.4201925 0.292442 -0.8590204 -0.1540507 0.9279506 -0.3393763 -0.453226 0.4966115 -0.7402454 -0.3784206 0.6789242 -0.6291739 -0.3808944 0.6714912 -0.6356251 -0.4838426 0.4393617 -0.7568737 -0.0935375 0.9824614 -0.1613084 -0.3809297 0.796366 -0.4697807 -0.5934544 0.41473 -0.6897906 -0.3235694 0.8652692 -0.3828997 -0.5750784 0.5396109 -0.6149024 -0.3025317 0.8998429 -0.3142569 -0.6641677 0.4661155 -0.5844807 -0.649944 0.4935964 -0.5778715 -0.526008 0.7496057 -0.4017547 -0.7939115 0.240099 -0.5586208 -0.5226173 0.7685329 -0.369091 -0.07376176 0.9960108 -0.05021739 -0.7730714 0.4403474 -0.4565685 -0.6013347 0.7103664 -0.3657543 -0.1524801 0.9844355 -0.08738851 -0.8441624 0.3463842 -0.4091553 -0.7920674 0.5187633 -0.3217357 -0.5832622 0.7566198 -0.2955195 -0.3867107 0.9083164 -0.1594247 -0.8123349 0.5126296 -0.27807 -0.7763368 0.5872845 -0.2289069 -0.4155176 0.897019 -0.1506723 -0.7843673 0.5901823 -0.1909267 -0.9334561 0.3266338 -0.1482235 -0.6707944 0.7319204 -0.119697 -0.3618226 0.9304572 -0.05774164 -0.8983491 0.4319905 -0.07970821 -0.3649888 0.9291326 -0.05912393 -0.7627787 0.6444845 -0.05299317 -0.7093486 0.7047314 -0.01335853 -0.1635994 0.9864016 -0.01572066 -0.9592264 0.2825146 0.008387863 -0.6123299 0.7905912 -0.004230737 -0.8727652 0.4856519 0.04922622 -0.8615985 0.4992502 0.09163647 -0.9541638 0.2465307 0.1696885 -0.4855135 0.8727194 0.05135601 -0.3371322 0.9407052 0.03762763 -0.6863866 0.7148049 0.1338934 -0.8345316 0.502914 0.2250216 -0.6933302 0.7043948 0.1520567 -0.8694968 0.3845437 0.3100024 -0.1435508 0.9887797 0.04132789 -0.7999101 0.4905424 0.3457053 -0.4731469 0.8617985 0.1828538 -0.3932453 0.9055917 0.1589393 -0.6830258 0.6613173 0.3100566 -0.8274285 0.33583 0.4500891 -0.633095 0.6347154 0.4430882 -0.7266019 0.393247 0.5633885 -0.3401242 0.915318 0.2156587 -0.6738195 0.5985617 0.4332335 -0.5135841 0.7747681 0.3687354 -0.119578 0.9879511 0.09825307 -0.6424167 0.4871814 0.59157 -0.4754441 0.7647545 0.4348604 -0.4733642 0.7677968 0.4317573 -0.6501748 0.3887374 0.6528062 -0.2332105 0.9435241 0.2353194 -0.5400958 0.4745431 0.6950579 -0.5242247 0.5031563 0.6870387 -0.4332491 0.7014512 0.5659165 -0.3568165 0.7847999 0.5067258 -0.4740496 0.4297818 0.768482 -0.2401078 0.9055056 0.3498685 -0.3550302 0.6254022 0.6948566 -0.1431365 0.9547712 0.2606225 -0.345173 0.6300886 0.695589 -0.3509714 0.3695523 0.8603779 -0.1631112 0.9228733 0.3488548 -0.3336365 0.6009759 0.7263022 -0.1543216 0.9049286 0.3965968 -0.2899467 0.2713342 0.9177739 -0.1952508 0.7554785 0.6254035 -0.2492766 0.3662222 0.8965169 -0.1736566 0.7287145 0.6624339 -0.1533567 0.7409031 0.6538688 -0.1672829 0.3456041 0.9233496 -0.108263 0.5826633 0.8054705 -0.06340569 0.9000721 0.4311034 -0.04236 0.9672014 0.2504536 -0.0847637 0.5962672 0.7982985 -0.0132097 0.4201565 0.9073556 -0.01170778 0.9929729 0.1177617 -0.02862268 0.8221564 0.5685417 0.01630342 0.4445801 0.8955908 0.04418426 0.7690947 0.6376058 0.06731593 0.3809457 0.9221438 0.01408511 0.8348019 0.5503703 0.1266183 0.5338181 0.8360658 0.01819664 0.9453077 0.3256722 0.1120831 0.7112457 0.6939504 0.2070782 0.3213986 0.9240247 0.1287997 0.7465089 0.6527902 0.07520741 0.9501378 0.3026251 0.2526355 0.3466376 0.9033371 0.2671198 0.5845933 0.7660925 0.2390198 0.5631543 0.791029 0.07444894 0.9680358 0.2395083 0.3433003 0.4965346 0.7972443 0.2175351 0.8377024 0.5009325 0.1695489 0.9102105 0.3778492 0.3733806 0.5635953 0.7368496 0.3971547 0.5500725 0.7346349 0.4203435 0.6110171 0.6707977 0.43838 0.6005263 0.6687237 0.5804558 0.3060367 0.7545944 0.2112197 0.9192575 0.3321925 0.2019696 0.9339541 0.2948524 0.4399446 0.7154673 0.5427296 0.6276715 0.3533287 0.6936768 0.328819 0.8629804 0.3835923 0.6007007 0.4976109 0.6257333 0.6185209 0.5596814 0.5515331 0.6411367 0.5403283 0.5449671 0.3432954 0.8736552 0.3447825 0.6526681 0.5824487 0.4845389 0.2732453 0.9347522 0.227102 0.4431606 0.8469911 0.2936236 0.7357618 0.4935472 0.4637519 0.06769686 0.9966464 0.04596948 0.7317651 0.5331454 0.4245892 0.4716436 0.8414814 0.2635554 0.8105467 0.4430541 0.3830369 0.4222319 0.8836286 0.2022889 0.7350963 0.62522 0.2621707 0.4522926 0.8695719 0.198182 0.8781932 0.4147553 0.2382331 0.7656424 0.598809 0.2349887 0.9405863 0.2953402 0.167546 0.637434 0.7574385 0.1412976 0.398263 0.9122856 0.09550732 0.8788214 0.4673734 0.09609878 0.7673273 0.6365706 0.07737344 0.2973618 0.9531749 0.05507808 0.9723657 0.2326157 0.01987248 0.7447676 0.6644055 0.06234228 0.4807402 0.8768501 0.004779458 0.4126592 0.9108586 0.00700891 -0.001316666 0.9999985 0.0011608 -8.94072e-4 0.9999986 0.001412153 -6.86299e-4 0.9999966 0.002556502 -0.005215227 0.999985 0.001702845 -0.005132377 0.9999838 0.002469778 -7.66618e-4 0.9999964 0.002555787 -0.003604233 0.9999884 0.003192067 -0.001532435 0.9999988 2.11154e-4 -7.56685e-4 0.9999964 0.002588033 4.10839e-5 0.9999987 0.001615762 -0.0013628 0.9999992 7.73472e-5 -0.001646041 0.9999987 -1.30744e-4 4.91221e-4 0.9999986 0.001633822 0.001527786 0.9999959 0.00246489 -0.001024127 0.9999995 -3.87763e-4 0.001511096 0.9999959 0.002461612 -0.00117588 0.999999 -8.46374e-4 -0.003797352 0.9999818 -0.004697561 0.00603187 0.9999762 0.003371119 -0.004023373 0.9999811 -0.004660367 0.005084216 0.999976 0.00471276 -0.00452882 0.9999851 -0.003066003 0.005401015 0.9999746 0.004669189 0.004421472 0.9999871 0.002513408 -6.9767e-4 0.9999981 -0.001843333 0.00472337 0.9999884 0.001060426 -3.91102e-4 0.9999974 -0.002258837 0.002212703 0.9999952 0.002219319 -2.94068e-5 0.9999977 -0.002154648 3.54763e-4 0.9999966 -0.002583742 0.002366602 0.9999971 -3.05579e-4 0.005096018 0.9999841 -0.002425849 6.41114e-4 0.9999976 -0.002114832 0.005438089 0.9999627 -0.006715536 0.008476793 0.9999557 -0.004107177 0.001284897 0.999997 -0.002064526 0.007798373 0.9999696 5.61654e-4 6.06777e-4 0.9999985 -0.001717448 9.31702e-4 0.9999993 -8.30215e-4 0.9991405 0.01684015 -0.0378797 0.9896776 0.06629455 -0.127057 0.9673664 -0.04274243 -0.2497508 0.9613534 0.009162724 -0.2751652 0.8930025 -0.01277858 -0.4498703 0.9089332 0.03513199 -0.4154592 0.8615427 0.04105085 -0.5060227 0.781124 -0.01012891 -0.6242939 0.7775783 0.00231105 -0.6287819 0.7027514 0.05998188 -0.7089024 0.6494144 0.01926243 -0.7601907 0.6220356 -0.03607946 -0.7821573 0.5538899 0.03592115 -0.8318148 0.4694184 -0.03091657 -0.8824344 0.4378951 0.02661907 -0.8986319 0.3427858 0.04432666 -0.9383672 0.2374337 -0.06800305 -0.9690206 0.23349 -0.05716019 -0.9706777 0.1678307 0.03243488 -0.9852821 0.07689499 0.07761037 -0.994014 -0.0669679 -0.06505978 -0.9956318 -0.04074847 -0.007605135 -0.9991405 -0.1581403 0.03637772 -0.9867464 -0.2353482 0.03238838 -0.9713714 -0.2954853 -0.04510927 -0.9542818 -0.3393844 0.01942199 -0.9404473 -0.4412121 0.04223161 -0.8964086 -0.5141184 -0.05941915 -0.8556587 -0.5674422 0.04800283 -0.8220129 -0.7004073 -0.02147036 -0.7134203 -0.7047692 -0.008804678 -0.7093821 -0.7878265 0.02985012 -0.6151734 -0.8222413 -0.04387462 -0.5674454 -0.8626161 0.04288798 -0.504038 -0.9300385 -0.06528019 -0.3616173 -0.9150194 0.007496833 -0.4033403 -0.9576587 0.05328518 -0.2829322 -0.9851754 0.04151594 -0.166451 -0.9928097 -0.08707469 -0.08213943 -0.999305 0.02752041 -0.02514356 -0.9900489 0.04866403 0.1320423 -0.9774996 -0.04192847 0.2067285 -0.9730238 -1.84432e-4 0.2307047 -0.929894 0.05311834 0.3639722 -0.8966374 -0.02408027 0.4421105 -0.8906096 -0.002630054 0.4547612 -0.7691665 -0.06418251 0.6358173 -0.8152214 0.03062796 0.578339 -0.7455845 0.009004712 0.6663503 -0.6772781 0.07684421 0.7317031 -0.602199 0.03708726 0.7974842 -0.5406863 -0.07253879 0.8380911 -0.5218308 -0.02676749 0.852629 -0.4338983 0.05020719 0.8995619 -0.3388246 0.01348745 0.9407529 -0.2854575 -0.0671854 0.9560336 -0.2368567 0.02629321 0.9711887 -0.136486 0.08275711 0.9871792 0.02781897 -0.05496466 0.9981007 0.01412284 -0.02825331 0.9995011 0.1082259 0.04633927 0.9930458 0.1866689 0.06047242 0.98056 0.2913348 -0.02702987 0.9562392 0.2997373 -0.04477846 0.9529703 0.3964813 0.04739242 0.9168187 0.4968235 -0.03340929 0.8672084 0.5144304 0.005883276 0.857512 0.6430153 0.06117868 0.763406 0.7157647 -0.07968771 0.6937801 0.7490108 0.01502168 0.6623876 0.8341254 0.07867115 0.5459356 0.8944278 -0.03829401 0.44557 0.9016343 -0.08267062 0.4245247 0.9280414 0.008761107 0.3723739 0.9608804 0.06037968 0.2703019 0.9841815 -0.002193212 0.1771495 0.986276 -0.03035515 0.1622907 0.9967284 0.02257663 0.07760661 0.9993889 -0.0331813 -0.01098966 0.9989325 -0.03977382 -0.02349591 0.9944614 0.05397373 -0.09018588 0.9843311 -0.04917269 -0.1693347 0.9620938 -0.02814549 -0.2712628 0.9359226 0.09148263 -0.3401176 0.9102748 -0.05410254 -0.4104543 0.8439392 -0.06452172 -0.5325445 0.7860001 0.06483042 -0.6148179 0.7722787 0.1087433 -0.6259077 0.7100921 -0.04871702 -0.7024214 0.6143832 -0.06554353 -0.7862808 0.5426545 0.02370476 -0.8396216 0.5279735 0.06597089 -0.8466947 0.4325345 -0.04205083 -0.9006363 0.3275158 -0.01528459 -0.9447222 0.2956699 0.02732276 -0.9548994 0.2594699 -0.01555252 -0.965626 0.1357096 -0.02335411 -0.9904734 0.09253048 0.02121645 -0.9954839 0.0468527 -0.0315231 -0.9984043 -0.1000308 0.001121997 -0.9949837 -0.1150764 0.02536505 -0.9930328 -0.2004061 -0.05051368 -0.9784099 -0.3370181 0.01571863 -0.941367 -0.3487634 0.04013288 -0.9363511 -0.4338895 -0.04559838 -0.8998115 -0.5339673 -0.01904511 -0.8452907 -0.5621137 0.03413844 -0.8263552 -0.629472 -0.04189693 -0.7758928 -0.7223306 0.01414364 -0.6914033 -0.7369141 0.05979341 -0.6733368 -0.8060315 -0.07378357 -0.5872555 -0.8651016 -0.05111581 -0.4989854 -0.9100486 0.09242123 -0.4040668 -0.9035142 0.03728997 -0.426933 -0.9430783 -0.03651624 -0.33056 -0.969998 -0.01818174 -0.2424322 -0.9785397 0.05482834 -0.1986308 -0.9908345 -0.03797733 -0.1296334 -0.9983972 -0.05461299 -0.0148518 -0.9964584 0.0375815 0.07522153 -0.9983575 -0.007369697 0.05681681 -0.9750311 -0.02071738 0.2211 -0.9692026 0.02043819 0.2454153 -0.9340233 -0.05327993 0.3532166 -0.8898628 0.03000366 0.4552407 -0.8910971 0.02522844 0.4531109 -0.8391913 -0.03663587 0.5426011 -0.7763484 9.31316e-4 0.6303034 -0.7832848 0.02048271 0.6213257 -0.6817936 -0.04134368 0.7303754 -0.6334635 0.05283921 0.7719663 -0.5677304 -0.04659318 0.8218951 -0.4810324 -0.01845198 0.8765087 -0.3749814 -0.03505849 0.9263692 -0.4277893 0.06689292 0.9013999 -0.2919017 -0.06740969 0.9540699 -0.1891164 -7.51944e-4 0.9819544 -0.1519731 0.06176322 0.986453 -0.1038997 -0.009641706 0.9945411 0.00109893 -0.05597406 0.9984316 0.05080181 -0.03613811 0.9980548 0.1044194 0.05923479 0.9927678 0.1951887 -0.04474472 0.9797446 0.3141317 -0.01142698 0.9493106 0.3892206 -0.01120376 0.9210765 0.3523426 0.04922413 0.9345757 0.5197949 -0.08195835 0.8503506 0.6003283 0.003261387 0.7997471 0.6809077 -0.04377037 0.7310602 0.6123782 0.03315705 0.7898693 0.7620596 0.0295782 0.646831 0.7782648 -0.01279699 0.6278059 0.837579 -0.04218798 0.544685 0.8943959 -0.01295477 0.4470887 0.8795558 0.03223806 0.4747025 0.9342544 -0.02745801 0.3555486 0.9487676 0.02837032 0.3146989 0.9727107 -0.04610937 0.2273934 0.9925383 0.02175652 0.119977 0.9925734 0.02275454 0.1195007 0.2834706 -0.9589151 0.01124101 0.9479725 -0.299342 0.108363 0.5072003 -0.8612399 0.03183847 0.9013589 -0.4149473 0.1239798 0.1367424 -0.9905045 0.01423144 0.794882 -0.6002278 0.08882099 0.6014472 -0.7948868 0.08010268 0.9075855 -0.3641297 0.2090415 0.5308758 -0.8383569 0.1238097 0.8588223 -0.4564372 0.2325714 0.3575418 -0.929933 0.08595627 0.6180014 -0.7661937 0.1761294 0.8807962 -0.3436551 0.325729 0.8140878 -0.4641013 0.3491006 0.6008917 -0.7555466 0.2609188 0.8358831 -0.3262019 0.4414657 0.1827424 -0.9795224 0.0845052 0.5401093 -0.8006654 0.2592621 0.8012468 -0.379121 0.462894 0.332243 -0.9272105 0.1729027 0.6146157 -0.7000735 0.3635169 0.7990052 -0.3288663 0.503426 0.7029764 -0.4712763 0.5326565 0.5768663 -0.7184579 0.3886433 0.699654 -0.433261 0.5681278 0.3495373 -0.8968167 0.2711892 0.3354104 -0.9031863 0.2678706 0.6891266 -0.4455835 0.5714542 0.4995012 -0.7106164 0.4955027 0.6559161 -0.3224496 0.6824958 0.3813135 -0.8483542 0.3672809 0.5482529 -0.5539608 0.6265351 0.5079454 -0.5544886 0.6591919 0.2126256 -0.9339798 0.2871798 0.4515002 -0.6190271 0.6426143 0.4702832 -0.3446868 0.8124191 0.22605 -0.920898 0.3175662 0.4389377 -0.5951279 0.673169 0.345073 -0.6891789 0.6371477 0.3967399 -0.4053362 0.8235898 0.2243452 -0.8847641 0.408487 0.3345552 -0.5813658 0.7416784 0.1532151 -0.9206389 0.3590953 0.2655581 -0.6464536 0.7152459 0.1718758 -0.8421255 0.511159 0.2480969 -0.4587588 0.8532223 0.1216744 -0.8646208 0.4874695 0.1683371 -0.377612 0.9105339 0.1804614 -0.4636419 0.8674502 0.1191543 -0.7024777 0.7016605 0.08824521 -0.3634927 0.9274082 0.03273642 -0.9626799 0.2686555 0.02867019 -0.6216486 0.7827714 0.03843402 -0.7322619 0.6799378 0.0189808 -0.8382552 0.5449476 -0.04306238 -0.4900524 0.8706288 -0.08685445 -0.4936443 0.8653159 -4.31773e-4 -0.9987637 0.04970848 -0.06035447 -0.8600659 0.5066003 -0.1043805 -0.5356996 0.8379325 -0.1921831 -0.4536839 0.8701935 -0.07185822 -0.9187501 0.3882455 -0.2160815 -0.480624 0.8498879 -0.2210131 -0.5132442 0.8292971 -0.1350824 -0.8681502 0.4775647 -0.1626684 -0.8709744 0.4636193 -0.3600758 -0.4502009 0.8171075 -0.3232704 -0.5474386 0.7718855 -0.3093436 -0.6160802 0.7243975 -0.4434281 -0.3447854 0.8273419 -0.1521384 -0.9292638 0.3366345 -0.3074973 -0.7711933 0.5574104 -0.538231 -0.3711164 0.7566903 -0.4809237 -0.4774279 0.735374 -0.0955736 -0.9796713 0.1763799 -0.3622997 -0.7419904 0.5640827 -0.3379851 -0.8194384 0.4629113 -0.5844888 -0.4212726 0.6934713 -0.3666576 -0.8141914 0.450172 -0.6362074 -0.3464936 0.6893348 -0.3584629 -0.84649 0.3936485 -0.6392407 -0.4663874 0.6114363 -0.4470937 -0.7854243 0.4280373 -0.1250522 -0.9853206 0.1162125 -0.710251 -0.4042993 0.5762687 -0.705617 -0.4493449 0.5478996 -0.4671562 -0.797018 0.3827889 -0.4037608 -0.8691482 0.2855849 -0.7761667 -0.3862784 0.4983516 -0.7506146 -0.4391936 0.4936466 -0.6539639 -0.6474071 0.391402 -0.4205463 -0.8627867 0.2806067 -0.8568863 -0.2787238 0.4336576 -0.8333808 -0.4049065 0.3762015 -0.3479586 -0.9208257 0.1760824 -0.6977044 -0.6378598 0.3261036 -0.6533275 -0.700413 0.2873757 -0.8797704 -0.3309769 0.3412599 -0.3755623 -0.9091023 0.180239 -0.8333535 -0.4858147 0.2636399 -0.69993 -0.6741863 0.2357352 -0.907624 -0.3640585 0.2089979 -0.5269771 -0.8390664 0.1351404 -0.3981469 -0.9101715 0.1143106 -0.8440973 -0.5194693 0.1328584 -0.6348487 -0.7658917 0.1018691 -0.6008047 -0.7927694 0.1027157 -0.9058855 -0.4143004 0.08790099 -0.1130164 -0.9934464 0.01707965 -0.9439409 -0.3273411 -0.04270172 -0.328119 -0.9444534 0.01859015 -0.8356534 -0.5490753 -0.01414173 -0.8118913 -0.5835496 -0.01738911 -0.6356497 -0.771976 0.00166589 -0.4641782 -0.8856373 -0.01361781 -0.9574832 -0.2617607 -0.1212741 -0.7406048 -0.6600023 -0.1261012 -0.4468829 -0.8940137 -0.03217691 -0.9005388 -0.4053627 -0.1571971 -0.2601007 -0.9645565 -0.04448002 -0.7375718 -0.663945 -0.1231464 -0.9260748 -0.3116478 -0.2127472 -0.6980623 -0.69909 -0.1548625 -0.8087385 -0.5339101 -0.2467432 -0.4468301 -0.8839271 -0.1378979 -0.4439244 -0.8841416 -0.1456871 -0.7852048 -0.5456778 -0.2927272 -0.7942183 -0.5280239 -0.3006799 -0.5906943 -0.7700307 -0.2411077 -0.8255351 -0.4079105 -0.3900014 -0.7925874 -0.4366424 -0.4256156 -0.7968289 -0.3911904 -0.4604712 -0.1896533 -0.9778052 -0.0890426 -0.5414838 -0.7909117 -0.285051 -0.4554809 -0.8476619 -0.2720416 -0.7578157 -0.4291834 -0.491444 -0.7805625 -0.2657097 -0.5657921 -0.5818411 -0.6940192 -0.4240264 -0.461491 -0.8307912 -0.3111463 -0.6827616 -0.4220075 -0.5964447 -0.3007152 -0.9201441 -0.2508094 -0.5851703 -0.6359988 -0.503072 -0.6906028 -0.2794736 -0.667055 -0.5039525 -0.7160559 -0.4830071 -0.3601527 -0.8595683 -0.3625361 -0.590418 -0.4384559 -0.6776158 -0.5843105 -0.4309958 -0.6876219 -0.302781 -0.88657 -0.3497392 -0.5081763 -0.5358573 -0.6742507 -0.3529638 -0.7946112 -0.4939735 -0.4764998 -0.4048283 -0.7804242 -0.3132637 -0.7662097 -0.5610604 -0.2917401 -0.8263422 -0.4817119 -0.4381221 -0.457037 -0.7740584 -0.1318667 -0.9613832 -0.2415649 -0.07632887 -0.9898823 -0.1196119 -0.4070439 -0.3749778 -0.8328907 -0.3024468 -0.3703613 -0.8782703 -0.3126669 -0.4786847 -0.8204271 -0.2296531 -0.752452 -0.6173132 -0.2159428 -0.7725914 -0.5970523 -0.15189 -0.8959881 -0.4172946 -0.2041291 -0.3904262 -0.8977187 -0.1475334 -0.5531218 -0.8199331 -0.1354555 -0.7641212 -0.6306908 -0.08634477 -0.8735708 -0.4789767 -0.06515067 -0.9545984 -0.2906846 -0.07620602 -0.3651503 -0.9278243 -0.09096097 -0.4926218 -0.8654766 -0.0188958 -0.9923554 -0.1219589 -0.004787623 -0.7085392 -0.7056553 -0.002156257 -0.8567175 -0.5157815 0.0262643 -0.3570606 -0.933712 -0.008929789 -0.8710092 -0.4911856 0.04919832 -0.5188214 -0.8534659 0.1604056 -0.3227131 -0.9328056 0.03963422 -0.8880144 -0.4581043 0.1012638 -0.535647 -0.8383484 0.1189334 -0.7428969 -0.6587557 0.04006451 -0.9694316 -0.2420688 0.213005 -0.3079936 -0.9272372 0.2374169 -0.5505183 -0.8003517 0.140199 -0.7496723 -0.6467887 0.1359254 -0.8785557 -0.4578911 0.3391427 -0.3626535 -0.8680235 0.2614356 -0.5489114 -0.7939444 0.1579149 -0.8801466 -0.4476661 0.2291469 -0.7921265 -0.5657095 0.09676516 -0.9719301 -0.2144493 0.4046049 -0.3505502 -0.8446359 0.4095937 -0.3799164 -0.8293953 0.2993658 -0.7474412 -0.5930529 0.4841631 -0.3354294 -0.8081296 0.3092219 -0.7934485 -0.5242343 0.2485675 -0.8841772 -0.3955311 0.1940172 -0.9306796 -0.3101496 0.46318 -0.5797508 -0.6703383 0.5837112 -0.3955668 -0.7090897 0.5143223 -0.5566508 -0.6523898 0.1163614 -0.982535 -0.1452071 0.4889113 -0.6821566 -0.543717 0.3487248 -0.8498545 -0.3951437 0.6524713 -0.4175599 -0.6323963 0.6933161 -0.3160507 -0.6476303 0.2691936 -0.9214715 -0.2800448 0.5680537 -0.6119443 -0.5503082 0.5212537 -0.7263941 -0.4479355 0.7446029 -0.2978976 -0.5973471 0.3307862 -0.9013072 -0.2796891 0.7504455 -0.4586644 -0.4758766 0.7301484 -0.488948 -0.4772979 0.3134111 -0.9161807 -0.249773 0.6620051 -0.6038936 -0.4439166 0.481945 -0.8265181 -0.2908555 0.458865 -0.853926 -0.2454655 0.7768216 -0.474308 -0.4142221 0.1361438 -0.9868442 -0.08719748 0.8880971 -0.2339706 -0.3956531 0.6810547 -0.662138 -0.3126305 0.5428324 -0.8039185 -0.2429983 0.85567 -0.4019177 -0.3260232 0.4974687 -0.8491194 -0.1775419 0.875078 -0.4045757 -0.2656256 0.4318792 -0.890881 -0.1407533 0.8307555 -0.5111599 -0.2203657 0.9125147 -0.3842517 -0.1402415 0.8372527 -0.5212037 -0.1653929 0.5755403 -0.8140353 -0.07810288 0.4072543 -0.9103525 -0.07350134 0.3249794 -0.9442706 -0.05236059 0.9606819 -0.276879 -0.02070122 0.9201514 -0.3897962 -0.03715175 0.8092426 -0.5873419 -0.01249468 0.6669735 -0.7447987 -0.02052688 0.006875216 -0.9999549 0.006566524 0.006744503 -0.9999434 0.008227825 0.004409313 -0.9999664 0.006919264 0.01219564 -0.9998974 0.007514178 0.006000339 -0.9999618 0.006372034 0.01233345 -0.9999026 0.006543219 0.004458427 -0.999967 0.006790339 0.003461122 -0.9999936 9.8473e-4 0.001253366 -0.9999881 0.004719078 0.004587829 -0.9999895 3.66458e-4 8.33158e-5 -0.9999587 0.009092628 0.0108478 -0.999941 -6.48157e-4 -1.95928e-4 -0.999978 0.00664252 0.008605837 -0.9999629 -3.60651e-4 0.01047068 -0.9999441 -0.001543402 -9.05272e-4 -0.9999915 0.004032433 0.02210909 -0.9996178 -0.01660215 0.008371233 -0.9999585 -0.003605186 -0.001824498 -0.999991 0.003836631 0.02015149 -0.9997739 -0.006802916 0.004577577 -0.9999845 -0.003165125 -0.01321971 -0.9998012 0.01493173 -0.01313185 -0.9997956 0.01537179 -0.009423494 -0.9998578 0.01398575 0.004096508 -0.999985 -0.00366503 0.001680314 -0.9999967 -0.001972854 -0.006070137 -0.999975 0.003641963 0.001009821 -0.9999976 -0.001942873 -0.005119681 -0.9999804 0.003624975 6.55279e-4 -0.9999713 -0.007558882 0.001893937 -0.9999665 -0.007973253 -0.005413115 -0.9999845 0.001368522 0.001131653 -0.9999377 -0.01111227 -0.009502708 -0.9999547 7.39316e-4 -0.008601367 -0.999963 2.12637e-4 -5.0053e-4 -0.9999479 -0.01020383 -0.008996725 -0.9999594 -6.84255e-4 -2.40606e-4 -0.999953 -0.009695947 -0.006231665 -0.9999797 -0.001320123 -0.001454889 -0.9999878 -0.004736185 -0.00562036 -0.9999676 -0.005783617 -0.01513659 -0.999863 -0.006700873 -0.002774596 -0.9999842 -0.004904508 -0.005714714 -0.9999542 -0.007693409 -0.01165497 -0.999898 -0.008262038 -0.0107842 -0.9999288 -0.005110502 -0.005486071 -0.9999675 -0.005910217 0.948661 0.3162906 -0.001669347 0.8565853 0.5151339 -0.02998167 0.8997417 0.4149731 -0.1351385 0.8143187 0.5726222 -0.0948109 0.7411974 0.6642535 -0.09692138 0.5071706 0.8599886 -0.05654972 0.9162092 0.3102535 -0.2535814 0.3727987 0.9250864 -0.07236266 0.6190391 0.7650042 -0.1776494 0.7865548 0.5533936 -0.2740206 0.6348346 0.7469719 -0.1975297 0.119771 0.9922083 -0.03431761 0.8044462 0.4834702 -0.3451418 0.3891344 0.9041618 -0.1762552 0.7020798 0.6055355 -0.3747141 0.4067077 0.8896405 -0.2076745 0.7201821 0.5228223 -0.4560644 0.3322661 0.9207755 -0.2043816 0.7083798 0.53289 -0.4628462 0.4868997 0.789358 -0.3739556 0.7358242 0.3611473 -0.5728312 0.1296701 0.9868959 -0.09603267 0.581228 0.5966338 -0.5533554 0.4575857 0.793696 -0.4008266 0.3628739 0.8669788 -0.3415707 0.5878249 0.549261 -0.5939481 0.556532 0.3765304 -0.7406058 0.5199416 0.5747383 -0.631931 0.3543135 0.8014706 -0.4817746 0.5321575 0.316336 -0.7853279 0.2922261 0.8788149 -0.3772112 0.4408531 0.4776268 -0.7599482 0.3628332 0.6921103 -0.6239675 0.1268198 0.9737394 -0.1890724 0.4150951 0.3439449 -0.8422577 0.2408131 0.8001931 -0.5492723 0.3068399 0.3558471 -0.8827356 0.1914224 0.8703846 -0.4536389 0.3126098 0.481172 -0.8189925 0.2732526 0.6257906 -0.7305608 0.2424729 0.3053622 -0.920848 0.1062039 0.9365 -0.3341982 0.1687572 0.4822779 -0.8596099 0.1599746 0.6959941 -0.7000003 0.1076789 0.8234874 -0.5570223 0.1532922 0.4583868 -0.875433 0.07015866 0.5046164 -0.8604884 0.06897008 0.8316363 -0.5510211 0.05768173 0.4741064 -0.8785762 0.0114386 0.9150339 -0.4032148 -0.04725927 0.4369072 -0.8982643 1.56604e-6 0.9030804 -0.4294716 -0.03715443 0.4799429 -0.8765127 -0.04513692 0.6272032 -0.7775468 -0.1204255 0.3451307 -0.9307967 -0.05360043 0.8954457 -0.4419322 -0.09616053 0.7901039 -0.6053835 -0.2440133 0.3831045 -0.890892 -0.1968194 0.5159183 -0.8337209 -0.164089 0.7176674 -0.676778 -0.1812112 0.766758 -0.6158286 -0.327453 0.3321953 -0.8845455 -0.3095302 0.3768581 -0.8730229 -0.1013073 0.9482895 -0.3008058 -0.05397272 0.9790764 -0.1962051 -0.2514795 0.688273 -0.6804693 -0.4080466 0.3414196 -0.8467175 -0.4095078 0.3873398 -0.8259972 -0.3062399 0.7192319 -0.6236368 -0.3032347 0.7352176 -0.606221 -0.1988983 0.9002218 -0.3873503 -0.5162743 0.3620926 -0.7761121 -0.5528044 0.2555264 -0.7931669 -0.1696937 0.9469821 -0.272817 -0.4395695 0.6207436 -0.6491966 -0.5946059 0.4149051 -0.6886927 -0.4293969 0.7206663 -0.5442963 -0.3651621 0.8234968 -0.4341771 -0.666158 0.3183628 -0.674447 -0.6689147 0.3786701 -0.6396579 -0.3666698 0.8510484 -0.375859 -0.4878115 0.7555745 -0.4372035 -0.7469993 0.3194185 -0.5830642 -0.7479127 0.3171758 -0.5831176 -0.1695211 0.975092 -0.1430325 -0.5524394 0.7231353 -0.4145915 -0.5365408 0.7618293 -0.3629602 -0.8094399 0.3488248 -0.4723647 -0.804941 0.3585197 -0.4727936 -0.3388848 0.9138436 -0.2237123 -0.6111704 0.701637 -0.3663007 -0.5995404 0.7419607 -0.3000764 -0.8459664 0.3700481 -0.383934 -0.8105676 0.4774056 -0.339211 -0.4469856 0.8727875 -0.1960763 -0.8150601 0.4863778 -0.3148233 -0.3102444 0.9392163 -0.147042 -0.1343817 0.9894852 -0.05348449 -0.9325244 0.2374656 -0.2720447 -0.6531727 0.7332867 -0.1888278 -0.5216947 0.8372926 -0.1636329 -0.8793131 0.4520524 -0.1498574 -0.8873429 0.4345735 -0.1541702 -0.3827332 0.9187496 -0.09702843 -0.7294069 0.6665803 -0.153741 -0.4059353 0.9132817 -0.033665 -0.8870697 0.4540061 -0.08358132 -0.439347 0.8964395 -0.05805641 -0.9907413 0.133842 -0.02276188 -0.7963411 0.6041786 -0.02844607 -0.6088036 0.7932859 -0.007468402 -0.9296038 0.366805 0.03593081 -0.5870224 0.8093748 0.01780825 -0.9228579 0.374718 0.08899313 -0.8227944 0.5566408 0.11472 -0.4233797 0.9043518 0.05382847 -0.8053436 0.5782959 0.1303671 -0.6112287 0.7815387 0.1248877 -0.8879146 0.4008215 0.225721 -0.1856418 0.982033 0.03388857 -0.7998568 0.5310288 0.2797097 -0.5993571 0.7759233 0.1967598 -0.8186779 0.4828754 0.3108024 -0.5020349 0.8445979 0.186053 -0.3431041 0.9314956 0.1208124 -0.8275297 0.3447127 0.4431341 -0.7532021 0.5400399 0.3755577 -0.6648557 0.6582082 0.3531697 -0.5374826 0.801067 0.2634471 -0.6286464 0.6703748 0.3942098 -0.1057656 0.9925237 0.06091225 -0.7673113 0.3395637 0.5439943 -0.7435156 0.3959993 0.5388591 -0.3051066 0.9313189 0.1988845 -0.4203341 0.8493008 0.3193864 -0.6791737 0.4576863 0.5737999 -0.4211118 0.845921 0.3272348 -0.6774185 0.432715 0.594863 -0.6152256 0.4819673 0.6238631 -0.6108887 0.4182676 0.6722106 -0.3301282 0.8840057 0.3309823 -0.3530617 0.857875 0.3733603 -0.570111 0.4438915 0.6913276 -0.5691404 0.354336 0.7419739 -0.4108343 0.7226349 0.5558903 -0.3498119 0.8089324 0.4725041 -0.2823131 0.8606596 0.4237504 -0.4787917 0.4070782 0.777847 -0.4757741 0.4141271 0.7759755 -0.05150383 0.9966239 0.06394082 -0.2445707 0.8421808 0.480538 -0.3758217 0.5058775 0.7764316 -0.4028646 0.4525129 0.7955703 -0.2264562 0.8556362 0.4654079 -0.3084406 0.4770967 0.8229479 -0.2901881 0.511396 0.8088666 -0.06823831 0.9813311 0.1798139 -0.2101161 0.7950611 0.568972 -0.2173722 0.5072572 0.8339301 -0.1888754 0.5644949 0.803537 -0.1367493 0.8514063 0.5063666 -0.1036619 0.8975592 0.4285346 -0.09327971 0.4244321 0.9006422 -0.06156992 0.9111188 0.4075192 -0.1121312 0.548401 0.8286635 -0.04197984 0.8133283 0.5802886 -0.0264815 0.390034 0.9204196 0.02883756 0.6044512 0.7961202 -0.008642256 0.8017257 0.5976297 0.08261358 0.565442 0.8206402 -5.5965e-4 0.9959716 0.08966803 0.0373184 0.9267928 0.3737146 0.2153155 0.386784 0.8966813 0.1358622 0.6797128 0.7207857 0.1474689 0.6635357 0.7334666 0.07783973 0.8921161 0.4450504 0.2754401 0.3037122 0.912081 0.2402957 0.7353512 0.6336534 0.3387098 0.4819806 0.8080658 0.3346809 0.5285878 0.7801178 0.0925883 0.9487661 0.3021097 0.2767997 0.6922601 0.6664517 0.05673068 0.9899698 0.1293893 0.2657717 0.8230051 0.5020239 0.4820976 0.4019703 0.7784613 0.09637552 0.9774576 0.187852 0.4842541 0.4582408 0.7453278 0.3671989 0.7559319 0.5419704 0.3644219 0.7702121 0.5234215 0.6047002 0.3153316 0.7313711 0.2642186 0.8971422 0.354012 0.5711084 0.553505 0.606191 0.4892161 0.6889529 0.5348004 0.2513106 0.9267563 0.2792235 0.3735933 0.8552889 0.359039 0.7055429 0.3610857 0.6097758 0.6551162 0.4751256 0.5874339 0.3835262 0.8553989 0.3481388 0.5575394 0.699123 0.4476349 0.7761512 0.3804955 0.5028047 0.7751068 0.3826722 0.5027638 0.2521928 0.9509159 0.1793256 0.6167704 0.6678025 0.4166945 0.5422896 0.7780663 0.3170724 0.8137502 0.3876487 0.4330581 0.3494969 0.9131408 0.2098233 0.7888934 0.4717148 0.3938685 0.6375303 0.7037658 0.3134786 0.6086761 0.7500886 0.2586131 0.8743892 0.3576982 0.3278652 0.8605468 0.4153434 0.2948716 0.2976776 0.944029 0.1421173 0.1811029 0.9812461 0.06601506 0.6553061 0.720766 0.2259877 0.6751238 0.7020614 0.2265341 0.9063382 0.336077 0.2561316 0.8890882 0.4092343 0.2050597 0.3310166 0.9397457 0.08547633 0.7033941 0.6859236 0.1864013 0.921999 0.3524541 0.1602938 0.597872 0.7941707 0.1088206 0.9039781 0.410674 0.1190403 0.3568616 0.9307905 0.07923913 0.6944139 0.7167375 0.06384962 0.9650709 0.252867 0.0685324 0.6848503 0.7266606 0.05426293 0.4257703 0.9048112 0.006038248 0.2427304 0.9699488 0.01677286 -0.006091952 0.99996 0.006552875 -0.010019 0.9998331 0.01528197 -0.007381856 0.9999567 0.005666196 -0.004343271 0.9999873 0.002558588 -0.01017284 0.9998319 0.0152648 -0.001545608 0.9999932 0.003376483 -0.004104435 0.9999907 0.00135684 -5.61414e-4 0.999996 0.002808928 -0.006465852 0.999979 5.93485e-4 -0.02225899 0.9997522 -3.91383e-4 5.85625e-4 0.9999803 0.006243407 1.24255e-5 0.9999929 0.003771722 -0.01929253 0.9998027 0.004734992 -0.004903793 0.9999874 -0.001164495 0.001353621 0.9999843 0.005449891 -0.007975816 0.9999603 -0.004015088 0.002956509 0.9999701 0.007156789 0.002446293 0.9999879 0.004294812 -0.006597876 0.9999696 -0.004179537 -0.007888495 0.9999438 -0.007088661 0.006350159 0.9999762 0.002725601 -0.00575751 0.9999621 -0.006528675 0.007028639 0.9999535 0.006601989 0.007368862 0.9999511 0.006609261 0.00628519 0.999974 0.003551185 -0.005789577 0.9999485 -0.008344948 -0.00286436 0.9999718 -0.006945669 0.005761146 0.9999769 0.003635942 -0.002728521 0.9999533 -0.009276628 0.00227648 0.9999973 5.75874e-4 -4.69449e-4 0.9999758 -0.006944358 0.002815902 0.9999961 4.5124e-5 0.004096925 0.999893 -0.01404821 0.01448309 0.9998907 -0.002979397 0.002886831 0.9998734 -0.01564913 0.001885771 0.9998909 -0.01464682 0.01449114 0.9998902 -0.00310254 0.01285862 0.9999154 -0.001984417 0.006452858 0.9999749 -0.002917826 0.004246413 0.9999578 -0.008150875 0.00676465 0.9999312 -0.009597063 0.006845235 0.9999574 -0.006199657 0.006585538 0.9999485 -0.00772649 0.009016275 0.9999352 -0.006957709 0.9990258 0.02438348 -0.03678071 0.9827819 0.06680941 -0.1722683 0.967716 -0.03314638 -0.249854 0.9606369 0.01335728 -0.2774857 0.9284862 0.05938845 -0.3665876 0.8880238 -0.05537545 -0.456451 0.8682194 0.02485334 -0.4955576 0.8070727 0.04714375 -0.5885671 0.753952 -0.04483026 -0.6553983 0.7560418 -0.05246037 -0.6524178 0.680404 0.05055254 -0.7310916 0.6038177 0.006093978 -0.7970992 0.582185 -0.04007238 -0.8120684 0.5211443 0.03138196 -0.8528915 0.4323654 -0.01237595 -0.9016135 0.4232624 0.006748139 -0.905982 0.2611684 -0.02925765 -0.9648498 0.2994521 0.02925622 -0.9536628 0.1888794 0.03705298 -0.981301 0.0897777 -0.04075324 -0.9951278 0.05724269 0.02200454 -0.9981179 -0.0632078 0.04899466 -0.9967971 -0.1333682 -0.05570352 -0.9895 -0.09183359 0.02327972 -0.9955023 -0.205897 0.03519958 -0.9779404 -0.3506195 -0.02400714 -0.9362103 -0.3353132 -0.07121986 -0.9394109 -0.4420012 0.07005709 -0.8942745 -0.5731424 -0.004538357 -0.8194432 -0.5840888 -0.03277897 -0.8110277 -0.6469755 0.04253768 -0.7613234 -0.7556632 -0.02418345 -0.6545138 -0.7388635 -0.08634012 -0.668301 -0.8087776 0.05499845 -0.5855374 -0.8680061 0.04870009 -0.4941596 -0.8968686 -0.06355434 -0.4377073 -0.9298046 0.04598116 -0.3651701 -0.9677274 -0.03341358 -0.2497743 -0.974249 0.02099901 -0.2244952 -0.995759 0.04155308 -0.08208191 -0.9982608 -0.05551475 -0.01983863 -0.9996414 0.01296633 0.02343487 -0.9903179 0.04808819 0.1302236 -0.971454 -0.07523769 0.2249813 -0.9652112 0.009474694 0.2613003 -0.9359923 0.07591563 0.3437374 -0.8948255 0.02298253 0.4458243 -0.8810067 -0.03786218 0.4715864 -0.8407078 0.03042542 0.5406335 -0.7807422 -0.01234382 0.6247315 -0.7821066 -0.01676714 0.6229192 -0.7171848 0.04293233 0.6955594 -0.6413187 -0.04529768 0.7659363 -0.6382749 -0.03524047 0.7690016 -0.5583143 0.05435454 0.8278471 -0.4547759 -0.03332507 0.8899823 -0.4708086 0.003306865 0.8822293 -0.3472124 0.04007947 0.9369297 -0.2931243 -0.01442974 0.9559655 -0.248263 0.0410934 0.9678207 -0.09849238 -0.02024626 0.9949319 -0.1050083 -0.03764194 0.9937587 0.005426526 0.0585553 0.9982694 0.1275226 -0.02697056 0.991469 0.1019513 0.01492923 0.9946774 0.1972126 0.04057043 0.979521 0.3072532 -0.001482486 0.9516267 0.2957016 0.01605808 0.9551454 0.3870981 0.05825716 0.9201962 0.5030536 -0.07234132 0.8612225 0.4691398 0.004779577 0.883111 0.5647526 0.04791277 0.8238683 0.6467768 0.08143007 0.7583198 0.7371914 -0.09760922 0.6685965 0.744176 -0.07365727 0.6639102 0.8103808 0.05528348 0.5832895 0.8634641 0.04965937 0.5019599 0.8943348 -0.03940725 0.4456596 0.9097808 0.008028686 0.4150114 0.9480392 0.009512305 0.3180115 0.9590688 -0.02873402 0.2817115 0.9723914 0.06089228 0.2252714 0.996556 0.02770835 0.07815718 0.9965149 -0.08106368 0.01967161 0.9972683 0.004611372 -0.07372093 0.9973199 0.00342369 -0.07308512 0.9838106 -0.03861171 -0.1750029 0.9683855 0.04587769 -0.2452037 0.9509139 -0.04771161 -0.3057558 0.9139637 -0.02992713 -0.4046909 0.8639124 -0.0132023 -0.5034692 0.8838931 0.07561391 -0.4615364 0.8113504 -0.05322289 -0.5821323 0.7500174 0.03515172 -0.6604835 0.750009 0.03513938 -0.6604937 0.6824111 -0.04009419 -0.7298682 0.6003918 0.01509696 -0.7995635 0.6051127 0.00656557 -0.7961128 0.52438 -0.0541082 -0.8497635 0.4648566 0.0260365 -0.8850032 0.4027391 -0.04662442 -0.9141266 0.2835909 0.02236407 -0.9586846 0.2879627 0.01546239 -0.9575169 0.2098916 -0.05392837 -0.9762364 0.09547448 0.007108747 -0.9954066 0.1012407 -0.003102004 -0.9948571 -0.003282845 -0.04182505 -0.9991196 -0.064785 0.03475922 -0.9972938 -0.1436116 -0.05075186 -0.9883319 -0.2464036 0.007695615 -0.9691367 -0.2535378 0.02092331 -0.9670992 -0.3438968 -0.05079311 -0.9376328 -0.4399308 0.03797465 -0.8972284 -0.4668964 -0.01616859 -0.8841642 -0.562855 -0.02721214 -0.8261076 -0.6021693 0.03110355 -0.7977625 -0.6412259 -0.02623295 -0.7669036 -0.7220553 -0.006749153 -0.6918026 -0.731846 0.02918261 -0.6808449 -0.8307557 -0.04958266 -0.5544245 -0.8605289 0.0363667 -0.5081018 -0.8891366 -0.02617186 -0.4568931 -0.9323348 -0.003994107 -0.3615742 -0.936188 0.01194232 -0.3512968 -0.9618086 -0.05227023 -0.2686859 -0.990532 -0.01158887 -0.1367923 -0.98509 0.04316693 -0.1665368 -0.9972704 -0.04578477 -0.05792778 -0.9981001 0.04643237 0.04050159 -0.9977445 -0.00635755 0.06682544 -0.983735 -0.05384975 0.1713642 -0.9596438 0.03922444 0.2784698 -0.9652184 0.001853764 0.2614384 -0.9324288 -0.03522175 0.3596335 -0.9021331 0.03179097 0.4302853 -0.8871623 -0.02542388 0.4607567 -0.8423644 -0.05325871 0.5362704 -0.7735249 -0.003220796 0.6337578 -0.7878222 0.04522848 0.6142399 -0.6818564 -0.04517835 0.7300896 -0.6022017 0.005044341 0.7983281 -0.6203211 0.05633509 0.7823222 -0.4802811 -0.09065544 0.8724172 -0.3992432 -0.002337574 0.9168421 -0.3668265 0.07782393 0.9270285 -0.2938079 -0.0298509 0.9553984 -0.1957089 -0.03534364 0.9800249 -0.1441859 0.02908027 0.9891233 -0.1077131 -0.02005183 0.9939798 0.009919166 -0.03199118 0.999439 0.0546211 0.03458553 0.9979081 0.1410785 -0.05037921 0.9887158 0.2491816 0.02111923 0.9682264 0.2499184 0.01951783 0.9680702 0.3811953 -0.0589134 0.9226155 0.4666569 0.05810707 0.8825277 0.4733685 0.04208374 0.8798587 0.5664641 -0.05614143 0.8221719 0.6464862 -0.01628845 0.7627518 0.6751943 0.04826462 0.7360593 0.7163948 -0.02562373 0.6972244 0.7793189 -0.02561008 0.626104 0.8098592 0.03706413 0.5854523 0.8372449 -0.02855712 0.5460819 0.8952867 -0.02597075 0.4447329 0.919111 0.05038964 0.3907634 0.9277172 0.01323962 0.373049 0.9615201 -0.07465475 0.264397 0.9841396 -0.02662241 0.1753869 0.988909 0.06558209 0.1332595 0.9980018 -0.05636948 0.02854752 0.9555462 -0.2923421 0.03830981 0.8964772 -0.4364474 0.07643675 0.7561698 -0.6526938 0.04688537 0.6244308 -0.7772864 0.07689094 0.4106116 -0.9103134 0.05222886 0.3810574 -0.9230107 0.0533533 0.9062656 -0.3990803 0.1393471 0.8087453 -0.5649178 0.1637044 0.8671043 -0.422693 0.2635543 0.7915817 -0.5769484 0.2013187 0.5463342 -0.8197503 0.1718383 0.8580104 -0.4046855 0.3163038 0.5132853 -0.8378228 0.1859872 0.7430805 -0.5787224 0.3360234 0.5736251 -0.7783526 0.2551895 0.8101611 -0.3931742 0.4348024 0.8033677 -0.3939427 0.4465529 0.1933795 -0.9743207 0.1153408 0.8164968 -0.2452116 0.5226895 0.4306814 -0.8687696 0.244444 0.7043412 -0.4667142 0.5348659 0.6130839 -0.6612879 0.4322344 0.5223184 -0.7683268 0.3699423 0.7086288 -0.4153407 0.5703835 0.4314658 -0.8314397 0.3500647 0.2251086 -0.9518043 0.2083136 0.6280495 -0.4794769 0.6129077 0.6285414 -0.4762857 0.6148884 0.512239 -0.7053583 0.4899804 0.2211562 -0.9532122 0.2060981 0.3144138 -0.8742661 0.3698686 0.5981062 -0.3574482 0.7172864 0.587481 -0.4466169 0.6748331 0.4283109 -0.7025023 0.5683665 0.5320544 -0.3320945 0.7788654 0.313542 -0.8719702 0.3759781 0.5132373 -0.3753831 0.7717998 0.4290693 -0.6323037 0.6450517 0.4670102 -0.2914384 0.8348444 0.1313185 -0.966784 0.219281 0.3347151 -0.7224256 0.6050348 0.1963152 -0.9018573 0.3848555 0.3578801 -0.5465301 0.7571173 0.3429864 -0.3749808 0.861249 0.3362269 -0.5322375 0.776965 0.2414018 -0.7078422 0.6638409 0.1795604 -0.8408463 0.5106229 0.2436295 -0.378166 0.8931042 0.2128719 -0.488761 0.8460487 0.1120038 -0.8969861 0.4276344 0.1598427 -0.5644927 0.8098137 0.1173408 -0.7656413 0.6324751 0.1248614 -0.4214236 0.898227 0.03139293 -0.9850463 0.1694054 0.02429413 -0.8202762 0.5714514 -0.001360833 -0.4348141 0.9005192 0.02083486 -0.5067632 0.8618336 0.008405506 -0.8727026 0.48818 -0.07333278 -0.4402406 0.8948802 -0.1065273 -0.5547523 0.8251677 -0.0205065 -0.8925701 0.4504424 -0.03538978 -0.9194079 0.3917104 -0.1057569 -0.5539357 0.8258152 -0.1150898 -0.7743836 0.622161 -0.05195045 -0.9091028 0.41332 -0.1922638 -0.4094983 0.8918217 -0.2274996 -0.4799084 0.8473087 -0.1667482 -0.7506817 0.6392746 -0.2841495 -0.3753572 0.8822506 -0.07694321 -0.9568615 0.2801712 -0.1678299 -0.8593409 0.4830801 -0.1450163 -0.8706243 0.4700892 -0.3335989 -0.4079619 0.84987 -0.3360334 -0.5576248 0.7590364 -0.1874363 -0.8822966 0.4317641 -0.3412774 -0.5666424 0.7499642 -0.2799464 -0.7783326 0.5619861 -0.4455438 -0.4319145 0.7841815 -0.4515643 -0.4730797 0.7564955 -0.3229566 -0.7811999 0.5342526 -0.1215946 -0.9715846 0.2030719 -0.3072477 -0.8304364 0.4647305 -0.2477553 -0.8994137 0.3601005 -0.5268841 -0.4433771 0.7251275 -0.5095052 -0.5737934 0.6412221 -0.5182754 -0.5814718 0.6271213 -0.6248641 -0.431344 0.6507589 -0.3531033 -0.8604173 0.3674237 -0.3520669 -0.862845 0.3626949 -0.6367142 -0.5202431 0.5691593 -0.5726336 -0.6533821 0.4951592 -0.7410995 -0.306973 0.5971091 -0.2126387 -0.9599459 0.1824519 -0.5583565 -0.7087619 0.4311552 -0.3852109 -0.8820067 0.271435 -0.7698853 -0.3748932 0.5164608 -0.3391047 -0.908752 0.2432648 -0.714128 -0.53533 0.4510467 -0.7051893 -0.5752046 0.4145452 -0.5513564 -0.7756614 0.3071738 -0.8164116 -0.4150486 0.4015058 -0.4987186 -0.8321613 0.2424615 -0.353018 -0.9230385 0.1528997 -0.2699977 -0.9549364 0.1232799 -0.8223653 -0.4537189 0.3432994 -0.7670911 -0.5733954 0.2877307 -0.772831 -0.5509286 0.3149766 -0.6016224 -0.7784889 0.1789013 -0.9045211 -0.3516209 0.2412562 -0.4196581 -0.8962987 0.1433039 -0.8751623 -0.4428735 0.194818 -0.6515373 -0.7431262 0.1525211 -0.9112631 -0.3798212 0.1591716 -0.6049664 -0.7885953 0.1101513 -0.5060778 -0.8591381 0.07594168 -0.8766181 -0.4704403 0.1011276 -0.264135 -0.9631589 0.05057466 -0.8956359 -0.4403564 0.0626319 -0.8673194 -0.4964705 0.0356968 -0.1063037 -0.9942548 0.01252561 -0.5737721 -0.8190139 0.001364946 -0.5250329 -0.8509691 0.01386481 -0.9289667 -0.3667706 -0.05000293 -0.9277656 -0.3446447 -0.1430777 -0.86784 -0.4855464 -0.105349 -0.7649044 -0.6359905 -0.1021634 -0.5664628 -0.8226121 -0.04928779 -0.3453554 -0.9364597 -0.06142419 -0.9080452 -0.3449942 -0.2375564 -0.8231952 -0.5147776 -0.2394867 -0.7338795 -0.6517608 -0.1913862 -0.4839825 -0.8631556 -0.1439562 -0.8304553 -0.4396924 -0.3420743 -0.7964985 -0.5233228 -0.3028587 -0.5032685 -0.8384974 -0.2089095 -0.4545412 -0.8739322 -0.1721481 -0.7904704 -0.4579851 -0.4067018 -0.8034542 -0.4151474 -0.4267485 -0.4229578 -0.875348 -0.234249 -0.501724 -0.8140292 -0.2926254 -0.8067542 -0.2203034 -0.5482829 -0.7762795 -0.4029877 -0.4847587 -0.3159865 -0.9268164 -0.2028889 -0.6057058 -0.6694136 -0.4301232 -0.7192798 -0.3771991 -0.5834016 -0.6069001 -0.6255829 -0.4902229 -0.2637482 -0.9396011 -0.2181438 -0.7150527 -0.1960417 -0.6710196 -0.4837998 -0.7459246 -0.4577493 -0.4607866 -0.7723153 -0.4372696 -0.6106535 -0.4489715 -0.6523243 -0.1084104 -0.9883832 -0.1065171 -0.529442 -0.6406354 -0.5561271 -0.5983741 -0.3324592 -0.7289851 -0.5352457 -0.4265676 -0.7290762 -0.4450423 -0.6965743 -0.5627802 -0.2719773 -0.9028623 -0.3329686 -0.2903215 -0.8658891 -0.4073691 -0.517189 -0.3697599 -0.7718766 -0.267632 -0.8762084 -0.4007893 -0.4785421 -0.4092094 -0.7768816 -0.3615829 -0.6779587 -0.6400234 -0.4559935 -0.2637356 -0.8500081 -0.2689371 -0.8667318 -0.4200583 -0.3474767 -0.4673359 -0.8129312 -0.3068681 -0.6607371 -0.6850245 -0.2257753 -0.794541 -0.5636756 -0.1715431 -0.9072124 -0.3841077 -0.1219817 -0.9494827 -0.289142 -0.3262802 -0.3906952 -0.8607547 -0.2439579 -0.5176048 -0.8201035 -0.2039211 -0.7551226 -0.6230619 -0.2164807 -0.471574 -0.8548416 -0.1642349 -0.5299826 -0.8319528 -0.1124098 -0.8489824 -0.5163266 -0.07717329 -0.9037086 -0.4211356 -0.1192891 -0.4480245 -0.8860272 -0.05421125 -0.9600433 -0.2745509 -0.1037726 -0.4693896 -0.8768721 -0.009521007 -0.996254 -0.08594948 -0.02683252 -0.7819084 -0.6228157 -0.0193299 -0.3860738 -0.9222655 0.02748924 -0.5770421 -0.8162516 -0.01860028 -0.7826275 -0.6222125 0.02046543 -0.9124068 -0.4087727 0.09171593 -0.5491238 -0.8306932 0.09091877 -0.5507562 -0.8296996 0.04485142 -0.9037653 -0.425672 0.1596145 -0.534104 -0.8302146 0.1810269 -0.6122055 -0.7696971 0.07421576 -0.9382534 -0.3378942 0.07348942 -0.9441162 -0.3213161 0.3096296 -0.3997192 -0.8627595 0.2544518 -0.5714339 -0.7802037 0.366809 -0.3290635 -0.8701543 0.2479279 -0.7578385 -0.6035004 0.1828244 -0.8833707 -0.4315457 0.1474205 -0.9168609 -0.3709897 0.378674 -0.556324 -0.7396686 0.3780786 -0.5562797 -0.7400064 0.5020272 -0.2593344 -0.8250543 0.3721588 -0.6796244 -0.632146 0.2405783 -0.8747821 -0.4205692 0.4615681 -0.6026527 -0.6509721 0.2010254 -0.9362885 -0.2880153 0.4722741 -0.6138458 -0.6325746 0.3278784 -0.8562877 -0.3990829 0.5811679 -0.4326519 -0.6892433 0.6228891 -0.4006701 -0.6719173 0.6273052 -0.4550402 -0.6320021 0.4635877 -0.7719292 -0.4349851 0.3764022 -0.8481224 -0.3728404 0.6997792 -0.3613134 -0.6162482 0.7020292 -0.4328396 -0.5655128 0.2261081 -0.9554952 -0.189484 0.5685665 -0.6915115 -0.4455828 0.760375 -0.3472948 -0.5488316 0.5539295 -0.7359774 -0.3892294 0.7548511 -0.4283773 -0.4966821 0.6425041 -0.6470697 -0.4104745 0.8411408 -0.2589929 -0.4747681 0.3782291 -0.8888195 -0.2587333 0.6610959 -0.6601634 -0.3565624 0.8382158 -0.3467073 -0.4209375 0.8680241 -0.2957087 -0.3988618 0.329665 -0.9280984 -0.1730735 0.1806661 -0.9800943 -0.08231109 0.5623137 -0.7838746 -0.2633324 0.9089782 -0.2966354 -0.2928589 0.8416568 -0.4492197 -0.2996925 0.7532266 -0.6055476 -0.2568307 0.6145061 -0.7526025 -0.2365838 0.3812277 -0.9178285 -0.1107096 0.8804023 -0.4412956 -0.1736377 0.7477169 -0.6416791 -0.1707848 0.6294584 -0.7663881 -0.1281853 0.384849 -0.9183219 -0.09260761 0.8892864 -0.4244881 -0.1702337 0.2309193 -0.9723948 -0.03353482 0.8882656 -0.4533901 -0.07363206 0.8318431 -0.5535127 -0.04075336 0.7220096 -0.6914628 -0.02411359 0.6509302 -0.7585534 -0.02977746 0.4814265 -0.8763759 -0.01392579 0.004619061 -0.9999517 0.008689582 0.001480281 -0.9999982 0.001261711 0.006777465 -0.9999388 0.00875616 0.007412672 -0.9998996 0.01207697 0.001894831 -0.9999977 0.001038074 0.02495014 -0.9996742 0.005396008 0.003495097 -0.999951 0.00927633 0.002552866 -0.9999487 0.009811758 0.02335178 -0.9996975 0.007735967 0.003180027 -0.9999392 0.01055884 0.01195776 -0.9999275 0.001448214 5.7097e-4 -0.9999852 0.005418598 0.01172101 -0.9999303 0.001483261 -3.1668e-4 -0.9999837 0.005700588 0.01169264 -0.9999311 -0.001056909 -7.21664e-4 -0.9999888 0.004682302 0.006720185 -0.9999765 0.001363277 0.002662479 -0.999996 -9.69998e-4 -0.003317534 -0.9999677 0.007323205 -0.003392338 -0.9999687 0.007145047 0.01149141 -0.999895 -0.008831202 -0.006464779 -0.9999333 0.009587883 0.01004743 -0.9999223 -0.007391452 0.01108026 -0.9998983 -0.008975625 -0.006383299 -0.9999494 0.007786691 -0.01035058 -0.9999127 0.008214175 -0.001884698 -0.9999896 0.004166543 0.007445335 -0.9999009 -0.01195067 0.008114039 -0.9998703 -0.01391512 -0.00282675 -0.999995 0.001430094 0.01066076 -0.9999044 -0.008812069 0.001426219 -0.9999884 -0.004608809 -0.003792226 -0.9999917 0.0015046 -0.003678321 -0.9999929 9.28284e-4 8.99468e-4 -0.9999767 -0.006765544 6.04585e-4 -0.9999786 -0.006515562 -0.01382911 -0.9999029 -0.001752257 -0.0192483 -0.9998142 0.001096069 -0.01959258 -0.9998081 -1.65501e-4 -5.64e-4 -0.999988 -0.004888951 -3.18205e-4 -0.9999697 -0.007778882 -0.008871078 -0.9999591 -0.00180298 -0.001274466 -0.9999935 -0.003418862 -0.007944941 -0.9999154 -0.01030868 -0.01801425 -0.9998016 -0.008511066 -0.007730424 -0.9999292 -0.009057819 -0.0140084 -0.9999015 -9.17288e-4 -0.006794691 -0.9999271 -0.009989738 -0.004144489 -0.9999571 -0.008293986 -0.005312919 -0.9999742 -0.00483632 -0.006978929 -0.9999433 -0.008045196 0.9076079 0.4187234 -0.03031355 0.8343747 0.5452487 -0.08076351 0.596031 0.8023135 -0.03225481 0.4641403 0.8849314 -0.03834414 0.864445 0.4839184 -0.1362278 0.7341001 0.6509817 -0.193184 0.4035256 0.9121769 -0.07141834 0.2195991 0.9740454 -0.05488044 0.7396811 0.6413292 -0.2038843 0.7137069 0.6600199 -0.2345128 0.8606626 0.3543717 -0.3656235 0.7287553 0.633585 -0.2597804 0.375674 0.912533 -0.1617183 0.3398391 0.9289873 -0.1466017 0.8013436 0.4322356 -0.4135469 0.6334472 0.6977502 -0.3344985 0.6093075 0.732452 -0.3037406 0.8243204 0.3122096 -0.4722512 0.7498628 0.4323759 -0.5007563 0.214545 0.9700735 -0.1137013 0.6002533 0.713321 -0.3617583 0.4391794 0.8428364 -0.3110439 0.7471826 0.4083814 -0.5243499 0.6701609 0.5115975 -0.537729 0.5112957 0.7448903 -0.4286201 0.4359781 0.8402423 -0.3223602 0.698774 0.3298377 -0.6347614 0.4501714 0.7726431 -0.4476254 0.4537904 0.7696674 -0.4490952 0.6280876 0.3782019 -0.6800509 0.6602951 0.3046035 -0.6864598 0.175548 0.969651 -0.170176 0.5884704 0.3947173 -0.7056209 0.2693142 0.9169982 -0.2942521 0.4948419 0.6176285 -0.6112828 0.5841192 0.2816339 -0.7612406 0.2480912 0.9143946 -0.3198959 0.3762691 0.7454322 -0.5502294 0.4902947 0.3564369 -0.7953389 0.4660097 0.4193531 -0.7790879 0.3742986 0.7337654 -0.567 0.4183709 0.4297436 -0.800179 0.08439224 0.9851934 -0.149238 0.26575 0.8194155 -0.5078732 0.40309 0.3056373 -0.8626148 0.1231211 0.9609893 -0.2476707 0.2851691 0.7449035 -0.6031564 0.2936149 0.4663259 -0.8344642 0.2493183 0.7099856 -0.6586053 0.2748268 0.3872384 -0.8800663 0.1314904 0.8697776 -0.475602 0.221181 0.4309665 -0.874841 0.1239227 0.8729895 -0.4717334 0.1769238 0.3248358 -0.9290747 0.1310762 0.7558079 -0.6415399 0.1312988 0.4180125 -0.8989028 0.09164285 0.6676678 -0.7387973 0.05175483 0.9611988 -0.2709581 0.05507975 0.2488214 -0.9669821 0.04646664 0.7126847 -0.6999439 0.02456027 0.7936834 -0.6078351 0.005347311 0.4185613 -0.9081728 0.007233202 0.9311398 -0.3645908 0.01160442 0.9508274 -0.3095039 -0.01732271 0.4058775 -0.9137634 -0.08543652 0.597992 -0.7969356 -0.1527467 0.3837092 -0.9107336 -0.08755356 0.5993963 -0.7956498 -0.1004049 0.8031736 -0.5872232 -0.1939905 0.3343663 -0.9222618 -0.06629347 0.9061282 -0.4177762 -0.2164224 0.3986124 -0.891218 -0.05849814 0.9618571 -0.2672244 -0.1978801 0.6781072 -0.7078235 -0.3183615 0.2599099 -0.9116429 -0.332128 0.4228253 -0.8431547 -0.2192664 0.7059828 -0.6734319 -0.1979116 0.8326669 -0.5172012 -0.4232409 0.3125965 -0.8503826 -0.3873164 0.4233518 -0.818999 -0.359245 0.6119939 -0.7045612 -0.2118491 0.8472163 -0.4871802 -0.1901575 0.9031857 -0.3848323 -0.3996045 0.6639882 -0.6320095 -0.2214236 0.8950551 -0.3871023 -0.5147937 0.3494414 -0.7828654 -0.4592332 0.5863779 -0.6672824 -0.1716073 0.9586622 -0.2269753 -0.4831292 0.6312676 -0.6067022 -0.2887866 0.9007643 -0.3243858 -0.5938287 0.485855 -0.6413365 -0.6098894 0.4971972 -0.6171142 -0.5475874 0.6673238 -0.504804 -0.7202021 0.2540256 -0.6455849 -0.3256874 0.8937063 -0.3085721 -0.2846959 0.9269594 -0.2443246 -0.7561516 0.355103 -0.5496696 -0.7426053 0.4145865 -0.5259804 -0.658608 0.5848191 -0.4735211 -0.09379452 0.9933955 -0.06609112 -0.5555451 0.7480543 -0.3630212 -0.8282622 0.301235 -0.472482 -0.8046604 0.4207594 -0.4189071 -0.5547184 0.7738999 -0.3055595 -0.4956105 0.8323913 -0.2479819 -0.8693114 0.3536254 -0.3453214 -0.855921 0.3992146 -0.3286746 -0.6778817 0.6916795 -0.2491104 -0.5145739 0.8287624 -0.2199239 -0.389034 0.9111242 -0.1360349 -0.8943265 0.3974753 -0.2054107 -0.8792641 0.4345853 -0.1950139 -0.1463729 0.9884733 -0.03867173 -0.7027543 0.6920874 -0.1647769 -0.6307702 0.7638358 -0.1366888 -0.5323166 0.8435413 -0.07125449 -0.9205263 0.3823528 -0.08023643 -0.8761026 0.4793457 -0.05169159 -0.5484941 0.8342975 -0.05569577 -0.4689899 0.8831399 -0.01061725 -0.9162382 0.3994036 0.03137397 -0.8853779 0.4647057 0.01244324 -0.5990255 0.7992723 0.04829525 -0.5449942 0.8376713 0.03589135 -0.9124103 0.3911824 0.1203493 -0.8908492 0.4355691 0.1291025 -0.6394845 0.7652921 0.0733999 -0.04549908 0.9989458 0.006108999 -0.8809161 0.4279221 0.2021624 -0.1982986 0.9794402 0.03707414 -0.7637066 0.6057099 0.2233104 -0.4949082 0.8589797 0.1312246 -0.5183145 0.842548 0.1465025 -0.7951241 0.5260976 0.3016606 -0.7486298 0.5788586 0.3232279 -0.4805486 0.8486675 0.2209902 -0.4460172 0.873216 0.1963736 -0.8085361 0.4132777 0.4188925 -0.1608089 0.9837161 0.08026993 -0.7624664 0.4059852 0.5038067 -0.7381244 0.4872909 0.4666048 -0.5697394 0.7292988 0.3788409 -0.4709814 0.8312843 0.2951999 -0.7373622 0.3403709 0.5834764 -0.3826619 0.8894894 0.249757 -0.6858754 0.432424 0.5853072 -0.5544128 0.6795916 0.4803975 -0.68353 0.2702146 0.6780641 -0.243849 0.947012 0.2090601 -0.4651055 0.7657883 0.4441229 -0.6350201 0.3455226 0.6909151 -0.123667 0.985131 0.1192616 -0.4603928 0.7402481 0.4899708 -0.6175977 0.2885012 0.7316696 -0.4034693 0.7765228 0.4839678 -0.5564511 0.3869684 0.7352671 -0.4109688 0.7282837 0.548368 -0.5372675 0.3105729 0.7841482 -0.1757272 0.9597932 0.2188997 -0.3662084 0.7507176 0.5498314 -0.4474996 0.4567099 0.7688695 -0.3713586 0.7144368 0.5930203 -0.4316912 0.3935492 0.8116415 -0.126971 0.968751 0.2130725 -0.1224722 0.9714281 0.2032929 -0.4027217 0.4292562 0.8084272 -0.296323 0.6553784 0.694746 -0.2533093 0.799558 0.5445563 -0.3425217 0.3161143 0.8847321 -0.1721742 0.9031335 0.3933269 -0.2628488 0.5714232 0.7774227 -0.261985 0.5721791 0.7771584 -0.1724931 0.763772 0.6220117 -0.120936 0.9233217 0.3644881 -0.2116582 0.3738362 0.9030212 -0.1903812 0.4118695 0.8911333 -0.1298441 0.7023211 0.6999183 -0.03323328 0.9864271 0.1608015 -0.1067286 0.3171467 0.9423519 -0.07206928 0.4484726 0.8908863 -0.07532155 0.7492321 0.6580107 -0.05421578 0.8051328 0.5906115 -0.03150206 0.9437056 0.3292833 -0.006102442 0.4036585 0.9148894 0.04634547 0.552141 0.8324617 0.03185153 0.7318967 0.6806707 0.08595418 0.4760623 0.8752009 0.0593993 0.85316 0.5182565 0.0510677 0.9364854 0.3469687 0.03631591 0.9625847 0.2685364 0.1593885 0.5216014 0.8381689 0.1636241 0.5485295 0.819965 0.226413 0.5859505 0.7780741 0.01281446 0.9988172 0.04690527 0.233864 0.6482945 0.7245841 0.1675041 0.8445228 0.5086489 0.3370916 0.5345054 0.7750312 0.1466958 0.9287316 0.3404967 0.4542314 0.4268665 0.7819584 0.368893 0.5921925 0.716398 0.2660744 0.8424172 0.4685485 0.5141417 0.3954278 0.7611145 0.2816306 0.8629456 0.4195345 0.5198076 0.5234051 0.6751645 0.4996715 0.5807255 0.6427179 0.6269285 0.2840799 0.7254374 0.2523498 0.8985277 0.3591207 0.4959201 0.7166987 0.4903125 0.6997313 0.3445404 0.6258339 0.6850925 0.3781551 0.6226131 0.2826484 0.9122793 0.296406 0.2115222 0.9568666 0.1991601 0.5564236 0.6558532 0.5101464 0.5425432 0.7206984 0.4315561 0.758677 0.3512733 0.5486496 0.7496227 0.4038954 0.524342 0.2930044 0.931321 0.2163097 0.6231648 0.6461238 0.4406696 0.2853155 0.9371726 0.2007551 0.5747942 0.7382339 0.3530188 0.3994455 0.8854439 0.2375554 0.8151466 0.3269258 0.4781795 0.7973992 0.4309493 0.4224183 0.691596 0.6270928 0.3583989 0.4054598 0.89177 0.2008702 0.8718163 0.294366 0.3915163 0.6372038 0.7175795 0.2811604 0.5409632 0.8068622 0.2373439 0.8549517 0.4016695 0.3282063 0.798178 0.5282027 0.2896789 0.1579846 0.9858883 0.05536472 0.7922463 0.5580835 0.2467563 0.943511 0.2585254 0.2072479 0.4240623 0.8972721 0.1227768 0.3358335 0.937463 0.09153813 0.6915391 0.7022327 0.1692423 0.8941255 0.4210425 0.1525222 0.7408995 0.6576299 0.1363484 0.6275333 0.7759972 0.06348544 0.9514189 0.2960476 0.08460479 0.3365639 0.9407393 0.041646 0.8644177 0.502324 0.02128249 0.7001617 0.7134032 0.02880388 0.2138953 0.9767813 0.0121268 -0.002623736 0.9999964 7.75732e-4 -0.004292845 0.9999846 0.003543615 -3.93908e-4 0.9999998 6.27749e-4 -0.005413651 0.9999818 0.00267446 -0.001125454 0.9999927 0.003669321 -0.01283037 0.9999103 0.003844499 -0.001103878 0.9999927 0.003678321 -0.01315641 0.9999096 0.002780616 -0.001114666 0.9999945 0.003128468 -0.01550686 0.9998765 0.00256139 4.11523e-5 0.999999 0.001468837 -0.008684098 0.999962 -7.21632e-4 -0.01208156 0.9999204 -0.003630042 0.002312242 0.9999804 0.005822062 0.002676248 0.9999579 0.008793354 -0.009870767 0.999944 -0.003834843 0.003154277 0.99998 0.005490541 0.009157061 0.9999259 0.008033275 -0.009414255 0.9999391 -0.005763828 -0.01102745 0.9999102 -0.007612884 -0.005312919 0.9999712 -0.005412757 -0.005313277 0.9999712 -0.005427241 0.008915364 0.9999228 0.00865817 6.98947e-4 0.9999889 0.00467205 0.006787061 0.9999712 0.003388047 -0.002333164 0.9999898 -0.003887534 0.006688833 0.9999727 0.00315231 -3.67521e-4 0.9998999 -0.01415103 -0.00467813 0.999875 -0.01511037 0.008446216 0.9999592 0.003214418 -0.004924893 0.9998908 -0.0139358 0.007083356 0.9999741 0.001285672 -6.58954e-4 0.9999515 -0.009831368 0.006229817 0.9999801 0.001028716 -0.003999829 0.9999886 -0.002656996 0.003939867 0.9999923 -4.14178e-5 0.004027366 0.9999918 -4.07724e-4 1.82442e-4 0.9999997 -7.4141e-4 0.002528905 0.9999846 -0.004960238 0.001937806 0.9999981 -5.1055e-4 0.002659559 0.9999839 -0.005018889 0.001754701 0.9999981 -8.85493e-4 0.007724642 0.999941 -0.00763756 0.005294084 0.999956 -0.007763206 0.005308032 0.9999638 -0.00665605 0.009065628 0.9999328 -0.007235825 0.00902462 0.9999338 -0.007146418 0.908447 -0.4124831 0.06768965 0.9310712 -0.3599647 0.05943048 0.6765062 -0.7343406 0.05552786 0.6153653 -0.7871305 0.04184859 0.4097974 -0.9114463 0.03649139 0.3154891 -0.9487196 0.01994806 0.8870817 -0.4349033 0.1547425 0.7975308 -0.5806178 0.1637917 0.8008896 -0.5766745 0.1613152 0.3647594 -0.9274903 0.08192861 0.8594267 -0.4454725 0.2508783 0.5385798 -0.8293294 0.1488106 0.8117817 -0.5143232 0.276554 0.5611746 -0.8071462 0.1832979 0.8404408 -0.4150609 0.3484017 0.1248958 -0.9913364 0.04066216 0.4887115 -0.8511653 0.1915171 0.8063908 -0.4670646 0.362746 0.620427 -0.7263062 0.2958879 0.3316463 -0.9325436 0.1427344 0.8211285 -0.3294779 0.4660389 0.5277997 -0.7892735 0.3138073 0.345025 -0.9192278 0.1896787 0.7259888 -0.5113539 0.4598451 0.5633928 -0.7442695 0.3586803 0.5081064 -0.7758283 0.3740566 0.7305202 -0.3817637 0.5662127 0.6278496 -0.5637608 0.5366366 0.2508614 -0.9423665 0.2213912 0.6412947 -0.406841 0.6505548 0.6044902 -0.5635719 0.5630083 0.09947448 -0.9922058 0.07505077 0.4272027 -0.7796912 0.4577988 0.296523 -0.9006237 0.3177279 0.5778805 -0.4589701 0.6748337 0.4931243 -0.6295098 0.6004548 0.5914419 -0.2390367 0.7701026 0.2391886 -0.9295052 0.2807297 0.5309621 -0.3521467 0.7707606 0.082295 -0.9904258 0.1108343 0.4411275 -0.6335228 0.6356535 0.4353324 -0.6570453 0.6154489 0.2951425 -0.8509838 0.4344162 0.5096303 -0.2508357 0.823018 0.4292904 -0.419236 0.7999694 0.3543079 -0.6815323 0.6402965 0.3591641 -0.6418759 0.6774927 0.2318872 -0.8873867 0.3984637 0.2341589 -0.8854399 0.4014546 0.4098553 -0.335922 0.848042 0.3416694 -0.4473857 0.8265035 0.3055312 -0.5540118 0.7744171 0.2846145 -0.6878653 0.6677095 0.166136 -0.886716 0.431432 0.1446661 -0.9287335 0.341359 0.2237642 -0.5704982 0.7902287 0.2260262 -0.5668369 0.7922173 0.1345359 -0.8222753 0.552959 0.1297553 -0.8501133 0.5103636 0.1672619 -0.427595 0.8883615 0.1355197 -0.4756628 0.8691257 0.1214171 -0.5219017 0.8443201 0.09866333 -0.7745953 0.6247141 0.04847472 -0.8366324 0.5456157 0.02931499 -0.3579974 0.9332624 0.05123537 -0.5218821 0.8514776 0.01050394 -0.992452 0.1221827 0.02527475 -0.6714788 0.7405927 0.01102238 -0.9521101 0.3055569 -0.04841721 -0.4694989 0.8816046 -0.03256785 -0.6637953 0.7472049 -0.09200286 -0.3387952 0.9363511 -0.06034684 -0.8022103 0.5939839 -0.159555 -0.4637055 0.8715041 -0.07309675 -0.8030232 0.591448 -0.1479223 -0.47953 0.8649681 -0.09399825 -0.8911544 0.4438562 -0.2938855 -0.3026123 0.9066736 -0.217881 -0.5846472 0.7814829 -0.1962587 -0.7634061 0.615381 -0.1491228 -0.8559619 0.4950675 -0.3248138 -0.2604436 0.9092113 -0.1174086 -0.9475819 0.2971597 -0.3577135 -0.4092847 0.8393611 -0.3012496 -0.6399666 0.7068886 -0.4178754 -0.3093942 0.8541988 -0.1843851 -0.9106438 0.3697703 -0.422047 -0.529592 0.7358049 -0.323861 -0.7362431 0.5941887 -0.3349887 -0.708696 0.6209128 -0.5134576 -0.3859736 0.7664109 -0.1344034 -0.9730159 0.187552 -0.327275 -0.8332688 0.4455944 -0.2006622 -0.9438543 0.262438 -0.5969898 -0.4000005 0.6954156 -0.5307788 -0.5270689 0.6636809 -0.4549773 -0.69384 0.5581951 -0.6395886 -0.4001812 0.6563394 -0.5599155 -0.6453689 0.519609 -0.4635206 -0.7565431 0.4612932 -0.3196943 -0.8947299 0.3118559 -0.7093467 -0.4382723 0.5520368 -0.6114273 -0.6157221 0.4970343 -0.7778051 -0.3024392 0.5509535 -0.2421528 -0.9500148 0.1970631 -0.5727576 -0.7015833 0.4239454 -0.3247496 -0.9159119 0.2358881 -0.7730082 -0.37706 0.5101805 -0.6764096 -0.6082969 0.4152652 -0.6710695 -0.6264588 0.3965038 -0.3572037 -0.9120365 0.2014816 -0.7578203 -0.5384318 0.3685103 -0.3321586 -0.9267629 0.1754458 -0.7534111 -0.5607894 0.3433471 -0.4294127 -0.8831717 0.1887128 -0.8001822 -0.5103018 0.3151199 -0.08014672 -0.996092 0.03711283 -0.7893759 -0.5447502 0.2830778 -0.5243631 -0.8370778 0.1560259 -0.438279 -0.8853765 0.1549839 -0.9018734 -0.3606552 0.2378071 -0.8966938 -0.388466 0.2122138 -0.5939686 -0.7949931 0.1232382 -0.517738 -0.8463457 0.1250857 -0.9390408 -0.301633 0.1649848 -0.8662414 -0.4900023 0.09758931 -0.6792606 -0.7304034 0.07152694 -0.2234315 -0.9741685 0.03277313 -0.6401889 -0.7665449 0.05066508 -0.9528797 -0.3019941 0.0286349 -0.3712705 -0.9283275 0.0191456 -0.8648715 -0.5010322 -0.03105127 -0.7429085 -0.6692138 -0.01549053 -0.325585 -0.9454276 -0.01268976 -0.9041282 -0.4211204 -0.07217913 -0.5390426 -0.8409089 -0.04801505 -0.1140431 -0.9933575 -0.01533359 -0.8231204 -0.5509925 -0.1374055 -0.6172663 -0.7784914 -0.1137254 -0.9159618 -0.3432149 -0.2078885 -0.5963592 -0.7940105 -0.1179122 -0.356886 -0.9299099 -0.08888196 -0.8422279 -0.4532695 -0.2918886 -0.8873156 -0.3598592 -0.2883963 -0.6921001 -0.6860843 -0.224245 -0.5853635 -0.7801331 -0.220776 -0.3864591 -0.9123696 -0.135023 -0.8303746 -0.4261031 -0.3590464 -0.6249116 -0.7270926 -0.2842918 -0.858475 -0.271617 -0.435023 -0.5845063 -0.7543933 -0.2987359 -0.7831721 -0.4345494 -0.4447567 -0.1795136 -0.9795486 -0.09088265 -0.6660823 -0.6368801 -0.3882245 -0.2893 -0.9423778 -0.1680167 -0.7818981 -0.2911255 -0.5512543 -0.7459363 -0.3802754 -0.5467813 -0.601234 -0.6796249 -0.420271 -0.5357573 -0.7468305 -0.3939652 -0.3369638 -0.9083019 -0.2478771 -0.2495286 -0.9456213 -0.2086526 -0.7081546 -0.3778739 -0.5964297 -0.5809902 -0.6046975 -0.5447857 -0.5855739 -0.6010429 -0.5439216 -0.6208102 -0.3973683 -0.6757909 -0.3981161 -0.8142147 -0.4225612 -0.310791 -0.8948624 -0.3203599 -0.598994 -0.3887665 -0.7000477 -0.5512794 -0.4764243 -0.6849168 -0.4103505 -0.7700676 -0.4884755 -0.1558783 -0.9664606 -0.2040981 -0.5116487 -0.4327384 -0.7422621 -0.4898654 -0.4694149 -0.7346302 -0.2913995 -0.8574705 -0.4240648 -0.3422721 -0.746732 -0.5702993 -0.3086278 -0.8056089 -0.5057106 -0.4455305 -0.3180925 -0.8368511 -0.3946033 -0.4275797 -0.8133043 -0.04206818 -0.996952 -0.06570446 -0.356562 -0.5812641 -0.7314339 -0.1725054 -0.9172934 -0.3589079 -0.3611901 -0.3105752 -0.8792524 -0.2960774 -0.4575152 -0.8384618 -0.2359432 -0.7285143 -0.6431157 -0.2359537 -0.7305608 -0.6407861 -0.1696687 -0.8946026 -0.413399 -0.2370423 -0.2994349 -0.9242023 -0.05777794 -0.9743714 -0.2173983 -0.1630318 -0.5278857 -0.833521 -0.1456081 -0.76542 -0.6268419 -0.08436059 -0.8822168 -0.4632242 -0.08679318 -0.33457 -0.9383656 -0.1085658 -0.4999646 -0.8592141 -0.04459851 -0.7708847 -0.6354116 -0.05283123 -0.8671277 -0.4952762 0.009569585 -0.4639541 -0.8858077 -0.005220592 -0.7217144 -0.6921713 0.03902816 -0.3952829 -0.9177299 0.08372622 -0.4818958 -0.8722193 0.00778222 -0.986462 -0.1638056 0.05873268 -0.8062215 -0.5886913 0.05915433 -0.8085274 -0.585478 0.03589636 -0.9464799 -0.3207607 0.1436148 -0.3883383 -0.9102572 0.1644653 -0.4658226 -0.8694599 0.141198 -0.7080672 -0.6918843 0.2673738 -0.3576686 -0.8947538 0.2750425 -0.4606983 -0.8438653 0.1619283 -0.8184061 -0.5513538 0.1855528 -0.7855559 -0.5903152 0.122978 -0.9090691 -0.3980827 0.3603064 -0.4087224 -0.8385257 0.06277209 -0.9875402 -0.1443054 0.3642759 -0.4963292 -0.7880105 0.2974597 -0.723205 -0.6232916 0.2925752 -0.7747177 -0.5605463 0.1570898 -0.9461599 -0.283027 0.4790375 -0.3809551 -0.7908201 0.4724327 -0.4614348 -0.750923 0.3919136 -0.6739603 -0.6262438 0.3637947 -0.7955361 -0.4845367 0.5908572 -0.3818418 -0.7106931 0.2303438 -0.9257705 -0.2998178 0.5895469 -0.3943279 -0.7049397 0.5064322 -0.6355938 -0.5827065 0.1894064 -0.9568652 -0.2203052 0.6979407 -0.2495446 -0.6712722 0.2389611 -0.9368523 -0.2553532 0.502976 -0.7075046 -0.4964399 0.6813955 -0.4314116 -0.5912564 0.5478876 -0.6697589 -0.5012407 0.7269896 -0.3591151 -0.5852541 0.4638285 -0.8099959 -0.358845 0.351102 -0.8966311 -0.2697783 0.7390815 -0.4613797 -0.4908029 0.7634623 -0.4180666 -0.4922864 0.5989456 -0.6995116 -0.3898047 0.247844 -0.9548698 -0.1636983 0.5634928 -0.758318 -0.327765 0.4531485 -0.8542717 -0.2547085 0.838991 -0.3438198 -0.4217609 0.7933335 -0.4401213 -0.4206129 0.6813743 -0.6419727 -0.3515682 0.05897766 -0.9978113 -0.02990484 0.8489891 -0.4132859 -0.3292604 0.8645405 -0.3838949 -0.3243371 0.6637105 -0.6929833 -0.2815362 0.4675768 -0.8670364 -0.172105 0.4144285 -0.8959116 -0.159974 0.9017431 -0.355487 -0.2459443 0.8626002 -0.4371545 -0.2545917 0.6693663 -0.7218936 -0.1755514 0.5200235 -0.8388153 -0.1611357 0.8866482 -0.4385159 -0.1468296 0.6961815 -0.7049056 -0.135792 0.9228428 -0.3651555 -0.1225667 0.5427371 -0.8376349 -0.06167906 0.3456019 -0.937318 -0.04465866 0.9379206 -0.3463848 -0.01796233 0.8788655 -0.4733457 -0.05949336 0.670736 -0.7406926 -0.038571 0.2912301 -0.9560486 -0.03400403 0.9996607 -0.002814352 -0.0258972 0.9911566 -0.00335288 -0.1326547 0.9968568 0.002830028 -0.07917428 0.9823824 0.005252361 -0.1868079 0.9651309 0.00152117 -0.2617635 0.9674419 -2.95557e-4 -0.2530936 0.9326752 -5.10133e-4 -0.3607172 0.9271462 0.002618372 -0.3746907 0.8905542 0.001484692 -0.454875 0.889607 0.001901328 -0.4567232 0.842547 -0.002820193 -0.5386156 0.8210042 0.003311157 -0.5709127 0.7866117 -0.003390729 -0.6174387 0.7464012 0.00300163 -0.6654896 0.7164344 -0.002254426 -0.6976509 0.6736333 0.003295898 -0.7390584 0.6343169 -0.004904568 -0.7730576 0.568063 0.005475521 -0.8229669 0.5181626 -0.006222665 -0.8552595 0.3962692 -0.00446099 -0.9181236 0.4442808 0.003804802 -0.8958796 0.287056 -0.005345702 -0.957899 0.330493 0.002563297 -0.943805 0.1552376 -0.004119992 -0.9878686 0.2044954 0.003557801 -0.978861 0.04519426 -0.001453936 -0.9989773 0.0814988 0.003949165 -0.9966656 -0.009521782 0.004051864 -0.9999465 -0.09605389 -0.002610921 -0.9953727 -0.104853 -4.67288e-4 -0.9944877 -0.1927885 0.003718495 -0.9812334 -0.2417913 -0.004828751 -0.9703164 -0.3047966 0.005542516 -0.9524013 -0.3799016 9.17416e-4 -0.9250265 -0.3839102 0.001783192 -0.9233687 -0.4812169 9.63777e-4 -0.8766012 -0.4854499 0.001951396 -0.8742624 -0.5614396 8.33039e-4 -0.8275174 -0.5678755 0.002424657 -0.8231109 -0.6401274 -0.003549337 -0.7682606 -0.7194147 -0.002647936 -0.6945757 -0.6867861 0.005334675 -0.7268401 -0.7424214 -0.004124164 -0.6699206 -0.8182463 -0.00325644 -0.5748587 -0.7786328 0.004178941 -0.627466 -0.845804 0.004677653 -0.5334734 -0.8910256 -0.005368351 -0.4539213 -0.9081575 0.002949893 -0.4186183 -0.9459801 -0.001892626 -0.3242195 -0.9502515 9.71842e-4 -0.3114822 -0.9778326 6.18688e-4 -0.2093875 -0.9731975 -0.00488317 -0.2299192 -0.9960334 -0.003943383 -0.08889305 -0.9923964 0.001284182 -0.1230768 -0.9996305 0.002364158 -0.0270785 -0.999495 -0.004257202 0.03149372 -0.9974811 0.002150774 0.07090008 -0.9871456 -0.00235635 0.1598072 -0.9833306 0.002592265 0.1818085 -0.9596154 -0.002554893 0.281304 -0.9473924 0.004226088 0.3200468 -0.9304482 -0.003340661 0.3664086 -0.8863019 0.001926124 0.463104 -0.8906804 -4.3702e-4 0.4546298 -0.8721237 -9.56147e-4 0.4892847 -0.8469949 0.003727376 0.531588 -0.809655 -0.003845691 0.5868937 -0.7835152 0.001067221 0.6213718 -0.7455039 -0.004665672 0.666485 -0.7283932 -0.00442779 0.685145 -0.7150963 -2.13821e-4 0.699026 -0.640194 -5.39605e-4 0.7682132 -0.6364112 4.67943e-4 0.77135 -0.5598616 -0.005081951 0.8285707 -0.5280416 0.002815485 0.8492138 -0.4472908 -0.002590715 0.894385 -0.4224743 0.003152608 0.9063695 -0.3484382 -0.0024513 0.9373286 -0.3016803 0.004842877 0.9533969 -0.2204314 -0.003993988 0.9753943 -0.2252817 -0.004030585 0.9742854 -0.1887797 0.002601504 0.9820161 -0.09402644 7.75332e-4 0.9955695 -0.1022641 -0.001263856 0.9947565 0.01669257 0.002826929 0.9998568 0.04694622 -0.002538561 0.9988943 0.104413 0.002361536 0.9945313 0.1008754 0.001628935 0.9948977 0.2728654 0.005513489 0.9620364 0.2115489 -0.003832161 0.9773599 0.2473964 -0.002484381 0.9689112 0.3437739 0.002151668 0.93905 0.3350346 1.1569e-4 0.9422059 0.4345183 2.04792e-4 0.900663 0.4426923 0.002076983 0.8966712 0.5187062 0.002506434 0.8549489 0.5131786 0.001060307 0.8582812 0.6159953 1.30557e-4 0.7877498 0.6106898 0.001530349 0.7918685 0.7142006 -0.004371523 0.6999275 0.6733559 0.004467785 0.739305 0.7572649 0.001776993 0.6531056 0.7850175 -0.003399848 0.6194643 0.8122409 0.003754794 0.5833102 0.8659406 -0.005050182 0.5001214 0.8881218 0.005386471 0.4595766 0.929543 -0.004321873 0.3686885 0.9639965 -0.004154205 0.2658826 0.94529 0.002987682 0.3262176 0.9788093 0.001849114 0.2047659 0.9749838 -0.003101527 0.2222548 0.9923561 0.003311276 0.1233638 0.9966762 -0.00311762 0.08140599 0.9996905 0.002571702 0.02474778 0.004120826 -0.9999815 0.004485607 0.005746543 -0.999973 0.004598319 0.004806935 -0.9999627 0.007180213 0.004862785 -0.999982 0.003519296 0.003284633 -0.9999556 0.008831381 0.003472447 -0.9999731 0.006460726 0.004722952 -0.9999868 0.002006292 0.005907177 -0.9999805 0.002064049 0.002130806 -0.9999637 0.008255362 0.004328846 -0.9999905 5.83208e-4 -5.9602e-5 -0.9998636 0.01651513 0.005062937 -0.9999873 2.7683e-4 0.001100003 -0.9997974 0.02010095 3.70688e-4 -0.9998121 0.01938349 0.004804253 -0.9999884 -3.53564e-4 -0.001278281 -0.9999606 0.008784353 0.009704709 -0.9999477 -0.003239929 0.01080769 -0.9999379 -0.002744853 -0.003069698 -0.9999653 0.007764279 -0.002186715 -0.999976 0.006591022 0.008072078 -0.9999634 -0.002853989 0.01400381 -0.9998752 -0.007326841 -0.005111157 -0.9999647 0.006687402 -0.004925549 -0.9999685 0.006235122 0.003028094 -0.999992 -0.002649724 -0.006547093 -0.9999629 0.005623042 -0.005889058 -0.9999721 0.004608511 0.002323389 -0.9999927 -0.003051161 0.003259479 -0.9999884 -0.003578782 0.001871764 -0.999992 -0.003562569 -0.009582638 -0.9999436 0.004575192 -0.007743 -0.9999654 0.003059267 0.002436041 -0.9999699 -0.007370471 0.002111136 -0.9999731 -0.007028222 -0.008567571 -0.9999607 0.002326548 -0.00807321 -0.9999645 0.002467691 0.001315295 -0.999916 -0.01290148 1.40019e-4 -0.9999641 -0.008481681 -0.004747629 -0.9999887 1.96275e-4 -5.64713e-4 -0.9999622 -0.00868541 -0.005887567 -0.9999825 -6.11138e-4 -0.004390299 -0.9999901 -7.42941e-4 -0.002053797 -0.9999564 -0.009111166 -0.002084374 -0.9999663 -0.007944583 -0.003627538 -0.9999926 -0.00136131 -0.003297984 -0.9999721 -0.006722152 -0.003548741 -0.9999696 -0.006950914 -0.004709541 -0.9999853 -0.002704083 -0.004555404 -0.9999861 -0.002677321 -0.002044022 -0.9999943 -0.002684831 -0.002248585 -0.9999953 -0.002103209 -0.004530251 -0.9999858 -0.002835631 0.5551485 0.8305205 -0.04523336 0.3949092 0.9186797 -0.008628487 0.9168553 0.3943154 -0.06238496 0.8831024 0.4623636 -0.07968777 0.5303614 0.847226 -0.03041285 0.8711824 0.4723394 -0.1339283 0.7643117 0.6255218 -0.1566848 0.5213979 0.8500769 -0.07425379 0.8870612 0.3745121 -0.2699321 0.7585314 0.6229221 -0.1913065 0.5836396 0.7894941 -0.1899055 0.3245221 0.9424155 -0.08086103 0.8753768 0.3567518 -0.3262571 0.7689765 0.5500923 -0.3256899 0.6014583 0.7637602 -0.2343469 0.07251077 0.99699 -0.0274437 0.1439209 0.9871102 -0.07000231 0.7738544 0.4779058 -0.4156386 0.4730837 0.8519654 -0.2243806 0.740354 0.5264973 -0.4179433 0.5172333 0.8035852 -0.2944838 0.3932517 0.8795469 -0.2678627 0.7587843 0.3549554 -0.5461255 0.7466509 0.4008095 -0.5309088 0.3934361 0.879719 -0.2670252 0.5481922 0.7123348 -0.4382516 0.7261655 0.2662742 -0.6338626 0.6131157 0.5045971 -0.6078413 0.1884841 0.9683999 -0.1633263 0.5284295 0.6916637 -0.4923045 0.3777226 0.8421025 -0.3849533 0.6110657 0.4345648 -0.6616285 0.56659 0.4872933 -0.6644705 0.05022966 0.9972519 -0.05445683 0.3674517 0.7889003 -0.4925603 0.3108699 0.8678274 -0.3876023 0.5309482 0.3349522 -0.7783965 0.4850358 0.4446263 -0.7530258 0.1349896 0.9741644 -0.181057 0.3687921 0.7659438 -0.5266143 0.4337123 0.451143 -0.7799767 0.2448565 0.8580586 -0.4514207 0.4218641 0.2773271 -0.8632036 0.1557602 0.9459449 -0.2844768 0.2758387 0.7641677 -0.5830615 0.3574207 0.3814665 -0.8524868 0.2627568 0.7504763 -0.6064193 0.320043 0.2923295 -0.9011748 0.05684 0.9879735 -0.1437973 0.2052568 0.7984135 -0.5660438 0.2711253 0.4117069 -0.8700509 0.09139919 0.9547314 -0.2830802 0.2061898 0.7044895 -0.6791027 0.1733949 0.330469 -0.9277524 0.1846134 0.4355034 -0.8810533 0.1428068 0.6941239 -0.7055482 0.08688569 0.8104321 -0.5793538 0.09738135 0.3511163 -0.9312542 0.06348752 0.919753 -0.3873291 0.0303443 0.6086089 -0.79289 0.03980737 0.7478537 -0.662669 -0.009949922 0.9104243 -0.4135562 0.006398916 0.9847186 -0.1740354 -0.02662426 0.5222173 -0.8523969 -0.07632815 0.5564209 -0.8273875 -0.06885379 0.527518 -0.846749 -0.06526833 0.8176915 -0.5719448 -0.1797457 0.5157641 -0.8376628 -0.1821263 0.5102863 -0.8404986 -0.09469813 0.8317676 -0.5469872 -0.09564805 0.9216518 -0.3760446 -0.2417283 0.4993025 -0.8320243 -0.1641767 0.8636909 -0.4765335 -0.2638553 0.6276749 -0.7323964 -0.2171664 0.7830931 -0.5827556 -0.3520155 0.4824668 -0.8020666 -0.4010586 0.5217744 -0.7529301 -0.398135 0.5548292 -0.7305157 -0.2857875 0.8005041 -0.5268004 -0.2371262 0.8921547 -0.3844882 -0.5615434 0.2484129 -0.7892783 -0.2072433 0.9214008 -0.3287416 -0.1029946 0.9795613 -0.1727769 -0.4782849 0.5155093 -0.7109809 -0.4570319 0.6370754 -0.6206906 -0.5880622 0.4394842 -0.6789968 -0.5074952 0.6139996 -0.6045274 -0.6498051 0.3040306 -0.6966482 -0.4490726 0.7452576 -0.4928742 -0.366132 0.8459251 -0.3877604 -0.3305571 0.886799 -0.3229852 -0.6499427 0.5028096 -0.5698746 -0.6399081 0.5244725 -0.5616461 -0.7240359 0.3748402 -0.5790223 -0.4670209 0.8041508 -0.3677408 -0.72289 0.4681878 -0.5081637 -0.5542736 0.7389246 -0.3831076 -0.4722604 0.80659 -0.3555036 -0.8062622 0.3099384 -0.5038645 -0.567785 0.7567902 -0.3238652 -0.2254995 0.9649052 -0.1345664 -0.7840533 0.4768608 -0.3973216 -0.6858632 0.64151 -0.3435937 -0.8722504 0.2883052 -0.3950436 -0.2931025 0.94318 -0.1565328 -0.6527881 0.6977509 -0.2949768 -0.8858838 0.3450573 -0.3100732 -0.369522 0.9187812 -0.1389057 -0.3197134 0.939044 -0.126411 -0.8488221 0.4488064 -0.2794173 -0.75326 0.6055539 -0.2567176 -0.6076865 0.7749191 -0.1738319 -0.4369323 0.8887004 -0.138931 -0.9129815 0.3590694 -0.1937373 -0.869372 0.4512895 -0.2013212 -0.6898832 0.7079291 -0.1513192 -0.6279103 0.7716633 -0.101314 -0.9442291 0.3036604 -0.1273651 -0.3139271 0.9481567 -0.04948443 -0.2805283 0.9590237 -0.03971946 -0.8819168 0.4662135 -0.06977003 -0.7403069 0.6698842 -0.05657738 -0.9501324 0.3106589 -0.0271939 -0.6594388 0.751534 -0.01836544 -0.3487902 0.9371774 -0.006631731 -0.9059609 0.4175543 0.06988096 -0.282569 0.9591825 0.01112794 -0.9221554 0.381483 0.06403356 -0.7520219 0.6569532 0.05362462 -0.6601791 0.7464911 0.08315396 -0.462482 0.8844071 0.06272685 -0.9240704 0.3450238 0.1644763 -0.9087042 0.3821108 0.1680715 -0.7484663 0.6482051 0.1401016 -0.6832867 0.7098008 0.1711789 -0.5486048 0.8198909 0.1637426 -0.3635632 0.9262687 0.09923851 -0.8750827 0.3861978 0.2916874 -0.2680914 0.9600626 0.08004301 -0.8896656 0.3508945 0.2921783 -0.8251472 0.4752522 0.3053973 -0.667516 0.6967369 0.2626407 -0.8231342 0.3949521 0.4079989 -0.7238041 0.570793 0.3876894 -0.6101078 0.7370602 0.2907072 -0.3702026 0.906892 0.2012388 -0.3438043 0.9207755 0.1843124 -0.7706278 0.3663493 0.5214605 -0.6982338 0.5579493 0.4485113 -0.6929298 0.5719017 0.4390637 -0.4091156 0.8723821 0.2675335 -0.3839986 0.8829151 0.2701965 -0.754546 0.260789 0.602204 -0.5444194 0.7001022 0.4620223 -0.6993117 0.3763621 0.6077128 -0.5436606 0.7034729 0.4577762 -0.688318 0.2885126 0.6655666 -0.4141878 0.8021978 0.4300317 -0.6167112 0.4115485 0.6710404 -0.1980678 0.9657753 0.1674733 -0.4141664 0.8025643 0.429368 -0.599689 0.3310006 0.7285683 -0.362994 0.8285384 0.4263328 -0.5518794 0.4185528 0.7212786 -0.4022682 0.7336475 0.5476693 -0.5023958 0.3224105 0.8022779 -0.4736469 0.3928753 0.7882308 -0.3525969 0.7450284 0.5662227 -0.3317387 0.7673451 0.548754 -0.08340013 0.988039 0.1297056 -0.3947876 0.3936945 0.8301491 -0.3947784 0.3839392 0.83471 -0.1534658 0.9458855 0.2859178 -0.3183976 0.6583853 0.6820204 -0.240225 0.7623949 0.6008712 -0.1496106 0.9264139 0.3455055 -0.261784 0.4733911 0.841053 -0.2576788 0.425166 0.8676611 -0.2163329 0.7234203 0.6556396 -0.08072441 0.9629507 0.2573124 -0.1056116 0.8892283 0.445106 -0.1901448 0.4328704 0.8811744 -0.1006733 0.8857908 0.4530338 -0.100961 0.6222999 0.7762408 -0.07626837 0.3986389 0.9139311 -0.1032407 0.6242295 0.7743895 -0.01641774 0.7753648 0.6313002 -0.006971538 0.361885 0.9321967 -0.007514417 0.975529 0.2197422 -5.15262e-4 0.9540659 0.2995967 0.04143065 0.6175088 0.7854722 0.1165123 0.3366781 0.9343837 0.05802452 0.6172868 0.7845956 0.09064912 0.7400586 0.6664054 0.07819294 0.8645157 0.4964861 0.2000489 0.4502581 0.8702001 0.1983287 0.4523556 0.8695057 0.09365767 0.9153034 0.3917244 0.2401877 0.5803462 0.778144 0.1990866 0.7765978 0.5977126 0.1147433 0.9009892 0.4183929 0.3257748 0.3991746 0.8570476 0.3721867 0.4447135 0.8146821 0.3634423 0.5764428 0.731863 0.2567942 0.7825954 0.567099 0.1836238 0.9194273 0.3477584 0.0952627 0.9750858 0.2003319 0.4756025 0.4556525 0.7524514 0.4182782 0.5599066 0.7152259 0.2860823 0.8544741 0.4336256 0.5237351 0.4602055 0.716877 0.5043417 0.5917131 0.6288999 0.2940649 0.8553884 0.4264229 0.5132005 0.5951887 0.6183652 0.6383524 0.3894882 0.6639317 0.4210194 0.7907227 0.4444101 0.2154248 0.9465511 0.2400696 0.2304694 0.9374907 0.2607589 0.6657935 0.4352288 0.6060488 0.6414335 0.5228031 0.5614624 0.5494709 0.6842882 0.4794074 0.2469733 0.9455897 0.2118121 0.4786955 0.7917956 0.3793554 0.1627902 0.9791137 0.1218026 0.7526789 0.4049294 0.5191403 0.7448336 0.4417618 0.5000695 0.58315 0.7244228 0.3676245 0.5532531 0.7542028 0.3536796 0.3817275 0.8960677 0.2265983 0.8443101 0.3106533 0.4366177 0.8335157 0.3548753 0.4234564 0.7049264 0.6081403 0.3650264 0.8409196 0.4349249 0.3220167 0.642547 0.7166733 0.2711327 0.4938347 0.8493691 0.1862779 0.3552325 0.9222211 0.152703 0.8773698 0.3692803 0.3063564 0.8439442 0.4810228 0.2374349 0.5672535 0.8093786 0.152085 0.5369377 0.8302106 0.1498283 0.9002295 0.3861849 0.2011171 0.8722855 0.4664808 0.1466757 0.6662672 0.7365423 0.1165912 0.924682 0.3642795 0.1107417 0.909689 0.4147255 0.02165156 0.8961833 0.4426901 0.02968585 0.1541313 0.9878115 0.02172863 0.7318519 0.6810492 0.02376389 0.5728777 0.8179654 0.0523805 0.3571234 0.9339038 0.01693117 -0.008083581 0.9999104 0.01067715 -0.008858382 0.9999049 0.01057434 -0.003631651 0.9999892 0.002901613 -0.008746087 0.9999106 0.01012313 -0.004007935 0.9999896 0.00215435 -0.0110473 0.9999336 0.0032866 -0.002427995 0.9999858 0.004761874 -0.00181055 0.9999844 0.005300402 -0.001508593 0.9999868 0.004919707 -0.01128023 0.9999315 0.003112792 -0.01015841 0.9999457 0.002359271 -4.84445e-4 0.999988 0.004888892 3.53807e-4 0.9999648 0.008395731 -0.009928822 0.9999475 0.002562046 -0.004437863 0.9999902 -8.59462e-5 -0.007192671 0.999971 -0.002528429 9.3715e-4 0.9999731 0.007285475 0.001946091 0.9999648 0.008162736 -0.00831753 0.9999632 -0.002139449 0.002342045 0.9999708 0.007277429 -0.007238686 0.9999738 -3.33222e-4 -0.002766489 0.9999954 -0.00133717 0.005470573 0.9999427 0.009198665 0.00549519 0.9999408 0.009399831 -0.008876979 0.9999091 -0.01014906 0.004651844 0.9999468 0.0092085 -0.01155543 0.9998832 -0.01001363 0.002423882 0.9999946 0.002202987 -0.01341748 0.9997979 -0.01497775 0.006657242 0.9999715 0.003570556 -0.01112443 0.999819 -0.01543527 -0.009844005 0.9998986 -0.01029688 0.006558299 0.9999731 0.003274142 -0.001632988 0.9999892 -0.004364609 0.01273053 0.9999154 0.00268203 0.01323622 0.9999049 0.003886938 0.01227486 0.9999161 0.004131376 -9.53852e-4 0.9999747 -0.007053852 -7.24407e-4 0.9997713 -0.02137684 0.002918481 0.9999958 5.70847e-5 -0.002912521 0.9998409 -0.0176022 2.37805e-4 0.9999966 -0.002627193 0.006689071 0.9999735 -0.002865135 6.49893e-4 0.999997 -0.002394974 0.006722033 0.9999759 -0.001736462 7.3785e-4 0.9999967 -0.002485454 0.007404088 0.9999703 -0.00213015 6.38309e-4 0.9999989 -0.001364529 0.00198394 0.9999975 -0.001025378 8.4984e-4 0.9999989 -0.001214861 0.001593291 0.9999979 -0.00138247 0.001954257 0.9999963 -0.00194025 -0.04575216 -0.2036412 -0.977976 -0.07932096 -0.5905585 -0.8030871 -0.03060543 -0.8257049 -0.5632716 -0.1699829 -0.5783069 -0.7979141 -0.3478282 -0.1543688 -0.9247627 -0.1982946 -0.7211627 -0.6637799 -0.1943368 -0.7503136 -0.6318723 -0.166124 -0.8317759 -0.5296713 -0.405364 -0.8276134 -0.3882474 -0.344112 -0.6657396 -0.662101 -0.5016105 -0.4590534 -0.7332509 -0.254494 -0.8861094 -0.387354 -0.2629657 -0.8794362 -0.3967884 -0.4803844 -0.6192088 -0.6211372 -0.2824175 -0.9102039 -0.3029344 -0.6574464 -0.4284905 -0.6198067 -0.6470324 -0.5046707 -0.5715389 -0.4655973 -0.8015888 -0.3750659 -0.7168987 -0.3978045 -0.5725451 -0.4065625 -0.8605677 -0.3068068 -0.7661968 -0.4562241 -0.4525507 -0.7689413 -0.4516527 -0.4524813 -0.3217229 -0.9295507 -0.1800833 -0.723478 -0.5963094 -0.3478429 -0.494073 -0.8537732 -0.1642048 -0.8949017 -0.3621871 -0.2607137 -0.6770029 -0.6909288 -0.2535443 -0.7791454 -0.6127506 -0.1321717 -0.9350978 -0.2316489 -0.2681995 -0.7885848 -0.6011765 -0.1293093 -0.1947243 -0.9804883 -0.02693319 -0.9074172 -0.4165219 -0.05570822 -0.658002 -0.7526009 0.02500468 -0.8547331 -0.5090759 0.1013565 -0.9067916 -0.4143556 0.07770693 -0.7401579 -0.6679065 0.07789373 -0.9855406 0.06310254 0.1572505 -0.1580812 -0.9873906 0.008374154 -0.8792049 -0.44736 0.1639138 -0.7094457 -0.6755713 0.2007245 -0.6975675 -0.6658632 0.2646237 -0.6228049 -0.759577 0.1875016 -0.8267345 -0.4078865 0.3874776 -0.4229866 -0.8642826 0.2722094 -0.8022724 0.2495191 0.5423092 -0.5424976 -0.7373962 0.4024219 -0.6773635 0.5078845 0.5321958 -0.5706169 -0.6579137 0.4914733 -0.4535937 -0.7641772 0.4585694 -0.4069964 -0.7325949 0.5455811 -0.540959 -0.4366255 0.7188336 -0.2150739 -0.8822352 0.4188131 -0.3965679 -0.5155457 0.7595701 -0.3797941 -0.362663 0.8510183 -0.2627499 -0.5294085 0.8066531 -0.3111554 -0.6518051 0.6916158 -0.174887 -0.8803885 0.4408296 -0.182131 -0.4111227 0.8932002 -0.1910092 -0.6471453 0.7380505 -0.0280022 -0.9636573 0.2656702 -0.05403286 -0.6954956 0.7164959 -0.02288538 -0.6178801 0.7859394 0.004314184 -0.9433639 0.3317322 0.219497 -0.9694862 -0.1091672 0.04574835 -0.627605 0.7771866 0.1720651 -0.5917872 0.7875161 0.1736358 -0.5887908 0.789415 0.07307803 -0.9576812 0.2783996 0.27574 -0.4563115 0.8460186 0.2561079 -0.7275787 0.636426 0.383997 -0.2830836 0.8788686 0.3240994 -0.674297 0.6635384 0.2703841 -0.7732197 0.573606 0.420381 -0.5894102 0.6898374 0.399788 -0.1257421 0.907942 0.536861 -0.418592 0.7325033 0.2457802 -0.9238888 0.2932945 0.51065 -0.6198601 0.5958272 0.6239266 -0.5362719 0.5684436 0.6020764 -0.6164183 0.5074766 0.6636239 -0.3846591 0.6415924 0.4830147 -0.7555665 0.4425112 0.7132539 -0.4229503 0.5589115 0.3607125 -0.8982895 0.2509234 0.6717056 -0.6136528 0.4150202 0.8188338 -0.4091994 0.4025757 0.4552097 -0.8615445 0.2247781 0.5775744 -0.7715533 0.2666711 0.7389234 -0.6183712 0.2675992 0.887803 -0.4006788 0.2264117 0.3376232 -0.9372169 0.08737927 0.8362695 -0.5394489 0.09822535 0.8334941 -0.5439512 0.09697872 0.8938065 -0.4411976 0.08034169 0.4141522 -0.9090103 0.04667168 0.8847841 -0.4596522 0.07666242 0.6045382 -0.7960528 0.02887076 0.8570982 -0.5126025 -0.05119979 0.8694272 -0.4904537 -0.05959594 0.4008235 -0.9155972 -0.03197586 0.7994968 -0.5882663 -0.1214404 0.4465542 -0.8868409 -0.1187549 0.9287229 -0.2208914 -0.2977934 0.6168124 -0.7755591 -0.1343525 0.6477908 -0.6848779 -0.3336306 0.8189588 -0.4283799 -0.3818339 0.2617332 0.9599964 -0.0995118 0.5032346 -0.8308088 -0.2377223 0.656481 -0.6115671 -0.4416088 0.4733524 -0.8044717 -0.3588353 0.7279601 -0.3586423 -0.584337 0.3246929 -0.9026443 -0.2825028 0.540111 -0.6238914 -0.5648361 0.55254 -0.4512606 -0.7007592 0.3392767 -0.8382299 -0.4269214 0.3472265 -0.8308049 -0.4349681 0.4344892 -0.6160024 -0.6570847 0.3827441 -0.486736 -0.7852358 0.2909521 -0.8654096 -0.4079377 0.2644985 -0.7039785 -0.6591319 0.3516167 -0.2949967 -0.8884497 0.1496094 -0.8242792 -0.5460595 0.2178993 -0.5358737 -0.8156957 0.1599573 -0.3597586 -0.919232 0.1306402 -0.6715779 -0.729326 0.08811593 -0.8012514 -0.591804 0.0620867 -0.5556183 -0.8291162 0.08127999 -0.853576 -0.5145888 0.1102985 -0.7001724 -0.7054027 -0.01898211 -0.9833655 -0.1806439 -0.0257371 -6.4015e-4 0.9996685 -0.07456642 2.52441e-4 0.9972161 -0.1987193 -8.67629e-4 0.9800561 -0.2287454 -2.21012e-5 0.9734863 -0.3311666 4.85309e-4 0.9435722 -0.4018452 -8.73893e-4 0.9157072 -0.4536039 4.32199e-4 0.8912034 -0.5687901 -1.48112e-4 0.8224827 -0.5805538 -6.05776e-4 0.8142217 -0.6997718 7.97632e-5 0.7143664 -0.7231286 -7.47586e-4 0.6907131 -0.8080691 -8.02019e-5 0.589088 -0.8287748 -4.60556e-4 0.559582 -0.8360471 -2.16843e-4 0.5486577 -0.8771802 5.41522e-4 0.480161 -0.8929684 -3.23648e-4 0.4501193 -0.947871 -6.72294e-4 0.3186535 -0.9597871 2.878e-4 0.2807286 -0.9856612 -5.37997e-4 0.1687359 -0.9937906 6.23889e-4 0.1112653 -0.999126 -3.34216e-4 0.04180103 -0.999399 3.65932e-4 -0.03466683 -0.9946172 -7.18138e-4 -0.1036151 -0.9868605 2.36515e-4 -0.1615746 -0.9566482 -3.75434e-4 -0.2912459 -0.9639506 3.79084e-4 -0.266081 -0.917934 4.73771e-5 -0.3967332 -0.9085505 4.14446e-4 -0.417775 -0.8862351 -7.0161e-5 -0.463236 -0.8428632 6.91029e-4 -0.5381276 -0.8160436 2.77e-5 -0.5779905 -0.760209 5.5709e-4 -0.6496785 -0.7555696 3.60865e-4 -0.6550684 -0.6838493 -3.73872e-4 -0.7296232 -0.6238996 6.32182e-4 -0.7815042 -0.5801196 -5.90542e-4 -0.8145313 -0.4649255 -2.74036e-4 -0.8853499 -0.4738144 -4.02676e-5 -0.8806248 -0.359926 -3.2504e-4 -0.9329808 -0.3409809 1.91454e-4 -0.9400702 -0.2162871 5.99507e-4 -0.9763297 -0.1745879 -6.02491e-4 -0.9846414 -0.05163091 4.06867e-4 -0.9986662 0.0181688 -8.18228e-4 -0.9998347 0.09263837 4.56773e-4 -0.9956998 0.1852546 -6.58505e-4 -0.9826903 0.2541965 5.58351e-4 -0.9671525 0.3332139 -2.77713e-4 -0.9428513 0.3532083 -8.39908e-4 -0.9355443 0.4671745 4.52543e-5 -0.8841651 0.4883812 -2.65483e-4 -0.8726304 0.5576617 5.71097e-4 -0.8300682 0.6050076 -3.99079e-4 -0.7962197 0.6998053 9.73345e-4 -0.714333 0.7217918 1.75949e-4 -0.6921104 0.8216729 6.64419e-4 -0.5699591 0.8192434 5.74941e-4 -0.5734456 0.863379 -3.27129e-4 -0.504556 0.8972235 3.64956e-4 -0.4415765 0.9285821 -0.001095414 -0.3711255 0.9587301 2.02451e-5 -0.2843183 0.9780857 -6.66424e-4 -0.208202 0.985214 1.94614e-4 -0.171328 0.9993461 -4.42594e-4 -0.03615862 0.9991523 -3.12402e-4 -0.04116654 0.9931564 6.1617e-4 0.1167908 0.9919966 3.02993e-4 0.126264 0.9664893 -5.4139e-4 0.2567065 0.9417559 0.001206934 0.3362951 0.901841 -7.67509e-4 0.4320673 0.8534765 6.02798e-4 0.521131 0.8295898 -3.95165e-4 0.5583733 0.7437609 1.07333e-4 0.6684458 0.7460449 1.86905e-4 0.6658957 0.6639288 4.62678e-4 0.7477957 0.6476979 -1.67546e-4 0.7618973 0.5360051 -6.5278e-4 0.8442146 0.4938011 6.75729e-4 0.8695746 0.3718582 -5.42443e-4 0.9282895 0.340185 3.58899e-4 0.9403585 0.2027385 -1.12911e-4 0.9792329 0.1684113 -9.37938e-4 0.9857165 0.0816285 5.04309e-4 0.9966628 -9.79631e-4 -0.9999994 -7.02411e-4 1.42823e-4 -0.9999995 -9.98612e-4 -0.001737177 -0.9999985 -1.30401e-4 -0.003319859 -0.9999923 0.00207895 -6.64396e-4 -0.9999998 2.4001e-4 0.006354331 -0.9999791 0.001262664 0.003344714 -0.9999944 2.48069e-4 -4.69526e-4 -0.9999982 0.001864671 3.41814e-4 -0.9999999 3.19411e-4 -0.002717435 -0.9999961 8.12991e-4 -0.005986928 -0.9999821 -2.47488e-4 -8.79747e-5 -0.9999995 -0.001044869 -0.004091918 -0.9999865 -0.003226697 5.10174e-4 -0.9999996 -8.85462e-4 8.54598e-4 -0.9999995 -5.82496e-4 0.001431465 -0.999999 -3.20905e-4 -0.002593278 -0.9999958 -0.001359641 1.85466e-5 -0.9999973 -0.002338826 -0.001542806 -0.9999985 -8.56757e-4 0.00126177 -0.9999958 0.002613961 3.79401e-4 -0.9999978 -0.00207901 6.69223e-4 -0.9999951 0.003068745 0.002624392 -0.9999926 0.002824306 1.38198e-4 -0.9999995 0.00108695 0.001398205 -0.9999961 0.002410769 0.002695202 -0.9999924 0.002857804 -0.002996087 -0.9999914 -0.002907812 0.004851698 -0.9999855 -0.002359807 -0.001824915 -0.9999984 5.19106e-5 8.51225e-4 -0.9999997 -3.05824e-4 -5.0192e-4 -0.9999983 0.001789569 -1.36344e-4 -1 1.95826e-4 -1.23834e-4 -1 1.93321e-4 7.02983e-5 -0.9999991 -0.00140661 0.003529429 -0.9999866 -0.003789186 -7.62404e-4 -0.9999984 0.001610398 -5.075e-4 -0.999997 0.002425074 -2.6569e-4 -0.9999994 0.001151502 -0.01681149 0.5913435 0.8062447 -0.02075469 0.6315746 0.7750373 -0.1429553 0.5260838 0.8383315 -0.1502773 0.566183 0.810465 -0.05172002 0.9081295 0.4154827 -0.27198 0.3340325 0.9024685 -0.1116844 0.9130194 0.3923293 -0.3532925 0.5220571 0.7762994 -0.3518624 0.4622974 0.8139251 -0.2446675 0.7952775 0.5546814 -0.2450803 0.7938246 0.5565773 -0.4821842 0.3826082 0.788105 -0.2459478 0.8575575 0.4517798 -0.4739975 0.6029589 0.6416909 -0.3988935 0.7474091 0.531285 -0.4066721 0.6888912 0.600039 -0.567232 0.6299568 0.5304738 -0.7141159 0.4025838 0.5726821 -0.3117796 0.89489 0.3193202 -0.6817504 0.5326355 0.5015136 -0.5291678 0.7897455 0.3102961 -0.8739885 0.1905758 0.447018 -0.4550527 0.8456101 0.2790534 -0.554236 0.7606025 0.3380922 -0.7316554 0.5966449 0.3296897 -0.273054 0.95673 0.1005449 -0.7966275 0.5195506 0.3089528 -0.5338022 0.8344609 0.1368595 -0.9207539 0.3301559 0.2078688 -0.5355172 0.8326143 0.1413317 -0.4251908 -0.8998122 0.09772837 -0.8496769 0.5083398 0.1401422 -0.668106 0.7341313 0.1211842 -0.8962384 0.4417591 0.04007279 -0.9344991 0.3499928 0.0649349 -0.5506249 0.8344206 0.02355003 -0.6481714 0.7612619 -0.01882779 -0.8455007 0.5242585 -0.1013994 -0.8906516 0.4465569 -0.08559656 -0.447531 0.89198 -0.06393617 -0.8534388 0.4775441 -0.2087914 -0.7169153 0.6579144 -0.2306105 -0.4596878 0.8769283 -0.1402997 -0.9334018 0.03085058 -0.3575044 -0.7393534 0.6081544 -0.2889721 -0.6697127 0.6843458 -0.2883673 -0.5721681 0.7431467 -0.3469247 -0.7397641 0.464345 -0.4869629 -0.5519508 0.7206891 -0.4194731 -0.4866265 0.7977215 -0.3561395 -0.6134884 0.6059619 -0.5064013 -0.5900828 0.4888355 -0.6425279 -0.6042866 0.3901261 -0.6947227 -0.5101342 0.6507626 -0.5623801 -0.2243447 0.9318444 -0.2851938 -0.5038982 0.5206932 -0.6891773 -0.508431 0.3538426 -0.7850435 -0.1947891 0.914209 -0.355358 -0.3816848 0.5573632 -0.7373351 -0.2977297 0.4797216 -0.8253632 -0.2970477 0.5245365 -0.7978875 -0.1683291 0.8554668 -0.4897365 -0.1905429 0.7919268 -0.5801255 -0.1044937 0.7002896 -0.7061697 -0.159866 0.5615018 -0.811886 -0.0712645 0.9302309 -0.3599891 -0.001311063 0.4558164 -0.8900729 0.01530569 0.5330618 -0.8459379 0.01987963 0.3036917 -0.9525631 -1.62185e-4 0.9263266 -0.3767217 0.03769606 0.4536473 -0.8903837 0.05109381 0.7843084 -0.6182636 0.1712813 0.319318 -0.9320401 0.1811817 0.5575773 -0.8101117 0.08479428 0.8636842 -0.4968497 0.2677912 0.6960787 -0.666155 0.3155848 0.5162722 -0.7961592 0.2833689 0.5943148 -0.7526568 0.3600023 0.3950651 -0.8451756 0.3926579 0.606546 -0.6913189 0.4537587 0.5178092 -0.7252426 0.1625905 0.9534536 -0.2539504 0.4585197 0.6814458 -0.5704308 0.5355243 0.6186314 -0.5748991 0.3413448 0.8753433 -0.3424293 0.4739353 0.7711217 -0.4251552 0.7437097 0.3665788 -0.5590313 0.5210011 0.7928437 -0.3161593 0.6788982 0.6223939 -0.3895164 0.539265 0.7772487 -0.3241569 0.8980687 0.2341212 -0.3723707 0.7590745 0.5844381 -0.2867718 0.6953331 0.6646497 -0.2734095 0.2794783 0.9567347 -0.08093613 0.8809292 0.4385495 -0.1778711 0.9501032 0.2646912 -0.165053 0.5633972 0.8224546 -0.07843571 0.6938098 0.7179023 -0.05695998 0.8304486 0.5560288 -0.03445374 0.4115604 0.9105634 0.03862982 0.9175322 0.3973359 0.01609402 0.3989291 0.9145216 0.06712514 0.8505077 0.5115325 0.1223565 0.833391 0.5417854 0.109216 0.7831229 0.5824859 0.2177813 0.7875423 0.5751627 0.2212808 0.594091 0.7824937 0.186439 0.5022928 0.8102175 0.3020754 0.7795034 0.5199643 0.3493016 0.7303786 0.4542918 0.5100648 0.7129902 0.5071371 0.4842078 0.5365746 0.7630039 0.3604344 0.413873 0.8606964 0.2964978 0.5778053 0.6266517 0.5229234 0.5570389 0.5450953 0.6265612 0.5773048 0.5132858 0.6350251 0.2292665 0.943637 0.238718 0.4488711 0.5821371 0.6779611 0.3377596 0.7923839 0.5079825 0.4629817 0.3581258 0.8107984 0.3062561 0.8255344 0.4740257 0.3141322 0.4757024 0.821601 0.3142561 0.4740684 0.8224976 0.2198023 0.7532266 0.6199491 0.1858482 0.8667405 0.4628407 0.1374238 0.5826306 0.8010345 0.05286079 0.930503 0.3624498 0.1441574 0.6734991 0.7249949 0.02259349 0.510544 0.8595549 0.009666442 0.8617217 0.5072891 -0.002722203 0.9999902 -0.003503382 -0.001269459 0.9999991 -5.77535e-4 0.002172827 0.999997 0.001249015 -2.93913e-4 1 1.39993e-4 0.003073155 0.9999843 0.00469613 0.002010464 0.999998 1.74838e-4 -2.7245e-5 1 1.28805e-4 0.002493023 0.9999123 -0.01300913 -9.19931e-4 0.9999988 -0.001354992 0.002601146 0.9999736 0.006794691 -0.004606664 0.9999893 -5.85994e-4 -2.94608e-4 0.9999999 -5.22158e-4 0.001033663 0.9999994 5.28541e-4 0.001917719 0.9999848 -0.005183041 0.001588523 0.9999988 9.32161e-5 0.001742005 0.9999985 -2.05657e-4 -7.17739e-4 0.9999814 0.00607407 -6.7899e-4 0.9999986 -0.001504719 8.04933e-4 0.9999997 2.40051e-4 -0.00121814 0.9999992 -5.02323e-4 0.002422451 0.9999969 -8.13519e-4 -0.001918673 0.9999981 3.18894e-4 0.001150131 0.999987 -0.00497508 0.003880858 0.9999861 -0.003586053 -2.74005e-4 0.9999988 0.001573383 -0.004250526 0.9999874 0.002682209 -0.002420902 0.9999956 -0.001746594 -0.002434074 0.9999971 1.57856e-4 -0.003243923 0.9999929 0.001948952 0.00109744 0.9999989 -0.001096308 0.001164257 0.9999926 -0.00367099 2.59963e-4 0.9999989 -0.001461505 0.001254439 0.9999881 0.004716038 2.87589e-4 0.9999981 0.001956224 1.67674e-4 0.9999936 0.003604173 3.52393e-4 0.9999989 -0.001467406 -0.001001417 0.9999991 -9.37801e-4 0.003567874 0.999993 0.0010885 -0.003756225 0.9999923 -0.001195013 -9.97882e-4 0.9999963 -0.00257796 -0.004330694 0.9999631 -0.007434368 0.004841387 0.9999672 0.00650084 -1.525e-4 0.9999939 0.003505885 -0.9742197 0.005100369 -0.2255438 -0.9691973 -0.003274679 -0.246264 -0.8442683 0.003634989 -0.5359085 -0.8493989 0.008101642 -0.5276893 -0.6926788 -0.01261639 -0.7211359 -0.629394 0.01261162 -0.776984 -0.4179788 -0.008107006 -0.9084206 -0.4267603 -0.003636479 -0.9043574 -0.1074199 0.003634095 -0.9942072 -0.09172213 -0.003639996 -0.995778 0.223001 0.003282606 -0.9748127 0.2379888 -0.002768576 -0.971264 0.4789208 0.002601921 -0.8778544 0.4922319 -0.002861976 -0.8704594 0.7162594 0.003212809 -0.6978269 0.7031631 0.01112997 -0.7109416 0.8334574 -0.0132786 -0.5524242 0.9010646 0.01668709 -0.4333637 0.9617552 -0.01707297 -0.2733783 0.9852843 0.01325345 -0.1704093 0.9967135 -0.01282769 0.07998669 0.9938889 -8.89838e-4 0.1103813 0.9468234 0.008994936 0.3216281 0.9151058 -0.01332283 0.4029936 0.844013 0.01070052 0.5362161 0.7838659 -0.008690834 0.6208694 0.6715662 0.01006913 0.7408761 0.6254251 -0.008806884 0.7802346 0.3990896 0.009545266 0.9168623 0.355185 -0.007334947 0.9347674 0.1274185 0.006465137 0.991828 0.08815795 -0.007178068 0.9960806 -0.1607496 0.007369995 0.9869678 -0.2390947 -0.01492559 0.9708815 -0.3665042 0.01254069 0.9303319 -0.5449553 -0.01529556 0.8383257 -0.6257204 0.01337909 0.7799327 -0.7514879 -0.01071035 0.6596601 -0.824507 0.01397591 0.5656793 -0.8837108 -0.01101911 0.4679039 -0.9577178 -0.001546204 0.287705 -0.963536 0.006942152 0.267489 -0.9985754 0.004365921 0.05318182 -0.9997849 -0.006005823 0.0198521 0.9952544 -0.01242488 0.09651112 0.9740335 0.02063608 0.2254613 0.9310159 -0.01654988 0.3646033 0.8351741 0.009641289 0.5499011 0.8125663 -0.001970529 0.5828657 0.6733505 0.002130448 0.7393204 0.6623048 -0.002690136 0.7492297 0.4554796 0.002689599 0.8902422 0.4422196 -0.002130806 0.8969043 0.2377606 0.002130687 0.9713214 0.2150506 -0.005441963 0.9765878 -0.05038934 0.009580254 0.9986837 -0.1074051 -0.01289355 0.9941318 -0.3811222 0.01289534 0.9244348 -0.4484618 -0.01621431 0.8936549 -0.6823136 0.01975739 0.7307927 -0.7381176 -0.01229161 0.6745602 -0.893262 4.31537e-5 0.4495365 -0.9090446 0.01436108 0.4164512 -0.9741224 -0.01146042 0.2257304 -0.9954987 0.01162981 0.09405982 -0.9999046 -0.008516848 0.01087886 -0.9811755 0.01272344 -0.192699 -0.9594557 -0.01571911 -0.2814212 -0.8766375 0.01423233 -0.4809409 -0.8277631 -0.0107463 -0.5609748 -0.7251192 0.007943451 -0.6885775 -0.6720611 -0.00744152 -0.7404584 -0.5472087 0.008923888 -0.8369486 -0.4826838 -0.00929445 -0.8757454 -0.2837876 0.0108456 -0.9588258 -0.2354589 -0.008149921 -0.9718502 0.09161895 0.006897032 -0.9957703 0.1132164 -0.004105925 -0.9935619 0.4587438 0.003925263 -0.88856 0.4553616 0.005719661 -0.8902883 0.6654412 -0.009424746 -0.7463908 0.7252362 0.01652508 -0.6883019 0.8673911 -0.01911211 -0.49726 0.9111684 0.01535892 -0.4117478 0.993795 0.009120821 -0.1108529 0.9866399 -0.00838989 -0.1627005 0.8915193 0.4458636 -0.07999414 0.5853923 0.8102244 -0.02919495 0.9154564 0.3869691 -0.1104292 0.889323 0.427838 -0.1614289 0.9335167 0.2854745 -0.216912 0.4748306 0.8775854 -0.06617999 0.6613175 0.7322215 -0.1628217 0.5125059 0.8508898 -0.1154308 0.8932341 0.3334274 -0.3015943 0.391959 0.9130045 -0.1130977 0.8892831 0.3432347 -0.3022674 0.7501525 0.6131748 -0.2475642 0.3949156 0.9039506 -0.1640582 0.8285948 0.4180321 -0.3723978 0.6487148 0.7060378 -0.2840421 0.5701246 0.7777847 -0.2645919 0.8522337 0.3026448 -0.4267365 0.1739585 0.9803407 -0.09311652 0.6738528 0.5842338 -0.4523198 0.5615827 0.7443258 -0.3613916 0.6867903 0.5512053 -0.4738058 0.4173042 0.8594153 -0.2954024 0.3712776 0.8785206 -0.3005906 0.6684697 0.4895262 -0.5599218 0.6332034 0.4452354 -0.6331025 0.6177765 0.5402252 -0.5714098 0.4854286 0.7394598 -0.4664316 0.1589084 0.9743824 -0.1591448 0.5852217 0.3844408 -0.7139474 0.5759904 0.4545923 -0.6793974 0.4383822 0.7150387 -0.5445556 0.3890531 0.7983908 -0.459576 0.2860282 0.8919615 -0.3501324 0.5259686 0.3255361 -0.7857375 0.4796258 0.4247893 -0.7677977 0.4075383 0.6301184 -0.6609565 0.2055895 0.9178234 -0.3396075 0.2822991 0.7838014 -0.553139 0.4290623 0.2302914 -0.8734251 0.2905949 0.7914231 -0.537777 0.3022139 0.61983 -0.7242082 0.2757953 0.3982222 -0.8748462 0.2626237 0.6106285 -0.7471022 0.1956052 0.721363 -0.6643599 0.1287522 0.9184306 -0.3740431 0.1887736 0.3176323 -0.9292332 0.1574293 0.4389352 -0.8846197 0.1615939 0.7212335 -0.6735798 0.07977211 0.854216 -0.5137619 0.05728 0.9743752 -0.2175133 0.09435963 0.4769123 -0.8738713 0.04603588 0.8152299 -0.577305 0.05100697 0.3690525 -0.928008 0.01006424 0.4211051 -0.9069561 -0.01325833 0.7463374 -0.6654359 0.02014952 0.8281388 -0.5601608 -0.03812134 0.3566237 -0.9334701 -0.09408885 0.4917092 -0.8656612 -0.01741564 0.972908 -0.2305361 -0.06760293 0.7174422 -0.6933301 -0.1240022 0.432027 -0.8932951 -0.08942979 0.7992354 -0.5943273 -0.01174372 0.9967051 -0.08025646 -0.2415966 0.3663533 -0.8985636 -0.196195 0.4935004 -0.8473283 -0.1584903 0.7626461 -0.6270978 -0.1719505 0.7899681 -0.5885435 -0.1412747 0.8974269 -0.4179312 -0.3081532 0.4276177 -0.8498145 -0.3128757 0.416073 -0.8538103 -0.2675811 0.6247972 -0.7335045 -0.4129165 0.373066 -0.8308561 -0.4171128 0.4708413 -0.7773836 -0.342926 0.6929602 -0.6341986 -0.3350825 0.7177093 -0.6104205 -0.1880681 0.9078918 -0.3746505 -0.1415538 0.9588351 -0.2461662 -0.5352876 0.2954959 -0.7912961 -0.5127478 0.5490102 -0.6600587 -0.4069156 0.7301079 -0.5489648 -0.342839 0.8344895 -0.43138 -0.6136431 0.4308519 -0.6616713 -0.337691 0.8663578 -0.3679525 -0.2247739 0.9485308 -0.2230834 -0.6173323 0.5238115 -0.5869604 -0.4972894 0.7293834 -0.4697906 -0.6901369 0.4114168 -0.5953548 -0.7255017 0.4057391 -0.5558985 -0.4671398 0.8199496 -0.3308521 -0.3945536 0.8759373 -0.2775994 -0.701083 0.5351988 -0.4712165 -0.5697554 0.7317908 -0.3739802 -0.7874259 0.4097009 -0.4605492 -0.2651996 0.95187 -0.153664 -0.748601 0.5638908 -0.3487461 -0.5776492 0.7596499 -0.2987533 -0.4006505 0.8958057 -0.1923836 -0.8397188 0.4083967 -0.3578889 -0.7528332 0.5589824 -0.3475356 -0.9043288 0.3062478 -0.2973244 -0.8778774 0.4109997 -0.2457857 -0.3831325 0.9134787 -0.1369905 -0.8114488 0.5454151 -0.2099367 -0.6813639 0.7008755 -0.2109901 -0.4584884 0.8775907 -0.140082 -0.8016244 0.5737185 -0.1680643 -0.6233788 0.7770391 -0.08723133 -0.9479386 0.3013064 -0.1030865 -0.4347787 0.8956577 -0.09362113 -0.9272429 0.3677869 -0.07038205 -0.7680099 0.6396369 -0.03202486 -0.6248623 0.7781769 -0.06315076 -0.3071707 0.9516358 -0.005957305 -0.1797025 0.983631 -0.01330721 -0.980601 0.1948082 0.02171313 -0.7748458 0.6282767 0.06987494 -0.8008499 0.596538 0.05274462 -0.4631041 0.8852752 0.0426914 -0.8056443 0.5890951 0.06248438 -0.9326091 0.3202369 0.1663993 -0.8875606 0.4107476 0.2086212 -0.7090761 0.6895167 0.1475737 -0.5730722 0.8070536 0.1423123 -0.8981574 0.3620511 0.2494639 -0.4143403 0.9059799 0.08673375 -0.8618324 0.4226967 0.2803076 -0.6430148 0.7305308 0.2299061 -0.8823598 0.3311356 0.3343508 -0.7579759 0.5350782 0.3730467 -0.1551103 0.9867121 0.0483756 -0.5961911 0.7619296 0.2530208 -0.407369 0.891685 0.1973538 -0.7804417 0.4589408 0.4245988 -0.7435314 0.4707065 0.4749701 -0.7402656 0.4755511 0.4752454 -0.3271343 0.9199715 0.2159529 -0.3330324 0.9164008 0.222034 -0.68327 0.4713186 0.5576746 -0.6791389 0.4951411 0.5418539 -0.3833885 0.8723425 0.3033677 -0.6353622 0.4909917 0.596022 -0.6614474 0.244821 0.7089077 -0.5049875 0.6709113 0.5430154 -0.3289999 0.878902 0.3453844 -0.5269156 0.5452982 0.6519278 -0.256023 0.9212069 0.2929676 -0.5356717 0.356071 0.7656822 -0.5018438 0.5395157 0.6760738 -0.4236256 0.6540213 0.6267357 -0.2534716 0.8955167 0.3657897 -0.4675322 0.3299835 0.8200761 -0.1890769 0.9275737 0.3222687 -0.3728111 0.5921441 0.714407 -0.4045801 0.5537052 0.7278226 -0.2716501 0.7863709 0.5548216 -0.08706617 0.9827266 0.1633033 -0.3339725 0.431722 0.8379012 -0.3174535 0.454762 0.8321147 -0.2313565 0.7295123 0.6436505 -0.2741475 0.3390603 0.8999341 -0.2294111 0.3941472 0.8899543 -0.1645634 0.669702 0.7241672 -0.1653404 0.7928686 0.586534 -0.1957795 0.2615572 0.9451234 -0.08814769 0.9271622 0.3641434 -0.05019736 0.9600645 0.2752389 -0.1133109 0.6423414 0.7579962 -0.08496624 0.3534057 0.9316036 -0.10209 0.3986809 0.9113897 -0.04294919 0.8013697 0.5966256 -3.65889e-4 0.4653972 0.8851019 -0.03238266 0.9050889 0.4239877 0.001761078 0.7105741 0.7036203 0.03363662 0.3950309 0.9180519 0.05125463 0.7876048 0.6140454 0.01659363 0.9221234 0.38654 0.1011455 0.5167888 0.850117 0.05294322 0.7852144 0.6169565 0.109181 0.5050489 0.8561572 0.1990154 0.5852614 0.786042 0.2050936 0.5740743 0.7927013 0.02447688 0.9902103 0.1374206 0.1226406 0.8330277 0.5394665 0.1069123 0.9149685 0.3891047 0.2985441 0.5011187 0.8122509 0.2829773 0.5346433 0.7962918 0.1944149 0.8653857 0.4618557 0.3633322 0.4689624 0.8050243 0.2064908 0.879948 0.4278471 0.3778024 0.5847922 0.7178325 0.2667743 0.8342612 0.4825348 0.4917477 0.4169741 0.7644062 0.2910152 0.8417199 0.4547723 0.5482085 0.2997054 0.7807973 0.4991156 0.4143022 0.7610766 0.4092903 0.7210952 0.5590199 0.5950949 0.3956721 0.699504 0.4609311 0.6855149 0.5635707 0.6197054 0.3577122 0.6985751 0.6202297 0.5152929 0.5914291 0.1409401 0.9774433 0.157292 0.4483075 0.7679226 0.4575098 0.3774935 0.85381 0.3584792 0.6792672 0.4464368 0.5824865 0.22991 0.9466701 0.2257369 0.6834686 0.4741148 0.555055 0.4953883 0.7767226 0.3889635 0.7543495 0.3848631 0.5318247 0.7391211 0.4876597 0.4646375 0.4966129 0.8050311 0.3245006 0.4384215 0.8603929 0.2598283 0.4002059 0.8869717 0.2304704 0.7922233 0.4466281 0.4158189 0.7799365 0.4879268 0.3919522 0.2203435 0.9660598 0.1348237 0.4424465 0.878809 0.1787061 0.797274 0.5123416 0.3191558 0.7769381 0.5556297 0.2960456 0.07234543 0.9966893 0.03710144 0.3808214 0.9146348 0.1357149 0.7955593 0.5564412 0.2397053 0.9419645 0.2565329 0.2165499 0.9053801 0.4021904 0.1361251 0.4179301 0.9028657 0.1008366 0.6748505 0.7250952 0.1371632 0.6226833 0.7730141 0.1213047 0.9167475 0.3795795 0.1244736 0.939193 0.3433274 0.00655198 0.8902993 0.4532406 0.04404836 0.1764248 0.9840887 0.02106577 0.5603806 0.8280729 0.01640003 0.570867 0.8209353 0.01327377 0.9991653 -0.0242542 -0.0328713 0.9934883 -0.01078897 -0.1134222 0.9929643 -0.006240665 -0.1182506 0.97538 -0.006250441 -0.2204428 0.9753508 -0.006138265 -0.2205744 0.9497422 -0.009823262 -0.312879 0.9451982 0.002282917 -0.3264894 0.9102632 -0.01141393 -0.4138728 0.8662974 -0.001819491 -0.4995253 0.8862308 0.02158856 -0.4627408 0.8275431 0.01352888 -0.5612391 0.8102383 -0.002633035 -0.5860949 0.7484335 -0.01112061 -0.6631166 0.7727168 0.006155848 -0.6347212 0.7148859 0.01378351 -0.6991053 0.6510064 -0.005935788 -0.7590491 0.644075 5.12362e-4 -0.7649621 0.5687603 -0.005067586 -0.8224877 0.558592 0.004738211 -0.8294292 0.4722158 -0.01044267 -0.8814212 0.391497 0.002535045 -0.920176 0.4265784 0.02216571 -0.904179 0.2993041 -0.01097947 -0.9540946 0.3372275 0.01329147 -0.9413294 0.195084 0.005796313 -0.9807694 0.1974272 0.00308901 -0.9803128 0.06320297 -0.003279507 -0.9979953 0.06039863 -5.98124e-4 -0.9981742 -0.04515206 -0.002477347 -0.9989771 -0.05515462 0.005075812 -0.9984649 -0.1406586 7.80317e-4 -0.990058 -0.1535889 0.01049369 -0.9880791 -0.2587004 0.009816944 -0.9659078 -0.2386671 -0.003103733 -0.9710966 -0.3197824 -0.01512801 -0.9473702 -0.3478006 0.006832599 -0.9375436 -0.4334648 0.002088546 -0.9011682 -0.440177 0.007385015 -0.8978807 -0.5322838 -0.01605629 -0.8464137 -0.5670009 0.01825302 -0.8235151 -0.6421831 -0.01430785 -0.7664179 -0.6738789 0.007940709 -0.7387992 -0.7068728 -0.009395539 -0.7072783 -0.7470549 0.01312661 -0.6646327 -0.7890753 -0.01184624 -0.6141823 -0.8103604 0.0107612 -0.5858329 -0.8621777 0.005546867 -0.5065755 -0.8657613 0.01214289 -0.5003097 -0.9180662 0.007238209 -0.3963611 -0.9084296 -0.008577287 -0.4179499 -0.9439568 -0.007008075 -0.3299946 -0.94718 9.75712e-4 -0.3207011 -0.9764248 -9.42564e-4 -0.2158559 -0.9765648 -3.14187e-4 -0.2152239 -0.9962909 -0.01576733 -0.0845918 -0.9909679 0.02550554 -0.1316518 -0.9996216 0.004623889 0.02711695 -0.9993778 0.01097708 0.03352016 -0.9916884 -0.008036673 0.1284121 -0.9870654 0.01431918 0.1596776 -0.962515 -0.01371067 0.2708821 -0.9656511 -0.002047717 0.2598341 -0.9251738 -4.16934e-4 0.3795437 -0.9266167 -0.004072606 0.3759854 -0.8915378 0.007128536 0.4528902 -0.8744452 -0.01417744 0.4849171 -0.8070344 -0.007121264 0.5904614 -0.8384253 0.01366752 0.5448452 -0.7497374 -0.01528793 0.6615589 -0.7777174 0.01004236 0.6285338 -0.6489245 -0.002457618 0.7608488 -0.6768212 0.02608293 0.7356852 -0.5651403 -0.01145404 0.8249155 -0.593082 0.01109635 0.8050657 -0.4718311 0.008610785 0.8816469 -0.473964 0.006736993 0.8805186 -0.4017837 -0.002632617 0.9157308 -0.400909 -0.003456532 0.9161115 -0.3012016 0.00219345 0.953558 -0.282688 -0.01235365 0.9591324 -0.1962774 0.006733715 0.9805253 -0.159315 -0.01539099 0.9871079 -0.08932042 0.0137614 0.995908 -0.03548943 -0.01783603 0.999211 0.08381778 -0.01133811 0.9964167 0.04750144 0.0100913 0.9988203 0.1615985 0.01904934 0.9866728 0.2044842 0.01277464 0.9787865 0.214039 0.003307104 0.9768196 0.3390288 0.001179039 0.9407752 0.3334589 -0.00521475 0.9427502 0.4670963 0.001894652 0.8842045 0.4434748 0.016254 0.8961396 0.469646 0.002990305 0.8828498 0.5637436 0.009005606 0.8259007 0.5680599 0.0034222 0.8229801 0.6386896 -0.014023 0.7693367 0.6812002 0.01918405 0.7318458 0.7251156 -0.006174743 0.6885995 0.7461856 0.01211601 0.6656278 0.8123803 -0.005623281 0.5831011 0.8186141 0.002452373 0.5743388 0.8666029 -0.01559138 0.4987549 0.8873937 0.0186941 0.4606334 0.9315947 0.00644952 0.3634417 0.9344903 -0.00228101 0.3559816 0.9578947 -0.01593911 0.2866771 0.9844421 -0.01271897 0.1752486 0.9704442 0.0138241 0.2409298 0.9976168 -0.01044625 0.06820183 0.9932668 0.009453058 0.115463 0.9998377 0.006693184 0.01672846 0.9085227 -0.4089987 0.08547979 0.4298747 -0.902756 0.01547509 0.8446951 -0.5326218 0.05295568 0.4319145 -0.9014503 0.0289331 0.6407951 -0.7634365 0.08091145 0.9175319 -0.36599 0.1555204 0.867349 -0.4625936 0.1836109 0.6721549 -0.7273696 0.1383525 0.8946124 -0.3743658 0.243965 0.1864227 -0.9815701 0.04203462 0.5805398 -0.7992793 0.1553263 0.2986294 -0.9504653 0.08623307 0.7215499 -0.634394 0.2773267 0.8412076 -0.3838685 0.3808079 0.7190421 -0.6301537 0.2930611 0.6013541 -0.7452327 0.2881002 0.3742024 -0.9108802 0.1739823 0.8340733 -0.3100062 0.4563089 0.7018952 -0.5588822 0.4415811 0.6183188 -0.698881 0.3595097 0.7340983 -0.4016373 0.5475282 0.6998043 -0.5081902 0.5020126 0.2058908 -0.9705231 0.1252754 0.3335294 -0.9109194 0.2428659 0.4929895 -0.7531068 0.4356507 0.6785673 -0.3372702 0.6525299 0.681762 -0.3119429 0.6617343 0.3422101 -0.8986426 0.27447 0.5090285 -0.7022956 0.4976654 0.1355072 -0.980059 0.1453351 0.4635616 -0.7268025 0.5068222 0.6131259 -0.3180817 0.7231188 0.5918827 -0.3688995 0.7166506 0.4651514 -0.6820322 0.5643281 0.1799914 -0.9602585 0.2133232 0.4170228 -0.7201796 0.5544667 0.534517 -0.2923493 0.792984 0.4786605 -0.4083153 0.777279 0.2204564 -0.923392 0.314239 0.4192618 -0.6285284 0.655112 0.446586 -0.3255349 0.8334196 0.3695442 -0.4583061 0.808327 0.278127 -0.7764889 0.5654296 0.2130196 -0.8585349 0.4664123 0.1543783 -0.9430586 0.2946319 0.3279324 -0.2336037 0.9153631 0.3345426 -0.4046039 0.8511034 0.2096164 -0.6726666 0.7096342 0.1726757 -0.8219262 0.5427894 0.2155515 -0.4042554 0.8888842 0.2054786 -0.6327012 0.7466377 0.1928899 -0.3428597 0.9193698 0.0832206 -0.9184206 0.3867532 0.1421265 -0.4123511 0.8998703 0.1172988 -0.6355385 0.7631067 0.09528261 -0.3308344 0.9388663 0.06008446 -0.7758192 0.6280881 0.02572947 -0.5408089 0.8407519 0.01192665 -0.9956083 0.09285444 0.03882253 -0.7690387 0.6380223 -2.89913e-4 -0.8460873 0.5330445 -0.04954582 -0.4262434 0.9032507 -0.06926274 -0.4602161 0.8851011 -0.01562857 -0.9286813 0.3705493 -0.08169382 -0.6048687 0.7921237 -0.1479728 -0.277175 0.9493567 -0.05279356 -0.9401654 0.3366034 -0.1916121 -0.4945862 0.8477437 -0.1341742 -0.6770626 0.7235907 -0.1158596 -0.8472757 0.5183632 -0.2655204 -0.4084019 0.873331 -0.02494752 -0.9961385 0.08417737 -0.1541431 -0.8455882 0.5110976 -0.284738 -0.456699 0.8428229 -0.2655047 -0.6475017 0.714317 -0.3623271 -0.3343724 0.8700082 -0.1400607 -0.9278533 0.3456463 -0.3725454 -0.5683129 0.7336419 -0.3092493 -0.6851597 0.6594855 -0.2224379 -0.8662942 0.4472759 -0.4747822 -0.3814716 0.7931338 -0.4165303 -0.5272386 0.7406228 -0.5349143 -0.298981 0.7902386 -0.3801718 -0.748028 0.5439885 -0.2543883 -0.884726 0.3905722 -0.5530852 -0.4184403 0.7204197 -0.4550264 -0.6695067 0.5871217 -0.6294283 -0.2676792 0.7294984 -0.1759539 -0.9552202 0.2378964 -0.4789653 -0.7178139 0.5053074 -0.6506581 -0.4046699 0.6425623 -0.2475344 -0.932698 0.2622999 -0.4462361 -0.7721115 0.452457 -0.6925366 -0.3411198 0.6356339 -0.5062308 -0.7655893 0.3969931 -0.7687765 -0.3551863 0.5318133 -0.6867536 -0.5184011 0.5095389 -0.1631648 -0.9776455 0.132615 -0.6270023 -0.6307543 0.457184 -0.3024219 -0.9292984 0.2120035 -0.8285145 -0.2868109 0.4809402 -0.6138425 -0.7085065 0.3481609 -0.363628 -0.9062426 0.2156366 -0.7151709 -0.6037057 0.352236 -0.7110592 -0.6019939 0.3633155 -0.8549507 -0.3996249 0.330695 -0.5377255 -0.8182161 0.2034059 -0.3972078 -0.9055383 0.1490854 -0.8443769 -0.4551369 0.2826273 -0.2964373 -0.9457252 0.1331493 -0.693967 -0.6864339 0.217298 -0.9173192 -0.3115202 0.2479531 -0.324097 -0.9424806 0.08180111 -0.8579362 -0.4952297 0.1367226 -0.6792803 -0.7220979 0.1309697 -0.5082988 -0.8571775 0.08294045 -0.8882838 -0.4437606 0.1184424 -0.9257212 -0.377882 0.01567125 -0.8785574 -0.4756824 0.04316473 -0.6628411 -0.74876 -4.6965e-4 -0.4696145 -0.8826599 0.01933419 -0.9512273 -0.2969129 -0.08372253 -0.9204934 -0.3852331 -0.06547826 -0.7656763 -0.6389119 -0.07437449 -0.2752674 -0.9613464 -0.006408035 -0.7081014 -0.6966073 -0.115459 -0.1048876 -0.9944428 -0.009066045 -0.5449962 -0.8308368 -0.1126473 -0.9144803 -0.3441179 -0.2128589 -0.9058408 -0.3730924 -0.2006354 -0.495007 -0.8605725 -0.1199296 -0.878579 -0.3943696 -0.2693914 -0.7872498 -0.5472028 -0.2842657 -0.5094292 -0.8455746 -0.1596421 -0.4407137 -0.8814866 -0.1695666 -0.8462547 -0.3490527 -0.4025113 -0.7710731 -0.5410636 -0.3357032 -0.6395685 -0.7025136 -0.3121328 -0.8277721 -0.2878107 -0.4816206 -0.6107746 -0.7076758 -0.3551753 -0.1765891 -0.9800481 -0.09122645 -0.798681 -0.3574345 -0.4840964 -0.5268306 -0.7764299 -0.3458413 -0.7396209 -0.3906018 -0.5480796 -0.3235834 -0.9201304 -0.2205762 -0.5806354 -0.6880655 -0.435234 -0.7535758 -0.2818896 -0.5938534 -0.6895975 -0.3358898 -0.6415866 -0.2443481 -0.943787 -0.2226213 -0.5815961 -0.5600765 -0.5899664 -0.4947304 -0.7353416 -0.4631572 -0.3387097 -0.8785922 -0.3366774 -0.5420358 -0.5140422 -0.6647991 -0.5212429 -0.5411761 -0.6598746 -0.3260074 -0.8314708 -0.4498618 -0.286396 -0.8582223 -0.4259482 -0.4811752 -0.3600934 -0.7992517 -0.4803186 -0.3943963 -0.7834193 -0.2814565 -0.8337796 -0.4749674 -0.4009535 -0.3215586 -0.8578091 -0.4054884 -0.3964681 -0.8236457 -0.2497725 -0.8398137 -0.4820029 -0.2722368 -0.7197338 -0.6386473 -0.3347885 -0.3300167 -0.882613 -0.2528189 -0.6015716 -0.7577561 -0.2471988 -0.7064191 -0.6632232 -0.08592039 -0.9691461 -0.2310274 -0.1095376 -0.9163691 -0.3850576 -0.1862817 -0.3821902 -0.9051131 -0.1847563 -0.5704601 -0.8002753 -0.133468 -0.6910361 -0.7103911 -0.1437422 -0.2973417 -0.9438889 -0.09091281 -0.9044787 -0.4167173 -0.08090186 -0.4239925 -0.902045 -0.03513258 -0.9502928 -0.3093696 -0.0799666 -0.6664689 -0.7412318 -0.04402363 -0.363822 -0.9304276 -0.03232848 -0.7568222 -0.6528208 -0.03019058 -0.9329 -0.3588681 -0.002138555 -0.4357264 -0.9000766 0.007620036 -0.7033061 -0.7108464 0.05993455 -0.2980135 -0.9526782 0.04273098 -0.7387754 -0.6725957 0.1022675 -0.4326729 -0.8957319 0.09220474 -0.6282256 -0.7725484 0.04481965 -0.8856972 -0.4620949 0.1893225 -0.2654132 -0.9453639 0.06148147 -0.9311164 -0.3595028 0.2255775 -0.4344863 -0.8719728 0.1693419 -0.6873266 -0.7063325 0.1678755 -0.7303642 -0.6621073 0.2772787 -0.3648785 -0.8888083 0.04513871 -0.9788072 -0.1997475 0.3159862 -0.4615469 -0.8289315 0.2112139 -0.742604 -0.6355533 0.2010658 -0.8504416 -0.4861295 0.3463471 -0.4307104 -0.833386 0.3804508 -0.5007567 -0.7774961 0.2278414 -0.8501706 -0.4746562 0.2265512 -0.8513892 -0.4730865 0.4554361 -0.3636419 -0.8126147 0.4285565 -0.4381824 -0.7901491 0.5361905 -0.2833133 -0.795131 0.4047927 -0.7009444 -0.5872136 0.3320457 -0.8029083 -0.4950594 0.5308034 -0.5128974 -0.6746734 0.09261429 -0.9842559 -0.1505425 0.5908122 -0.4254249 -0.6855325 0.2471284 -0.9138211 -0.3222709 0.5620036 -0.4909369 -0.6656823 0.5125072 -0.6718385 -0.5347613 0.2744092 -0.9167174 -0.2903946 0.7251614 -0.2330946 -0.6479259 0.3124747 -0.8954102 -0.3171754 0.666292 -0.5244981 -0.5300536 0.6062916 -0.6166355 -0.5021665 0.4029208 -0.8558253 -0.3243733 0.7286965 -0.4602111 -0.5071561 0.7312607 -0.4731742 -0.4912883 0.4639999 -0.8440729 -0.2687847 0.8030457 -0.368901 -0.468006 0.3601445 -0.9023377 -0.2368178 0.4803589 -0.8362795 -0.264371 0.8273347 -0.4222645 -0.3704187 0.8008174 -0.4718199 -0.3688871 0.7061339 -0.6340812 -0.3151445 0.9035928 -0.2954602 -0.3101992 0.6358736 -0.7407966 -0.21653 0.3689912 -0.9203234 -0.1298096 0.8253315 -0.5211008 -0.2174444 0.7392887 -0.6412308 -0.2056097 0.2953636 -0.9508056 -0.09343099 0.8731911 -0.4472997 -0.1935472 0.8644944 -0.4856858 -0.1294561 0.7633351 -0.6413651 -0.07726991 0.6175148 -0.7814819 -0.08922898 0.3959642 -0.9163523 -0.05925244 0.8386117 -0.5447149 -0.004019439 0.7753409 -0.6305878 -0.03472065 0.2904184 -0.9566736 -0.02080452 0.001814842 -0.9999982 6.44809e-4 7.70097e-4 -0.9999994 8.47396e-4 -0.001618146 -0.9999958 0.00238949 0.001557528 -0.9999983 0.001023948 0.001225829 -0.9999986 0.001205623 0.001330316 -0.9999958 0.00260508 0.001344382 -0.9999987 9.24599e-4 6.85891e-4 -0.9999959 0.002806544 9.87944e-4 -0.9999996 2.37726e-4 0.002359569 -0.9999963 0.001406073 0.001023948 -0.9999993 -7.38791e-4 -2.08645e-5 -1 4.1315e-4 0.001387953 -0.9999991 -1.48596e-4 -0.001892387 -0.999998 6.83944e-4 0.001240551 -0.9999941 -0.003206431 -8.44118e-4 -0.9999976 0.002051591 0.003008604 -0.9999945 -0.001371383 0.002766549 -0.9999935 -0.002358019 -9.16354e-5 -0.9999973 0.002343237 0.005651295 -0.9999841 4.4059e-5 -9.05936e-4 -0.9999991 9.73846e-4 0.001117289 -0.9999988 -0.001058042 -0.001229524 -0.9999989 8.31747e-4 9.17319e-5 -0.999998 -0.002005517 0.001029968 -0.9999976 -0.001992523 -0.001203 -0.9999989 8.98728e-4 -0.001161634 -0.9999992 5.32969e-4 7.88979e-4 -0.9999974 -0.002147197 -0.002251088 -0.9999963 -0.001597881 1.77429e-4 -0.9999982 -0.001925766 -0.00240308 -0.9999971 2.33088e-4 -0.002481937 -0.999997 4.33237e-5 2.0764e-4 -0.9999982 -0.00191766 -0.002106845 -0.9999978 -4.12568e-4 -0.001999437 -0.9999976 -8.88899e-4 -8.53287e-4 -0.9999956 -0.002883434 -0.002219617 -0.9999976 1.10459e-4 -0.001005351 -0.9999994 -5.47806e-4 -0.004468083 -0.99999 -3.30745e-4 -0.002518832 -0.9999894 -0.003856658 -8.30693e-4 -0.9999994 -8.00108e-4 7.49578e-4 -0.9999787 -0.006498575 0.7608985 -0.645124 0.06963074 0.6761537 -0.7332414 0.07192546 0.9462761 -0.3017915 0.116118 0.9310607 -0.3446736 0.1196925 0.1567916 -0.9876103 0.006503283 0.6020609 -0.7925804 0.09663897 0.2803591 -0.9586681 0.0485239 0.8786879 -0.4108362 0.2431485 0.8822361 -0.4034216 0.2427152 0.6553467 -0.735862 0.170376 0.5131863 -0.8394197 0.1789259 0.8255706 -0.4442148 0.3480035 0.2397306 -0.9676451 0.07869035 0.5428524 -0.8131914 0.2098356 0.831214 -0.4229704 0.3608039 0.1505686 -0.9868974 0.05798763 0.6754021 -0.6197592 0.3996633 0.4990267 -0.8262192 0.2614081 0.7776111 -0.3793313 0.5014268 0.3217412 -0.9284272 0.1857567 0.6796699 -0.6054202 0.414144 0.6095955 -0.6650309 0.4314248 0.7450277 -0.3138943 0.5885611 0.3894036 -0.8693788 0.3042131 0.7497252 -0.2664877 0.6057198 0.2643527 -0.9455792 0.1897305 0.6330059 -0.600488 0.4885875 0.1096934 -0.9896014 0.09304141 0.6850134 -0.3253461 0.6518486 0.61819 -0.4638567 0.6345692 0.5231515 -0.6948159 0.4935012 0.4461748 -0.7860899 0.4277741 0.5809224 -0.3891689 0.7148965 0.5727373 -0.4410917 0.6909488 0.3323128 -0.8645365 0.3770213 0.2597957 -0.9170816 0.3024364 0.424342 -0.7122058 0.5591931 0.5061584 -0.2738066 0.8178226 0.1775091 -0.9498529 0.2574295 0.3562316 -0.7411099 0.5690827 0.4317396 -0.4745017 0.7671044 0.35769 -0.6969265 0.6215716 0.2864467 -0.7557929 0.5888341 0.3619235 -0.3640612 0.8581789 0.3610799 -0.3946415 0.8449138 0.1349508 -0.939919 0.3135932 0.07355058 -0.9874793 0.1395532 0.2885132 -0.6403455 0.7118412 0.2808162 -0.2974191 0.9125153 0.2202873 -0.6878607 0.6916078 0.2277521 -0.4298606 0.8736984 0.139837 -0.8394063 0.5252075 0.17958 -0.3883798 0.903832 0.1168436 -0.8553678 0.5046719 0.1555101 -0.4406032 0.8841299 0.1020371 -0.6896063 0.71696 0.05172985 -0.9424929 0.330199 0.04361248 -0.2740577 0.9607239 0.05614024 -0.3661847 0.9288473 0.02723908 -0.6247239 0.7803707 0.05022829 -0.7229607 0.689061 0.01806157 -0.9174686 0.3973984 -0.06160724 -0.4504051 0.8906964 0.004554688 -0.9285284 0.3712335 -0.02250283 -0.6145249 0.7885765 -0.04751116 -0.8639268 0.5013713 -0.07812654 -0.4233223 0.9026042 -0.1232993 -0.4921215 0.8617504 -0.1237729 -0.7661101 0.6306787 -0.2027552 -0.3054636 0.9303669 -0.07134062 -0.8636655 0.4989914 -0.1499794 -0.7516853 0.6422426 -0.2545121 -0.3706799 0.8932078 -0.2594183 -0.5108954 0.8195658 -0.2820938 -0.5412592 0.7921249 -0.04090046 -0.9899135 0.1356409 -0.1874138 -0.8285195 0.5276661 -0.3574294 -0.4508685 0.8179008 -0.1698833 -0.8980833 0.405692 -0.3797539 -0.481249 0.7900547 -0.3798027 -0.5750638 0.7246044 -0.1849951 -0.8902537 0.4162033 -0.3928377 -0.578988 0.714459 -0.5403326 -0.3223132 0.7772741 -0.3523736 -0.7932266 0.4966129 -0.5452467 -0.4522697 0.7058032 -0.2126629 -0.9235981 0.318969 -0.1869257 -0.9443546 0.2706535 -0.3823918 -0.7658664 0.5169385 -0.6056376 -0.4176765 0.6773104 -0.5871885 -0.5420775 0.6011337 -0.4452008 -0.7478148 0.4925132 -0.2805038 -0.922438 0.2653784 -0.6440876 -0.5137942 0.5667157 -0.6452237 -0.4902738 0.5859335 -0.2798091 -0.9231385 0.2636708 -0.4523799 -0.8198716 0.3509463 -0.7710734 -0.3393746 0.538768 -0.7058759 -0.4775949 0.5231083 -0.6169971 -0.6638755 0.422592 -0.4692718 -0.8120479 0.3469328 -0.07760524 -0.9953621 0.05684942 -0.7911517 -0.4111759 0.4527841 -0.6749195 -0.630004 0.3841597 -0.8651381 -0.2419112 0.439335 -0.3545801 -0.9115788 0.2080798 -0.6410986 -0.6909695 0.3339969 -0.497976 -0.8323779 0.2432425 -0.8256307 -0.4381737 0.3554403 -0.8461908 -0.4333551 0.3101042 -0.7614738 -0.6054528 0.2314834 -0.487482 -0.8532552 0.1852489 -0.3014481 -0.9495002 0.08705425 -0.878089 -0.4442812 0.1776907 -0.7809295 -0.5922266 0.1985365 -0.8946245 -0.4291182 0.1245181 -0.5249608 -0.8484926 0.06690782 -0.508651 -0.8585615 0.06439208 -0.7827022 -0.619719 0.05766767 -0.9184063 -0.3951557 -0.01954507 -0.3741884 -0.927172 0.01830667 -0.8252344 -0.5647726 0.004509508 -0.9432595 -0.3258594 -0.06385403 -0.681759 -0.7300209 -0.0476889 -0.5824046 -0.8115797 -0.04629701 -0.8791206 -0.4594382 -0.1267421 -0.1320892 -0.9912275 -0.004536509 -0.8865513 -0.4339457 -0.1603683 -0.4438936 -0.892322 -0.08197718 -0.8591878 -0.4799659 -0.1772824 -0.5146031 -0.8474837 -0.130212 -0.4611725 -0.8810298 -0.1053872 -0.8646203 -0.4243829 -0.2689439 -0.7606376 -0.5842484 -0.2829918 -0.5343859 -0.8315578 -0.1514712 -0.7454676 -0.5739579 -0.3388959 -0.7392997 -0.5877559 -0.3286017 -0.4290827 -0.8820068 -0.194813 -0.08030247 -0.9961962 -0.03383612 -0.3408641 -0.9237241 -0.1747727 -0.6962983 -0.5995332 -0.3946249 -0.4365239 -0.8559182 -0.27722 -0.7517355 -0.4496381 -0.48241 -0.7416276 -0.4295632 -0.5152319 -0.4222615 -0.8595671 -0.287819 -0.6049976 -0.606532 -0.5158457 -0.6691241 -0.4111401 -0.6190612 -0.6165511 -0.6227539 -0.4817078 -0.1747289 -0.9716098 -0.1595124 -0.6277282 -0.403793 -0.6655137 -0.59187 -0.4658026 -0.6578129 -0.4077671 -0.8082796 -0.4247471 -0.3321372 -0.8684839 -0.3679953 -0.5509717 -0.4729716 -0.6875523 -0.4273949 -0.6578938 -0.6200883 -0.322851 -0.8607605 -0.3935208 -0.4713171 -0.3202344 -0.8217727 -0.4182478 -0.6532718 -0.6311139 -0.3160043 -0.7519798 -0.5785048 -0.4320446 -0.3207831 -0.8428735 -0.1297159 -0.9659528 -0.2238503 -0.3314785 -0.5682421 -0.7531421 -0.1738815 -0.9222819 -0.3451974 -0.3205525 -0.5679998 -0.7580386 -0.3030663 -0.4022744 -0.8639018 -0.1314915 -0.9191077 -0.3714177 -0.177702 -0.7988211 -0.5747235 -0.2244287 -0.3047094 -0.9256263 -0.2449657 -0.4349846 -0.8664758 -0.164117 -0.7319937 -0.6612494 -0.1530637 -0.3380036 -0.9286146 -0.03945481 -0.9852848 -0.1663043 -0.1435553 -0.3107095 -0.9396018 -0.1132137 -0.7458665 -0.6564038 -0.09443467 -0.7701638 -0.6308169 -0.04584926 -0.9205836 -0.3878451 -0.03460174 -0.4172725 -0.9081225 -0.0364142 -0.4273118 -0.9033707 -0.0321232 -0.6250511 -0.7799227 0.02712011 -0.7643854 -0.6441891 0.02123051 -0.9078459 -0.4187663 0.08816504 -0.3155738 -0.9447965 0.009052634 -0.934635 -0.3554936 0.1236142 -0.4751542 -0.8711764 0.1029975 -0.6343696 -0.7661376 0.1625066 -0.4065222 -0.8990726 0.1244045 -0.8043268 -0.581018 0.07209372 -0.905272 -0.4186707 0.04445832 -0.9870046 -0.1544194 0.2846785 -0.4195891 -0.8619184 0.2586323 -0.5048174 -0.8235709 0.2238354 -0.683025 -0.6952515 0.1771902 -0.7736548 -0.6083272 0.3618149 -0.3092535 -0.8794614 0.1228653 -0.9388503 -0.3216588 0.2947021 -0.7354341 -0.6101536 0.1834884 -0.9049274 -0.3839771 0.3992724 -0.4513694 -0.7980271 0.3687077 -0.6300066 -0.6834812 0.3893115 -0.637668 -0.6646924 0.5244628 -0.3954731 -0.7540159 0.3270919 -0.8186911 -0.4719701 0.5480115 -0.380122 -0.7451112 0.1834473 -0.938578 -0.2922645 0.5533194 -0.5232445 -0.6481149 0.09695357 -0.9865704 -0.1314495 0.3979397 -0.7756646 -0.4898861 0.5731275 -0.5010078 -0.6484721 0.3395888 -0.873951 -0.3476909 0.7259113 -0.3237067 -0.6068499 0.5947935 -0.5881237 -0.5480248 0.5286006 -0.7137261 -0.4595395 0.3764529 -0.8600741 -0.3443197 0.7564792 -0.3230096 -0.5686861 0.2788274 -0.9361795 -0.2140635 0.661952 -0.6081108 -0.4382017 0.6616505 -0.6095808 -0.436612 0.3747922 -0.8964686 -0.2363787 0.7592824 -0.5021268 -0.4139555 0.761761 -0.5111784 -0.3980163 0.8641996 -0.3274091 -0.3820502 0.6496931 -0.7017163 -0.2923922 0.3501686 -0.9202172 -0.1748785 0.3058709 -0.9414997 -0.1414971 0.8764039 -0.3669076 -0.3119215 0.8062919 -0.5335762 -0.255323 0.6811208 -0.6900054 -0.2448821 0.4790571 -0.8647065 -0.1509544 0.07561093 -0.9967665 -0.02719604 0.9030369 -0.3858957 -0.1887034 0.8213587 -0.5320817 -0.2055703 0.5978225 -0.7933112 -0.1151764 0.4546034 -0.8841608 -0.1076823 0.2933108 -0.9540646 -0.06107109 0.929616 -0.3514738 -0.1108165 0.6537894 -0.7540916 -0.06249099 0.9451867 -0.3258914 -0.02042388 0.9427894 -0.3328772 -0.01846468 0.9242392 -0.3676353 -0.1030839 0.8112056 -0.5846974 0.008627951 0.6236158 -0.7808739 -0.0365976 0.4967724 -0.8678287 -0.009519815 0.2748193 -0.9614658 -0.007622122 0.9998296 0.003906726 -0.01804828 0.9998322 0.003817498 -0.01791715 0.9920757 0.002168297 -0.1256234 0.9908239 0.008960604 -0.1348621 0.9733536 -0.01508164 -0.2288131 0.9501602 -0.01397454 -0.311449 0.9642078 0.005663752 -0.2650876 0.9096996 -0.00852108 -0.4151797 0.9287951 0.01067465 -0.37044 0.8622879 -0.01351398 -0.5062382 0.8894925 0.007682025 -0.4568853 0.8445025 -5.04402e-4 -0.5355514 0.8202101 -0.01746624 -0.5717957 0.7820645 0.01022917 -0.6231136 0.7367354 -0.01673191 -0.6759742 0.7139045 -0.00443381 -0.7002291 0.6900233 -0.01694953 -0.7235888 0.644521 0.006639659 -0.7645579 0.6102435 -0.01225441 -0.7921191 0.5573722 0.01088321 -0.8301915 0.5063648 -0.01574498 -0.8621757 0.4901841 -0.01353782 -0.8715138 0.4627147 0.009719729 -0.8864541 0.3929401 0.009991645 -0.9195099 0.4106408 -0.004564583 -0.9117859 0.2812556 0.001041769 -0.9596324 0.2863299 -0.003246307 -0.9581256 0.2071784 -0.004507958 -0.9782928 0.1931869 0.005726039 -0.9811453 0.09210038 -0.01220756 -0.9956749 0.05285841 0.01949232 -0.9984118 -0.03864651 0.002987682 -0.9992485 -0.03395104 -3.52794e-4 -0.9994235 -0.1406612 -0.004334211 -0.9900484 -0.1631374 0.01382368 -0.9865065 -0.2073728 0.0224837 -0.9780036 -0.2490266 0.002517879 -0.9684934 -0.2948681 0.01675659 -0.9553911 -0.3502628 -0.01757562 -0.9364866 -0.4224281 -3.03094e-4 -0.9063964 -0.4323531 0.01098525 -0.9016376 -0.5435635 0.00900346 -0.8393198 -0.530362 -0.001419365 -0.8477701 -0.5887581 7.11407e-4 -0.8083091 -0.5888124 7.58633e-4 -0.8082694 -0.6768237 -3.10642e-4 -0.736145 -0.68116 0.004346251 -0.7321217 -0.7560741 0.005671918 -0.6544615 -0.7513553 6.94072e-4 -0.6598976 -0.8047463 -0.01467019 -0.5934377 -0.7897174 0.001235425 -0.6134696 -0.869913 0.005793988 -0.4931712 -0.8626241 -0.005709171 -0.5058134 -0.9074061 -0.01657158 -0.4199281 -0.9117316 -0.008892595 -0.4106904 -0.9482057 -0.009125947 -0.3175258 -0.9493278 -0.00566101 -0.3142368 -0.9833396 -0.009299039 -0.18154 -0.9769247 0.01611369 -0.2129757 -0.9969692 0.006622195 -0.07751464 -0.9971496 0.009092688 -0.07490038 -0.9992027 -0.009971439 0.03865963 -0.99796 0.001594781 0.0638228 -0.9944359 -0.01688659 0.1039826 -0.9852486 0.008133828 0.1709358 -0.9734077 -0.01702791 0.228446 -0.960969 1.6257e-5 0.2766559 -0.9492411 -0.02163743 0.3138043 -0.9166209 0.0154336 0.3994597 -0.8904718 -0.02478694 0.4543627 -0.8577483 0.01648592 0.5138055 -0.8142482 -0.01444238 0.5803374 -0.7815915 0.01623654 0.6235793 -0.7477662 -0.01509165 0.6637906 -0.6779328 0.001961529 0.7351213 -0.6871887 -0.01228052 0.7263752 -0.5591533 -0.02347558 0.828732 -0.5933432 0.008832037 0.8049012 -0.4774511 0.01069557 0.8785932 -0.4791274 0.008821189 0.8777011 -0.378497 -0.01010882 0.9255473 -0.3523631 0.006745994 0.9358391 -0.3051138 -0.002452909 0.9523128 -0.2570605 0.02239185 0.9661359 -0.1960316 -0.0142256 0.9804944 -0.1014687 0.006374359 0.9948184 -0.09890282 0.003886461 0.9950896 0.0341618 -2.90483e-4 0.9994164 0.04786968 -0.01464772 0.9987463 0.1594324 0.009013116 0.9871678 0.1885768 -0.01282227 0.9819748 0.2923798 0.01362025 0.9562054 0.281263 0.002057909 0.9596287 0.3967375 -0.001497864 0.917931 0.3956681 -0.002629399 0.9183899 0.5198842 0.005331754 0.8542201 0.5234439 6.56349e-4 0.85206 0.6398196 0.008640527 0.7684766 0.6295108 -0.004035294 0.7769813 0.7112362 0.01053142 0.7028742 0.7189087 3.15616e-4 0.6951045 0.7871444 -0.01026791 0.6166833 0.808726 0.02006679 0.5878432 0.8643251 -2.54561e-4 0.5029335 0.8644724 -8.95202e-5 0.5026805 0.9073845 -0.03220593 0.419066 0.9303241 0.01734799 0.3663281 0.9443507 0.01677113 0.3285127 0.9625754 -0.0202682 0.2702555 0.9787905 0.02039605 0.2038462 0.9921913 -0.01292574 0.1240547 0.9970831 0.0258488 0.07181429 0.8721671 0.4857005 -0.05847811 0.8624776 0.5029807 -0.05606395 0.9470936 0.2929393 -0.1311501 0.6914283 0.7167122 -0.09083265 0.4420248 0.8964821 -0.03056246 0.2331638 0.9718033 -0.03511512 0.8758742 0.4385694 -0.2012497 0.7021486 0.6944258 -0.1573536 0.6992489 0.6972597 -0.157734 0.9182585 0.3034384 -0.2544144 0.4236156 0.8985623 -0.1146107 0.8497303 0.4121616 -0.3287573 0.8260133 0.457184 -0.3296739 0.7066854 0.6603396 -0.2540616 0.4287591 0.886161 -0.1757396 0.3820859 0.9069782 -0.1772032 0.788486 0.4668701 -0.4004026 0.8192606 0.4179852 -0.3925563 0.6032107 0.7237572 -0.3351303 0.4067738 0.8897897 -0.2069047 0.7922918 0.3137507 -0.5232917 0.7747702 0.3986383 -0.4907329 0.6434662 0.638283 -0.4225472 0.7457918 0.3103016 -0.5894977 0.7298742 0.346437 -0.5892921 0.2974426 0.931376 -0.2099207 0.5513229 0.7131685 -0.4329364 0.5275686 0.7371854 -0.422172 0.683798 0.3245669 -0.6535111 0.6112157 0.4682749 -0.6380705 0.1187908 0.9874934 -0.1036609 0.4976299 0.734714 -0.461042 0.5990635 0.3328632 -0.7282343 0.3074582 0.885888 -0.3473788 0.590341 0.4511161 -0.6693219 0.3945109 0.7447738 -0.538213 0.5326479 0.3472723 -0.7718084 0.3183654 0.8570664 -0.4050686 0.5073648 0.4050919 -0.7605798 0.3986508 0.7147182 -0.5746787 0.4548224 0.4156979 -0.7876116 0.3374118 0.6491667 -0.6817154 0.321074 0.7505413 -0.5775807 0.1668291 0.9432843 -0.287024 0.3425101 0.3452338 -0.8737853 0.08887487 0.9793598 -0.1815374 0.3090886 0.6410244 -0.7025325 0.2719154 0.6920911 -0.6686344 0.2900802 0.2794477 -0.9152937 0.1297629 0.9197606 -0.3704081 0.2137828 0.4893442 -0.8454816 0.199892 0.6504918 -0.7327371 0.1674511 0.4086632 -0.8971927 0.1252167 0.8008694 -0.5856016 0.1014289 0.9022291 -0.4191598 0.1585261 0.4242727 -0.8915504 0.08962678 0.7390444 -0.6676678 0.04200589 0.9663067 -0.253943 0.06597739 0.7531899 -0.654486 0.06562817 0.3261007 -0.9430543 0.01297867 0.569984 -0.8215533 0.01263433 0.9252252 -0.3792082 -0.06693482 0.364225 -0.9289025 0.004730343 0.9304023 -0.3665094 -0.01190477 0.5722855 -0.8199681 -0.04768919 0.7260498 -0.6859865 -0.09242379 0.3673042 -0.9254975 -0.008088588 0.9600528 -0.2797023 -0.1361301 0.5835973 -0.8005517 -0.09858894 0.7255119 -0.6811115 -0.176713 0.5314488 -0.8284533 -0.008152663 0.9989699 -0.04464125 -0.1013789 0.860887 -0.4985941 -0.08905678 0.8946155 -0.4378723 -0.2962902 0.401347 -0.8666792 -0.06573945 0.9714447 -0.2279775 -0.2565292 0.612066 -0.7480429 -0.2086607 0.6460499 -0.7342209 -0.2428231 0.7610893 -0.6014816 -0.1899177 0.882148 -0.4309829 -0.383633 0.3982679 -0.8331918 -0.3763458 0.5269033 -0.7620611 -0.4160742 0.5516188 -0.7229101 -0.4081892 0.6720185 -0.6178776 -0.2033626 0.9021564 -0.3804705 -0.4005318 0.672132 -0.6227462 -0.5488882 0.4686016 -0.6921952 -0.3062294 0.8803824 -0.3621473 -0.1270952 0.9726272 -0.1945332 -0.5904289 0.4858141 -0.6444985 -0.5844233 0.5317496 -0.6129371 -0.318331 0.8772018 -0.3594197 -0.2736923 0.9267529 -0.2573355 -0.6380682 0.5116869 -0.5753657 -0.6360176 0.5374045 -0.5537853 -0.4569165 0.8197576 -0.3452894 -0.7605959 0.3490338 -0.5474205 -0.4521192 0.8198378 -0.3513606 -0.7854986 0.4081028 -0.4652355 -0.7932754 0.3770109 -0.4780972 -0.6677465 0.6288054 -0.3983948 -0.589235 0.7493533 -0.3021124 -0.8455428 0.3671988 -0.3875855 -0.3451226 0.920822 -0.1815968 -0.3418109 0.9225183 -0.1792353 -0.818578 0.4590579 -0.3452479 -0.6986982 0.6492066 -0.3005858 -0.8794454 0.3658999 -0.3044557 -0.06457614 0.9975311 -0.02760088 -0.5451695 0.8199974 -0.1743401 -0.5438333 0.8224444 -0.1668251 -0.9056337 0.3773956 -0.1933916 -0.8452061 0.4896825 -0.2140976 -0.2539779 0.9652826 -0.06103116 -0.6490914 0.7438595 -0.1592274 -0.6357399 0.7622551 -0.1216629 -0.8568508 0.5083435 -0.08598697 -0.4246984 0.9042735 -0.04382759 -0.9053279 0.4200581 -0.06271213 -0.8584433 0.5060895 -0.08335793 -0.3260631 0.9445888 -0.03787851 -0.5635436 0.8259635 -0.01425063 -0.8907657 0.453631 0.02748256 -0.7412937 0.6701945 0.03637486 -0.5732603 0.81936 0.004689812 -0.935816 0.3474394 0.05945122 -0.1039113 0.994586 0.001120269 -0.9187604 0.3574225 0.1677155 -0.4118567 0.9100215 0.04727554 -0.8973175 0.415627 0.1485792 -0.6531984 0.7481981 0.1163253 -0.6941905 0.7073678 0.1331558 -0.458086 0.8855664 0.07700335 -0.8962389 0.361663 0.2568184 -0.9158052 0.313579 0.2509365 -0.7425631 0.6323447 0.220772 -0.2748382 0.9580113 0.081721 -0.8636016 0.3735599 0.3385932 -0.6680455 0.6972557 0.2599032 -0.6847004 0.6807619 0.2602857 -0.8916376 0.2179838 0.3968194 -0.4285161 0.8866386 0.173914 -0.8458593 0.3140037 0.4311889 -0.4031725 0.8950762 0.1905013 -0.6893343 0.6358377 0.3471727 -0.8396883 0.2478843 0.4831948 -0.619919 0.7011188 0.3523252 -0.5675358 0.7555571 0.3271645 -0.7201051 0.5040214 0.4768766 -0.7068261 0.5026963 0.4976881 -0.4029277 0.8677152 0.2910663 -0.7651653 0.1934229 0.6140925 -0.2030957 0.9707601 0.1279723 -0.596099 0.6435201 0.4801543 -0.4275145 0.8406355 0.3325105 -0.6290636 0.5050969 0.5908944 -0.6209911 0.5050677 0.599397 -0.6518705 0.2788326 0.7052073 -0.4616251 0.7193303 0.5191013 -0.313781 0.8961827 0.3136846 -0.5712565 0.3365266 0.7486093 -0.5225454 0.4610695 0.7171899 -0.162257 0.9692173 0.1851772 -0.4515613 0.7056149 0.546077 -0.2557443 0.8794069 0.401545 -0.4684764 0.4983469 0.729507 -0.3581654 0.701789 0.6158001 -0.265293 0.8851352 0.3823028 -0.4556012 0.3076309 0.8353388 -0.3463345 0.5193274 0.7812501 -0.3261301 0.7030153 0.631988 -0.1644966 0.9105406 0.3792843 -0.1387151 0.9495883 0.2811411 -0.3289718 0.5099228 0.7948312 -0.2664708 0.5948703 0.7583684 -0.1592301 0.8925473 0.4219068 -0.272964 0.5976815 0.7538352 -0.2222678 0.3499246 0.9100274 -0.1416458 0.7603605 0.6338679 -0.1051681 0.8619627 0.4959435 -0.09947723 0.9124287 0.3969613 -0.1902053 0.411906 0.891154 -0.147838 0.6017249 0.7849021 -0.1017906 0.2513765 0.962522 -0.0507186 0.5186064 0.8535075 -0.08296245 0.4537332 0.8872674 -0.01919084 0.7266848 0.686703 -0.03250694 0.8697755 0.4923759 -0.00528562 0.9981956 0.05981308 0.05185705 0.3315129 0.9420244 0.04503124 0.3708232 0.9276112 0.004871845 0.9713184 0.237733 0.03895467 0.6669452 0.7440879 0.08164376 0.7560839 0.6493625 0.1392632 0.2600265 0.9555062 0.02510529 0.9551184 0.2951586 0.1767373 0.4797151 0.8594402 0.1374157 0.7050976 0.6956683 0.1356927 0.7089411 0.6920911 0.2728139 0.3125077 0.9098964 0.108113 0.9258457 0.3621068 0.3100639 0.4538645 0.8353847 0.06135392 0.9700725 0.2349363 0.2256299 0.7154933 0.6611812 0.194068 0.8447061 0.4988077 0.3621616 0.3841248 0.8492863 0.3899046 0.4519872 0.802298 0.2255645 0.8600865 0.4575718 0.3141788 0.7549231 0.5756587 0.4900218 0.311078 0.8143151 0.1295143 0.967562 0.21691 0.4650486 0.6039252 0.6473054 0.4582842 0.5972945 0.6581907 0.5855479 0.4201949 0.6932316 0.3092496 0.8766976 0.3684644 0.6028546 0.4423562 0.6639934 0.7018754 0.2102289 0.6805694 0.532486 0.6764021 0.5088604 0.3128551 0.8945537 0.3192107 0.3258227 0.8869711 0.3272947 0.70388 0.43196 0.5638825 0.6303689 0.5840205 0.5114246 0.7698555 0.2851296 0.570985 0.552654 0.7424516 0.3786017 0.4191325 0.8572517 0.2990778 0.8261994 0.3432715 0.4467207 0.7713559 0.4518339 0.44817 0.6220159 0.6836927 0.3816549 0.8493714 0.3593565 0.3865633 0.1930255 0.9756955 0.1037282 0.5431237 0.8051224 0.2383163 0.7315891 0.6235765 0.2755536 0.3628658 0.9189562 0.1544277 0.8900628 0.3823379 0.2482056 0.7672421 0.5929033 0.2445511 0.9288211 0.3047868 0.2107047 0.6451544 0.7513101 0.1389573 0.8206712 0.5593526 0.1167204 0.3395778 0.9385251 0.06211072 0.3499252 0.9346609 0.06293946 0.8422095 0.5340731 0.07381802 0.781167 0.6236541 0.02887302 0.5297062 0.8480443 0.01524263 -0.005403757 0.999985 -9.13619e-4 -0.003470659 0.9999894 0.00303924 -8.90499e-4 0.9999859 0.005239188 -5.22626e-4 0.9999996 8.07748e-4 -0.001526474 0.9999986 8.05622e-4 -2.25943e-4 0.9999994 0.001139938 -0.002470612 0.999997 -2.0557e-4 -0.001709342 0.9999985 4.70595e-4 -2.78831e-4 0.9999994 0.001134276 -0.001888155 0.9999949 0.002562522 -7.58305e-4 0.9999995 6.93917e-4 -2.71225e-5 1 -1.01893e-5 2.25934e-5 1 2.57396e-4 -2.52544e-5 1 0 9.59164e-5 1 2.55823e-4 -7.06304e-4 0.9999953 -0.003005564 0.006990909 0.9999716 0.002852261 -6.21907e-4 0.9999916 0.004058957 -0.002637684 0.9999952 -0.001629292 0.001170337 0.9999983 0.00146228 -0.00290364 0.9999951 -0.001170754 -0.001648902 0.9999971 -0.001721084 0.001564681 0.999998 0.001239001 0.006958663 0.9999759 2.13331e-5 -0.002655267 0.9999964 -5.24137e-4 9.62001e-4 0.9999859 0.005238533 -3.99954e-4 0.9999997 -8.44482e-4 7.19941e-4 0.9999997 3.13734e-4 -4.70526e-4 0.9999997 -7.83193e-4 -4.78099e-5 0.9999999 -5.27289e-4 0.002440392 0.9999911 -0.003434002 0.003816604 0.9999927 3.0499e-4 0.003376066 0.9999917 0.002312779 1.24812e-4 1 -5.07788e-4 0.002931714 0.9999944 -0.001644849 0.001250803 0.9999992 -3.53751e-4 4.99819e-4 0.9999982 -0.001883029 7.83197e-4 0.9999988 -0.001383006 0.001258432 0.9999992 -2.83295e-4 9.77435e-4 0.9999994 -6.41722e-4 8.29955e-4 0.999999 -0.001228153 0.00112152 0.9999988 -0.001134157 0.9963498 0.0473836 -0.07100725 0.9717908 -0.03279834 -0.2335528 0.9725165 -0.0458455 -0.2282761 0.9538491 0.03972065 -0.2976478 0.9044355 0.06240874 -0.422021 0.8678385 -0.003705978 -0.4968327 0.8510143 -0.0685116 -0.5206543 0.7842929 0.04225754 -0.6189498 0.7254988 0.03508198 -0.6873288 0.6721642 -0.06332558 -0.7376891 0.6431825 4.09657e-4 -0.7657129 0.555027 0.07193839 -0.8287159 0.426679 -0.01449728 -0.9042869 0.4180506 -0.03158813 -0.9078745 0.346143 0.02494627 -0.9378501 0.1888841 -0.03947567 -0.9812057 0.2290576 0.01219779 -0.9733365 0.1212922 0.0380361 -0.9918879 -0.0999844 -0.05315363 -0.9935683 -0.05923682 0.01117366 -0.9981815 -0.1593583 0.02566611 -0.9868872 -0.2541773 0.06963807 -0.9646474 -0.3865565 -0.0122736 -0.9221841 -0.4250516 -0.08964341 -0.9007192 -0.4882839 0.02364522 -0.8723646 -0.6412777 0.06534868 -0.7645211 -0.706551 -0.1031759 -0.7001004 -0.7745294 0.05354046 -0.6302679 -0.8659877 0.04595828 -0.4979491 -0.8962176 -0.05586129 -0.4400836 -0.9324746 0.04511988 -0.3584068 -0.9728726 -0.03080314 -0.2292819 -0.9798727 0.01436024 -0.1991068 -0.9995182 -0.01985043 -0.02386438 -0.9954805 0.03111422 -0.08972477 -0.9992612 0.03406554 0.01779669 -0.9840595 0.01579898 0.1771367 -0.9776621 -0.03573471 0.2071229 -0.9449132 0.04267179 0.3245278 -0.9137879 -0.03592598 0.4046 -0.8914473 0.02427631 0.4524739 -0.8159584 -0.01387238 0.5779442 -0.8332137 0.01522362 0.5527417 -0.7829676 0.03499555 0.6210774 -0.6852074 -0.01961863 0.7280838 -0.6758096 0.003287434 0.737069 -0.6038771 0.05224555 0.7953634 -0.5134837 7.13727e-6 0.8580995 -0.5479949 -0.07226592 0.8333543 -0.4340177 0.04681831 0.899687 -0.326898 0.03706103 0.9443327 -0.2673299 -0.06411749 0.9614696 -0.1736467 0.03582912 0.984156 -0.01951795 -0.04920023 0.9985983 -0.04556035 0.003494441 0.9989555 0.1397837 0.08266562 0.9867253 0.2835953 -0.03619515 0.9582607 0.2916002 -0.05391645 0.9550197 0.3976798 0.05042439 0.9161376 0.5234352 -0.05184596 0.8504868 0.5597288 0.03331047 0.8280062 0.7329493 -0.04194885 0.6789887 0.7085053 0.02748268 0.7051702 0.8133353 0.04155939 0.5803091 0.8695589 -0.0496571 0.4913264 0.8908492 0.02360844 0.4536852 0.9244479 0.06799411 0.3751972 0.9658232 -0.001307845 0.2591985 0.9692409 -0.03490865 0.2436258 0.9956161 0.04293006 0.08310055 0.9990784 -0.04059416 0.01395225 0.9966962 -0.03247153 -0.07444697 0.9855196 -0.01917463 -0.1684745 0.9891396 0.01710641 -0.1459804 0.9569742 -0.06299579 -0.2832525 0.8899254 -0.04385316 -0.4539933 0.9175949 0.04997986 -0.3943623 0.8444572 -0.01364368 -0.5354493 0.8267167 0.02553975 -0.5620384 0.7767646 -0.04213339 -0.6283802 0.6888509 0.008375167 -0.7248547 0.6674409 0.05291432 -0.7427805 0.6121622 -0.03005385 -0.7901608 0.5229994 -0.06004226 -0.8502156 0.3866409 -0.02195674 -0.921969 0.4337488 0.06085658 -0.8989763 0.2549005 -0.03141909 -0.9664567 0.1821672 0.05737036 -0.9815924 0.1443418 -0.003414392 -0.989522 0.002690553 -0.05797129 -0.9983147 -0.1384572 0.02059942 -0.9901542 -0.1153832 0.06816112 -0.9909798 -0.297859 -0.08262109 -0.9510278 -0.4172515 0.0592693 -0.9068563 -0.4612061 -0.01821225 -0.8871061 -0.5600852 -0.02999192 -0.827892 -0.622313 0.04186564 -0.7816482 -0.6510354 -0.01524513 -0.7588944 -0.7142508 -0.06539583 -0.696828 -0.7832391 -0.0316807 -0.6209129 -0.805646 0.04552572 -0.5906456 -0.8837413 -0.03837972 -0.4663994 -0.930688 -0.02576452 -0.3649058 -0.9141905 0.02021753 -0.4047801 -0.9750686 -0.002910733 -0.2218846 -0.9802752 0.04251778 -0.1930099 -0.9938921 -0.06163126 -0.0915426 -0.9990306 -0.03703141 0.02380484 -0.9938277 0.05446135 0.09664762 -0.991497 0.004309833 0.1300585 -0.9605707 -0.04055029 0.2750631 -0.9462912 0.01340597 0.3230378 -0.9291319 -0.02564787 0.3688578 -0.8724399 -0.007124662 0.4886698 -0.8528513 0.04516732 0.5201967 -0.8080213 -0.04539173 0.5874021 -0.7503257 -0.05464231 0.6588063 -0.6728422 0.04675 0.7383074 -0.6869438 0.001676321 0.7267086 -0.5376796 -0.01338112 0.8430431 -0.4952054 0.04131352 0.8677931 -0.4346983 -0.05289858 0.8990212 -0.2620447 -0.01952207 0.9648584 -0.2189563 0.0695151 0.9732553 -0.1039647 -0.05056703 0.9932948 0.05309355 0.04076868 0.9977571 0.05306905 0.04085248 0.9977549 0.2084056 -0.07245498 0.975355 0.3282324 0.05740803 0.942851 0.375308 -0.01964432 0.9266921 0.4866834 -0.01890254 0.8733739 0.5239031 0.0371533 0.8509673 0.5973116 -0.04374688 0.8008153 0.6987109 0.004977405 0.7153869 0.699184 0.006033241 0.7149164 0.7850165 -0.02953201 0.6187706 0.8230633 0.03954249 0.5665717 0.8654927 -0.05980324 0.4973391 0.9112158 -0.05442702 0.4083179 0.9457595 0.03282839 0.3232049 0.9456166 0.03186929 0.3237184 0.9744421 -0.04612785 0.2198522 0.9970774 0.004481732 0.07626795 0.9961016 0.02101498 0.08567458 0.9526042 -0.2966898 0.06723493 0.2608301 -0.9653566 0.007374584 0.8942951 -0.4347421 0.1059979 0.719074 -0.6905542 0.07789528 0.6549271 -0.7490402 0.1000463 0.902131 -0.3885136 0.1876619 0.8248385 -0.5230293 0.214667 0.4424051 -0.8925625 0.08723527 0.3307791 -0.9418034 0.0599308 0.8004517 -0.5411395 0.2577699 0.7696511 -0.5796947 0.2675656 0.1438854 -0.9885138 0.04623204 0.5532816 -0.8102654 0.1932605 0.7760018 -0.530209 0.3416134 0.3913726 -0.902234 0.181111 0.7239904 -0.5796378 0.3739759 0.770943 -0.4283027 0.471385 0.4454374 -0.8592272 0.251623 0.7039529 -0.4670221 0.5351082 0.3868405 -0.8829771 0.2659061 0.7064264 -0.4628815 0.5354461 0.4413363 -0.8253698 0.3521182 0.6169937 -0.5023858 0.6057453 0.4978487 -0.7000538 0.5119291 0.4207205 -0.824325 0.3787909 0.6447197 -0.3237115 0.6924936 0.5656906 -0.3473634 0.7478855 0.5302389 -0.4235391 0.7344803 0.2121201 -0.9436408 0.2540611 0.4282345 -0.7273426 0.5362723 0.3016334 -0.8533046 0.42531 0.472975 -0.4321494 0.7678163 0.4602755 -0.3349779 0.8221534 0.3089668 -0.7601101 0.57164 0.2797695 -0.8338827 0.4757823 0.3506545 -0.3128926 0.8826889 0.3661791 -0.4067854 0.8369221 0.2827165 -0.700999 0.6547303 0.1053478 -0.9574642 0.2686342 0.2316556 -0.7501239 0.6193949 0.2642242 -0.4051057 0.8752571 0.1909506 -0.6840589 0.7039896 0.2060038 -0.6720486 0.7112758 0.06800711 -0.9772959 0.2006685 0.2045606 -0.2209707 0.9535863 0.1528978 -0.3695465 0.9165467 0.07138812 -0.9067841 0.4155075 0.1394436 -0.6195034 0.7725097 0.07488471 -0.7362723 0.6725291 0.06072115 -0.8966012 0.4386564 0.04634177 -0.279562 0.9590086 0.05533742 -0.2484534 0.9670619 0.02164542 -0.6543974 0.7558409 -0.05335658 -0.3515416 0.9346505 0.008189082 -0.9434229 0.331491 -0.0277704 -0.6784579 0.7341143 -0.04590553 -0.6237704 0.7802585 -0.1011105 -0.2104417 0.9723637 -0.04085397 -0.8548871 0.5172032 -0.1901522 -0.400943 0.8961512 -0.06833803 -0.8608835 0.5041919 -0.162733 -0.6002558 0.783078 -0.1640407 -0.6820893 0.7126323 -0.2544375 -0.2096605 0.944089 -0.2037541 -0.7332096 0.6487588 -0.06728422 -0.9799205 0.1876934 -0.06757986 -0.9797782 0.188329 -0.3498664 -0.4300695 0.8322463 -0.2871776 -0.6458541 0.7073907 -0.3940378 -0.3384737 0.8544997 -0.3054732 -0.7406616 0.59842 -0.1120721 -0.9624025 0.2474296 -0.4503473 -0.5467098 0.7059007 -0.3306269 -0.7322811 0.5953573 -0.5154844 -0.4112525 0.7517628 -0.2586582 -0.8861113 0.3845813 -0.462401 -0.5349902 0.7070863 -0.4495649 -0.6781702 0.5813576 -0.2683415 -0.888172 0.3730194 -0.6261732 -0.3159859 0.7127834 -0.5971489 -0.5113415 0.6180155 -0.5216376 -0.6410012 0.5630381 -0.2254978 -0.9419851 0.2486258 -0.3997775 -0.8310388 0.3867203 -0.6670472 -0.4451366 0.5974124 -0.1231967 -0.9851814 0.1193327 -0.7613534 -0.3882881 0.5192045 -0.6725341 -0.5544044 0.4902384 -0.6236808 -0.6441395 0.4428391 -0.5070614 -0.7777314 0.3715143 -0.8418658 -0.2570942 0.4745152 -0.3846353 -0.8887687 0.2492908 -0.3317173 -0.9185202 0.2151378 -0.8070699 -0.462873 0.3665883 -0.7496644 -0.5759997 0.325926 -0.6770825 -0.6640347 0.3172024 -0.5404142 -0.8008663 0.2580031 -0.371825 -0.918543 0.1342577 -0.7581147 -0.5875433 0.2829402 -0.1829628 -0.9804939 0.07180804 -0.9240524 -0.2934731 0.2449505 -0.6262368 -0.7639155 0.1557588 -0.8892515 -0.4221636 0.1760959 -0.6197199 -0.7681179 0.1610658 -0.9110912 -0.3938253 0.1217147 -0.8951464 -0.4339512 0.1019765 -0.5809388 -0.8110787 0.06827658 -0.06111776 -0.9980262 0.01444208 -0.6345833 -0.7670558 0.0944972 -0.178407 -0.9838606 0.0137577 -0.9315983 -0.3630892 0.01706016 -0.8956333 -0.4433462 -0.03585159 -0.576574 -0.817045 -1.33233e-4 -0.2659406 -0.9639893 -6.24377e-4 -0.6279822 -0.7779044 -0.02243226 -0.9210007 -0.3833895 -0.06906741 -0.906448 -0.3607048 -0.2196457 -0.572378 -0.8136872 -0.1014725 -0.8572544 -0.4855626 -0.1713014 -0.6509663 -0.7459542 -0.1406955 -0.2699205 -0.9610348 -0.05962425 -0.2377103 -0.9700726 -0.04952883 -0.8523719 -0.4270331 -0.3018358 -0.6323417 -0.7460336 -0.2087533 -0.8597431 -0.3975144 -0.3206622 -0.5453839 -0.8113539 -0.2103834 -0.3532939 -0.9266165 -0.1287069 -0.8328477 -0.3092382 -0.4590606 -0.7753415 -0.4925534 -0.395268 -0.6382238 -0.6877259 -0.345982 -0.5908758 -0.7492356 -0.2991852 -0.1531908 -0.9838518 -0.09256458 -0.5729121 -0.7207946 -0.3901628 -0.7680703 -0.2822726 -0.574796 -0.1300117 -0.9887514 -0.07394343 -0.631999 -0.585141 -0.5081214 -0.3103554 -0.9164893 -0.2524425 -0.5671443 -0.6286984 -0.5320581 -0.3193631 -0.9018846 -0.2908805 -0.5739516 -0.5755099 -0.5825529 -0.5622271 -0.4268952 -0.7082805 -0.5520963 -0.5704809 -0.6080636 -0.2131687 -0.9438571 -0.2523747 -0.5132794 -0.4269121 -0.7445068 -0.4906171 -0.4635483 -0.7378468 -0.3632646 -0.7422813 -0.5630784 -0.331892 -0.8137525 -0.4771316 -0.2653918 -0.8874367 -0.3768598 -0.430507 -0.3342823 -0.8384028 -0.34176 -0.4988664 -0.79645 -0.1437264 -0.9450201 -0.2937342 -0.2827332 -0.6715728 -0.6848738 -0.2772316 -0.7377753 -0.615492 -0.0798071 -0.9763893 -0.2007356 -0.2906065 -0.2097172 -0.9335773 -0.2356751 -0.7044345 -0.6694993 -0.1835375 -0.4567954 -0.8704321 -0.1134202 -0.8778378 -0.465335 -0.1762743 -0.5533908 -0.8140553 -0.1341406 -0.683645 -0.7173813 -0.1425095 -0.3357731 -0.9311003 -0.09462594 -0.8469739 -0.5231456 -0.04445344 -0.4904149 -0.8703547 0.008860528 -0.249617 -0.9683042 -0.036426 -0.8860843 -0.4620908 -0.02800738 -0.497682 -0.8669072 0.01587921 -0.6643106 -0.7472879 0.1355176 -0.4063457 -0.9036141 0.04090619 -0.6643002 -0.7463458 0.01138919 -0.9819468 -0.1888143 0.1295887 -0.4150348 -0.9005293 0.1703243 -0.4417254 -0.8808339 0.08890253 -0.8915075 -0.4441967 0.2372687 -0.328234 -0.9143118 0.1738504 -0.7550086 -0.6322484 0.1042124 -0.8801574 -0.4631013 0.3028339 -0.4536661 -0.8381401 0.2302466 -0.6973652 -0.6787255 0.363639 -0.3654163 -0.8568768 0.3869889 -0.4296714 -0.8158567 0.1327303 -0.9376848 -0.3211388 0.2633528 -0.7948477 -0.5466833 0.2508507 -0.8361535 -0.4877718 0.4811087 -0.3527609 -0.8025549 0.257467 -0.8363164 -0.4840307 0.4864528 -0.5163673 -0.7047898 0.4990682 -0.521352 -0.6921873 0.2454498 -0.9067842 -0.3427781 0.3728385 -0.8104886 -0.4517739 0.5664951 -0.4348806 -0.699973 0.43579 -0.7699701 -0.4660829 0.6488996 -0.3527432 -0.6741673 0.5905729 -0.4387081 -0.6773174 0.09870541 -0.9886469 -0.1132902 0.6763259 -0.4272397 -0.6000415 0.4634112 -0.7860704 -0.4090765 0.7239464 -0.3641136 -0.5859376 0.4548131 -0.8001867 -0.3909556 0.7329909 -0.4230622 -0.5326751 0.3536564 -0.8922153 -0.2808543 0.6871396 -0.5611926 -0.4614132 0.3490534 -0.9082623 -0.2306978 0.6855354 -0.5901683 -0.4263128 0.8706802 -0.2549991 -0.4205849 0.6195484 -0.7041999 -0.3467887 0.859637 -0.3389363 -0.3822911 0.2273719 -0.9664086 -0.1198189 0.6504239 -0.7002323 -0.2943189 0.6287874 -0.7313728 -0.264046 0.8948858 -0.3291479 -0.3013983 0.4642634 -0.86792 -0.1765625 0.7889885 -0.5714468 -0.2257119 0.779664 -0.5930308 -0.2010934 0.6484886 -0.7485304 -0.1384374 0.8964251 -0.4132942 -0.1600313 0.4638895 -0.879549 -0.1058308 0.4035744 -0.9113771 -0.0807439 0.9193543 -0.3932382 -0.01231753 0.7811997 -0.6232103 -0.03655141 0.7819538 -0.6218627 -0.04283785 0.6814214 -0.7318156 -0.01053285 0.4099403 -0.9119081 -0.01930606 0.005611419 -0.9999651 0.006196975 0.005583643 -0.9999696 0.005445241 0.00392425 -0.9999629 0.007685065 0.00350517 -0.9999914 0.002230882 0.00431472 -0.9999727 0.006020307 0.00132811 -0.9999946 0.003031373 0.004297971 -0.9999897 0.001465857 0.001725018 -0.9999961 0.002181053 3.41583e-4 -0.9999964 0.002661406 0.001259863 -0.9999992 1.43123e-4 0.004679262 -0.9999818 -0.003827214 -0.003940761 -0.9999739 0.006069183 0.004483044 -0.9999812 -0.004196226 0.009399235 -0.9999545 -0.001622557 -0.001205503 -0.999972 0.007401466 -1.3217e-4 -0.9999761 0.006917417 0.009949147 -0.9999506 -7.07499e-5 -9.66441e-4 -0.9999966 0.002430379 0.001707375 -0.9999982 -8.29511e-4 -7.31569e-4 -0.9999961 0.00271511 6.29493e-4 -0.9999996 -7.82631e-4 0.001279175 -0.9999985 -0.001246809 0.001989543 -0.9999805 -0.005917906 6.01188e-4 -0.9999998 -4.15999e-4 0.006922006 -0.9999595 -0.005746185 0.001104474 -0.9999974 -0.002025783 8.51984e-4 -0.9999997 -2.59047e-4 4.57531e-4 -0.9999979 -0.002000212 4.80082e-5 -1 -3.55593e-4 -8.738e-4 -0.999992 -0.003937721 -3.55854e-4 -1 1.27692e-5 -4.7662e-4 -0.9999902 -0.004413604 -3.47345e-4 -1 -7.82955e-5 -0.003412246 -0.9999887 -0.003323376 -0.001324355 -0.9999884 -0.00464642 -0.003748178 -0.999992 -0.001420736 -0.001574039 -0.999993 -0.003405511 -0.002151072 -0.9999968 -0.001364231 -0.002317607 -0.9999933 -0.00285089 -9.37924e-4 -0.9999963 -0.002608716 0.6818575 0.7312858 -0.01706963 0.9655502 0.2503314 -0.07104271 0.4580494 0.8888751 -0.009595215 0.3990006 0.9167488 -0.01923871 0.8729639 0.4653163 -0.1463383 0.8142564 0.5616226 -0.1468557 0.783692 0.600274 -0.159681 0.4140929 0.9054824 -0.0928902 0.4069749 0.9086037 -0.0938664 0.8947795 0.3098472 -0.3215036 0.7767891 0.5880917 -0.2252708 0.5961257 0.7668607 -0.2378211 0.8749964 0.3147752 -0.3678287 0.1072551 0.9934737 -0.038814 0.749044 0.5486823 -0.3713231 0.6010226 0.7656374 -0.2292842 0.8211476 0.2673537 -0.5042209 0.4143857 0.8843934 -0.2147855 0.7349759 0.5525465 -0.3930686 0.2760884 0.9500879 -0.1452866 0.6334039 0.6704901 -0.3863193 0.5041522 0.8076385 -0.3058605 0.7645398 0.3409191 -0.5470405 0.6760209 0.5296628 -0.5123018 0.6115139 0.5894747 -0.5277978 0.5298548 0.708374 -0.4663262 0.641146 0.429643 -0.6358764 0.3823398 0.8684759 -0.3155409 0.2421158 0.9435969 -0.2258428 0.1519625 0.9792815 -0.1338474 0.5758087 0.4173432 -0.7030428 0.3712836 0.8271581 -0.4218508 0.5747276 0.4510236 -0.6828367 0.3066722 0.8882679 -0.3419539 0.4197164 0.7389077 -0.5271182 0.5143443 0.3835428 -0.7670364 0.5145868 0.3737242 -0.7717064 0.3469925 0.7392076 -0.5772074 0.3421831 0.7521139 -0.5632367 0.219087 0.9065738 -0.3607283 0.4206101 0.3499808 -0.837019 0.3573533 0.5215839 -0.7747573 0.3324162 0.6516473 -0.681803 0.1121039 0.9674139 -0.2270312 0.2796035 0.3766351 -0.883158 0.276705 0.484824 -0.8296868 0.2034335 0.6681573 -0.715668 0.2348778 0.266068 -0.9349012 0.1869071 0.8132519 -0.5510782 0.1365814 0.9015576 -0.4105355 0.1429942 0.4872614 -0.8614692 0.1632573 0.6551771 -0.7376246 0.0875675 0.4087763 -0.908424 0.09141123 0.4401957 -0.8932366 0.0457524 0.9463461 -0.3198996 0.06959408 0.8305133 -0.552634 0.04591304 0.9486155 -0.3130824 0.0321002 0.7171694 -0.6961593 -7.7054e-4 0.7379084 -0.6749005 -0.02868437 0.2851449 -0.9580552 -0.02054762 0.8615735 -0.5072171 -0.06308227 0.5610167 -0.8253976 -0.05611383 0.89459 -0.4433509 -0.1489542 0.6153953 -0.7740164 -0.1602693 0.5921199 -0.7897517 -0.09672778 0.8512493 -0.5157697 -0.2732056 0.3412664 -0.8993864 -0.2078858 0.558164 -0.8032662 -0.01873326 0.9963716 -0.08302342 -0.3548163 0.2796185 -0.892143 -0.373161 0.4870154 -0.7896625 -0.1299625 0.9188429 -0.3726091 -0.2619847 0.6953771 -0.6691896 -0.1829718 0.8810777 -0.4361463 -0.4383513 0.4656704 -0.7687647 -0.4239389 0.3705611 -0.8264141 -0.2082722 0.8982041 -0.3871074 -0.3524906 0.7572352 -0.5498593 -0.2731389 0.8527973 -0.4451202 -0.5321625 0.4311181 -0.7286565 -0.4642555 0.6437906 -0.6082767 -0.631807 0.1788419 -0.7542119 -0.04604125 0.9968838 -0.0640549 -0.6144178 0.4821177 -0.6245425 -0.4868269 0.6724777 -0.5574705 -0.2436853 0.9327461 -0.265711 -0.3750619 0.8484201 -0.3735131 -0.6509255 0.4852291 -0.5838225 -0.283756 0.9136531 -0.2910681 -0.5240802 0.730869 -0.4372304 -0.7354719 0.3296249 -0.5919702 -0.7471544 0.4007627 -0.5302355 -0.6269317 0.6670812 -0.4024416 -0.5620332 0.739678 -0.3701287 -0.8412017 0.2301986 -0.4892733 -0.4370868 0.8622251 -0.2559746 -0.1739229 0.9786887 -0.1091758 -0.7905308 0.459149 -0.4052698 -0.1916781 0.9744815 -0.1168137 -0.876784 0.349594 -0.3302026 -0.8044845 0.4821888 -0.3468412 -0.6041176 0.7614606 -0.2349886 -0.8568107 0.4678211 -0.2168388 -0.5642235 0.805634 -0.1805708 -0.4948819 0.8574277 -0.1411024 -0.8755177 0.4425688 -0.1939112 -0.2695577 0.9595825 -0.08087033 -0.845227 0.5158549 -0.1395886 -0.5660577 0.8184351 -0.09870576 -0.8716907 0.4795899 -0.1007426 -0.1343666 0.9905812 -0.02635622 -0.4755663 0.8792017 -0.02900278 -0.823305 0.5673196 -0.01781809 -0.7690277 0.6391689 -0.007719635 -0.9492327 0.3125541 0.03559917 -0.4674186 0.8834228 -0.03292578 -0.6810144 0.7297177 0.06108707 -0.4396978 0.8971516 0.0422489 -0.4249292 0.9044733 0.03692227 -0.950336 0.2583248 0.1735789 -0.909637 0.3926941 0.13547 -0.7873405 0.6033033 0.1269651 -0.8887135 0.3685698 0.272662 -0.4572029 0.8837158 0.1000608 -0.6844904 0.7042686 0.1883578 -0.9087684 0.2777066 0.311479 -0.6859354 0.702834 0.1884597 -0.5443602 0.8165203 0.1922668 -0.5628879 0.7923479 0.2352491 -0.3000011 0.948844 0.09846162 -0.8143982 0.4123051 0.4083626 -0.8158379 0.4065571 0.4112417 -0.6835963 0.6489573 0.3339918 -0.07713627 0.9963379 0.03688824 -0.791792 0.3773393 0.480292 -0.6875966 0.5318968 0.4942639 -0.2892584 0.9396722 0.1826084 -0.5981926 0.6659505 0.4457306 -0.7450677 0.2447978 0.620442 -0.5089554 0.7850537 0.3530651 -0.390613 0.8777734 0.2773721 -0.6723989 0.3437503 0.6555269 -0.5709174 0.5685037 0.5923317 -0.5440312 0.643661 0.5382664 -0.3059507 0.9029245 0.3018637 -0.3134028 0.8954156 0.3162431 -0.5164623 0.5595154 0.6482356 -0.2653741 0.903483 0.3365935 -0.4350809 0.6515221 0.6214689 -0.4438349 0.4326654 0.7847365 -0.4179072 0.6369934 0.6477602 -0.142188 0.9632559 0.2278612 -0.2815849 0.7830721 0.5545341 -0.3802121 0.390409 0.8384627 -0.3808817 0.4565528 0.8040453 -0.06605893 0.9900978 0.1238658 -0.2641178 0.7440767 0.6136708 -0.3081412 0.2839729 0.9079694 -0.1887406 0.7996533 0.5700278 -0.1568567 0.8424018 0.5155145 -0.2204984 0.4470885 0.8668866 -0.1784298 0.4246174 0.8876164 -0.1111416 0.8558105 0.5052089 -0.1452958 0.4833492 0.863286 -0.09594762 0.6895423 0.7178618 -0.03639125 0.2942904 0.9550229 -0.02819818 0.9550197 0.2951986 -0.01860129 0.7233639 0.6902165 -0.02593755 0.3334667 0.9424051 -0.001481235 0.7572267 0.6531506 1.0115e-5 0.9996376 0.02692025 0.003451526 0.8763089 0.4817374 0.09679776 0.4361734 0.8946413 0.08521401 0.5975148 0.7973173 0.1319795 0.3124774 0.9407122 0.05840969 0.9302783 0.3621748 0.1435291 0.7637277 0.6293802 0.2516849 0.3895717 0.8859394 0.1200922 0.8613176 0.4936698 0.257788 0.5120224 0.819377 0.2895269 0.5279686 0.7983881 0.3883939 0.3288457 0.8608198 0.1552842 0.8913515 0.4258867 0.2666344 0.7653349 0.5858061 0.4379508 0.4448381 0.7812287 0.3301032 0.7349203 0.5923885 0.06426709 0.9905762 0.1209492 0.5421128 0.2443883 0.8039826 0.3292567 0.7706962 0.5455434 0.555246 0.4889604 0.6727702 0.2184678 0.9249892 0.3109131 0.4963287 0.6272611 0.6001679 0.6896394 0.2441834 0.681742 0.4273157 0.7876291 0.443894 0.3002735 0.8968236 0.3248745 0.695037 0.4076368 0.5922465 0.2070291 0.9590423 0.1933311 0.5436295 0.7024863 0.4593256 0.7863859 0.2553963 0.5624678 0.5176793 0.7724788 0.3678107 0.7769572 0.4335884 0.4564413 0.3269801 0.9212306 0.2107563 0.3130636 0.9276661 0.203536 0.7322657 0.5399404 0.4150319 0.7170363 0.6128342 0.3321042 0.4374945 0.8791784 0.1887963 0.8183755 0.4819766 0.3129858 0.521451 0.826185 0.2133241 0.9061943 0.3571893 0.2263352 0.8212445 0.5104206 0.2550067 0.6193395 0.7655125 0.1743823 0.8845844 0.4451035 0.1392607 0.7048395 0.7018374 0.1030803 0.1682847 0.9847186 0.04482871 0.566534 0.8163661 0.1121857 0.4341653 0.8979178 0.07241666 0.9450772 0.3169065 0.07999724 0.8877956 0.4597463 0.02126967 0.7672651 0.6412357 0.01100254 -0.004411876 0.9999887 0.00178349 -0.004430055 0.9999821 0.004053711 -0.002331554 0.9999852 0.004927873 -0.005612671 0.9999786 0.003390848 -0.00483793 0.9999853 0.002444028 -0.002560675 0.9999838 0.005091369 -0.004332542 0.9999902 9.96173e-4 -0.004903078 0.999988 -1.98711e-4 -5.7944e-4 0.9999855 0.00537765 -2.78249e-4 0.9999826 0.005896747 -0.005023777 0.9999874 4.5546e-5 -0.004325866 0.9999896 0.001462578 9.38471e-4 0.9999905 0.004262268 -6.97366e-4 0.9999998 -2.02005e-4 0.001816451 0.99999 0.004091858 0.00209701 0.9999888 0.00424838 -5.74196e-4 0.9999988 -0.001491427 -0.002152204 0.9999967 -0.001447498 0.002472102 0.9999931 0.002809703 -0.001692116 0.9999969 -0.001857995 0.001313984 0.9999946 0.00302118 -0.001574397 0.9999939 -0.003136456 0.001913964 0.9999973 0.001370906 -0.001748502 0.9999936 -0.003160536 0.00620675 0.9999808 -3.38056e-4 0.005612909 0.9999819 0.002189755 -9.05317e-4 0.9999927 -0.003744423 0.007145643 0.9999735 0.001473605 -2.59213e-5 0.9999781 -0.00661683 0.007691085 0.9999673 0.002505719 0.00436443 0.9999905 4.23016e-4 7.3995e-4 0.9999786 -0.006500542 -0.001241505 0.9999906 -0.004166364 0.003672897 0.9999932 -6.07775e-4 0.00311309 0.9999951 4.61675e-4 0.003369271 0.9999892 -0.003216862 0.003132164 0.9999764 -0.006118476 6.18683e-4 0.9999998 -3.52377e-4 0.00430727 0.9999792 -0.004820227 5.70883e-4 0.9999887 -0.004727065 0.9946591 0.05777335 -0.08553034 0.9824204 0.03525704 -0.1833224 0.9671179 -0.04836797 -0.2496874 0.960755 -0.003055095 -0.2773817 0.9312805 0.04254376 -0.3618103 0.8849415 -0.03878551 -0.4640845 0.8822656 -0.02421605 -0.4701288 0.8423241 0.05153888 -0.5365015 0.7833266 0.04346179 -0.6200892 0.7370147 -0.04925256 -0.6740799 0.7146426 0.001025378 -0.6994891 0.6354972 0.04628694 -0.7707145 0.5954838 -0.0409156 -0.8023248 0.4780972 0.06273591 -0.8760637 0.4024314 -0.04260879 -0.914458 0.3512122 0.02900743 -0.9358465 0.1887435 -0.05673468 -0.9803863 0.2416199 0.0141012 -0.9702686 0.1449606 0.01615804 -0.9893055 0.05352336 0.06156575 -0.996667 -0.07542741 -0.05596244 -0.9955797 -0.05228406 -0.01120942 -0.9985694 -0.1693642 0.04639679 -0.9844609 -0.2581033 0.01804971 -0.9659487 -0.3107011 -0.07105374 -0.9478482 -0.3960466 0.07497423 -0.9151645 -0.4776937 0.07114309 -0.8756412 -0.5836008 -0.05600231 -0.8101074 -0.5832733 -0.05498886 -0.8104126 -0.6719523 0.0553196 -0.7385255 -0.7716528 -0.03004443 -0.6353341 -0.7579051 0.01000207 -0.6522883 -0.840125 0.05071598 -0.5400167 -0.8895856 -0.04174363 -0.4548571 -0.9059942 0.01657813 -0.4229654 -0.9400259 0.05657815 -0.3363782 -0.9747605 -0.02624034 -0.2217054 -0.968334 -0.06908559 -0.2399094 -0.9892357 0.06055068 -0.1332155 -0.9985568 0.04526281 -0.02890759 -0.9971417 -0.0561127 0.05059629 -0.9966133 -0.001366317 0.08222043 -0.9817011 0.04228597 0.185674 -0.9645128 -5.63878e-4 0.2640357 -0.9672262 -0.01789891 0.253285 -0.930981 0.0372045 0.3631669 -0.8847113 -0.04494571 0.4639674 -0.8808628 -0.02210032 0.4728554 -0.8363376 0.0663653 0.5441829 -0.7139963 -0.06434041 0.6971869 -0.7567968 0.01707482 0.6534273 -0.7036995 -0.03003132 0.7098628 -0.6430029 0.06202286 0.7633484 -0.5608483 0.07781112 0.824254 -0.4462571 -0.09774893 0.8895503 -0.4925015 0.008660376 0.8702686 -0.379938 0.02840286 0.9245759 -0.2965115 0.06734687 0.9526518 -0.188926 -0.01324856 0.981902 -0.1726152 -0.05001896 0.9837185 -0.05489951 0.04103475 0.9976484 0.0673623 -0.03703838 0.9970409 0.05842864 -0.05953907 0.9965146 0.1533638 0.06270265 0.9861785 0.2854037 0.05412 0.9568781 0.3575629 -0.06023222 0.9319447 0.3970503 0.008226752 0.91776 0.5571474 -0.03392922 0.8297202 0.5213702 0.03307175 0.8526896 0.6358718 0.04221272 0.7706395 0.7065422 -0.01779472 0.7074472 0.7198905 0.01028108 0.6940116 0.7874959 0.03241556 0.6154669 0.8290227 -0.01921945 0.5588848 0.8373548 0.006352007 0.5466229 0.8865205 0.07645434 0.4563292 0.9461073 -0.0422061 0.3210912 0.9483263 -0.0653721 0.3104897 0.9732235 0.04226207 0.2259425 0.9919654 0.04966062 0.1163555 0.9987631 -0.03313177 0.03707635 0.9972249 -0.07179772 0.01968902 0.9991199 0.01794904 -0.03791272 0.9930811 -0.009238481 -0.1170668 0.9955374 0.06786227 -0.06557595 0.9713034 -0.05072975 -0.2323712 0.9289073 -0.01598095 -0.3699673 0.9406869 0.06558984 -0.332876 0.8490509 -0.04133075 -0.5266921 0.7937483 0.07832425 -0.6031823 0.8068469 0.03703349 -0.5895985 0.7493661 -0.04459321 -0.6606528 0.6810784 -0.05269193 -0.7303122 0.5886319 0.07924741 -0.8045076 0.5890112 0.07841801 -0.8043112 0.5168058 -0.05197763 -0.8545234 0.4015671 -0.07460248 -0.9127861 0.279756 0.1157084 -0.953073 0.3112789 0.03637701 -0.9496222 0.1814512 -0.04724746 -0.9822644 0.06685441 0.0837695 -0.9942401 0.01343369 -0.03503578 -0.9992958 -0.1073995 -0.08072757 -0.9909332 -0.2528982 0.08441436 -0.9638034 -0.22966 0.01540344 -0.9731491 -0.377803 -0.03633624 -0.9251728 -0.4621211 0.06164503 -0.8846717 -0.4896883 -0.005345761 -0.8718813 -0.521258 -0.05194193 -0.851817 -0.6354452 -0.06099367 -0.7697332 -0.7210472 0.1023721 -0.6852817 -0.7134642 0.07484734 -0.6966828 -0.7683423 -0.03728282 -0.6389523 -0.8363104 -0.05509251 -0.5454812 -0.8938977 0.06573158 -0.4434259 -0.8812187 -0.02659249 -0.4719603 -0.9601467 -0.01362019 -0.2791647 -0.9548887 0.02441161 -0.2959591 -0.9840374 -0.05340284 -0.1697605 -0.9993476 -0.007296025 -0.03537058 -0.9960945 0.05433332 -0.06959712 -0.9961156 -0.04068034 0.07809561 -0.9826831 0.04776477 0.1790317 -0.9804587 0.007396399 0.1965864 -0.9594753 -0.06966733 0.2730453 -0.9237516 -0.04902178 0.3798419 -0.8948864 0.05407065 0.4430064 -0.867321 -0.02748042 0.4969902 -0.7896539 0.03235971 0.6126987 -0.7834132 0.009240806 0.6214325 -0.7178527 -0.05782425 0.6937896 -0.6050475 -0.002360284 0.7961859 -0.6249604 0.05431252 0.7787648 -0.5107631 -0.06882721 0.8569621 -0.3922861 0.0350998 0.9191734 -0.3968649 0.02236545 0.9176046 -0.2426772 -0.03736239 0.9693874 -0.1827677 0.01601827 0.9830257 -0.1577411 -0.02094691 0.9872584 -0.00454837 -0.04633486 0.9989156 0.07392454 0.09210324 0.9930016 0.1445651 -0.03562378 0.9888539 0.2469355 -0.07339853 0.9662482 0.3285253 -0.02847641 0.9440658 0.447486 -0.03534162 0.8935924 0.3637043 0.04816532 0.9302684 0.5393388 0.01556611 0.841945 0.5590878 -0.02382361 0.8287663 0.6418352 -0.04448902 0.765551 0.720528 1.88514e-4 0.6934258 0.7062139 0.03255987 0.7072495 0.8092977 -0.03445845 0.5863872 0.8444122 0.06769156 0.5314 0.886545 -0.05848371 0.4589309 0.9340902 -0.06081598 0.3518197 0.9589396 0.03357023 0.2816166 0.9621044 0.09234708 0.2565681 0.9839574 -0.03429067 0.1750777 0.9940073 -0.07782983 0.07675915 0.9524267 -0.2970896 0.06797999 0.8937609 -0.4323908 0.1192892 0.2611919 -0.9652305 0.01043957 0.1298499 -0.9914582 0.01224178 0.6588584 -0.7496055 0.06322365 0.5772108 -0.8133953 0.07222098 0.9040814 -0.3984004 0.1546419 0.869086 -0.4551206 0.1937909 0.7864251 -0.5827763 0.2047134 0.5615089 -0.8202157 0.1093341 0.4387298 -0.8916869 0.111404 0.7535215 -0.6104826 0.2439599 0.4528893 -0.8775108 0.1576905 0.806263 -0.4970604 0.320735 0.8237091 -0.3483374 0.4473973 0.3844937 -0.9083764 0.1643687 0.7420801 -0.5548127 0.376165 0.7313237 -0.5707207 0.3734216 0.1526542 -0.9852941 0.07676249 0.5137274 -0.814931 0.2682755 0.7883408 -0.238284 0.5672211 0.6210628 -0.6475 0.4416162 0.4200134 -0.850627 0.3162634 0.4646493 -0.8205117 0.3329591 0.7200219 -0.417792 0.5540923 0.4022007 -0.8491462 0.3423238 0.6415135 -0.4586013 0.6149353 0.646613 -0.4275371 0.6317467 0.48982 -0.7279649 0.4797327 0.1805841 -0.9646236 0.1920701 0.5986706 -0.4111439 0.6874259 0.535959 -0.5020813 0.6787212 0.3899514 -0.7566621 0.524786 0.3778149 -0.7805146 0.4980491 0.5247319 -0.3412013 0.7798963 0.2478725 -0.9147863 0.318944 0.4335312 -0.5102927 0.7427329 0.3647675 -0.7129835 0.5988315 0.3988696 -0.379084 0.834984 0.2554196 -0.8202238 0.5118532 0.3718529 -0.4151447 0.8302894 0.1391784 -0.9515709 0.2741208 0.2630369 -0.7041224 0.659563 0.3318973 -0.2995092 0.8945047 0.2293744 -0.5557785 0.7990606 0.2183631 -0.709883 0.6696146 0.1506406 -0.8232784 0.5472844 0.04256319 -0.9913841 0.1238793 0.1850543 -0.3679074 0.9112624 0.1820669 -0.4535334 0.8724444 0.05237835 -0.9805599 0.1891003 0.1459895 -0.178193 0.9731055 0.1072794 -0.6334086 0.7663451 0.09937053 -0.8156345 0.5699702 0.05514502 -0.9001191 0.4321398 0.05382275 -0.3702816 0.927359 0.04948461 -0.6036921 0.7956805 0.02397125 -0.6530861 0.7569042 -6.0973e-4 -0.1521481 0.9883576 0.01128923 -0.8876892 0.4603047 -0.05509257 -0.5290787 0.8467825 -0.01348924 -0.9263918 0.3763197 -0.1034513 -0.5509376 0.8281097 -0.1213826 -0.6348302 0.7630576 -0.06828993 -0.8869039 0.4568785 -0.2649858 -0.3848804 0.8841096 -0.07770192 -0.9184162 0.3879098 -0.2177813 -0.5685626 0.7932894 -0.2289992 -0.7094725 0.6664894 -0.3653602 -0.2952827 0.8827911 -0.1819331 -0.8563156 0.4833468 -0.3690158 -0.4463121 0.8152502 -0.09345334 -0.9745234 0.2038891 -0.182196 -0.8672134 0.4634064 -0.4059382 -0.5196736 0.751767 -0.3446011 -0.7188367 0.6037582 -0.4710483 -0.3779754 0.7970247 -0.3403543 -0.786571 0.5152329 -0.5743894 -0.3577231 0.7362819 -0.2229323 -0.9237654 0.3113821 -0.5671174 -0.4542015 0.68708 -0.4731559 -0.6531592 0.5911909 -0.1920448 -0.9526134 0.235895 -0.6783888 -0.3054459 0.6682003 -0.6460633 -0.3854826 0.6587909 -0.391044 -0.8395338 0.3771842 -0.3169035 -0.8966026 0.3093154 -0.5339342 -0.7087578 0.4610603 -0.7019147 -0.4756468 0.530166 -0.5761459 -0.6741772 0.4621052 -0.7385253 -0.4118875 0.5337874 -0.2121771 -0.9633734 0.1639898 -0.7928389 -0.3873056 0.4705325 -0.7677024 -0.4790285 0.4256349 -0.5243615 -0.7976443 0.2980079 -0.4749127 -0.8331163 0.2835054 -0.3417913 -0.9170382 0.2054745 -0.8141478 -0.4609948 0.353054 -0.2252682 -0.9685084 0.106046 -0.7687011 -0.5679472 0.2941682 -0.605404 -0.7582272 0.2420284 -0.4775687 -0.8631651 0.1639339 -0.8167949 -0.5189577 0.2520496 -0.7612025 -0.6239558 0.1767769 -0.505268 -0.8556438 0.1121519 -0.88186 -0.4532726 0.1298732 -0.4618938 -0.8825224 0.08836609 -0.4941298 -0.8678609 0.05150985 -0.9279608 -0.367873 0.05965167 -0.8785287 -0.4714066 0.077223 -0.8281122 -0.5571562 0.06170338 -0.9591617 -0.2811944 -0.03063756 -0.4401976 -0.8978167 0.01230633 -0.3850417 -0.9228992 1.63468e-4 -0.7343091 -0.6785501 -0.01897466 -0.9070896 -0.4159583 -0.06455332 -0.775524 -0.6290938 -0.05294775 -0.4386111 -0.8974986 -0.04600793 -0.7026068 -0.7059811 -0.08907556 -0.9254474 -0.3493947 -0.146528 -0.868278 -0.4676445 -0.1655355 -0.7406119 -0.6585729 -0.1333264 -0.892981 -0.3547241 -0.2770482 -0.323796 -0.9431732 -0.07470351 -0.6248779 -0.7632574 -0.1642124 -0.8877742 -0.366057 -0.2790328 -0.3972716 -0.9110983 -0.1098884 -0.7085751 -0.6622042 -0.2437356 -0.659339 -0.7038299 -0.264378 -0.8563556 -0.3432099 -0.3858269 -0.4815127 -0.8527022 -0.2025945 -0.394752 -0.9059659 -0.1529601 -0.7145127 -0.6218642 -0.3205566 -0.8740575 -0.2314737 -0.427134 -0.7686718 -0.4373136 -0.4667981 -0.6825419 -0.6067957 -0.4073519 -0.01189643 -0.9999169 -0.004977881 -0.7878576 -0.3388975 -0.5142266 -0.1332854 -0.98829 -0.07428252 -0.5493773 -0.7550511 -0.3578861 -0.4272657 -0.8643772 -0.2651342 -0.2746831 -0.9440709 -0.1824265 -0.7343914 -0.3450165 -0.5844938 -0.2984064 -0.9162013 -0.2674489 -0.6064953 -0.5855724 -0.5378367 -0.5424559 -0.7142127 -0.4423143 -0.6045269 -0.4483026 -0.6584619 -0.5767763 -0.5734247 -0.5818189 -0.3337537 -0.8561283 -0.3945286 -0.5880207 -0.3824595 -0.7127106 -0.2500166 -0.9335269 -0.2569423 -0.5585067 -0.4193189 -0.7157108 -0.3985642 -0.7036436 -0.588245 -0.3293436 -0.8347412 -0.4412934 -0.5166897 -0.3315997 -0.7893501 -0.3835331 -0.6271002 -0.6779732 -0.3747557 -0.6306605 -0.6795774 -0.3751792 -0.4361997 -0.8179062 -0.1611744 -0.9421758 -0.293816 -0.2235186 -0.8525303 -0.4724739 -0.3545674 -0.4057636 -0.8424001 -0.035461 -0.9960203 -0.0817697 -0.2719554 -0.5130639 -0.8141288 -0.2328298 -0.6366555 -0.7351599 -0.2356224 -0.2757177 -0.931913 -0.1759264 -0.8454028 -0.5043253 -0.1323847 -0.891125 -0.4340168 -0.07741051 -0.9589005 -0.2729788 -0.119822 -0.7288951 -0.6740584 -0.138635 -0.4336478 -0.8903539 -0.1181181 -0.7271592 -0.6762304 -0.1078273 -0.3438492 -0.9328135 -0.04262709 -0.8310349 -0.5545845 -0.03971821 -0.9536622 -0.2982463 0.02098625 -0.2751708 -0.9611663 -0.01142561 -0.4414229 -0.8972265 0.008505046 -0.6891359 -0.7245823 -0.02225112 -0.8168854 -0.5763709 0.06727039 -0.6887996 -0.7218241 0.1315395 -0.3977982 -0.9079946 0.03499466 -0.9380269 -0.3447915 0.1279779 -0.4732543 -0.8715803 0.08843475 -0.8291753 -0.551949 0.1717711 -0.2366235 -0.9562971 0.06639683 -0.9028581 -0.4247808 0.1801573 -0.6575364 -0.7315664 0.2816364 -0.379419 -0.8813185 0.2776271 -0.3345057 -0.9005716 0.08333486 -0.938116 -0.3361455 0.2282348 -0.6197227 -0.7509012 0.2443376 -0.7145649 -0.6555122 0.3795707 -0.2396157 -0.8935941 0.20046 -0.8336036 -0.5147047 0.3675099 -0.5380193 -0.7585985 0.1804729 -0.9230063 -0.3398367 0.4390143 -0.5402554 -0.7179071 0.4203714 -0.5676259 -0.7078762 0.2307528 -0.8928468 -0.3867532 0.5818619 -0.3441994 -0.7368606 0.4881861 -0.5273542 -0.6953934 0.444496 -0.7090589 -0.547411 0.6300891 -0.3487852 -0.6937844 0.2954743 -0.8892132 -0.3492779 0.6188166 -0.4734179 -0.6268506 0.2687779 -0.9061614 -0.3265424 0.6209197 -0.4782749 -0.621057 0.5854642 -0.6187528 -0.5238098 0.3854369 -0.8456042 -0.3693131 0.05871796 -0.9967625 -0.05492401 0.6987334 -0.5035612 -0.5081316 0.6255118 -0.6034365 -0.4945698 0.3040494 -0.9237332 -0.2329612 0.4503571 -0.8446547 -0.2893733 0.8053261 -0.3746967 -0.4594045 0.751484 -0.4882216 -0.4437473 0.6533801 -0.6637089 -0.3641222 0.4584324 -0.8410954 -0.2870511 0.8918485 -0.2681804 -0.3642607 0.8598472 -0.3915541 -0.3276405 0.3361215 -0.9292023 -0.1536404 0.2040722 -0.9751248 -0.08652377 0.6642633 -0.694384 -0.2767404 0.5741095 -0.7898598 -0.2156847 0.8662903 -0.4400635 -0.2364007 0.6073948 -0.775082 -0.174125 0.9040771 -0.368085 -0.217159 0.5054414 -0.8578798 -0.09258162 0.504521 -0.8583822 -0.09294474 0.8921245 -0.4343085 -0.1244599 0.3314254 -0.9409601 -0.06893032 0.8686243 -0.4833677 -0.1088464 0.9342355 -0.3566567 7.28672e-5 0.8485066 -0.5280704 -0.03432613 0.7110114 -0.7031136 -0.00970447 0.494738 -0.8680056 -0.04243475 6.04846e-4 -0.9999997 6.18269e-4 0.006228446 -0.9999737 0.003724634 0.006158769 -0.9999721 0.004232823 3.77865e-4 -0.9999998 6.05084e-4 0.009301304 -0.9999471 0.004408538 3.5694e-4 -0.9999995 0.001039206 0.007897913 -0.9999653 0.002690017 0.001748681 -0.9999579 0.009006798 0.01104372 -0.9999387 9.37017e-4 0.01099228 -0.9999392 9.39095e-4 4.10561e-4 -0.9999701 0.007718503 3.33747e-4 -0.9999691 0.007858812 0.004118263 -0.999988 0.002667427 0.008737742 -0.9999611 -0.00128591 -0.001480817 -0.9999773 0.006581306 -0.009188592 -0.9998048 0.01748961 -0.002805411 -0.9998773 0.01540988 0.003773987 -0.9999916 -0.001616895 0.01056694 -0.9999122 -0.00801146 -0.002849698 -0.9999835 0.00500673 0.01115649 -0.9999091 -0.007591545 -0.005052566 -0.9999732 0.005301594 0.01181638 -0.9998877 -0.009223639 -0.005058526 -0.9999729 0.005360662 0.004748463 -0.999975 -0.005264163 -0.004121303 -0.999977 0.005392611 -0.002806186 -0.9999946 0.001711905 0.003129839 -0.9999741 -0.006498098 0.005230188 -0.9997383 -0.02227449 0.0131908 -0.9997777 -0.01644724 -0.01583188 -0.9998602 0.005395472 -0.01252079 -0.9999216 3.50503e-4 0.001393198 -0.9999709 -0.007514774 -0.01518136 -0.999867 0.005955874 -0.001639306 -0.9998954 -0.01437652 -0.01101082 -0.9999389 0.001074552 0.005540668 -0.9997947 -0.01949173 -0.007945835 -0.9999647 0.002761602 -2.60542e-4 -0.9999975 -0.002261579 -0.005168378 -0.9999861 -0.001024425 -0.004336535 -0.999976 -0.00540924 -0.009429454 -0.9999468 -0.004169344 -0.005712509 -0.9999069 -0.0124005 -0.007928609 -0.9999632 -0.003272891 -0.003786146 -0.999989 -0.002773642 -0.006919801 -0.9999386 -0.008668005 -0.003451704 -0.999966 -0.007493913 0.9502337 0.3036724 -0.06956279 0.7044035 0.7066372 -0.06692945 0.3496936 0.9364156 -0.02898955 0.8634667 0.4927812 -0.1076673 0.5164887 0.8527007 -0.07836502 0.8883079 0.4200418 -0.1856719 0.519178 0.8476879 -0.1089943 0.8497012 0.4758835 -0.2270303 0.8203485 0.5223268 -0.232816 0.8057622 0.5313488 -0.2615638 0.8756562 0.3286492 -0.3538588 0.3634803 0.9240516 -0.1183671 0.6580406 0.7049983 -0.2644996 0.5145848 0.8297734 -0.2160525 0.09388786 0.9947983 -0.03951597 0.8276888 0.3854825 -0.4078415 0.7654692 0.5032829 -0.400953 0.6984634 0.5785933 -0.4211637 0.457754 0.8515534 -0.2555742 0.757254 0.4040066 -0.5131716 0.3463814 0.9137366 -0.2123807 0.7037233 0.5556176 -0.4427896 0.7397179 0.3090637 -0.5977434 0.692185 0.3824629 -0.6120476 0.6473438 0.4775452 -0.5940511 0.5223355 0.7332447 -0.4353365 0.3973934 0.8491226 -0.3479502 0.3492697 0.8886001 -0.2973226 0.5733367 0.536264 -0.6194401 0.5269385 0.6164998 -0.5850332 0.6200271 0.1777796 -0.7641733 0.4191724 0.785562 -0.4551779 0.1125355 0.9859011 -0.1238341 0.3008405 0.8712219 -0.3879016 0.1891165 0.9492627 -0.2512677 0.3969255 0.6820586 -0.6142037 0.4882226 0.4096034 -0.7706257 0.3971381 0.6773619 -0.6192433 0.4722023 0.2437344 -0.8471238 0.2927845 0.7631883 -0.576039 0.3650392 0.4679216 -0.8048576 0.1417122 0.9518771 -0.2717493 0.2923151 0.7321044 -0.6152846 0.3193173 0.3249629 -0.8901885 0.07378286 0.9816771 -0.1756879 0.2610225 0.4196801 -0.8693307 0.1992998 0.7616714 -0.6165519 0.2302566 0.3570144 -0.905275 0.1506773 0.8298785 -0.5372133 0.1000454 0.9278461 -0.3592948 0.1395872 0.4336709 -0.8901938 0.1322033 0.4535062 -0.8813935 0.1032526 0.7521876 -0.6508094 0.03500205 0.9600101 -0.2777688 0.03751909 0.309961 -0.9500087 0.05320286 0.8279746 -0.5582362 0.06211608 0.427559 -0.9018509 -0.008464097 0.7331762 -0.6799861 -0.0442146 0.2905163 -0.955848 -0.06157696 0.3578597 -0.9317429 0.002986192 0.9911986 -0.1323496 -0.03702241 0.6849495 -0.7276493 -0.01812368 0.7358011 -0.6769553 -0.1353209 0.3217746 -0.9370964 -0.0448454 0.900042 -0.4334896 -0.002399146 0.9998856 -0.0149405 -0.1651439 0.602733 -0.7806668 -0.1463417 0.6503679 -0.7453896 -0.08142423 0.884686 -0.4590216 -0.264247 0.441994 -0.8572136 -0.2225427 0.5745332 -0.7876461 -0.2230964 0.7228501 -0.6539999 -0.09533309 0.9222562 -0.37464 -0.08511483 0.9491688 -0.3030417 -0.3591361 0.3281366 -0.8736977 -0.2588839 0.7421578 -0.6182079 -0.2049833 0.8764095 -0.4357616 -0.3520924 0.5893058 -0.7271517 -0.4817528 0.4088501 -0.7750844 -0.2044405 0.90564 -0.3715108 -0.3991117 0.5756915 -0.713645 -0.5168536 0.3726364 -0.7707169 -0.2929903 0.8462335 -0.4450231 -0.5203914 0.5673702 -0.638188 -0.3021088 0.8471148 -0.4371808 -0.2543025 0.9180862 -0.3040528 -0.6093125 0.4483978 -0.6539707 -0.5623618 0.5416185 -0.6248189 -0.49796 0.7099272 -0.4980353 -0.333953 0.8798223 -0.3382133 -0.7140574 0.3341352 -0.6152037 -0.6624722 0.5614348 -0.495905 -0.6616729 0.5487241 -0.5109705 -0.4820779 0.8135711 -0.3251203 -0.7751744 0.3949085 -0.4931043 -0.2605045 0.9440422 -0.2022915 -0.2880616 0.9333262 -0.214296 -0.7564246 0.5068632 -0.4134147 -0.5618988 0.7610406 -0.3241711 -0.7860802 0.4748034 -0.3957774 -0.7534707 0.5985131 -0.2721469 -0.7761941 0.5585746 -0.2924333 -0.4715337 0.8614437 -0.1886019 -0.4215854 0.8923296 -0.1612882 -0.2477072 0.9632565 -0.1038177 -0.8218479 0.5327208 -0.2019274 -0.7945008 0.5839139 -0.1667723 -0.6150695 0.7817214 -0.1029629 -0.481763 0.8709607 -0.09660261 -0.9175902 0.3814521 -0.1119049 -0.8686944 0.4937062 -0.04030394 -0.6640123 0.7460829 -0.0494787 -0.9119651 0.4102526 -0.003523051 -0.1593849 0.9871465 -0.01176518 -0.910654 0.4126834 0.02004879 -0.94985 0.3056272 0.06615972 -0.4875229 0.8729299 0.01775032 -0.6951427 0.7147668 0.07671475 -0.5364404 0.8426487 0.04663652 -0.899475 0.415152 0.1363588 -0.7995181 0.5828134 0.1452566 -0.7800096 0.6033832 0.165873 -0.6174068 0.7700763 0.1605972 -0.4386472 0.8940778 0.09062927 -0.8804894 0.3928848 0.2652923 -0.1915696 0.9798142 0.05714285 -0.8871148 0.2853404 0.3627786 -0.8473979 0.4330726 0.3071887 -0.6380053 0.7255212 0.2580085 -0.6602888 0.7066703 0.2542359 -0.8607196 0.2951179 0.4148097 -0.3582059 0.9192734 0.163172 -0.7491204 0.5234902 0.4059271 -0.6584618 0.6734958 0.3359041 -0.4588925 0.8444439 0.2762828 -0.7526009 0.4273773 0.5009398 -0.3466465 0.9166973 0.1987525 -0.6937375 0.5125493 0.5059857 -0.1312459 0.9867951 0.09492218 -0.5176342 0.773009 0.3667586 -0.6788138 0.4853962 0.5510013 -0.5977218 0.5801392 0.5533239 -0.4452503 0.806351 0.3892948 -0.5950477 0.5628138 0.5737237 -0.3130066 0.899203 0.3057137 -0.343805 0.8765114 0.3369362 -0.522368 0.5487393 0.6526997 -0.514966 0.6210404 0.5908628 -0.3612071 0.8321186 0.4208421 -0.4730732 0.5535869 0.6853782 -0.4405897 0.5946218 0.6725367 -0.3009545 0.8373053 0.4564495 -0.2787588 0.8751431 0.3954975 -0.1393322 0.9692218 0.2029669 -0.426448 0.3805553 0.8205607 -0.4180492 0.5376051 0.7322675 -0.08428102 0.9868776 0.13773 -0.3747252 0.3798324 0.845759 -0.1953938 0.8829831 0.4268047 -0.3123494 0.527272 0.7902039 -0.2662989 0.7278183 0.6319537 -0.2027548 0.8407531 0.5020206 -0.2043272 0.8397293 0.5030957 -0.2521153 0.4040966 0.879286 -0.1735467 0.2885744 0.9415978 -0.1917563 0.4710512 0.8610113 -0.1465184 0.6389148 0.7551956 -0.04872214 0.9737952 0.2221465 -0.1342212 0.7581726 0.6380903 -0.06243473 0.9120382 0.405325 -0.0595653 0.3344366 0.9405341 -0.03566366 0.4595778 0.8874213 -0.04529225 0.5901468 0.8060244 0.001814961 0.8342064 0.5514495 0.03527003 0.3813123 0.9237734 0.02000856 0.8523689 0.5225581 0.05162334 0.8264888 0.5605812 0.149868 0.4394119 0.8856957 0.1021275 0.5154224 0.850829 0.08841949 0.858555 0.5050402 0.1515902 0.4417552 0.8842357 0.1822872 0.7185632 0.671147 0.267325 0.3284788 0.9058913 0.2813543 0.4775815 0.8323194 0.2056474 0.7049039 0.6788371 0.04629492 0.9889569 0.1407877 0.3667284 0.3832495 0.8477207 0.2094129 0.8393297 0.5016692 0.3931556 0.5090639 0.7656911 0.1037235 0.9630139 0.248688 0.3089076 0.7492015 0.5858952 0.4947816 0.346179 0.7970893 0.3164873 0.7983515 0.5123192 0.5098548 0.438887 0.7398827 0.3917253 0.7185099 0.5747128 0.2233461 0.913571 0.3398597 0.590727 0.3645544 0.7198206 0.5939828 0.4672941 0.6548441 0.1789391 0.9580014 0.2240853 0.4723389 0.7121953 0.5193014 0.6594327 0.3763916 0.6507518 0.4070454 0.8169725 0.4084973 0.3406157 0.8747919 0.3445581 0.676096 0.4759246 0.5624855 0.6304069 0.6038383 0.4878181 0.5742653 0.6817087 0.4533132 0.2426113 0.9536163 0.1782017 0.7051014 0.534691 0.4657654 0.3684237 0.8981835 0.2398548 0.7025442 0.5853828 0.4046711 0.8426078 0.3482076 0.4108086 0.5447053 0.7904901 0.2800387 0.4253546 0.8730927 0.2382912 0.8399331 0.4386298 0.3195565 0.582791 0.7755993 0.2424885 0.5415189 0.8166416 0.1996345 0.8625376 0.4035285 0.3052766 0.2151474 0.9733746 0.07907837 0.8380923 0.4915772 0.2365443 0.2120665 0.9741811 0.07745397 0.6437895 0.7463831 0.1686636 0.9197636 0.3400837 0.1959031 0.6378229 0.7634318 0.1017545 0.5984598 0.7915267 0.1238208 0.9146047 0.382395 0.1314246 0.3620519 0.9289864 0.07682985 0.8822408 0.4580087 0.1089923 0.9270017 0.3749276 0.009861946 0.869105 0.4935282 0.03296202 0.7273134 0.6862388 0.009568989 0.5743485 0.8178769 0.03466248 0.3933705 0.9193037 0.01184666 0.2584262 0.965771 0.02241313 -4.47233e-4 0.9999999 4.8778e-4 -6.9536e-4 0.9999997 4.88454e-4 -0.00527352 0.9999835 0.002297818 -4.18634e-4 0.9999997 7.1792e-4 -0.003107845 0.9999535 0.009139418 -0.005277216 0.9999834 0.002325236 -0.002557694 0.9999547 0.009183526 -0.007917165 0.9999673 0.001679182 -0.01086109 0.9999396 0.001716315 -0.001778244 0.9998893 0.01478141 -2.63568e-4 0.999909 0.01349592 -0.01162588 0.9999324 -2.74719e-4 1.25238e-4 0.9998999 0.01414638 -0.01487445 0.9998882 -0.001577317 -0.01225578 0.9999207 -0.002898395 0.004212915 0.9998897 0.01423931 8.85223e-5 0.9999682 0.007980227 -0.01230543 0.9999198 -0.00301373 -0.006629765 0.9999728 -0.003256082 -0.006837427 0.9999676 -0.004276812 0.001536548 0.9999957 0.002500832 0.007782816 0.9999547 0.005502283 -0.003729343 0.9999862 -0.003698348 0.007997274 0.9999406 0.007417201 -0.005725264 0.9999127 -0.01190513 0.008043706 0.9999402 0.007419228 0.006841838 0.9999691 0.003879904 -0.008235812 0.9999055 -0.0110166 -0.003536045 0.9999657 -0.007495164 0.007971227 0.9999617 0.003648698 0.005509972 0.9999839 0.001388251 -0.001499533 0.9998881 -0.01489239 -0.001738607 0.9999768 -0.006597638 0.006804049 0.9999769 9.44135e-5 0.005298972 0.9999859 4.93534e-4 2.27836e-4 0.9999994 -0.001179397 0.01121449 0.9999206 -0.005747854 0.01430529 0.9998919 -0.003438889 0.0141946 0.9998937 -0.003350138 0.001131653 0.9999964 -0.002447903 0.001048326 0.9999982 -0.001596689 0.00233823 0.9999963 -0.001443922 0.001956462 0.9999958 -0.002140879 0.00221014 0.9999949 -0.002313435 0.9946827 0.07101708 -0.07458502 0.9845041 0.01145684 -0.1749874 0.9808067 -0.02377063 -0.1935286 0.9617876 0.04055988 -0.270776 0.9302563 0.003122389 -0.3668974 0.9302856 0.002950787 -0.3668244 0.8879727 0.05324345 -0.4568038 0.8437285 -0.01613509 -0.5365278 0.8457773 -0.02301579 -0.5330395 0.7752513 0.04539227 -0.63002 0.7258963 -0.03249365 -0.6870363 0.6902678 0.03138053 -0.7228733 0.6023998 0.01605969 -0.798033 0.6200359 -0.02862691 -0.7840511 0.5148692 0.04895418 -0.85587 0.4473464 -0.009619712 -0.8943091 0.4308429 0.01618462 -0.9022819 0.2931633 0.007578015 -0.9560325 0.3061779 -0.02277326 -0.9517019 0.1967548 0.04513466 -0.9794133 0.09846889 -0.02785766 -0.9947502 0.1016089 -0.03468149 -0.9942198 0.002297043 0.0518347 -0.9986531 -0.1334961 -0.03348791 -0.9904834 -0.1144701 -0.001025855 -0.9934262 -0.2022368 0.0423696 -0.9784198 -0.3353492 -0.01447021 -0.9419828 -0.3352585 -0.01464444 -0.9420124 -0.4434276 0.04612398 -0.8951227 -0.5221786 -0.02361166 -0.8525093 -0.5174825 -0.03420293 -0.8550099 -0.608894 0.0594573 -0.7910202 -0.7099756 -0.04301351 -0.7029115 -0.7144445 -0.02782392 -0.6991387 -0.8045821 0.05654668 -0.5911431 -0.8570612 -0.04935204 -0.5128456 -0.8661728 -0.01734411 -0.4994436 -0.9108845 0.04300397 -0.4104145 -0.9515787 -0.009177625 -0.3072683 -0.9342123 -0.106306 -0.3405094 -0.9743516 0.06899839 -0.2141918 -0.996022 0.02818495 -0.08453297 -0.9953234 -0.09402406 -0.02215772 -0.9997332 -0.003646016 0.02281254 -0.9902726 0.06629526 0.1223323 -0.9723305 -0.01442068 0.233164 -0.9596084 -0.09553498 0.2646219 -0.9316727 0.05872464 0.3585212 -0.8849086 0.04492044 0.4635936 -0.8522163 -0.03890544 0.5217411 -0.8478388 -0.0225442 0.5297747 -0.7751903 0.04736155 0.62995 -0.7090705 -0.02848261 0.7045622 -0.7126735 -0.04141694 0.7002723 -0.6251602 0.07000344 0.7773509 -0.4888954 -0.07025676 0.8695088 -0.5266067 0.01463449 0.849983 -0.4360661 0.02454656 0.8995799 -0.3345103 0.0568214 0.9406776 -0.2471156 -0.03161758 0.9684701 -0.2522439 -0.0178337 0.9674993 -0.05461126 -0.03680282 0.9978293 -0.1103994 0.03488487 0.9932749 -7.1596e-5 0.03311222 0.9994517 0.1498478 -0.05747318 0.9870373 0.09658795 0.02276211 0.9950642 0.2041497 0.03161501 0.9784291 0.3088567 0.05015665 0.9497852 0.383345 -0.04597365 0.9224603 0.4016982 -0.008779346 0.9157301 0.5150173 0.06147843 0.8549723 0.5987747 -0.03925567 0.799955 0.5950333 -0.02706575 0.8032453 0.6801694 0.03684449 0.7321286 0.7567126 -0.04153615 0.652427 0.7542315 -0.05032473 0.6546772 0.8097805 0.05653309 0.5840032 0.8726067 0.04394257 0.4864429 0.9007104 -0.0367794 0.4328603 0.9096384 -0.004445612 0.4153774 0.9597522 0.03314143 0.2788865 0.9713306 -0.0348981 0.2351578 0.9859652 0.03876686 0.1623879 0.9980207 -0.04165935 0.04711019 0.999625 0.0061872 0.0266754 0.9976441 -0.009895324 -0.06788426 0.9973248 0.001155734 -0.07309031 0.9778926 -0.02150088 -0.2079994 0.9710435 0.02981168 -0.2370353 0.9450507 -0.04231399 -0.3241742 0.9120417 0.0121358 -0.4099179 0.9082181 0.02795559 -0.4175624 0.8668535 -0.0425651 -0.4967425 0.7974429 0.03298175 -0.6024923 0.8077932 0.004202365 -0.5894511 0.7494307 -0.05456972 -0.6598302 0.686057 -0.01199483 -0.7274489 0.6813962 0.002812266 -0.7319095 0.5716142 -0.01342791 -0.8204128 0.5507605 0.01710551 -0.834488 0.4758216 -0.06423628 -0.877193 0.3914014 0.008825838 -0.9201778 0.365387 0.06222611 -0.9287735 0.287592 -0.05599105 -0.9561151 0.1444011 -0.02784019 -0.9891276 0.1086531 0.04985761 -0.9928287 5.73716e-4 -0.057024 -0.9983727 -0.1353117 -2.34458e-4 -0.9908031 -0.1150014 0.0416556 -0.9924916 -0.2418918 -0.05476778 -0.9687564 -0.3572431 0.06340318 -0.931857 -0.3563176 0.06084126 -0.9323821 -0.4760695 -0.08795291 -0.8749985 -0.5958889 0.04125916 -0.8020064 -0.5892871 0.01844 -0.8077133 -0.6856745 -0.0314868 -0.727227 -0.7321375 0.007935523 -0.6811108 -0.7338808 0.003343939 -0.67927 -0.8158578 -0.05833256 -0.5753028 -0.8607414 0.0290693 -0.5082117 -0.8819218 -0.03113186 -0.4703667 -0.9308823 0.001117587 -0.3653175 -0.9359761 0.0245198 -0.3512086 -0.9624781 -0.04615861 -0.267405 -0.987309 0.01840269 -0.1577419 -0.986003 0.003417432 -0.1666925 -0.9954148 -0.06037372 -0.07419151 -0.9981021 0.0463894 0.04050135 -0.9977636 -0.006235361 0.06655073 -0.9819711 -0.05439281 0.1810369 -0.9658942 0.01120436 0.2586949 -0.9650731 0.01750349 0.2613954 -0.9278091 -0.03395986 0.3715066 -0.9016981 0.04437392 0.4300832 -0.866814 -0.05686146 0.4953791 -0.8066583 -0.01458442 0.5908381 -0.7819657 0.06219255 0.6202112 -0.7203128 -0.05740696 0.6912698 -0.6327196 -0.0188269 0.7741521 -0.5483872 -0.02219074 0.8359301 -0.5935593 0.06922513 0.8018077 -0.4343459 -0.05580097 0.8990162 -0.359687 0.04969465 0.9317488 -0.3072052 -0.02744078 0.9512476 -0.3309006 -0.008900225 0.9436236 -0.1891258 -0.02403819 0.9816586 -0.1528208 0.02397102 0.9879631 -0.1015282 -0.02831375 0.9944297 -0.00624001 -0.006261408 0.999961 0.02953726 0.04919922 0.9983522 0.09974277 -0.051005 0.9937052 0.1954188 -0.05170184 0.9793561 0.3140417 -0.01971828 0.9492045 0.2735377 0.06092339 0.95993 0.3924496 -0.040609 0.9188766 0.4813483 0.0369153 0.8757517 0.4809335 0.03792941 0.8759363 0.5675041 -0.05921041 0.821239 0.6411582 -0.02622312 0.7669606 0.6752246 0.04683786 0.7361237 0.719814 -0.03606367 0.6932297 0.8102948 0.01718825 0.5857706 0.8085885 0.0235325 0.5879037 0.8698257 -0.05204367 0.4906066 0.90121 -0.01448494 0.4331409 0.9186025 0.06030094 0.3905553 0.9445928 -0.05317389 0.3239091 0.9744868 -0.06173425 0.2157883 0.9964533 -0.0358898 0.07611089 0.9889085 0.06558918 0.1332596 0.9215905 -0.3808159 0.07516741 0.8792092 -0.4732633 0.05489385 0.7187457 -0.693199 0.05366438 0.6196278 -0.7840822 0.0357294 0.4557679 -0.889487 0.03299605 0.4166164 -0.9061938 0.07241368 0.8884366 -0.4183328 0.1888865 0.8387934 -0.5078355 0.1962875 0.7364447 -0.6566088 0.1628319 0.6332737 -0.7595559 0.1484559 0.2362415 -0.9694395 0.06615966 0.8442889 -0.4546359 0.2836946 0.5347386 -0.8255152 0.1804979 0.4186093 -0.8955686 0.1507428 0.7622443 -0.5740448 0.2990924 0.7513767 -0.5611786 0.3471479 0.7277009 -0.5871242 0.3545936 0.4460779 -0.8629236 0.2374397 0.768179 -0.4358994 0.4689273 0.3886932 -0.8926212 0.2283533 0.7631713 -0.4402733 0.4730002 0.76169 -0.3322734 0.5562579 0.5341391 -0.7507667 0.3886452 0.4054226 -0.8718301 0.2748546 0.7113277 -0.4229707 0.5613453 0.5646553 -0.6958595 0.4437837 0.6813924 -0.3437005 0.6462 0.2665547 -0.938242 0.220569 0.653039 -0.4039379 0.6406046 0.4852087 -0.7296753 0.4818159 0.4666692 -0.7612811 0.4501898 0.3267745 -0.8910221 0.3151162 0.5842451 -0.4288371 0.6890257 0.5512211 -0.4913176 0.6743607 0.4689118 -0.6842804 0.5584642 0.2369201 -0.9302791 0.2800889 0.3313235 -0.8301986 0.4483247 0.5092815 -0.4110018 0.756115 0.4831033 -0.4490514 0.751641 0.3534783 -0.7239738 0.5923809 0.3203124 -0.8190537 0.475974 0.4556359 -0.3221908 0.8298127 0.3847794 -0.43792 0.8125091 0.08938962 -0.9790316 0.1830484 0.3348662 -0.5704869 0.7499395 0.3111973 -0.7221112 0.6178283 0.1468421 -0.9195737 0.364447 0.2848162 -0.5802296 0.7630292 0.275502 -0.3227226 0.9055103 0.18007 -0.7763531 0.6040289 0.1368741 -0.9005799 0.412579 0.195888 -0.3771557 0.905197 0.1630971 -0.4859721 0.8586213 0.1511592 -0.7373161 0.6584192 0.0559768 -0.9619324 0.2674936 0.08298462 -0.3310688 0.9399505 0.06657129 -0.8701746 0.4882261 0.05550175 -0.9083309 0.4145535 0.1162155 -0.4857503 0.8663375 0.05257266 -0.7207781 0.6911694 0.005083143 -0.3773539 0.9260553 -0.01552629 -0.4702099 0.8824181 0.009908914 -0.687408 0.7262039 -0.005485773 -0.9510582 0.3089633 -0.03248554 -0.8606624 0.5081389 -0.08280318 -0.4428107 0.8927835 -0.09520709 -0.4744744 0.8751056 -0.1061435 -0.7347252 0.6700093 -0.08308684 -0.804302 0.5883832 -0.2004287 -0.3119231 0.9287263 -0.01252043 -0.9960693 0.0876888 -0.2191591 -0.3640724 0.9052186 -0.2145124 -0.5947034 0.7747983 -0.1734547 -0.678332 0.7139882 -0.07920032 -0.949903 0.3023438 -0.07781231 -0.9508547 0.2997008 -0.3192779 -0.4809575 0.8165425 -0.2540954 -0.6074987 0.7525829 -0.2263044 -0.8119939 0.5380079 -0.1641809 -0.9060592 0.390002 -0.4161176 -0.3541995 0.8374897 -0.3728172 -0.4723651 0.7986732 -0.3333917 -0.6754893 0.6576962 -0.48622 -0.4064999 0.7735297 -0.1414943 -0.9497418 0.279231 -0.4756115 -0.4854009 0.7336074 -0.358255 -0.696476 0.6217513 -0.2894502 -0.8459018 0.4479606 -0.501973 -0.5289121 0.6843063 -0.3305371 -0.8394695 0.431319 -0.3274653 -0.8479159 0.4168995 -0.5924276 -0.3954896 0.7018672 -0.6051501 -0.4567314 0.6520658 -0.08890318 -0.9910876 0.09920519 -0.4095391 -0.7993133 0.4397457 -0.6599522 -0.3949728 0.6391086 -0.6560215 -0.4825891 0.5802962 -0.5199021 -0.7284426 0.4461762 -0.4113212 -0.8283086 0.3804204 -0.7468813 -0.3629996 0.5571354 -0.298245 -0.920289 0.2532157 -0.2745941 -0.9413516 0.1960999 -0.7201486 -0.5016493 0.4793059 -0.571262 -0.7258338 0.3831778 -0.4787836 -0.8282513 0.2911465 -0.8146558 -0.3612127 0.4537196 -0.7907736 -0.4736555 0.3877208 -0.4998825 -0.8189493 0.2818503 -0.858421 -0.3824304 0.3418485 -0.8274603 -0.4426252 0.3455322 -0.6044078 -0.7683322 0.2106105 -0.4345715 -0.8812631 0.1858041 -0.8813272 -0.3916224 0.2643756 -0.1757793 -0.9827996 0.05662786 -0.8138873 -0.5424744 0.2081086 -0.6193971 -0.761099 0.1925503 -0.4374501 -0.8947186 0.09008884 -0.8971963 -0.4188797 0.1399241 -0.4044179 -0.9107758 0.08326762 -0.8242487 -0.5437432 0.1579802 -0.6081273 -0.7884213 0.09259033 -0.9241314 -0.376021 0.06774502 -0.8814777 -0.4708511 0.03600507 -0.6638495 -0.7476415 0.01833379 -0.252263 -0.9676354 0.006718397 -0.6033753 -0.7974433 -0.004738628 -0.408349 -0.9127554 -0.01135814 -0.9208799 -0.3871632 -0.04566073 -0.7705396 -0.6320513 -0.08234041 -0.8683904 -0.4643599 -0.1739776 -0.7533106 -0.6462855 -0.1218126 -0.6412562 -0.7570559 -0.1251274 -0.3617923 -0.930598 -0.05562275 -0.8928408 -0.3670601 -0.2609643 -0.8506838 -0.4432634 -0.2825859 -0.1579934 -0.9864673 -0.04382318 -0.6208103 -0.7591395 -0.1957089 -0.5713654 -0.7973677 -0.1942848 -0.8610212 -0.3788812 -0.3392516 -0.3175666 -0.9408873 -0.1178247 -0.8351169 -0.4181272 -0.3574205 -0.6376327 -0.7052842 -0.3098365 -0.8556911 -0.2670028 -0.4432858 -0.6181587 -0.7209652 -0.3131918 -0.4065739 -0.8887311 -0.2117892 -0.6974219 -0.5764876 -0.4257522 -0.6904249 -0.5744331 -0.4397047 -0.7438285 -0.3874448 -0.5446152 -0.2362163 -0.9565541 -0.1708989 -0.4563859 -0.8172754 -0.3518137 -0.6869918 -0.4299486 -0.5858212 -0.3029907 -0.9228125 -0.2379363 -0.6100944 -0.5680521 -0.5523601 -0.5172888 -0.6429142 -0.5648661 -0.3388037 -0.8658638 -0.3680924 -0.5810391 -0.4289992 -0.6916308 -0.5280174 -0.5984005 -0.6025898 -0.576748 -0.2860135 -0.7652177 -0.2091917 -0.9382589 -0.2755161 -0.4674307 -0.4658292 -0.7513401 -0.3919377 -0.6651318 -0.6355979 -0.3795157 -0.7057144 -0.5982768 -0.1965972 -0.9294404 -0.3122339 -0.4616812 -0.2615327 -0.8476149 -0.2413048 -0.8834676 -0.4015683 -0.3587124 -0.5005814 -0.7878729 -0.3357544 -0.6341226 -0.6965326 -0.2461481 -0.7913836 -0.559574 -0.3178912 -0.3232111 -0.891336 -0.3170016 -0.4250919 -0.8478248 -0.04214864 -0.9929218 -0.1110402 -0.1868995 -0.7460619 -0.6391089 -0.1745238 -0.8339185 -0.5235661 -0.2444439 -0.2469664 -0.9376859 -0.06863129 -0.9729601 -0.2205417 -0.1742458 -0.4517037 -0.874987 -0.1609721 -0.7103033 -0.6852425 -0.1313796 -0.389767 -0.9114939 -0.08510291 -0.8038985 -0.5886465 -0.1005241 -0.4593377 -0.8825553 -0.06636607 -0.6871657 -0.7234632 -0.06535357 -0.8684383 -0.4914712 -0.003432929 -0.3751379 -0.9269627 0.01740211 -0.4917007 -0.8705904 -0.009260416 -0.6867099 -0.7268726 0.002907633 -0.9480887 -0.3179929 0.02456206 -0.8460448 -0.5325458 0.0132972 -0.9276403 -0.3732383 0.07854646 -0.5299823 -0.8443632 0.07950556 -0.7149628 -0.6946272 0.1486383 -0.2919631 -0.9448091 0.1387156 -0.7647667 -0.6291978 0.2130962 -0.4274495 -0.8785653 0.1838332 -0.6649098 -0.7239477 0.2721124 -0.3051944 -0.912585 0.08860009 -0.9316362 -0.352426 0.3129838 -0.4192193 -0.8522302 0.0862891 -0.9483631 -0.3052242 0.295969 -0.6165059 -0.7296047 0.2974091 -0.6300517 -0.7173442 0.1679777 -0.9009535 -0.4000827 0.3364195 -0.5983019 -0.7272254 0.46516 -0.2306805 -0.8546419 0.1632695 -0.9384405 -0.3044219 0.4184504 -0.6721876 -0.6107891 0.4133718 -0.5972297 -0.687343 0.2365301 -0.8949506 -0.3783079 0.5503916 -0.3977066 -0.7340973 0.4923653 -0.5363078 -0.6855294 0.4615883 -0.6722067 -0.5788562 0.2646166 -0.8988991 -0.3492256 0.6292424 -0.3213991 -0.7076416 0.2216221 -0.9406319 -0.2570901 0.5523319 -0.6121949 -0.5658153 0.5496384 -0.6388708 -0.5382766 0.3880134 -0.8466036 -0.3642911 0.6197395 -0.5622979 -0.5474891 0.7697607 -0.3601001 -0.527064 0.6457085 -0.5881587 -0.48696 0.5263138 -0.7701274 -0.3604133 0.3828922 -0.8735498 -0.3005066 0.08961474 -0.9945363 -0.05354213 0.8079014 -0.3511732 -0.4732576 0.7818923 -0.4553039 -0.4258438 0.5331254 -0.773079 -0.3436948 0.3882128 -0.9021623 -0.188133 0.8062114 -0.4640665 -0.3669682 0.7990791 -0.4859508 -0.3540118 0.4343112 -0.8794784 -0.1946579 0.9046157 -0.311064 -0.2913926 0.8393359 -0.458291 -0.2923777 0.7023388 -0.6840823 -0.1968549 0.9531502 -0.2158694 -0.2119085 0.4857438 -0.8604344 -0.1539669 0.8852754 -0.4367765 -0.1597302 0.3286346 -0.941834 -0.07034289 0.7480023 -0.6445811 -0.1581385 0.5972474 -0.798457 -0.07590758 0.4448754 -0.8937057 -0.05810469 0.8926244 -0.4458524 -0.06661427 0.904825 -0.4213042 -0.06159985 0.7262015 -0.6853895 -0.05359703 0.3088656 -0.9511052 9.3519e-4 0.006637394 -0.9999561 0.006631791 0.00754112 -0.9998292 0.01687693 0.00790739 -0.999946 0.006747126 0.01400524 -0.9997469 0.0176143 0.007601618 -0.9999598 0.004774391 0.004045307 -0.9999716 0.006360471 0.01468086 -0.999878 0.005338668 0.002103209 -0.9999915 0.003537774 0.001719892 -0.9999889 0.004403054 0.003970444 -0.9999849 0.003820359 0.0153799 -0.9998733 0.004101276 5.67215e-5 -0.9999998 7.76234e-4 0.006498038 -0.9999786 -7.71706e-4 0.007289171 -0.9999734 -4.75786e-4 -9.81007e-4 -0.9999956 0.002809405 -8.84695e-4 -0.9999884 0.00473982 0.007909297 -0.9999659 -0.002414882 0.009849548 -0.9999455 -0.003479301 -0.001568973 -0.9999922 0.003640115 -0.009680151 -0.9998965 0.01064711 0.01162499 -0.9998992 -0.008158445 0.01345729 -0.999861 -0.009846687 -0.009316086 -0.9998891 0.01162171 -0.001624643 -0.9999677 0.007880628 0.01105177 -0.999875 -0.01131725 -0.002005934 -0.9999967 0.001601397 0.006659805 -0.9999364 -0.009112715 0.006646871 -0.9999535 -0.006986081 -0.01491886 -0.9998615 0.007384836 -0.0138058 -0.9999004 0.002945244 0.001621782 -0.999984 -0.005418479 -0.01314049 -0.9998854 0.007529139 0.001963436 -0.9999801 -0.006003677 -0.003823041 -0.9999926 6.96622e-4 3.58151e-4 -0.9999859 -0.005317926 -0.005289375 -0.999986 -3.75481e-4 1.20165e-4 -0.9999817 -0.006054043 -0.006027042 -0.9999818 -5.65195e-4 -0.001156151 -0.9999874 -0.00488615 -0.01008528 -0.9999443 -0.003127992 -0.008606374 -0.9999583 -0.003070414 -0.007811784 -0.9999607 -0.004187464 -0.002108812 -0.9999783 -0.006246984 -0.001849412 -0.999992 -0.003553867 -0.009127378 -0.9999379 -0.006394088 -0.005514979 -0.9999702 -0.005403995 -0.005240976 -0.9999785 -0.003953754 0.5137791 0.8578981 -0.006497383 0.3925538 0.9193514 -0.02635753 0.8581365 0.5100102 -0.05908811 0.8274715 0.5566906 -0.07339352 0.8104653 0.5687245 -0.1403507 0.8048246 0.5761571 -0.1424795 0.4144047 0.9066376 -0.07922786 0.3603383 0.9288487 -0.08600252 0.8051299 0.5472657 -0.2286182 0.4543362 0.8791756 -0.1436285 0.7772439 0.5816054 -0.2400566 0.7864818 0.5365737 -0.3058351 0.740271 0.5900661 -0.3222126 0.4439662 0.8721848 -0.2053973 0.762285 0.5103957 -0.3980177 0.4012052 0.8937563 -0.2005849 0.3768217 0.9060834 -0.1924013 0.7014676 0.5757917 -0.4200085 0.7590248 0.3946902 -0.5177847 0.6973146 0.5558702 -0.4525049 0.5340952 0.7434828 -0.4024623 0.756077 0.2424629 -0.6079139 0.3396923 0.9143761 -0.2202848 0.1546679 0.9799557 -0.125557 0.5063663 0.7454669 -0.4334425 0.6035594 0.5315662 -0.5942673 0.6050708 0.52865 -0.5953306 0.2677735 0.9263153 -0.2650238 0.5174106 0.6049175 -0.6052778 0.4386315 0.7163774 -0.5425918 0.2545986 0.9252012 -0.2813936 0.5652865 0.3442638 -0.7496224 0.1632746 0.9639056 -0.2103032 0.3690853 0.75139 -0.5469819 0.4908216 0.3919371 -0.7781257 0.2264577 0.9042477 -0.3620125 0.4197917 0.5567542 -0.7167983 0.3678003 0.4558093 -0.8105312 0.3570755 0.5702261 -0.7398239 0.1636523 0.9221481 -0.3505156 0.2580547 0.7605985 -0.5957329 0.09008216 0.9692353 -0.2290596 0.2821906 0.3572927 -0.890343 0.2285561 0.4836382 -0.8449003 0.1855053 0.6873367 -0.7022507 0.1672047 0.7229549 -0.6703572 0.1923682 0.3432143 -0.9193468 0.09554111 0.9117248 -0.3995372 0.09052646 0.4647079 -0.8808244 0.08431434 0.4418989 -0.8930938 0.08897083 0.6789702 -0.7287549 0.02799314 0.9526817 -0.3026778 0.01132571 0.9816183 -0.1905189 0.0285595 0.8398835 -0.5420147 -0.01123529 0.3497726 -0.9367673 0.01463675 0.4430293 -0.8963877 -0.009262263 0.7647855 -0.6442185 -0.07631236 0.3513323 -0.9331356 -0.1072966 0.5414604 -0.8338514 -0.05022364 0.7678132 -0.6387023 -0.06381738 0.853008 -0.5179814 -0.1998968 0.4403523 -0.8752892 -0.1648404 0.5304836 -0.8315136 -0.1120268 0.8809559 -0.4597465 -0.1119772 0.8807088 -0.4602317 -0.2730338 0.4494477 -0.8505584 -0.314737 0.3504736 -0.8821048 -0.2093611 0.7890778 -0.5775156 -0.04067188 0.9931213 -0.1097995 -0.2331867 0.7998371 -0.5530683 -0.3804452 0.4352579 -0.8159731 -0.3781009 0.4830401 -0.7897544 -0.2709437 0.7593278 -0.5916172 -0.1127805 0.9644359 -0.2390482 -0.4816582 0.4433596 -0.7559351 -0.4388164 0.5161545 -0.7355439 -0.3134875 0.786362 -0.5323163 -0.2904332 0.8419528 -0.4547134 -0.5670517 0.3912454 -0.7248306 -0.534474 0.4616466 -0.707969 -0.4217556 0.7327646 -0.534021 -0.3084384 0.8478301 -0.431335 -0.225673 0.9342686 -0.2760689 -0.6650283 0.3707338 -0.6483007 -0.6676856 0.3503475 -0.6568505 -0.468563 0.7457957 -0.4735374 -0.4039244 0.8360972 -0.3711965 -0.2740521 0.9232238 -0.2693575 -0.4319543 0.8215254 -0.3721716 -0.7069333 0.4171545 -0.5711632 -0.7576246 0.3447628 -0.5542055 -0.7554666 0.4312822 -0.4932198 -0.05613327 0.9976708 -0.03875672 -0.5534525 0.7585884 -0.3438519 -0.439853 0.8459637 -0.3014549 -0.8135831 0.3354241 -0.4749455 -0.8198763 0.398236 -0.4113526 -0.2089742 0.9702296 -0.1224105 -0.7101074 0.633603 -0.3070745 -0.5967502 0.7531819 -0.2767782 -0.411606 0.8935236 -0.1794331 -0.7411066 0.6042155 -0.2927196 -0.8808745 0.3763895 -0.2870386 -0.3508517 0.9297572 -0.1116009 -0.8830062 0.4255627 -0.197981 -0.8977581 0.3874722 -0.209513 -0.6223119 0.7689305 -0.1465392 -0.6813408 0.7170619 -0.1469591 -0.4452591 0.888723 -0.1091598 -0.9229893 0.3772101 -0.07617884 -0.8956106 0.4406536 -0.0608794 -0.3048672 0.9516349 -0.03804081 -0.7059291 0.7057758 -0.05953842 -0.6663453 0.7440981 -0.04797857 -0.3980942 0.9169397 -0.0272535 -0.9283623 0.3711062 0.02058643 -0.8905708 0.4516655 0.05368429 -0.6568556 0.752202 0.0522781 -0.6662572 0.7437133 0.05469983 -0.9413453 0.3140178 0.123539 -0.3669176 0.9297876 0.02943682 -0.3388864 0.940311 0.03116732 -0.9063345 0.3901634 0.1622664 -0.7250109 0.676936 0.1269525 -0.9272828 0.3024073 0.2206728 -0.8752437 0.4137768 0.2504739 -0.6362277 0.7542251 0.1623545 -0.546615 0.8227914 0.1556484 -0.3974972 0.9115998 0.104795 -0.8691511 0.3666665 0.3318619 -0.8712452 0.3590301 0.3347077 -0.5889177 0.7697867 0.2461796 -0.1386724 0.988715 0.05668121 -0.5948368 0.7657409 0.2445609 -0.8355804 0.3736659 0.4027149 -0.3356241 0.9267061 0.169034 -0.6965649 0.6041257 0.3870784 -0.6965712 0.6041352 0.387052 -0.5708392 0.7443724 0.3464859 -0.4046656 0.8827614 0.2387011 -0.7702243 0.3782199 0.5135216 -0.7151958 0.4286651 0.5520337 -0.6679738 0.5155926 0.5366334 -0.5345123 0.7302161 0.4255364 -0.5046223 0.7600145 0.4095537 -0.3078607 0.9193363 0.2450362 -0.2152832 0.9583033 0.1879038 -0.6364825 0.4274039 0.6420404 -0.5839354 0.512241 0.6297847 -0.4460686 0.7656459 0.4634751 -0.3419831 0.8565977 0.3863781 -0.5598537 0.4554233 0.6922091 -0.5151735 0.5177938 0.6829977 -0.355668 0.7968845 0.4883395 -0.3163529 0.8629645 0.3939712 -0.4715306 0.4490191 0.7589736 -0.4318974 0.5182032 0.7381938 -0.3322802 0.7857563 0.5217058 -0.09744554 0.9819624 0.1620322 -0.2037525 0.8932991 0.4006266 -0.3797835 0.4343524 0.8167635 -0.386639 0.5177109 0.7632076 -0.2169522 0.8509558 0.4783367 -0.3166874 0.4469428 0.8366309 -0.2833868 0.5170477 0.8076841 -0.1952534 0.8322979 0.5188028 -0.2021976 0.4342963 0.8777831 -0.2159438 0.5246243 0.8234911 -0.1272413 0.8417262 0.524697 -0.1241765 0.8811137 0.45631 -0.04140836 0.9811129 0.1889521 -0.1334789 0.4487331 0.8836414 -0.1074126 0.2631223 0.9587645 -0.06517982 0.7059959 0.7052103 -0.06870132 0.7897295 0.6095961 -0.003528416 0.3653841 0.9308502 0.005123376 0.4221884 0.9064938 -0.02070719 0.9352736 0.3533194 -0.01790809 0.6531819 0.7569894 0.03484231 0.7754606 0.6304341 0.1043424 0.3476469 0.9318017 0.085262 0.4334682 0.8971264 -7.66535e-4 0.9478635 0.3186759 0.08504563 0.6803025 0.7279806 0.06970268 0.7411707 0.6676883 0.01491713 0.9862872 0.1643624 0.1854242 0.2757439 0.9431772 0.08374249 0.9092013 0.4078483 0.215794 0.4558733 0.8634886 0.1861751 0.611214 0.769257 0.2720996 0.3685108 0.8889104 0.1814439 0.7760735 0.6039768 0.1384096 0.8840855 0.4463582 0.1556349 0.8586973 0.4882793 0.2967539 0.5531969 0.7784026 0.3618373 0.5315621 0.765843 0.3651726 0.5239043 0.769528 0.07452273 0.9820519 0.1732646 0.2964562 0.7426207 0.6005233 0.4711849 0.4149757 0.7783188 0.2783733 0.8413294 0.4633284 0.2147446 0.91183 0.3499299 0.4808334 0.4746802 0.7372096 0.3897615 0.7266298 0.5657696 0.5792226 0.3203954 0.7495653 0.5953955 0.3807148 0.7075031 0.180324 0.9540321 0.239387 0.4788227 0.6854382 0.5485467 0.4246727 0.7508711 0.5058121 0.3031886 0.8878693 0.3460705 0.6571895 0.2529639 0.710008 0.6959573 0.3539538 0.6247882 0.6850128 0.4092957 0.6026895 0.5891163 0.6064285 0.5340285 0.4892199 0.7806508 0.3889065 0.7684912 0.3435811 0.5397902 0.2979434 0.9189872 0.2582488 0.7339543 0.415444 0.5373243 0.5599223 0.7277663 0.3960344 0.1379137 0.9857342 0.0964787 0.5558061 0.7502166 0.3581268 0.804901 0.3377739 0.4878969 0.7038266 0.6015925 0.3777761 0.335907 0.9230773 0.1873364 0.8735338 0.3141698 0.3718013 0.6614732 0.6778696 0.3208522 0.7100202 0.6284402 0.3177015 0.444377 0.8730564 0.2007532 0.7089275 0.653795 0.2645262 0.8727428 0.3885893 0.2954967 0.9204069 0.2887872 0.2635399 0.6187593 0.7665685 0.1717842 0.5581077 0.8168694 0.14574 0.372631 0.9208212 0.1150422 0.8916437 0.4008024 0.2105446 0.9242717 0.3485583 0.1556566 0.1096593 0.9936828 0.0238592 0.5864236 0.8053584 0.08663326 0.895578 0.427733 0.1224112 0.9106711 0.410827 0.04358446 0.8592529 0.5113301 0.01503694 0.5483798 0.8360103 0.01914066 0.5142002 0.8565492 0.04383748 -0.005333602 0.9999722 0.005210697 -0.009798645 0.9999265 0.00714761 -0.004814147 0.9999287 0.01093387 -0.01006495 0.9999354 0.005281686 -0.0088225 0.9999477 0.005176961 -0.006122648 0.9999069 0.01219922 -0.004532873 0.999989 0.001246869 -0.006183266 0.9999076 0.01211452 -3.29962e-4 0.9999982 0.001890718 -0.005994558 0.9999817 -9.07795e-4 -0.008487701 0.9999639 4.31746e-4 1.39136e-4 0.9999979 0.002060532 -0.009616672 0.9999532 -0.001040518 0.002513587 0.9999528 0.009393453 -0.007572293 0.9999699 -0.001722931 0.002559661 0.9999535 0.009310185 -0.00794506 0.9999662 -0.002168059 0.001808226 0.9999873 0.004702925 -0.006698727 0.9999717 -0.003433942 0.002341389 0.9999912 0.003484308 -0.007084488 0.9999673 -0.003912925 -0.002239525 0.9999958 -0.001842796 0.005836188 0.99997 0.005108714 0.005755007 0.9999668 0.005773127 -0.001551926 0.9999966 -0.002146065 0.009009003 0.999941 0.006080627 0.007607936 0.9999562 0.00546354 -0.003044903 0.9999744 -0.006476759 0.007048249 0.9999725 0.002316415 -0.002813339 0.9999592 -0.008592069 -0.002547204 0.999972 -0.007043004 0.01326185 0.9999099 0.00207138 -4.51817e-4 0.9999823 -0.005947589 0.01084679 0.9999412 2.11265e-4 0.007971465 0.9999665 0.00189644 3.24217e-4 0.9999688 -0.007890522 0.001063287 0.9999843 -0.005518674 0.007074177 0.9999733 -0.001834869 0.01398777 0.9998818 -0.006380975 0.002078115 0.9999867 -0.004724144 0.002187073 0.9999784 -0.006198883 0.01464104 0.9998835 -0.004347085 0.007867753 0.9999605 -0.004136621 0.003065705 0.9999868 -0.00413984 0.007887363 0.9999598 -0.004281282 0.002186238 0.9999912 -0.00359857 0.002690017 0.9999935 -0.002468347 0.8576517 -0.5137906 0.02128064 0.6596969 -0.7511022 0.02540916 0.8989466 -0.4302942 0.08210986 0.5878763 -0.8047584 0.08225184 0.3755993 -0.9256777 0.04523473 0.807221 -0.5749458 0.1335351 0.6676063 -0.7355714 0.1150502 0.9264047 -0.3032764 0.2231544 0.8636803 -0.4211068 0.2769936 0.1865964 -0.981496 0.04298228 0.4843313 -0.8637893 0.138893 0.5307393 -0.8290149 0.1762111 0.901473 -0.2419818 0.3588753 0.8715144 -0.3677595 0.3243697 0.6113759 -0.7367395 0.2888501 0.4992449 -0.8421917 0.2036361 0.8273196 -0.3658759 0.4262361 0.6227788 -0.7168214 0.3135502 0.8402711 -0.269849 0.4702407 0.5872266 -0.7394203 0.3292759 0.7161717 -0.5061309 0.4805515 0.4158327 -0.8687075 0.2691293 0.7104133 -0.4908811 0.5043299 0.09239709 -0.993926 0.05978208 0.1521635 -0.9823909 0.1084177 0.640702 -0.577718 0.5057103 0.5257914 -0.7375645 0.4237241 0.6749263 -0.3997511 0.6202207 0.3664843 -0.8612771 0.3519817 0.3095384 -0.9025492 0.2993177 0.6164377 -0.467458 0.6336306 0.4812419 -0.701209 0.5260345 0.6213897 -0.2683156 0.7361261 0.5277241 -0.4755337 0.7038289 0.4480077 -0.6810244 0.5792193 0.1610295 -0.9657298 0.2035567 0.3675265 -0.7757132 0.5130239 0.2263861 -0.9167771 0.3290427 0.4928836 -0.3540291 0.7948139 0.4219765 -0.5050783 0.7528824 0.326985 -0.7219992 0.6097524 0.3418554 -0.6785309 0.6501774 0.197653 -0.9077573 0.3700135 0.3852458 -0.2478013 0.8889208 0.1200607 -0.9564319 0.2661266 0.3099396 -0.45354 0.8356069 0.277836 -0.6492035 0.708055 0.2757603 -0.3877559 0.8795462 0.2494717 -0.4342537 0.8655562 0.1646941 -0.8267717 0.5378891 0.1655019 -0.8248311 0.5406134 0.1656743 -0.7234879 0.6701623 0.1821545 -0.2974669 0.9371943 0.1274904 -0.4389571 0.8894172 0.1015573 -0.7263779 0.679751 0.101332 -0.6894462 0.717214 0.09251713 -0.3106796 0.9460015 0.03269964 -0.9173864 0.3966524 0.03235566 -0.9666072 0.2542118 0.01559633 -0.3825119 0.9238191 -0.006426692 -0.5335179 0.8457645 -0.02033388 -0.5684425 0.8224717 -0.03716546 -0.7791824 0.6256945 -0.01629966 -0.8737776 0.4860526 -0.1143698 -0.3498919 0.9297823 -0.1292221 -0.3721346 0.9191396 -0.09556639 -0.7585911 0.6445205 -0.1818159 -0.3001986 0.9363887 -0.03767997 -0.9655703 0.2573993 -0.1168884 -0.8065372 0.5795128 -0.2245138 -0.4620643 0.857957 -0.1481075 -0.7812071 0.6064485 -0.2790288 -0.3818176 0.881112 -0.02280813 -0.9950414 0.09681147 -0.1691831 -0.8243559 0.5401987 -0.3052301 -0.4479858 0.8403233 -0.2504165 -0.7068275 0.6615789 -0.3689258 -0.3471493 0.8621956 -0.1138587 -0.9404475 0.3203041 -0.3929809 -0.4244731 0.8157136 -0.3184314 -0.6995844 0.6396743 -0.4648188 -0.2803405 0.8398529 -0.3069705 -0.7699447 0.5594231 -0.177079 -0.9235439 0.3401612 -0.4961629 -0.383382 0.7789999 -0.121845 -0.9706732 0.2072374 -0.3553435 -0.7352724 0.577153 -0.5420643 -0.2960704 0.7864533 -0.3558626 -0.7892852 0.5003907 -0.255788 -0.9065618 0.3357356 -0.5869337 -0.3784568 0.7157369 -0.5817167 -0.4192937 0.6969925 -0.4853136 -0.6533106 0.5810819 -0.4610549 -0.7388519 0.4914532 -0.2772754 -0.9171122 0.2863979 -0.2365739 -0.937076 0.2567518 -0.6494418 -0.3956646 0.6493651 -0.6078884 -0.5603793 0.5625361 -0.3291637 -0.9028495 0.2766121 -0.7374306 -0.3669151 0.5670709 -0.6226114 -0.5837801 0.5211102 -0.5927888 -0.6460549 0.4808477 -0.2983942 -0.9269397 0.2274724 -0.7862205 -0.3545072 0.5061443 -0.783858 -0.3668088 0.5010171 -0.597776 -0.6975728 0.3950393 -0.5522485 -0.7573515 0.348483 -0.1124271 -0.9912183 0.06961792 -0.822558 -0.3561562 0.4433408 -0.7168297 -0.6093431 0.3389045 -0.5538452 -0.7767088 0.2999653 -0.3676325 -0.9136462 0.1734849 -0.8215768 -0.4844496 0.3005331 -0.7406125 -0.5976641 0.3070681 -0.8338033 -0.4828005 0.2677233 -0.414565 -0.8993657 0.1388427 -0.4307636 -0.8912345 0.1419289 -0.779008 -0.5920184 0.2065453 -0.5072894 -0.8504465 0.1392778 -0.8364821 -0.5220051 0.1667588 -0.4770336 -0.875768 0.07395529 -0.7991076 -0.590277 0.1140185 -0.6643229 -0.7439344 0.07236599 -0.9411965 -0.3309299 0.06807816 -0.6895127 -0.7230864 0.04145354 -0.8997071 -0.4359882 0.02100872 -0.1668894 -0.9859269 0.009803891 -0.9186789 -0.3945584 -0.01878571 -0.5801318 -0.8142607 -0.0206592 -0.828072 -0.5574016 -0.06000167 -0.4677849 -0.8832604 -0.03206938 -0.4649094 -0.8836987 -0.05418682 -0.8956049 -0.4166434 -0.1558859 -0.8328943 -0.5391625 -0.1248645 -0.6436118 -0.7564191 -0.1165943 -0.9121697 -0.355494 -0.2038883 -0.2496616 -0.9666548 -0.05698734 -0.7735132 -0.5850017 -0.2438246 -0.6085973 -0.7751673 -0.1694847 -0.4379556 -0.8889648 -0.1339272 -0.7659271 -0.5995253 -0.2322176 -0.9100527 -0.2096097 -0.3575861 -0.8463076 -0.3758452 -0.3774968 -0.724727 -0.6078956 -0.3243973 -0.3709519 -0.9120622 -0.1747496 -0.2317434 -0.9656605 -0.1174514 -0.6247058 -0.714644 -0.3146848 -0.5639318 -0.7728276 -0.2910647 -0.8406811 -0.2661806 -0.4715965 -0.792655 -0.3925797 -0.4664539 -0.7538874 -0.3570538 -0.5515127 -0.7331945 -0.449728 -0.5100693 -0.5450938 -0.7399613 -0.3941196 -0.4959136 -0.7809621 -0.3796947 -0.2857542 -0.9299586 -0.2313476 -0.6980221 -0.3493314 -0.6250863 -0.695429 -0.3688138 -0.6167292 -0.2380926 -0.9529553 -0.1875852 -0.5414177 -0.6911277 -0.4787582 -0.6512554 -0.3294394 -0.6836199 -0.4237277 -0.7821655 -0.4568064 -0.2973877 -0.9022197 -0.3123465 -0.5418951 -0.5386487 -0.6451413 -0.4547541 -0.7189036 -0.525715 -0.5407552 -0.4243128 -0.7263212 -0.1221511 -0.9787552 -0.1646738 -0.3210964 -0.8231571 -0.468305 -0.1750826 -0.9480044 -0.2657703 -0.4586718 -0.5276234 -0.7150062 -0.3832598 -0.6827151 -0.6221029 -0.4599649 -0.305069 -0.8338856 -0.3861775 -0.4344485 -0.8137084 -0.3055537 -0.7281721 -0.6135164 -0.2695384 -0.7771213 -0.5687105 -0.1854154 -0.9082736 -0.3750472 -0.3562034 -0.3457307 -0.8680953 -0.3192202 -0.42048 -0.849291 -0.2265074 -0.7205218 -0.6553952 -0.2203874 -0.7521625 -0.6210324 -0.2387648 -0.2893901 -0.9269546 -0.1063932 -0.9302433 -0.3511806 -0.2417372 -0.3362191 -0.9102308 -0.07892721 -0.9712224 -0.2247169 -0.197335 -0.6094875 -0.7678437 -0.01172286 -0.9989706 -0.0438224 -0.1588448 -0.3071083 -0.9383246 -0.1052838 -0.5618546 -0.8205088 -0.1246403 -0.6958909 -0.7072486 -0.06668138 -0.907674 -0.4143449 -0.05085968 -0.9257193 -0.3747761 -0.04358983 -0.3943177 -0.9179398 -0.06540596 -0.5512759 -0.8317555 -0.01538568 -0.7286925 -0.6846682 -0.02795892 -0.9107042 -0.412112 0.0238747 -0.3562407 -0.9340893 0.06557375 -0.6640659 -0.7447931 0.01426035 -0.9618098 -0.273347 0.06022071 -0.6562823 -0.7521085 0.06804567 -0.8113144 -0.5806366 0.147715 -0.433363 -0.8890315 0.01427501 -0.993777 -0.1104692 0.2128312 -0.4652624 -0.8592054 0.2117965 -0.4578328 -0.8634417 0.1605734 -0.7857139 -0.597386 0.1258943 -0.8406086 -0.5268092 0.07706612 -0.946191 -0.3142984 0.316541 -0.4287421 -0.8461572 0.3155611 -0.4311151 -0.845317 0.2082452 -0.7620049 -0.6131742 0.3818804 -0.4344674 -0.815724 0.08707916 -0.974281 -0.2078313 0.384588 -0.4782658 -0.7895277 0.2408744 -0.8424932 -0.4818557 0.2136654 -0.8648021 -0.4543837 0.4987207 -0.3373786 -0.7984069 0.4488596 -0.4671218 -0.7617889 0.3703216 -0.7339674 -0.5693452 0.2756313 -0.8372953 -0.4721907 0.5741664 -0.3277765 -0.7502637 0.5728258 -0.3425883 -0.7446502 0.4150528 -0.712645 -0.5655691 0.4033957 -0.7713465 -0.4922365 0.2970707 -0.8961472 -0.3296502 0.6023586 -0.4805175 -0.6373909 0.1304456 -0.9775625 -0.1653952 0.666925 -0.3564804 -0.6543187 0.6167979 -0.4657805 -0.6345148 0.5195762 -0.7239474 -0.4538069 0.3902326 -0.8509698 -0.3515239 0.7217729 -0.3782534 -0.5796278 0.6659691 -0.5542128 -0.4993329 0.6656771 -0.5491706 -0.5052581 0.5099894 -0.8012172 -0.3129885 0.8023297 -0.364224 -0.472872 0.2810019 -0.9414067 -0.1865248 0.2645913 -0.9475042 -0.1795191 0.7846505 -0.4379948 -0.4387302 0.5723068 -0.7525988 -0.3256688 0.8262608 -0.4242652 -0.3705298 0.8197073 -0.4444095 -0.3613588 0.6169221 -0.7324769 -0.2878973 0.2706876 -0.9575127 -0.09948742 0.8453674 -0.4388928 -0.3045113 0.7734611 -0.5877813 -0.2372159 0.4865961 -0.8550877 -0.1790235 0.3811938 -0.9152318 -0.1305453 0.9053413 -0.3815609 -0.1864631 0.7890903 -0.5842822 -0.1896072 0.6879686 -0.7111281 -0.1448999 0.4869444 -0.866402 -0.110602 0.9411424 -0.3152688 -0.1218881 0.8622377 -0.5031325 -0.05834347 0.8956617 -0.4444583 -0.01571708 0.7399605 -0.669373 -0.06631922 0.4683103 -0.8834283 -0.01549679 0.3103776 -0.9505071 -0.01420962 0.2988001 -0.9541935 -0.01527893 0.9998139 -0.003264546 -0.01901316 0.9929358 -4.97518e-4 -0.1186515 0.9962905 0.003238618 -0.08599275 0.9717909 -0.001440167 -0.2358403 0.9849269 0.005049526 -0.1728972 0.9513086 -9.66686e-4 -0.3082388 0.9614883 0.003098189 -0.2748289 0.9102786 -0.002768039 -0.413987 0.9338066 0.003792703 -0.3577584 0.8588089 -0.004692018 -0.5122747 0.8899898 0.00231105 -0.4559745 0.8321915 0.00344181 -0.5544779 0.8037068 0.002600073 -0.5950199 0.7891745 -0.002630054 -0.6141635 0.7111256 0.001322627 -0.7030639 0.7191406 -0.002085328 -0.6948615 0.6393883 0.002129614 -0.7688812 0.6130535 -0.003732442 -0.7900327 0.5633209 0.002790927 -0.8262335 0.5143058 -0.003031075 -0.8576015 0.4374366 -0.002964615 -0.8992445 0.4777744 0.001769661 -0.8784809 0.3375071 -0.003492593 -0.9413166 0.3804689 0.003445267 -0.9247874 0.24616 0.003196299 -0.9692239 0.2566017 1.81067e-4 -0.9665172 0.13521 3.78048e-4 -0.990817 0.1430598 -0.001321971 -0.9897132 0.05724644 -4.88559e-4 -0.99836 0.0627985 -0.001876831 -0.9980245 -0.01710063 0.005052328 -0.999841 -0.08353304 5.8531e-4 -0.9965049 -0.1338154 -0.002291858 -0.9910036 -0.0894941 0.001317143 -0.9959866 -0.2050257 0.005427777 -0.9787416 -0.2554191 -0.003780245 -0.9668231 -0.3809806 -0.003149867 -0.9245777 -0.3454367 0.005509316 -0.9384259 -0.4892973 0.001434743 -0.8721159 -0.4710866 -0.005031585 -0.8820727 -0.5988233 -0.002906799 -0.8008759 -0.5636631 0.001784563 -0.826003 -0.6741297 9.32025e-4 -0.7386125 -0.6228743 0.001621544 -0.7823204 -0.6845449 0.003753721 -0.7289611 -0.7500631 -0.002441108 -0.6613618 -0.8134036 -0.002594411 -0.581694 -0.7766399 0.003795862 -0.6299334 -0.8452181 0.003303229 -0.5344114 -0.86895 -0.004083514 -0.494883 -0.9110217 0.006617724 -0.4123057 -0.9339637 -0.002221107 -0.3573613 -0.9438682 0.002625048 -0.330312 -0.9713224 -0.001701891 -0.2377606 -0.9760277 0.002569794 -0.217631 -0.9925361 -0.002598881 -0.1219238 -0.9989903 -0.003186523 -0.04481518 -0.9970842 0.003068387 -0.07624918 -0.9959333 0.003024876 0.09004378 -0.9972035 -0.001696109 0.07471507 -0.9813191 -0.003275871 0.1923595 -0.9755017 0.002253532 0.2199805 -0.9610823 -0.001293003 0.2762593 -0.9473201 0.003990709 0.3202638 -0.9259 -0.005176305 0.3777332 -0.8966408 -0.001459598 0.4427564 -0.8885769 0.003433406 0.4587147 -0.8388063 -0.002432048 0.5444247 -0.8110207 0.005111634 0.5849952 -0.7755725 -0.00170803 0.6312562 -0.7490695 0.001790702 0.6624891 -0.7219768 -0.00272119 0.691912 -0.6463377 8.74921e-4 0.7630511 -0.6739862 0.004420101 0.7387308 -0.5655593 -0.001857817 0.8247056 -0.6066305 0.00632286 0.794959 -0.4799355 0.00282818 0.8772992 -0.4786208 0.003225922 0.8780158 -0.3902624 -0.003003478 0.9206989 -0.3450389 0.00414288 0.9385793 -0.2974554 -0.00158596 0.9547345 -0.2446098 0.003637671 0.9696148 -0.2047423 -0.003264784 0.9788105 -0.08598363 0.003923296 0.9962888 -0.09584689 0.001336276 0.9953952 -0.01205575 -0.004322946 0.999918 0.05269002 0.005261063 0.9985971 0.09791022 -0.002436935 0.9951924 0.202652 0.002007782 0.9792488 0.2005829 0.002601623 0.9796733 0.2915982 -0.003504574 0.9565346 0.4012308 -0.005105555 0.9159628 0.344834 0.004919528 0.9386509 0.5233374 -0.003043115 0.8521202 0.478328 0.005007505 0.878167 0.5586935 0.003182291 0.8293682 0.6439422 -9.64411e-4 0.7650735 0.6462922 -0.001912415 0.7630876 0.749161 8.72834e-4 0.6623874 0.7429243 -0.001655519 0.6693735 0.8091983 -0.001257419 0.5875344 0.8083732 -9.67169e-4 0.5886697 0.869848 -0.001331329 0.493318 0.8653809 7.41757e-4 0.5011144 0.9131706 0.00460112 0.4075516 0.9300998 -0.002263963 0.3673003 0.9451205 0.00459212 0.3266899 0.9756122 -0.002867937 0.2194828 0.9760017 -0.002427518 0.2177495 0.9942451 0.002955317 0.1070894 0.9910928 -0.00454241 0.1330961 0.9997025 0.003163695 0.02418774 3.64583e-4 -1 4.01742e-4 5.25844e-4 -0.9999998 3.7688e-4 0.002488493 -0.9999737 0.00682199 0.00905776 -0.9999513 0.003936648 0.003966689 -0.9999662 0.007214248 0.004092454 -0.9999312 0.0109989 0.008945167 -0.9999528 0.003812909 0.002872526 -0.9999452 0.01008129 0.003037452 -0.9999499 0.009538769 0.009657621 -0.999947 0.003604233 0.004883527 -0.9999879 6.48118e-4 1.0591e-4 -0.9999936 0.003598332 0.009940385 -0.9999493 -0.001659274 0.006188511 -0.9999808 -4.4859e-4 -6.21433e-4 -0.9999918 0.004018664 0.009282886 -0.9999544 -0.002260208 0.008518576 -0.9999628 -0.00143212 -0.002979397 -0.9999547 0.009045183 -0.003039956 -0.9999645 0.007867097 0.003783464 -0.9999914 -0.001737475 -0.002874135 -0.9999654 0.007803201 0.008638501 -0.9999281 -0.008321046 0.004038155 -0.9999875 -0.002970993 -0.002339661 -0.9999923 0.003165066 -0.003665268 -0.9999865 0.003698587 0.008112788 -0.999929 -0.008739531 0.00907123 -0.9998895 -0.01178073 -0.003602683 -0.9999894 0.002867758 0.006959974 -0.9999202 -0.01054984 -0.007173061 -0.9999673 0.003754377 -0.006736457 -0.9999722 0.003206729 0.003027915 -0.999966 -0.0076828 0.00629121 -0.9999179 -0.01117372 -0.010001 -0.99995 4.09834e-4 -0.0130155 -0.9999091 0.003523945 0.00229752 -0.9999589 -0.008768558 2.90914e-4 -0.9999965 -0.002653479 -0.01418644 -0.9998961 0.002596139 -0.006383717 -0.9999796 2.5708e-4 -2.62549e-4 -0.9999974 -0.002290904 -0.005648493 -0.9999837 -9.58051e-4 -0.01072865 -0.9999329 -0.004396855 -0.001159489 -0.9999918 -0.003867685 -0.001089274 -0.9999954 -0.002845585 -0.01116979 -0.999929 -0.004181146 -0.01017796 -0.9999452 -0.002452373 -0.003769934 -0.9999904 -0.002237915 -0.002062559 -0.9999939 -0.002827405 -0.004180252 -0.9999759 -0.005568146 -0.006497025 -0.9999575 -0.006551027 -0.006515026 -0.9999606 -0.006042182 0.9003874 0.4319049 -0.05254256 0.7973854 0.59776 -0.08282214 0.6269387 0.7777242 -0.04574924 0.1502373 0.9885473 -0.01424926 0.3619577 0.9304631 -0.05678999 0.8296312 0.5390871 -0.1452495 0.784419 0.5944189 -0.1770686 0.8408244 0.487667 -0.2349365 0.5149208 0.8465827 -0.1347384 0.8289566 0.4363733 -0.3498704 0.7658305 0.5745716 -0.2887408 0.5517976 0.8045163 -0.2197111 0.4666172 0.867122 -0.1742636 0.8247435 0.3664988 -0.4306703 0.3060867 0.9434238 -0.1275241 0.8052436 0.4361388 -0.4017035 0.6317411 0.7016606 -0.3295084 0.7886694 0.379227 -0.4839293 0.6975091 0.5452436 -0.464963 0.5477376 0.765488 -0.3376559 0.4547269 0.8402696 -0.2952464 0.29593 0.9361754 -0.1897399 0.7098979 0.4198724 -0.5654663 0.172871 0.9768262 -0.1261993 0.6794032 0.5162553 -0.5214326 0.53431 0.7224836 -0.4387829 0.6698195 0.3506019 -0.6545381 0.667583 0.3693833 -0.6464433 0.4611613 0.7722201 -0.4370428 0.4319326 0.7982677 -0.4197656 0.5955564 0.3802182 -0.7076346 0.59594 0.3694415 -0.7129998 0.4347178 0.7322587 -0.5242307 0.3851587 0.8156844 -0.4316384 0.2626624 0.909271 -0.3228543 0.5227638 0.38924 -0.7584263 0.5235301 0.3651861 -0.7697762 0.4075559 0.6837976 -0.605243 0.3759523 0.7202358 -0.5830269 0.2331216 0.9049623 -0.3559463 0.4485451 0.358103 -0.8188832 0.4241378 0.4188452 -0.8029171 0.3632929 0.6748656 -0.6423199 0.1542915 0.9491271 -0.2745031 0.226193 0.8306022 -0.5088582 0.3514639 0.4260296 -0.8336498 0.3582416 0.4088827 -0.8393318 0.2207456 0.8016763 -0.5555056 0.2186864 0.8026594 -0.5549001 0.2586694 0.4748786 -0.841178 0.2178632 0.6485518 -0.7293259 0.2447709 0.3118168 -0.9180727 0.09070599 0.9361757 -0.3396286 0.1369108 0.7424001 -0.6558182 0.08428865 0.9104032 -0.4050452 0.142428 0.4559395 -0.8785405 0.1138544 0.5766911 -0.80899 0.04247015 0.9364971 -0.3480942 0.09571397 0.59122 -0.8008108 0.02828228 0.8768159 -0.4799937 0.04144763 0.503806 -0.8628219 0.009160399 0.5270082 -0.849811 -0.02191871 0.6181659 -0.785742 0.02235823 0.8726457 -0.487842 -0.03512948 0.6214001 -0.7827056 -0.09872871 0.4893818 -0.866463 -0.05699598 0.8572973 -0.5116572 -0.03973007 0.9367733 -0.3476746 -0.1204226 0.5028589 -0.855939 -0.2005214 0.2829466 -0.9379405 -0.04028511 0.952846 -0.3007686 -0.1393888 0.6432701 -0.7528443 -0.2237018 0.4468125 -0.8662079 -0.1762328 0.6496114 -0.7395587 -0.1790006 0.8036797 -0.5675013 -0.1049039 0.9116792 -0.3972861 -0.3411219 0.198894 -0.9187366 -0.3000569 0.3978368 -0.8670016 -0.2814507 0.6186963 -0.7334851 -0.1925281 0.7952488 -0.5749021 -0.4021397 0.4322067 -0.8071438 -0.3582072 0.5611384 -0.7461979 -0.1841967 0.9061388 -0.3807678 -0.452633 0.3175894 -0.8332229 -0.3048538 0.775556 -0.5527904 -0.491429 0.3617174 -0.7922488 -0.1100928 0.9725672 -0.2049217 -0.4573087 0.6079345 -0.6490643 -0.3761266 0.7375442 -0.5608541 -0.5248689 0.5396808 -0.6582229 -0.2444134 0.9139764 -0.323897 -0.6448844 0.3703971 -0.6685284 -0.2368878 0.9268575 -0.2912379 -0.5479349 0.557208 -0.6239284 -0.4399419 0.7806752 -0.4438441 -0.6673976 0.4723334 -0.5757445 -0.07103943 0.9951304 -0.06832885 -0.5229851 0.7246425 -0.4487537 -0.462804 0.7818921 -0.4176806 -0.7356405 0.3338335 -0.5893966 -0.2319412 0.9552983 -0.1833264 -0.7651034 0.4138516 -0.493299 -0.759121 0.4334571 -0.4856442 -0.5809623 0.7208439 -0.3779775 -0.525641 0.7862802 -0.3247541 -0.3306955 0.919274 -0.2134847 -0.8158816 0.4245292 -0.3925713 -0.1640722 0.9833775 -0.07777678 -0.7303799 0.6034566 -0.3199772 -0.5911576 0.7561312 -0.2807106 -0.3824307 0.9121818 -0.1472113 -0.8374648 0.4789683 -0.2631392 -0.7595167 0.5916409 -0.2703616 -0.4562469 0.8790455 -0.1382681 -0.4520113 0.8826079 -0.1291871 -0.8608222 0.4727227 -0.1884632 -0.8764328 0.4367153 -0.2028434 -0.5887795 0.7997175 -0.1174342 -0.5654158 0.8201416 -0.08759498 -0.9134988 0.4004359 -0.07191115 -0.2833677 0.9587128 -0.02393329 -0.907474 0.4144246 -0.06887137 -0.1437736 0.9893944 -0.02068388 -0.6996831 0.7126315 -0.05099004 -0.6246961 0.7808147 -0.009122788 -0.362439 0.9319711 -0.008244693 -0.8774728 0.4792091 0.02000796 -0.6958503 0.7177304 0.02560293 -0.9477595 0.3105855 0.07272225 -0.6607758 0.7483137 0.05832719 -0.8892015 0.4446008 0.1079396 -0.7121716 0.6963066 0.08926796 -0.3242014 0.945646 0.0254389 -0.9086118 0.3698953 0.1939131 -0.8211763 0.5323747 0.20554 -0.6785345 0.7213022 0.1389759 -0.1799607 0.9830619 0.03469014 -0.4204498 0.8996117 0.1179872 -0.8740295 0.3728013 0.3115955 -0.8104932 0.5322028 0.244665 -0.5271427 0.8269079 0.1958165 -0.8230386 0.4430969 0.3553487 -0.7073239 0.624019 0.3321042 -0.5254292 0.8247539 0.2090578 -0.8794208 0.1500784 0.4517695 -0.7623155 0.4711502 0.4437261 -0.3528412 0.9183203 0.1794184 -0.6861413 0.6165102 0.3861677 -0.5878213 0.7270367 0.3548011 -0.7729752 0.3222315 0.5465128 -0.1800776 0.977722 0.1078503 -0.5123127 0.773443 0.3732584 -0.3464632 0.9015021 0.2593399 -0.02286863 0.9996095 0.01606047 -0.6185033 0.5982423 0.5094703 -0.6500834 0.4861488 0.5839956 -0.6184276 0.5977224 0.5101718 -0.2235285 0.9478362 0.2272479 -0.6041443 0.4893328 0.6289381 -0.5161938 0.6247402 0.58587 -0.4204735 0.7937387 0.4395238 -0.2598241 0.9252108 0.276544 -0.5257942 0.4406158 0.7275976 -0.4873172 0.6033561 0.6312555 -0.261112 0.887639 0.3793647 -0.3325404 0.8054186 0.49063 -0.431415 0.4218266 0.7974607 -0.4311351 0.4264778 0.7951347 -0.3509093 0.6830795 0.6405194 -0.207958 0.8506398 0.482872 -0.1303588 0.9636608 0.2331618 -0.3210383 0.4321864 0.8427036 -0.2743049 0.5464699 0.7912822 -0.2028368 0.8434446 0.4974521 -0.2099133 0.3992071 0.8925077 -0.227032 0.5296568 0.8172639 -0.0833528 0.9396756 0.3317562 -0.09339785 0.8506723 0.517333 -0.1309037 0.4520751 0.8823222 -0.1047151 0.6153702 0.7812519 -0.08889591 0.840865 0.5338949 -0.09622019 0.2410589 0.9657289 -0.002209663 0.4651878 0.8852093 -0.004494607 0.6727644 0.7398431 0.003299415 0.7249538 0.6887897 -0.01292061 0.875006 0.4839397 0.05373412 0.2846763 0.9571166 0.008134961 0.9496597 0.3131776 0.09756731 0.4425984 0.8913963 0.06802773 0.6890992 0.721467 0.08950001 0.780614 0.6185722 0.06805467 0.8831725 0.4640852 0.1885873 0.3198696 0.9285032 0.173911 0.3821537 0.9075866 0.160718 0.6552202 0.7381439 0.1902365 0.6906943 0.6976758 0.2863325 0.4848237 0.8264137 0.0939247 0.9561081 0.277553 0.09859937 0.9408671 0.3241104 0.3228744 0.3571833 0.8764544 0.2736314 0.5007281 0.8212169 0.1860882 0.8810004 0.4349822 0.3881992 0.461391 0.7977594 0.2838897 0.7374539 0.6128364 0.270447 0.774052 0.5724526 0.4308738 0.3829038 0.8171491 0.4518126 0.5772459 0.6801857 0.2983164 0.7901533 0.5354111 0.1357426 0.9775294 0.1612773 0.5254157 0.4147899 0.7428915 0.4320784 0.5894268 0.6825572 0.1727464 0.9499159 0.2604202 0.3816851 0.7831055 0.4909811 0.233099 0.9209362 0.3123162 0.5936602 0.3988871 0.6988968 0.5927862 0.4068648 0.6950292 0.4687187 0.7006924 0.5378967 0.4480722 0.7785143 0.4394846 0.6915303 0.3629096 0.624566 0.2431579 0.9377 0.2481797 0.6758701 0.4440119 0.5882627 0.5393673 0.6975945 0.4716406 0.7647673 0.3371452 0.5490576 0.1592773 0.9766821 0.1439545 0.500366 0.786139 0.3627939 0.391333 0.879754 0.2699838 0.7547925 0.4214836 0.502633 0.6667782 0.6089867 0.4295837 0.8298849 0.2744073 0.4857898 0.3589122 0.90846 0.2142023 0.7367543 0.5775979 0.3515309 0.6799859 0.6484753 0.3421975 0.5167616 0.8138052 0.2658547 0.7570036 0.5541938 0.3461429 0.1467278 0.9868248 0.06817561 0.768615 0.5664818 0.2972027 0.3428447 0.9302468 0.1307613 0.8712903 0.4017846 0.2818198 0.5340731 0.8311356 0.1548536 0.8705722 0.444625 0.2107433 0.8410155 0.5071753 0.1883247 0.6193965 0.7735171 0.134237 0.5494636 0.8254537 0.1292907 0.9183756 0.380881 0.1073132 0.3163598 0.9471463 0.05320262 0.6893147 0.7211939 0.06873613 0.923442 0.3828625 0.02591389 0.9086067 0.4065158 0.09580701 0.9078485 0.4190133 0.0154553 0.6104817 0.7917845 0.01973342 0.5886113 0.8082777 0.01497054 0.4183897 0.9080829 0.0183224 -0.00159502 0.9999975 0.001588284 -0.01091492 0.9999167 0.006901681 -0.01023662 0.9999278 0.006292223 -0.001072525 0.9999977 0.001897573 -0.004059016 0.9999061 0.01309472 -0.009772658 0.9999487 0.002692997 -0.00332427 0.999861 0.01634478 -0.00348109 0.9999052 0.01332932 -0.00616014 0.9999771 0.002829313 -0.002197742 0.9999207 0.01240485 -8.39163e-4 0.9998824 0.01531702 -0.002375304 0.9999972 -5.20221e-5 -0.005846321 0.9999818 -0.001547038 9.80608e-4 0.9999787 0.006463885 0.001611649 0.9999735 0.007095396 -0.005252242 0.9999849 -0.001699686 0.001700162 0.9999902 0.004093408 -0.006133079 0.9999774 -0.002776503 -0.004500627 0.9999863 -0.002694189 0.003145456 0.9999846 0.004588782 0.002991557 0.9999876 0.003988683 -0.005055725 0.9999747 -0.004996716 -0.004419386 0.9999818 -0.004105031 0.004354953 0.9999836 0.003747463 0.005461931 0.9999757 0.004341006 -0.002549111 0.9999881 -0.004154205 -0.003988206 0.9998972 -0.01377874 0.006670832 0.9999727 0.003216683 -0.005126118 0.9998828 -0.01442569 0.01664602 0.9998477 0.005239486 -0.008245646 0.9999493 -0.005783617 0.01625949 0.9998602 0.003928601 0.01063865 0.9999268 0.005774259 -0.001309216 0.9999521 -0.009704589 -0.001074433 0.999935 -0.01134878 0.006062984 0.9999816 2.84426e-4 0.001051008 0.999943 -0.01062273 0.01029503 0.9999457 -0.001679778 -0.00111109 0.9999796 -0.006294667 0.009375751 0.9999544 -0.001849412 0.001904726 0.9999788 -0.0062173 0.007372915 0.9998826 -0.01343464 0.00363028 0.9999925 -0.001426994 0.009382545 0.9999548 -0.00160396 0.006837785 0.9998835 -0.01365596 0.005164802 0.999911 -0.01230204 0.003164827 0.9999931 -0.002000868 0.00613147 0.9999484 -0.008110105 0.009896993 0.9998894 -0.01110506 0.01263147 0.9998702 -0.01000356 0.01219743 0.999859 -0.01153844 -0.06102907 -0.4389111 -0.8964556 -0.07295715 -0.553975 -0.8293305 -0.04030704 -0.820728 -0.5698956 -0.03981071 -0.8984017 -0.4373667 -0.2242978 -0.538971 -0.8119119 -0.2788031 -0.4142071 -0.8664303 -0.1122652 -0.9346846 -0.3372851 -0.3033261 -0.5759978 -0.7590915 -0.363912 -0.6509105 -0.6662459 -0.4121938 -0.5208137 -0.7475623 -0.2024942 -0.8886291 -0.4115028 -0.3968695 -0.547735 -0.7365331 -0.510128 -0.525612 -0.6808095 -0.5446081 -0.4662922 -0.6971182 -0.1957772 -0.9329442 -0.3021363 -0.6296931 -0.4807762 -0.6101975 -0.3971489 -0.8267318 -0.3984815 -0.672926 -0.3983224 -0.6233058 -0.3376788 -0.8910555 -0.3033038 -0.6612629 -0.5591003 -0.5001382 -0.5413053 -0.7679958 -0.3423028 -0.8153977 -0.3880978 -0.4295424 -0.7441808 -0.5217414 -0.4171103 -0.3569403 -0.9055644 -0.229231 -0.3881763 -0.8954942 -0.2177368 0.7236592 -0.2262112 -0.6520322 -0.9018011 -0.3264119 -0.283214 -0.746627 -0.6394855 -0.1833205 -0.6989155 -0.693042 -0.1766631 -0.1107441 -0.993496 -0.02648478 -0.807472 -0.5685403 -0.1573247 -0.9211255 -0.3869159 -0.04270935 -0.504765 -0.8621239 -0.04421144 -0.8702384 -0.492438 -0.01378351 -0.6902785 -0.7232668 0.02002316 -0.9378081 -0.3325909 0.09949582 -0.5043569 -0.8613836 0.06035488 -0.8771482 -0.4619526 0.1311909 -0.5128034 -0.8460857 0.1455048 -0.8905245 -0.3523897 0.2877285 -0.821408 -0.5173542 0.2400696 -0.4161355 -0.8975371 0.1458021 -0.5240438 -0.8087477 0.2670308 -0.861248 -0.2762386 0.4265493 -0.6927986 -0.6076349 0.3883428 -0.4700956 -0.8471245 0.2477707 -0.6424863 -0.5894541 0.4896482 -0.6384781 -0.5040798 0.5815922 -0.6767501 -0.4391549 0.5908913 -0.4675066 -0.7884541 0.3997222 -0.3535299 -0.8759511 0.3282172 -0.535709 -0.5180479 0.6668151 -0.5309943 -0.5551017 0.64024 -0.2045088 -0.9314123 0.3010769 -0.3501291 -0.7279049 0.5895456 -0.4875758 0.111456 0.8659374 -0.428901 -0.3154572 0.8464814 -0.2878637 -0.6824638 0.6718465 -0.1991856 -0.8964253 0.3959126 -0.2811836 -0.5355238 0.7963353 -0.218721 -0.3772566 0.8999103 -0.1035779 -0.9040034 0.4147888 -0.1417254 -0.5046041 0.8516388 -0.08663815 -0.3670544 0.926156 -0.09536767 -0.8090582 0.5799396 -0.06099915 -0.8561874 0.5130521 -0.01509779 0.9818482 0.1890664 0.03777194 -0.5457115 0.8371214 8.10484e-4 -0.7823526 0.6228353 0.1000925 -0.2731662 0.9567454 0.05187535 -0.926437 0.3728584 0.1594173 -0.5796273 0.7991361 0.350822 -0.3722245 0.8592863 0.1862921 -0.8202381 0.5408372 0.273705 -0.5910646 0.7587676 0.1871823 -0.8170682 0.5453095 0.3982216 -0.445127 0.8020483 0.2289484 -0.8913912 0.3911582 0.4143009 -0.6167249 0.6693319 0.3710077 -0.7758701 0.5102736 0.5659538 -0.4356779 0.6999151 0.5593261 -0.4740135 0.6800482 0.3611494 -0.7921778 0.491961 0.7390303 -0.2625359 0.6204105 0.4325764 -0.7944303 0.4263311 0.6273568 -0.5998309 0.4966151 0.5516985 -0.7053911 0.4450308 0.8154565 -0.307887 0.4901391 0.6841769 -0.6362102 0.3565652 0.2928195 -0.9416189 0.1661645 0.7273257 -0.6111799 0.3121803 0.5683913 -0.7991034 0.1958705 0.8818544 -0.4127781 0.2279188 0.8421549 -0.4987139 0.2050846 0.4090076 -0.90544 0.1135394 0.8432688 -0.5351843 0.0497561 0.6772633 -0.7355888 0.01495134 0.5305012 -0.8471985 0.02869224 0.9079238 -0.4184535 0.02389794 0.8410773 -0.5336937 -0.08809161 0.9184226 -0.3662939 -0.1494283 0.4997983 -0.8628343 -0.07562083 0.6061043 -0.7861716 -0.120714 0.809981 -0.5255349 -0.2602762 0.3333035 -0.9329662 -0.1359524 0.7631446 -0.6056378 -0.2254185 0.7363207 -0.5834749 -0.3426204 0.7487254 -0.5556748 -0.3614359 0.3184956 -0.9321715 -0.1720955 0.6376351 -0.6673625 -0.3847712 0.7480912 -0.3416319 -0.5689001 0.6103568 0.6558355 -0.4442347 0.6112263 -0.6102984 -0.5039229 0.5738831 -0.6805132 -0.4555875 0.6235812 -0.3183603 -0.713998 0.4075325 -0.8053157 -0.4305624 0.4096734 -0.6982827 -0.5870001 0.5534904 -0.2137178 -0.8049679 0.3303644 -0.7808215 -0.5302615 0.377065 -0.5209766 -0.7657713 0.3798777 -0.486267 -0.7869163 0.05505108 0.9938233 -0.09635716 0.2364498 -0.7797151 -0.5797724 0.2312001 -0.7983933 -0.5559808 0.2281556 -0.5164107 -0.8253878 0.2293142 -0.800352 -0.553942 0.1554634 -0.5396609 -0.8274039 0.09456712 -0.7081995 -0.6996503 0.07542914 -0.916606 -0.3926119 -0.002625465 -0.6695062 -0.7428019 -0.08849048 -6.26234e-4 0.9960768 -0.165844 7.9379e-4 0.9861518 -0.2643356 -5.74027e-4 0.9644306 -0.3142933 3.783e-4 0.9493259 -0.3744565 -1.99742e-4 0.9272445 -0.4239836 3.88584e-4 0.9056698 -0.5152344 -6.60151e-4 0.8570491 -0.5551812 6.47647e-5 0.8317295 -0.6156491 -4.78798e-4 0.7880204 -0.6466156 1.30632e-4 0.762816 -0.6975435 -2.48762e-4 0.7165425 -0.72338 3.43885e-4 0.69045 -0.7865503 -2.22001e-4 0.6175262 -0.8113292 4.88191e-4 0.5845894 -0.8576596 -3.41806e-4 0.5142177 -0.8930163 6.77519e-4 0.4500238 -0.9225671 -4.56575e-4 0.3858364 -0.9568052 9.99382e-4 0.290728 -0.9733256 4.64723e-5 0.2294282 -0.988915 0.001078248 0.148479 -0.9980747 -1.66556e-4 0.06202393 -0.9999874 7.55103e-4 -0.00496608 -0.9965378 -6.46816e-4 -0.083139 -0.9851651 7.99874e-4 -0.1716077 -0.9635819 -1.44619e-4 -0.2674139 -0.9517064 3.03408e-4 -0.3070098 -0.9425497 -1.76121e-4 -0.334066 -0.8831274 3.36979e-4 -0.4691333 -0.8812353 2.19653e-4 -0.4726778 -0.8207813 -2.64545e-4 -0.5712427 -0.8036663 2.72026e-4 -0.5950803 -0.7217465 -3.15964e-4 -0.6921574 -0.7400177 5.47378e-4 -0.6725872 -0.6549715 -5.8139e-4 -0.7556534 -0.5946065 4.41063e-4 -0.8040169 -0.5541764 -2.36663e-4 -0.8323993 -0.4958968 7.1437e-4 -0.8683813 -0.3861051 -3.79931e-4 -0.9224548 -0.3715032 -9.08903e-6 -0.9284317 -0.2480111 5.15431e-5 -0.9687573 -0.2719421 7.01432e-4 -0.9623135 -0.1366043 -2.0351e-4 -0.9906257 -0.1052814 5.08111e-4 -0.9944424 0.02873635 -2.9733e-4 -0.999587 0.04949587 4.78912e-5 -0.9987744 0.1520861 -3.97758e-4 -0.9883672 0.1337257 1.38855e-4 -0.9910185 0.3090477 -0.001001596 -0.9510461 0.2526634 8.03967e-4 -0.9675539 0.3886823 -2.07102e-4 -0.9213718 0.4468786 7.92223e-4 -0.8945943 0.4839652 4.86855e-5 -0.8750873 0.5444449 4.11223e-4 -0.8387965 0.6056366 -6.79694e-4 -0.7957411 0.6881639 -3.99151e-4 -0.7255553 0.6697174 2.75173e-4 -0.742616 0.7602508 -2.29131e-4 -0.6496298 0.7787134 3.96845e-4 -0.6273799 0.8316205 -1.57224e-4 -0.5553446 0.8560599 5.24376e-4 -0.5168763 0.9132021 -1.99477e-4 -0.4075069 0.9067627 -5.99743e-4 -0.4216411 0.9584462 5.43966e-4 -0.285273 0.9680713 -3.98627e-4 -0.2506747 0.9940316 1.89899e-4 -0.1090927 0.9957604 -2.73249e-4 -0.0919851 0.9982976 4.84149e-4 0.05832463 0.9954116 -5.50882e-4 0.09568536 0.9706259 7.00822e-4 0.2405929 0.956725 -6.37544e-4 0.2909929 0.8957264 -4.3648e-4 0.4446057 0.9153761 3.3597e-4 0.4025996 0.8600856 5.4134e-4 0.5101497 0.7953347 -7.79693e-4 0.6061701 0.7587026 6.43567e-4 0.651437 0.6734774 -5.15641e-4 0.7392076 0.6418493 4.42707e-4 0.7668308 0.52968 -1.4506e-4 0.8481976 0.5500386 6.29174e-4 0.835139 0.4143616 -2.49205e-4 0.9101123 0.3682238 7.23765e-4 0.929737 0.269211 -5.5347e-4 0.9630812 0.2199282 6.37534e-4 0.9755159 0.08027565 -5.70909e-4 0.9967726 0.01690715 8.39905e-4 0.9998568 0.004714429 -0.9999857 -0.002534985 -0.00221765 -0.9999975 5.0261e-4 -0.003654539 -0.999984 0.004320442 2.05263e-4 -0.9999992 0.00133562 0.001377642 -0.9999988 -8.35149e-4 0.001439034 -0.9999986 -7.98698e-4 0.001042306 -0.9999988 0.001216411 -0.001447975 -0.9999986 8.67583e-4 -2.23403e-4 -0.9999989 0.001518726 -0.002100586 -0.9999134 -0.01299566 -0.001117527 -0.9999994 -2.08737e-4 -0.003866434 -0.9999729 0.006255805 0.001355051 -0.9999976 0.001703262 -0.004408061 -0.9999831 -0.003782033 -0.001533448 -0.9999982 -0.00111109 -0.001621842 -0.9999976 -0.001501917 -1.99579e-4 -0.9999992 -0.001277208 -0.002560853 -0.9999926 -0.00287193 5.22867e-4 -0.9999991 -0.001257598 -0.001251459 -0.9999983 0.001347839 0.006085276 -0.9999722 0.004319429 2.41607e-4 -0.9999989 -0.001503229 0.001469194 -0.9999938 0.003202497 -9.36374e-4 -0.9999983 -0.001617014 5.78253e-4 -0.9999992 -0.001213967 0.001074373 -0.9999956 0.002782464 0.00186938 -0.9999983 -1.04579e-4 -3.76253e-4 -0.9999997 -7.42471e-4 0.001239061 -0.9999992 -2.16443e-4 -3.72297e-4 -0.9999999 4.11116e-4 0.001393675 -0.9999858 -0.005166292 0.001000285 -0.9999983 0.001550436 9.39687e-4 -0.9999983 0.001604735 -0.005479693 -0.9999849 -5.41178e-4 -3.3409e-4 -0.9999929 0.003764212 0.001977443 -0.9999944 -0.002723634 -0.001803278 -0.9999948 0.002705931 -0.001506567 -0.9999958 0.002489984 0.001454949 -0.9999855 -0.00519061 0.001924216 -0.9999982 -2.90884e-4 8.3343e-4 -0.9999982 0.001710355 -0.02530586 0.4914119 0.8705596 -0.05439651 0.5555818 0.8296808 -0.149978 0.3547967 0.9228358 -0.08538198 0.751028 0.6547268 -0.08573549 0.7655493 0.6376392 -0.2154009 0.5489878 0.8075982 -0.1953289 0.8404538 0.5054544 -0.3866266 0.1616001 0.9079678 -0.2119795 0.7509427 0.6254198 -0.3190122 0.6570942 0.6829776 -0.3982388 0.5410536 0.7407205 -0.2466687 0.8341334 0.4933317 -0.3981765 0.5508586 0.7334919 -0.5395146 0.4157709 0.7321603 -0.2702748 0.8952226 0.3542996 -0.5298169 0.5198856 0.6700844 -0.5820932 0.582473 0.5673558 -0.5462855 0.6023575 0.5820119 -0.6901174 0.4322978 0.5803935 -0.3051712 0.9137926 0.2680555 -0.6765183 0.4898851 0.5498505 -0.3474931 0.9202721 0.1798555 -0.7550928 0.4913358 0.4340785 -0.6285711 0.6583367 0.414115 -0.7482441 0.5912368 0.3009483 -0.7328765 0.610709 0.2998775 -0.5599405 0.7978712 0.223312 -0.7549434 0.5869201 0.2925501 -0.6594168 0.7376486 0.1450659 -0.7674575 0.6344018 0.09243136 -0.9508851 0.29808 0.08346188 -0.5792387 0.8151561 -0.001733303 -0.1037634 0.9945812 0.006439208 -0.8247027 0.5554458 -0.106515 -0.6532101 0.7538653 -0.07073777 -0.7088888 0.7023779 -0.06435769 -0.1379216 0.990338 -0.01444125 -0.857071 -0.4312459 -0.2818804 -0.7408553 0.6358758 -0.2163222 -0.641105 0.737879 -0.2109951 -0.5386738 0.8254256 -0.1688292 -0.4937925 -0.8591158 -0.1344957 -0.7160306 0.5811951 -0.3866685 -0.7712538 0.5011307 -0.392474 -0.3861603 0.9048586 -0.1791958 -0.7107821 0.5031098 -0.4915989 -0.5435602 0.7558395 -0.3650328 -0.7390205 0.3698871 -0.5630562 -0.3491049 0.8974528 -0.2696371 -0.6215337 0.5335536 -0.5735996 -0.5708588 0.4937275 -0.6560133 -0.6026399 0.4396079 -0.6660106 -0.2489873 0.9254499 -0.2855658 -0.4504787 0.5040539 -0.7368844 -0.4108733 0.6906356 -0.5951518 -0.3486188 0.7757583 -0.5259886 -0.1925473 0.8152642 -0.5461411 -0.3692945 0.4794091 -0.7961085 -0.2480589 0.7588577 -0.6021643 -0.254651 0.1782917 -0.9504552 -0.2203171 0.76797 -0.6014004 -0.1840702 0.6032534 -0.7760178 -0.2392916 -0.2347872 -0.9421331 -0.06623804 0.7485656 -0.659744 0.01547223 0.6908915 -0.722793 -0.008994698 0.6318345 -0.7750512 0.09758007 0.6248193 -0.7746477 0.06912124 -0.4147449 -0.9073086 0.1521086 0.5190259 -0.8411154 0.07056939 0.8905434 -0.4493914 0.209167 0.6415073 -0.7380499 0.3002241 0.5521405 -0.7778216 0.1173669 0.945041 -0.3051601 0.303188 0.6002336 -0.7401329 0.3912876 0.6010926 -0.696837 0.3885409 0.6243985 -0.6776154 0.3310741 0.7552873 -0.5656247 0.6008008 0.4271038 -0.6757372 0.6010146 0.05829197 -0.7971096 0.4173751 0.7966191 -0.4372598 0.4710353 0.7431963 -0.4751687 0.6645801 0.5141352 -0.5422163 0.3436091 0.9080592 -0.2395026 0.6171921 0.5808959 -0.5306921 0.6417851 0.6657305 -0.3806766 0.6925359 0.6168287 -0.3740541 0.7998526 0.4587171 -0.387059 0.5661002 0.7666665 -0.3029077 0.5784451 -0.7641765 -0.2853692 0.5751731 0.7798725 -0.2469309 0.8728393 0.4299175 -0.2309172 0.8885341 0.3890685 -0.2431728 0.6089673 0.7805714 -0.1409517 0.8418343 0.5152984 -0.16057 0.8467897 0.5265069 -0.07574963 0.1236699 0.9920667 -0.02257382 0.9175724 0.394973 -0.04535663 0.5243334 0.8504296 -0.042943 0.8424009 0.5302865 0.09569287 0.8678829 0.4886341 0.08953189 0.7017267 0.7076672 0.08238208 0.4429801 0.896036 0.02980101 0.5831688 0.8117298 0.03176617 0.7980805 0.5559659 0.2323138 0.7552267 0.6134985 0.2307647 0.7449279 0.6363843 0.2002437 0.436221 0.8876287 0.1477381 0.3347265 0.921715 0.1959586 0.8428342 0.4450232 0.3026298 0.6765787 0.6560016 0.3345195 0.7240893 0.463656 0.5106053 0.4094505 0.8698386 0.2751929 0.318751 0.919969 0.2281557 0.6725212 0.5493806 0.4958792 0.6266897 0.4424008 0.6415151 0.5461477 0.559495 0.6234486 0.2805847 0.8967835 0.3421282 0.5496411 0.544479 0.6335909 0.6666587 0.2416411 0.705107 0.3852479 0.6914667 0.611112 0.4881245 -0.5610715 0.6685307 0.351458 0.5764526 0.7376854 0.1991414 0.9177537 0.3436145 0.3720962 0.5402427 0.7547731 0.2623724 0.468729 0.8434773 0.2038381 0.5973775 0.7756225 0.1398275 0.9002167 0.4123812 0.1502665 0.8065583 0.5717375 0.1326664 0.4328475 0.8916516 0.03941202 0.9340737 0.3548987 0.07078611 0.5981932 0.7982196 0.003371715 0.9228134 0.3852327 0.006938397 0.9999685 0.003876566 -0.004841446 0.9999517 -0.008557677 -0.001741707 0.9999972 -0.001603603 0.00115174 0.9999991 7.13107e-4 0.001191377 0.9999954 0.002803623 0.001095116 0.9999989 0.00106132 -7.67792e-4 0.9999997 -2.1793e-4 -4.43163e-4 0.9999998 5.33485e-4 0.004870057 0.9999865 -0.001846253 -9.33108e-4 0.9999988 0.001329123 0.001178145 0.9999984 -0.001410722 0.002649545 0.9999946 -0.001959025 8.43544e-4 0.9999997 -1.35533e-4 -0.00250858 0.9999969 1.95823e-4 -0.00289911 0.9999958 1.80863e-4 3.43078e-4 0.9999771 -0.00676167 -0.002703905 0.9999964 2.7559e-4 -2.21562e-4 1 1.67013e-4 -0.004016101 0.9999896 0.002138912 0.001466512 0.999999 -4.87724e-5 0.001740038 0.9999979 -0.001142442 -1.18117e-4 0.9999994 0.001140475 -5.654e-5 0.9999959 0.002887725 0.001329958 0.9999973 -0.001938819 2.51274e-4 0.999995 -0.003176271 1.86711e-4 0.9999997 7.06215e-4 -0.006159722 0.9999811 5.36479e-5 -0.001662194 0.9999981 0.001086533 -0.001357972 0.9999918 0.003813862 0.001470625 0.999998 -0.001413106 0.002002656 0.999998 1.61661e-4 0.00151652 0.9999986 -7.22656e-4 0.003932952 0.999992 7.75178e-4 -0.001286268 0.9999982 0.001417815 0.002063035 0.9999979 9.61812e-5 -3.3924e-4 0.9999976 0.002184808 -5.25007e-4 0.999999 -0.001346766 -9.57984e-5 0.9999999 -5.88961e-4 -0.003766059 0.9999899 -0.00249952 -3.59162e-4 0.9999977 0.002173125 -0.9742205 0.005106627 -0.2255402 -0.9691971 -0.003281295 -0.2462648 -0.8442702 0.003637731 -0.5359055 -0.8310362 -0.007530868 -0.5561673 -0.6294348 0.0094558 -0.7769959 -0.577546 -0.01169282 -0.8162745 -0.425485 0.010127 -0.9049088 -0.3269318 -0.01338428 -0.9449532 -0.1728518 0.01208215 -0.9848737 -0.03366923 -0.01407861 -0.999334 0.07566618 0.0146718 -0.9970254 0.3102489 -0.02153581 -0.9504114 0.4190242 0.02154117 -0.9077196 0.6293055 -0.0159558 -0.7769942 0.6985545 0.01165032 -0.7154621 0.8244366 -0.0113458 -0.5658408 0.8704263 0.0136047 -0.4921109 0.9546552 -0.01349842 -0.2974076 0.9822328 0.01529324 -0.1870427 0.9989058 -0.01450932 -0.04446232 0.9937915 0.01402461 0.1103713 0.9579634 -0.01511979 0.286492 0.946861 -0.001974761 0.3216372 0.8440038 0.01140838 0.5362159 0.7872352 -0.01709342 0.616416 0.6715187 0.01588517 0.7408174 0.5727642 -0.01339364 0.8196108 0.3777564 0.009711563 0.9258542 0.4148072 -0.007972717 0.9098745 0.2097536 0.01027202 0.9777004 0.1154353 -0.01391875 0.9932175 -0.07783752 0.01085186 0.9969071 -0.1357877 -0.005260646 0.990724 -0.3272865 0.003597795 0.9449183 -0.362488 -0.006394445 0.9319665 -0.5292913 0.0103622 0.8483769 -0.5963593 -0.01036047 0.8026509 -0.7407288 0.007136881 0.6717663 -0.7584591 -9.13591e-4 0.6517201 -0.903272 0.01221549 0.4288944 -0.8837704 -9.14663e-4 0.46792 -0.9634431 -0.01527649 0.2674778 -0.9961767 0.01463365 0.08612686 -0.9997848 -0.00600773 0.01985508 0.9742402 0.001294076 0.2255091 0.9756167 0.004449725 0.2194365 0.853401 -0.01103943 0.5211383 0.8260163 0.01103496 0.5635384 0.6033535 -0.004324555 0.7974622 0.62423 0.008803427 0.7811912 0.4197387 -0.01122224 0.9075757 0.3101457 0.01574397 0.9505587 0.1991655 -0.009625613 0.9799186 0.00772947 0.007657408 0.9999409 -0.02411985 -0.002689182 0.9997055 -0.2953014 0.00321424 0.9553989 -0.2940312 0.003777861 0.9557884 -0.5469554 -0.009634196 0.8371063 -0.6040776 0.0177524 0.7967278 -0.800314 -0.01781696 0.5993163 -0.8503262 0.01385647 0.5260735 -0.9538721 -0.01197969 0.2999743 -0.9610571 -0.002583146 0.2763378 -0.9975416 0.0120294 0.06903749 -0.9984519 -0.01750731 -0.05279558 -0.9794601 0.01705813 -0.2009152 -0.9364511 -0.01694905 -0.3503885 -0.8413452 0.01763677 -0.5402104 -0.8196849 0.002349615 -0.5728099 -0.6720255 -0.01317322 -0.7404108 -0.5748229 0.01701122 -0.8181011 -0.4732053 -0.01189267 -0.8808719 -0.3153081 0.01192581 -0.9489145 -0.2118921 -0.009276688 -0.9772491 -0.08783179 0.009300112 -0.9960919 0.01406097 -0.01185727 -0.9998309 0.1865593 0.01217216 -0.9823684 0.2834634 -0.009491503 -0.9589362 0.4158676 0.01005703 -0.9093695 0.5065622 -0.01370447 -0.8620946 0.684219 0.01949882 -0.7290159 0.7437199 -0.01192373 -0.668385 0.8996158 6.90716e-4 -0.4366818 0.9066651 0.008106231 -0.4217734 0.9938356 0.001295804 -0.1108565 0.9918868 -0.005824446 -0.1269908 0.7708782 0.6361473 -0.03261113 0.4972356 0.8676055 -0.004208683 0.4470704 0.8944756 -0.006461262 0.9098717 0.4041732 -0.09368818 0.8097476 0.5831053 -0.06555163 0.9497889 0.2663851 -0.164134 0.3457394 0.9364815 -0.05887925 0.6554255 0.7425463 -0.137994 0.887151 0.4017493 -0.2270696 0.4588667 0.8825464 -0.1027294 0.8058478 0.5482664 -0.2236367 0.8741614 0.3231645 -0.3625004 0.7653533 0.5785078 -0.2820693 0.6666949 0.6925451 -0.2754982 0.4281111 0.887943 -0.1681616 0.8147528 0.3932918 -0.4260278 0.2931164 0.9461998 -0.137072 0.7216931 0.5650055 -0.3999099 0.6887467 0.5988483 -0.4086672 0.5514129 0.7497213 -0.3658714 0.7633222 0.3243532 -0.5586899 0.3598561 0.9051833 -0.2261568 0.7234393 0.3838495 -0.5738426 0.5573257 0.7092245 -0.4317277 0.7130874 0.3137052 -0.6269732 0.1869104 0.9700322 -0.1552492 0.6635065 0.3870722 -0.6402611 0.4997071 0.7069987 -0.5004456 0.4626998 0.7770589 -0.4267182 0.6546616 0.3087784 -0.6899813 0.2743031 0.9249756 -0.2630171 0.5000995 0.5577187 -0.6624578 0.462552 0.7081426 -0.5334603 0.5512518 0.3433745 -0.7604048 0.2418597 0.9268553 -0.2871292 0.515441 0.5899029 -0.6215587 0.1717514 0.9553735 -0.2403395 0.3982992 0.694949 -0.5986683 0.4943352 0.3460018 -0.797443 0.4532088 0.4387544 -0.7759488 0.2475343 0.8720205 -0.4222644 0.4111686 0.444768 -0.7956895 0.314733 0.6105284 -0.7267726 0.2380567 0.8622141 -0.4471197 0.308637 0.6089592 -0.7306928 0.3169513 0.2946894 -0.9014988 0.2157452 0.7291842 -0.6494187 0.2288634 0.3357278 -0.9137333 0.1211642 0.935185 -0.3327888 0.1795527 0.6850891 -0.7059842 0.1882402 0.4532727 -0.8712689 0.06067085 0.9746933 -0.2151557 0.1756691 0.5370521 -0.825055 0.1437924 0.2145897 -0.9660616 0.069637 0.8965435 -0.4374477 0.06803852 0.6752739 -0.7344222 0.04153621 0.4363618 -0.8988122 0.05697864 0.878268 -0.4747618 0.02865415 0.5664743 -0.8235812 -0.02228438 0.612985 -0.7897803 -0.04047149 0.8266912 -0.5611985 -0.01021009 0.9432039 -0.3320574 -0.08905398 0.4552248 -0.885912 -0.01373475 0.9669806 -0.2544801 -0.2058032 0.3386396 -0.918133 -0.1482205 0.5041695 -0.8507902 -0.1308767 0.7603549 -0.6361854 -0.1504447 0.835645 -0.5282651 -0.2795802 0.4039886 -0.8709926 -0.06562471 0.9561192 -0.2855337 -0.2407151 0.6766438 -0.6958516 -0.1539751 0.8330963 -0.5312647 -0.3264785 0.2692652 -0.9060398 -0.3962274 0.3189207 -0.860984 -0.3861219 0.5298671 -0.7550834 -0.3529576 0.6138327 -0.7061377 -0.1776814 0.9069473 -0.3819372 -0.276004 0.8134419 -0.5119904 -0.4913946 0.3890318 -0.7792212 -0.04874497 0.9954729 -0.081595 -0.5143427 0.4892795 -0.7043133 -0.3291024 0.8308252 -0.4487997 -0.3200209 0.8472121 -0.4240498 -0.5945152 0.3778791 -0.7097599 -0.2353699 0.9256833 -0.2961613 -0.5982033 0.468148 -0.6503771 -0.5044323 0.6835627 -0.5275321 -0.6925631 0.3471183 -0.632349 -0.2563465 0.9361933 -0.2404757 -0.4910321 0.7534869 -0.4372017 -0.6140273 0.6365358 -0.4666826 -0.7235186 0.48596 -0.4902691 -0.5926426 0.6370881 -0.4928423 -0.7235812 0.486294 -0.4898453 -0.1651998 0.9781662 -0.1260946 -0.4126956 0.8730854 -0.2596232 -0.5521371 0.7808552 -0.2922499 -0.8333397 0.3382058 -0.4372206 -0.7546719 0.5555873 -0.3489886 -0.5448855 0.7846968 -0.2955518 -0.4667263 0.8616074 -0.1994978 -0.788302 0.5435267 -0.2883727 -0.7735314 0.5737788 -0.2691227 -0.6239061 0.7566558 -0.195482 -0.1837432 0.9810345 -0.06172358 -0.9346661 0.2928687 -0.2015621 -0.5488416 0.8264902 -0.1252476 -0.8983929 0.4113743 -0.1538231 -0.3219591 0.9440306 -0.07175469 -0.631385 0.7674005 -0.1115778 -0.9385985 0.3363482 -0.0768305 -0.1873751 0.9821082 -0.01881945 -0.6399863 0.7670931 -0.04456257 -0.8794029 0.4757809 -0.01683056 -0.9054197 0.4238038 -0.02460986 -0.4685633 0.883381 0.009294807 -0.4918797 0.8706331 0.007236003 -0.8192276 0.570576 0.05752456 -0.8575801 0.4998154 0.121413 -0.409506 0.9110884 0.0471493 -0.8484145 0.5126768 0.1317395 -0.6892139 0.7098588 0.145206 -0.9339416 0.2803895 0.2216638 -0.2331987 0.9713202 0.04642593 -0.6743382 0.7203378 0.162424 -0.5798629 0.7959588 0.1738069 -0.8841295 0.3640745 0.2928566 -0.8823476 0.3682762 0.292977 -0.4303206 0.8911918 0.1435322 -0.8388598 0.4472133 0.310346 -0.7667031 0.566492 0.3020817 -0.860677 0.2605031 0.4374624 -0.381273 0.9080587 0.173379 -0.7831358 0.4575926 0.4210788 -0.6699187 0.6593464 0.3412789 -0.6383051 0.6952168 0.3305151 -0.2687957 0.9535444 0.1360215 -0.7599228 0.3549079 0.5445712 -0.5343002 0.7539468 0.3822143 -0.6877788 0.4869061 0.5384077 -0.330702 0.9124794 0.2408685 -0.602412 0.6408429 0.4758364 -0.02645951 0.9994663 0.01916038 -0.7097221 0.3331677 0.6207205 -0.2180879 0.958032 0.1860444 -0.4755645 0.7413302 0.4735693 -0.3211369 0.889276 0.3256675 -0.6420294 0.3858419 0.6625136 -0.5241374 0.6229773 0.5806715 -0.5384838 0.3814055 0.7513755 -0.4815515 0.6227711 0.616656 -0.3461692 0.7854194 0.5131114 -0.22128 0.9236952 0.3127659 -0.1932871 0.9405048 0.2794476 -0.4500092 0.3729116 0.8114363 -0.449238 0.3748662 0.8109627 -0.3422477 0.7047578 0.6214362 -0.2872538 0.7503683 0.5953426 -0.3609691 0.3453356 0.8662821 -0.3499977 0.3751001 0.8583716 -0.1297974 0.9528725 0.2742019 -0.2939605 0.603872 0.7408954 -0.1710141 0.8968426 0.4079554 -0.2070949 0.7023787 0.681011 -0.1505047 0.8308465 0.5357635 -0.2541272 0.3288701 0.9095405 -0.1421587 0.8713982 0.4695277 -0.2127031 0.4870786 0.8470607 -0.1195867 0.4398756 0.890061 -0.1380066 0.5123032 0.8476436 -0.09884065 0.7993516 0.5926784 -0.01362693 0.9958582 0.08989393 -0.03560978 0.3357068 0.9412932 -0.05933773 0.4477539 0.8921858 -0.01472169 0.6792671 0.7337434 -0.0304557 0.8728652 0.48701 -0.02334505 0.8952436 0.4449651 0.05809688 0.4054995 0.9122473 0.04568153 0.5906044 0.8056672 0.08650237 0.3141124 0.9454368 0.04809027 0.9177533 0.3942287 0.09564936 0.7385848 0.6673409 0.07017248 0.8862478 0.4578657 0.1669809 0.409462 0.896916 0.173884 0.542355 0.8219584 0.114417 0.8880097 0.4453623 0.2974791 0.3968226 0.8683537 0.2141367 0.5758754 0.7889951 0.1953102 0.7438367 0.6391878 0.3490596 0.4411771 0.8267529 0.1050118 0.9463875 0.3054889 0.3414591 0.5589198 0.7556549 0.2388061 0.7620903 0.6018223 0.1843821 0.8919723 0.4127818 0.3907504 0.6341474 0.6672115 0.2015197 0.8954347 0.3969717 0.4897936 0.4189216 0.764596 0.39156 0.6333157 0.6675269 0.1368207 0.9673251 0.2134537 0.5938619 0.353804 0.7226001 0.5823353 0.3804487 0.718432 0.4126878 0.7642195 0.4956383 0.4033225 0.7731763 0.4894174 0.2551009 0.9149699 0.3126561 0.6302873 0.4830223 0.6078056 0.48327 0.7282721 0.4858701 0.6865378 0.3861697 0.6160673 0.2010989 0.9609552 0.1900643 0.4482825 0.7964398 0.4058653 0.706916 0.384316 0.5937768 0.290882 0.9228222 0.2525605 0.665251 0.5742183 0.4771946 0.6672448 0.5751385 0.4732865 0.8145236 0.2719196 0.5124562 0.5993366 0.7074175 0.3746414 0.3721614 0.8997116 0.228068 0.8571153 0.2681699 0.4398163 0.3262612 0.9268711 0.1856443 0.8161259 0.4432117 0.3708127 0.7180423 0.6083654 0.3380932 0.8701507 0.3521769 0.3446874 0.5475173 0.8091173 0.2134339 0.4052803 0.8989043 0.1664907 0.9182254 0.3119724 0.243999 0.8671118 0.4242032 0.2610919 0.66597 0.7227482 0.1847137 0.2347443 0.9693574 0.0723983 0.6214072 0.772488 0.1308258 0.936373 0.3094877 0.1655991 0.930568 0.3287668 0.1611071 0.3333207 0.9401004 0.0714752 0.6920869 0.7127087 0.1142901 0.7045341 0.7037688 0.09133005 0.8690636 0.4922727 0.04894888 0.8712403 0.4887341 0.04560035 0.2274315 0.9736596 0.01617968 0.9970434 0.01267951 -0.07578766 0.9983524 -7.89745e-4 -0.05737602 0.9830561 -8.19503e-4 -0.1833036 0.9848002 -0.01111334 -0.1733352 0.9511651 8.09109e-5 -0.308683 0.9599096 0.01560008 -0.2798755 0.9070232 -0.01724863 -0.4207276 0.9322547 0.02177971 -0.3611469 0.8839557 -0.01072275 -0.4674479 0.870397 0.01300984 -0.4921789 0.8113588 0.01034677 -0.584457 0.8248475 -0.01582002 -0.5651339 0.7503482 0.01313924 -0.6609123 0.7218803 -0.01198303 -0.6919142 0.6426596 -0.002248585 -0.7661486 0.672519 0.01559644 -0.7399155 0.5561263 -0.01463639 -0.8309689 0.6075716 0.01276957 -0.7941624 0.5048643 0.006520926 -0.8631742 0.5179665 -0.009650409 -0.8553466 0.3847033 -0.004738926 -0.9230281 0.4266473 0.01758116 -0.9042474 0.2824852 -0.01867616 -0.9590899 0.3518379 0.009605705 -0.9360117 0.2484297 0.001182079 -0.9686492 0.1517749 -0.01262438 -0.9883345 0.1440179 -0.006884157 -0.9895511 0.05780225 -0.02172011 -0.9980918 0.01226854 0.004893302 -0.9999128 -0.04913932 -0.008145213 -0.9987587 -0.08546704 0.01761794 -0.9961853 -0.1872894 -0.002956509 -0.9823004 -0.2032163 0.008424937 -0.9790977 -0.3011657 -0.01997137 -0.9533627 -0.3337229 0.00751084 -0.9426414 -0.4375984 -0.008462905 -0.8991307 -0.4411976 -0.005216181 -0.8973948 -0.5263729 -0.002413332 -0.8502505 -0.5244901 -0.004340887 -0.8514056 -0.6259582 -0.009015917 -0.7798045 -0.6419466 0.01193255 -0.7666566 -0.7235997 -0.01023805 -0.690144 -0.7515563 0.01505076 -0.6594972 -0.7784958 -4.58287e-4 -0.6276497 -0.8126937 0.0168913 -0.5824462 -0.8378914 -0.00838977 -0.5457726 -0.894227 0.0176059 -0.4472675 -0.8899915 0.005965471 -0.455938 -0.9450657 0.01171618 -0.3266702 -0.9404304 -0.002278745 -0.3399789 -0.9746792 0.0194295 -0.222762 -0.9737551 0.01547574 -0.227072 -0.9937563 -0.01872467 -0.1099905 -0.9967162 4.57245e-4 -0.08097332 -0.9998263 -0.01419991 -0.01208108 -0.9994972 0.00503093 0.03130626 -0.9975522 -0.004732966 0.06976532 -0.9936518 0.01407182 0.1116164 -0.9835469 -0.01081341 0.1803294 -0.9762599 0.002415359 0.216589 -0.9658505 -0.0161699 0.2585953 -0.9448376 0.009557425 0.3273997 -0.9292156 -0.01669132 0.3691613 -0.8932553 -0.006771564 0.4494989 -0.8885695 0.003573954 0.4587283 -0.8458386 -0.009349465 0.5333569 -0.7775399 -0.01483726 0.6286586 -0.8192363 0.01542699 0.5732486 -0.750275 0.01063209 0.6610404 -0.6874911 -0.003130137 0.7261861 -0.6697991 0.01618772 0.7423659 -0.6054341 0.00972402 0.7958361 -0.6100656 0.01556223 0.7921982 -0.5207511 -0.009478151 0.8536559 -0.4257842 -0.01275277 0.9047349 -0.4876022 0.01356226 0.8729606 -0.384093 0.004152178 0.9232852 -0.3531711 -0.01493889 0.9354395 -0.251198 0.007743835 0.9679048 -0.2413986 3.63834e-4 0.970426 -0.1566523 0.004589915 0.9876431 -0.1574264 0.003986597 0.9875227 -0.044743 -9.29117e-4 0.9989982 -0.04243177 7.9787e-4 0.9990991 0.04558694 -0.01435637 0.9988573 0.1425496 -0.008292317 0.989753 0.09422487 0.01365345 0.9954574 0.2624355 -0.004564642 0.9649388 0.213158 0.01735717 0.9768636 0.2928867 0.01114183 0.9560824 0.3817465 -0.02270811 0.9239881 0.4725108 -0.001984119 0.8813228 0.4314138 0.009708642 0.9021019 0.5130203 0.01723891 0.8582034 0.5682172 -0.02183228 0.8225891 0.6446008 0.02196115 0.764204 0.6755375 -0.004837036 0.7373098 0.7154937 0.008022308 0.6985732 0.7555778 -0.01785755 0.6548156 0.7880988 0.01207315 0.6154306 0.8394551 -7.01617e-4 0.5434286 0.8332261 -0.01175081 0.5528075 0.9116092 -0.02046167 0.4105485 0.8920001 0.008132874 0.4519619 0.9327237 0.01163989 0.3604043 0.9625403 -0.0122531 0.2708618 0.9614889 -0.008171975 0.2747225 0.9846694 -0.01461923 0.1738178 0.9878187 0.003999173 0.1555582 0.9993001 0.01176154 0.03551107 0.9997937 -0.002158761 0.02020061 0.9506085 -0.3091515 0.02772885 0.6228164 -0.7807582 0.05016481 0.4121869 -0.9097073 0.05034691 0.8922223 -0.4296319 0.1391255 0.8283327 -0.5412213 0.1447226 0.3617883 -0.9285199 0.0834279 0.8645236 -0.4258204 0.2669755 0.7797663 -0.594261 0.1970242 0.5590657 -0.8121433 0.1669394 0.1571998 -0.9864214 0.04755365 0.5452953 -0.8118004 0.208886 0.8249936 -0.4316351 0.3647968 0.8393688 -0.3883627 0.3803085 0.6943334 -0.6458115 0.3175355 0.3977082 -0.8994111 0.1813504 0.5630675 -0.7607196 0.3228945 0.3943983 -0.8937433 0.213712 0.7769982 -0.3839579 0.4988489 0.7660376 -0.4074589 0.4971558 0.5967174 -0.7098241 0.3742702 0.2126744 -0.966077 0.1465092 0.6882037 -0.4482511 0.5704795 0.5015072 -0.7789544 0.3764581 0.3598238 -0.8829575 0.3015178 0.6885471 -0.4093164 0.5986344 0.6215257 -0.4826353 0.6170648 0.4330684 -0.7839909 0.4447584 0.3566687 -0.8726996 0.3334411 0.6216534 -0.3952143 0.6762787 0.5450608 -0.4660205 0.6969459 0.3846563 -0.768732 0.5109705 0.5391263 -0.3509108 0.76564 0.326826 -0.8190831 0.4714739 0.2111247 -0.9236451 0.3198534 0.1338771 -0.9746742 0.1791284 0.401915 -0.5409387 0.7388164 0.4047495 -0.5451971 0.734124 0.3620489 -0.577916 0.7313917 0.338427 -0.4390366 0.8322945 0.1882628 -0.8606432 0.4731285 0.1637359 -0.9120243 0.3760349 0.2666424 -0.5208373 0.8109443 0.2058021 -0.6900134 0.6939215 0.1755909 -0.8352729 0.5210441 0.2335542 -0.2911403 0.9277337 0.1719366 -0.3944402 0.9026931 0.1573928 -0.6441829 0.7485024 0.1471625 -0.3396855 0.9289548 0.07398301 -0.9213928 0.3815257 0.08592265 -0.7866276 0.61142 0.05399656 -0.4414242 0.8956725 0.03168541 -0.5267859 0.8494073 0.02074962 -0.9830969 0.1819067 0.04420244 -0.7428624 0.6679832 -0.009101867 -0.8877865 0.4601658 -0.05716866 -0.3735682 0.9258394 -0.02470821 -0.4915667 0.8704894 -0.07364439 -0.7270537 0.6826197 -0.04751962 -0.8725708 0.486171 -0.1260711 -0.3803151 0.916224 -0.1509559 -0.516422 0.8429239 -0.06145828 -0.9174282 0.3931264 -0.2307271 -0.4322879 0.871718 -0.1974883 -0.5220725 0.8297221 -0.1852752 -0.7299697 0.6578885 -0.1087915 -0.8904907 0.4418043 -0.3053086 -0.3899626 0.8687438 -0.1184985 -0.9335389 0.3383243 -0.3244839 -0.6000498 0.731198 -0.2639752 -0.7231415 0.638266 -0.2117668 -0.8368276 0.5048508 -0.4219974 -0.3833276 0.8215706 -0.3262575 -0.5981865 0.7319351 -0.06472837 -0.987178 0.1459108 -0.4923242 -0.3473215 0.7981133 -0.4965428 -0.3375827 0.799677 -0.1892338 -0.9277079 0.3217901 -0.2127232 -0.9158646 0.3405012 -0.3760134 -0.7164672 0.5876128 -0.3588186 -0.7697731 0.5279191 -0.5659448 -0.3308024 0.7551665 -0.565582 -0.4155549 0.7123421 -0.4283714 -0.7185339 0.5479116 -0.6504877 -0.3103164 0.6932313 -0.1485945 -0.9740957 0.1704627 -0.4085342 -0.8044627 0.431207 -0.2392734 -0.9387189 0.2481034 -0.6435542 -0.4790875 0.5969198 -0.55936 -0.6599044 0.50164 -0.7561134 -0.235377 0.6106473 -0.5659896 -0.6807462 0.4650167 -0.7391388 -0.4471235 0.5037405 -0.7412018 -0.4460359 0.5016692 -0.422689 -0.8622294 0.2790959 -0.3671 -0.8990005 0.2388218 -0.2588003 -0.9493763 0.178065 -0.7056491 -0.5864229 0.3977029 -0.6714355 -0.6160883 0.4118367 -0.8504764 -0.2926641 0.4370786 -0.05271416 -0.9981734 0.02951669 -0.7043566 -0.645832 0.2945892 -0.3477609 -0.9247288 0.1547231 -0.705659 -0.642679 0.2983441 -0.5179283 -0.8338291 0.1909952 -0.8522911 -0.434312 0.2915014 -0.5224161 -0.8353729 0.1709785 -0.8700581 -0.4191325 0.2594743 -0.8088636 -0.5566425 0.1894438 -0.4220008 -0.9012469 0.09833323 -0.8806787 -0.4539914 0.135267 -0.8178461 -0.554297 0.1545405 -0.5551936 -0.8284233 0.07399392 -0.9000658 -0.4268646 0.08756858 -0.5247993 -0.8503756 0.03804272 -0.4193397 -0.9076685 0.01709598 -0.8420577 -0.5392942 -0.01004159 -0.1417323 -0.9897225 0.01901233 -0.8185379 -0.5742319 0.01592922 -0.826355 -0.5603145 -0.05643606 -0.9304348 -0.3446416 -0.1245526 -0.3988378 -0.9164149 -0.0333482 -0.6267222 -0.7748835 -0.08231091 -0.8949204 -0.4027824 -0.1920515 -0.9120414 -0.3510773 -0.2119556 -0.2213479 -0.9744833 -0.03724706 -0.6765317 -0.7198007 -0.1555373 -0.6285533 -0.7591856 -0.1689915 -0.5181084 -0.8404289 -0.1588812 -0.8864437 -0.3491644 -0.3038122 -0.869538 -0.3866761 -0.3072219 -0.8248863 -0.4448013 -0.3488759 -0.5628424 -0.7824073 -0.266547 -0.8483195 -0.313347 -0.4268113 -0.4693803 -0.8595804 -0.2019999 -0.286623 -0.9481236 -0.1375098 -0.7900429 -0.4080259 -0.4575446 -0.6200867 -0.6917917 -0.3700227 -0.8017942 -0.30761 -0.5123497 -0.5444556 -0.7487889 -0.3779991 -0.3255382 -0.9137136 -0.2432126 -0.719837 -0.413196 -0.5577669 -0.6407372 -0.556104 -0.5293433 -0.2700213 -0.9377232 -0.2185491 -0.6629639 -0.5458016 -0.5124251 -0.6567401 -0.3588606 -0.6632583 -0.6479323 -0.4112617 -0.64113 -0.4386554 -0.7833421 -0.440405 -0.2918678 -0.9170306 -0.2717868 -0.4573761 -0.7438412 -0.4873473 -0.6136558 -0.3034014 -0.7289542 -0.4709842 -0.5987633 -0.647809 -0.4205537 -0.7402014 -0.5246301 -0.1778793 -0.9500098 -0.2565938 -0.1331543 -0.9749243 -0.1783052 -0.4355995 -0.5671468 -0.6989976 -0.4325919 -0.5706198 -0.6980382 -0.2444897 -0.8492828 -0.467914 -0.2371287 -0.859973 -0.4519032 -0.3715824 -0.4379324 -0.8186218 -0.3547379 -0.4634509 -0.8120188 -0.2561169 -0.7167962 -0.6485427 -0.2941141 -0.2650183 -0.9182931 -0.2114901 -0.7488855 -0.6280466 -0.2091623 -0.4803895 -0.8517494 -0.1294799 -0.8642069 -0.486191 -0.1712457 -0.3855435 -0.9066594 -0.08345347 -0.9399235 -0.3310275 -0.1887794 -0.4817441 -0.8557366 -0.06468725 -0.9731606 -0.2208486 -0.1240578 -0.7114204 -0.6917303 -0.06280082 -0.4602236 -0.8855792 -0.06889706 -0.7207298 -0.6897839 -0.0309422 -0.9287786 -0.3693412 -0.06384736 -0.463711 -0.883683 -0.03012496 -0.8405454 -0.540903 0.03945022 -0.4950916 -0.8679448 0.002515077 -0.9865481 -0.1634519 0.07420605 -0.6308775 -0.7723258 0.04647266 -0.8127874 -0.5807039 0.0540235 -0.8807086 -0.4705678 0.1449881 -0.5268654 -0.8374912 0.09803855 -0.8813696 -0.4621431 0.1784452 -0.5658747 -0.8049492 0.1595557 -0.7578895 -0.6325706 0.2587416 -0.426634 -0.8666235 0.08803731 -0.9591789 -0.2687475 0.3009875 -0.5251649 -0.7959954 0.2447656 -0.7313703 -0.6365433 0.3779143 -0.3596354 -0.8531373 0.2284492 -0.8146644 -0.5330412 0.1763628 -0.8922076 -0.4157667 0.4332882 -0.4019287 -0.8066689 0.4334284 -0.4974807 -0.7514339 0.3498991 -0.7156767 -0.6044646 0.5347352 -0.3758247 -0.7568449 0.3284239 -0.8072383 -0.4904121 0.5420998 -0.4038134 -0.7369279 0.1866793 -0.9455804 -0.2665119 0.466223 -0.6528818 -0.596977 0.6215985 -0.2757631 -0.7331917 0.165305 -0.9605544 -0.2236279 0.6373354 -0.3652728 -0.6785126 0.508657 -0.6547087 -0.5591285 0.6884451 -0.2963172 -0.6619966 0.2565827 -0.9278663 -0.2706094 0.4690197 -0.75335 -0.4609604 0.6889938 -0.3792752 -0.6176066 0.5526915 -0.6875009 -0.4710358 0.5561951 -0.708016 -0.4351555 0.7784223 -0.2727703 -0.5653806 0.7727988 -0.3122239 -0.552538 0.1829979 -0.9738525 -0.134623 0.5241935 -0.7602443 -0.3837316 0.161992 -0.9801473 -0.114324 0.7808756 -0.429387 -0.4537183 0.7533023 -0.503874 -0.4226664 0.6003952 -0.7128633 -0.3624246 0.8669611 -0.3415229 -0.3629611 0.306281 -0.9401139 -0.1495926 0.7713528 -0.5207693 -0.3658063 0.6101166 -0.7500492 -0.2553114 0.4929877 -0.8373773 -0.2361409 0.8923434 -0.3373298 -0.2998867 0.875154 -0.3943256 -0.2803802 0.6487764 -0.7298327 -0.2154846 0.6128208 -0.7686992 -0.1831734 0.1683279 -0.9843489 -0.05218398 0.9092911 -0.3802946 -0.1690137 0.879755 -0.4526779 -0.1453063 0.3300038 -0.9407523 -0.07799255 0.7128117 -0.6890376 -0.130869 0.4742929 -0.8793023 -0.04328787 0.9165214 -0.3944191 -0.06649899 0.8814418 -0.4718589 -0.02023828 0.6867719 -0.7268716 0.001470685 0.4803296 -0.8755398 -0.05209285 0.2003244 -0.9797297 2.76871e-4 -1.22637e-4 -0.999997 0.002466678 4.21182e-4 -0.9999998 5.55675e-4 5.72972e-4 -0.9999998 3.89468e-4 0.002418458 -0.9999971 -2.27515e-4 4.24115e-4 -0.9999976 0.002188086 7.12753e-4 -0.9999974 0.002177834 8.99876e-4 -0.9999989 0.001191794 0.002020716 -0.9999979 4.68529e-4 -6.11674e-5 -0.9999966 0.002659142 2.07533e-5 -0.9999965 0.00268507 6.55616e-4 -0.9999964 0.002631664 0.001594245 -0.9999983 -9.80071e-4 0.001966297 -0.999998 -2.1685e-4 0.001849889 -0.9999974 0.001388728 -6.25243e-4 -0.9999977 0.002021908 0.001365363 -0.9999974 0.001851022 3.55715e-4 -1 -1.59074e-4 3.00683e-4 -0.9999998 -4.8841e-4 -2.02189e-4 -1 2.63409e-4 4.00606e-4 -0.9999998 -4.23388e-4 -0.001909255 -0.9999983 -5.27734e-5 -1.27857e-4 -0.9999988 -0.001565337 -0.001721024 -0.9999986 1.70757e-4 -0.001984655 -0.9999974 0.001226127 6.18189e-4 -0.999999 -0.001351356 -0.002083957 -0.9999977 5.98457e-4 -6.23169e-4 -0.9999969 -0.002443671 4.73213e-4 -0.9999968 -0.002487421 -0.002341151 -0.9999973 1.66692e-4 -0.001919686 -0.999998 5.68631e-4 -1.4709e-4 -0.9999986 -0.001667857 0.00107342 -0.9999969 -0.002246499 -0.001989424 -0.9999964 -0.001858472 4.8622e-4 -0.9999986 -0.001675665 -0.00311923 -0.999995 -6.38194e-4 -2.74625e-4 -0.9999997 -8.29531e-4 -0.003355503 -0.9999944 2.77964e-4 -0.001738727 -0.9999979 -0.001112163 -5.00061e-4 -0.9999997 -7.07744e-4 -0.001952826 -0.9999981 -1.36667e-4 -0.001373946 -0.9999989 -7.42368e-4 0.94744 -0.3198332 0.008014798 0.3174333 -0.9482786 0.001967787 0.8448597 -0.5268252 0.09309935 0.6582253 -0.7518475 0.03827422 0.4351496 -0.8993062 0.04351097 0.8554202 -0.5067421 0.1070923 0.3956081 -0.9162099 0.06366729 0.3460675 -0.9359871 0.06454008 0.8280181 -0.5341757 0.1704182 0.7663834 -0.6151899 0.1849273 0.3681747 -0.9229505 0.112294 0.8148584 -0.5017114 0.2903299 0.7356976 -0.6359598 0.2330331 0.638892 -0.7371143 0.2201805 0.8261824 -0.4022217 0.3945131 0.8052443 -0.4381688 0.3994871 0.2186259 -0.9710798 0.09595125 0.582552 -0.7552288 0.3004374 0.5552603 -0.7828122 0.2808755 0.3430728 -0.9208354 0.1853736 0.7886282 -0.374067 0.4879955 0.6794637 -0.562887 0.4706245 0.2935919 -0.9357427 0.1954215 0.7044857 -0.3935819 0.5905872 0.6540006 -0.5838723 0.4810161 0.516507 -0.7492408 0.4145587 0.6279237 -0.4598444 0.6278973 0.1194899 -0.9874135 0.1036195 0.4657924 -0.7718433 0.4327765 0.6257362 -0.4188593 0.6580358 0.3404141 -0.8671328 0.3635921 0.5771032 -0.4719006 0.6665297 0.3615389 -0.8107863 0.4603426 0.561542 -0.3227658 0.7619009 0.5353648 -0.3525773 0.7675116 0.3686408 -0.7378888 0.5653532 0.3307865 -0.8190405 0.4687785 0.5124692 -0.3075224 0.8017514 0.1639893 -0.9443083 0.2852885 0.3686949 -0.5837537 0.7233919 0.3643732 -0.5832826 0.725957 0.3142501 -0.6410727 0.7001947 0.1899036 -0.8643355 0.4656832 0.2846408 -0.4715053 0.8346631 0.2283822 -0.3755595 0.8982186 0.1402316 -0.8943012 0.4249242 0.2397864 -0.4902485 0.8379492 0.176529 -0.6647244 0.7259332 0.07992577 -0.9474213 0.3098463 0.1438568 -0.3590294 0.922173 0.1394726 -0.3363395 0.9313555 0.1149663 -0.6960055 0.708773 0.09040874 -0.7492095 0.6561337 0.01323759 -0.9957053 0.09162873 0.05253559 -0.3516768 0.9346463 0.0301162 -0.429306 0.9026569 0.05797481 -0.7536469 0.6547178 -0.003962695 -0.8578782 0.5138379 -0.03415369 -0.4421871 0.8962723 -0.05462896 -0.5323273 0.8447742 -0.01896262 -0.8407532 0.5410865 -0.1281983 -0.5638924 0.8158375 -0.07955211 -0.8522456 0.5170579 -0.1383457 -0.543564 0.8278881 -0.08499389 -0.8727242 0.4807584 -0.06671249 -0.9606791 0.2695279 -0.2553195 -0.5028356 0.8258138 -0.2348014 -0.5552762 0.7978326 -0.2028294 -0.7118155 0.6724426 -0.3190275 -0.4132286 0.8529149 -0.1969433 -0.8487014 0.4908354 -0.3438757 -0.4308515 0.8343361 -0.4120393 -0.282368 0.8663094 -0.3105499 -0.7084144 0.6338043 -0.2228835 -0.8410241 0.4929517 -0.4808099 -0.4109055 0.7745828 -0.4773671 -0.441183 0.7599198 -0.4260473 -0.5882992 0.6873048 -0.1771726 -0.9400247 0.2914848 -0.3707218 -0.7651524 0.5264098 -0.1284791 -0.9714664 0.1993645 -0.6085226 -0.3144413 0.7285787 -0.58568 -0.4987295 0.6389427 -0.4750618 -0.7004776 0.5325858 -0.4049531 -0.8258134 0.3924862 -0.2667712 -0.9307473 0.2500854 -0.6591185 -0.430469 0.6166517 -0.6044664 -0.6347053 0.4814247 -0.214486 -0.9591602 0.1844119 -0.7556873 -0.4026057 0.5165708 -0.621867 -0.6303492 0.464695 -0.4996698 -0.8114944 0.3029968 -0.8166539 -0.3278148 0.4749885 -0.5014886 -0.8122131 0.2980256 -0.792417 -0.4539873 0.4073953 -0.5942567 -0.740309 0.3143272 -0.8442933 -0.3802549 0.377591 -0.2897278 -0.9467216 0.1406278 -0.8227634 -0.4801204 0.3042118 -0.6265826 -0.7346612 0.2601293 -0.8590978 -0.4294142 0.278486 -0.8579614 -0.4348472 0.2735148 -0.4046553 -0.9060862 0.1235389 -0.4032285 -0.9069699 0.1217065 -0.7209624 -0.6739699 0.1611767 -0.6501681 -0.7470104 0.1387701 -0.9459483 -0.2697241 0.1800856 -0.9055227 -0.3977766 0.1476572 -0.1561987 -0.9872193 0.03162515 -0.9005449 -0.4261825 0.08595073 -0.8204664 -0.5700516 0.04331386 -0.6431862 -0.7641997 0.04806834 -0.5084989 -0.8608586 0.01874709 -0.8742367 -0.4851555 -0.01828354 -0.4719412 -0.8813346 -0.0228241 -0.8141507 -0.5737928 -0.08899861 -0.7566308 -0.6458563 -0.1018803 -0.6238884 -0.7774983 -0.07911795 -0.1587663 -0.9869776 -0.02585655 -0.8135437 -0.5486807 -0.192604 -0.3933442 -0.9143068 -0.09655785 -0.3774417 -0.9213909 -0.09261053 -0.8013021 -0.5278794 -0.2815289 -0.7493042 -0.617088 -0.2403033 -0.6034245 -0.769551 -0.2089741 -0.8178026 -0.4239026 -0.3892373 -0.5382698 -0.8119113 -0.2259773 -0.8041386 -0.4462637 -0.392696 -0.4033206 -0.8954522 -0.1884094 -0.6886634 -0.6297885 -0.3593177 -0.6268166 -0.6817547 -0.377242 -0.8051552 -0.3068048 -0.5075392 -0.3114876 -0.934813 -0.1705877 -0.7622052 -0.4049774 -0.5050116 -0.2547358 -0.9554543 -0.149053 -0.6436108 -0.63376 -0.4290843 -0.5836514 -0.6888941 -0.4298558 -0.7494212 -0.2672149 -0.6057756 -0.3496493 -0.8949003 -0.2773064 -0.6869514 -0.4009805 -0.6060631 -0.6230462 -0.566953 -0.5388671 -0.6767184 -0.3284366 -0.6589246 -0.2961973 -0.9144013 -0.2759302 -0.5987607 -0.4531803 -0.6603888 -0.4811838 -0.7132244 -0.5096796 -0.4521641 -0.7474373 -0.4867085 -0.5861698 -0.3819355 -0.7145141 -0.1354833 -0.9792662 -0.1506062 -0.5491967 -0.4223105 -0.7211358 -0.4408969 -0.6504311 -0.6185057 -0.3833003 -0.7745329 -0.5031696 -0.5439723 -0.2336978 -0.805903 -0.2656086 -0.8881357 -0.375056 -0.4503317 -0.3425703 -0.8245283 -0.4437268 -0.3646546 -0.818617 -0.396389 -0.5987226 -0.6959936 -0.2949305 -0.7480798 -0.5944684 -0.2116033 -0.8882146 -0.4077976 -0.3481466 -0.4520882 -0.8212248 -0.2883663 -0.6360817 -0.715713 -0.3379056 -0.2422338 -0.9094738 -0.1055185 -0.9597567 -0.2602558 -0.2559295 -0.6672187 -0.6995136 -0.2370756 -0.3552492 -0.9042086 -0.1398864 -0.8730606 -0.4671158 -0.210641 -0.4533169 -0.8661029 -0.2108291 -0.5311133 -0.8206521 -0.1210105 -0.8411241 -0.5271307 -0.15837 -0.4306842 -0.8884988 -0.0795924 -0.5815927 -0.8095771 -0.05772948 -0.8678336 -0.4934898 -0.02659589 -0.4621155 -0.8864209 -0.03262752 -0.9097427 -0.4138884 0.05901372 -0.3336305 -0.940855 -0.01039028 -0.9066201 -0.4218199 0.01633888 -0.4838004 -0.8750258 0.05298864 -0.7457181 -0.6641511 0.1316985 -0.3335211 -0.9334983 0.1486108 -0.430653 -0.8901983 0.06177949 -0.7462543 -0.6627879 0.02438104 -0.9793146 -0.2008695 0.1025535 -0.8613005 -0.4976387 0.08895218 -0.90464 -0.41679 0.1952136 -0.4620488 -0.8651027 0.2115721 -0.6422653 -0.7367039 0.3251946 -0.4251928 -0.8446654 0.2533515 -0.6281161 -0.7357196 0.4191879 -0.3283525 -0.8464432 0.1064097 -0.9553999 -0.2754777 0.2569418 -0.7646026 -0.5910701 0.2065609 -0.87342 -0.4409878 0.4216862 -0.5078647 -0.7511687 0.425561 -0.5110948 -0.7467797 0.3859082 -0.7026588 -0.5977839 0.2559369 -0.8738077 -0.4134689 0.5362521 -0.2946045 -0.7909752 0.2243968 -0.9174092 -0.3286434 0.5213293 -0.5687108 -0.6362263 0.523342 -0.5702683 -0.6331725 0.6322434 -0.3754524 -0.6777195 0.6169706 -0.4271194 -0.6609964 0.3546921 -0.8584474 -0.3704886 0.3261547 -0.8802295 -0.3447017 0.6245842 -0.5505493 -0.5538864 0.5432947 -0.7008036 -0.4622825 0.7516444 -0.2866201 -0.5940368 0.1130142 -0.9896606 -0.08831697 0.5406069 -0.7471589 -0.3866496 0.7921051 -0.301483 -0.5307331 0.7049657 -0.5718195 -0.4195783 0.3307558 -0.9213981 -0.2040252 0.8280214 -0.3877353 -0.4050211 0.7112575 -0.5799595 -0.3971897 0.5943788 -0.7506324 -0.2885568 0.4496796 -0.8662457 -0.2177308 0.867294 -0.3679944 -0.3352332 0.8753297 -0.3374345 -0.3463176 0.7335802 -0.6198363 -0.2786811 0.3556435 -0.9251692 -0.1325884 0.8768751 -0.4125841 -0.2467074 0.6984564 -0.6857873 -0.2045841 0.642095 -0.7470207 -0.1722621 0.9271443 -0.3039983 -0.2190628 0.4215419 -0.8987869 -0.1203519 0.8906807 -0.4313934 -0.1434842 0.325407 -0.9430809 -0.06862086 0.736201 -0.6652255 -0.1244319 0.9349911 -0.3372405 -0.1098208 0.9018613 -0.4306422 -0.03454881 0.0584954 -0.9982687 -0.006178557 0.6964978 -0.7172105 -0.02236115 0.6093924 -0.7912278 -0.05098539 0.489229 -0.8711148 -0.04259288 0.9990274 0.02088671 -0.03883516 0.9930792 0.007960855 -0.1171769 0.9933166 0.006577253 -0.1152341 0.9725026 -0.01833224 -0.2321699 0.9815223 0.01024347 -0.1910737 0.932586 -0.003068506 -0.3609349 0.9438025 0.01967787 -0.3299239 0.8855166 -0.01607447 -0.4643296 0.9133305 0.008911609 -0.4071217 0.8632139 -5.42109e-4 -0.5048381 0.8474665 -0.01393061 -0.5306661 0.8123691 0.0112065 -0.5830359 0.7706492 -0.01506537 -0.6370816 0.7451325 0.006792843 -0.6668819 0.7159996 -0.01109671 -0.6980125 0.6387633 0.01275604 -0.7692975 0.6498858 0.001228511 -0.760031 0.5673776 -0.01613253 -0.8232998 0.561441 -0.008962988 -0.8274683 0.4397451 -0.01683872 -0.8979648 0.4759567 0.00760895 -0.8794359 0.3259133 -0.004512786 -0.945389 0.3718053 0.01339364 -0.9282141 0.265366 -0.01572853 -0.9640195 0.3007412 0.003462731 -0.9536995 0.1582835 0.004395127 -0.987384 0.1753516 -0.01362949 -0.9844115 0.04514431 -0.003546297 -0.9989743 0.1083147 0.02212327 -0.9938705 -0.06179076 -9.00168e-4 -0.9980887 -0.01339274 0.01741868 -0.9997586 -0.1381726 -0.01375389 -0.9903127 -0.09265649 0.01018679 -0.9956461 -0.2440329 0.007507801 -0.969738 -0.2329515 -0.004099249 -0.9724798 -0.3134371 0.01225656 -0.9495299 -0.35342 -0.0154224 -0.9353377 -0.4665605 -0.001502811 -0.8844881 -0.4380907 0.01698487 -0.8987703 -0.5652289 -0.00407499 -0.8249241 -0.519427 0.01861602 -0.8543121 -0.6441506 -0.01313281 -0.7647861 -0.6048359 0.01592105 -0.7961911 -0.7092573 0.001123905 -0.7049489 -0.7156199 0.01009929 -0.698417 -0.78194 0.007843792 -0.6233044 -0.7828432 0.008960068 -0.6221547 -0.8447981 0.007402062 -0.5350342 -0.8327608 -0.01329535 -0.5534734 -0.8888581 0.01220369 -0.4580203 -0.9120541 -0.01687711 -0.4097227 -0.9339052 0.006311178 -0.3574653 -0.9486263 -0.01946628 -0.3157995 -0.9746426 -0.0100007 -0.2235438 -0.9734293 -0.01456743 -0.2285239 -0.9914386 -0.01154589 -0.1300624 -0.9922906 -0.006571292 -0.123759 -0.9998787 -0.00603491 -0.01436281 -0.9997394 2.09352e-4 -0.02283155 -0.9978197 -3.40187e-4 0.06599926 -0.9976895 -0.001706957 0.06791752 -0.9830137 3.04715e-4 0.1835321 -0.9831894 -6.92154e-4 0.1825879 -0.9460243 0.006087601 0.3240385 -0.9490171 0.01593357 0.3148218 -0.912024 0.001252949 0.410135 -0.9151183 -0.00331968 0.403172 -0.8661834 -0.005253553 0.4996987 -0.8618801 0.001867175 0.5071088 -0.800044 -0.01538485 0.5997442 -0.7833019 6.88025e-4 0.6216411 -0.7519217 -0.01837623 0.6589963 -0.709708 0.01412642 0.7043544 -0.6434788 -7.89554e-4 0.7654637 -0.6535919 -0.01383566 0.7567207 -0.5266577 -0.005282044 0.8500611 -0.5570674 0.01316678 0.8303629 -0.4328138 -0.01298487 0.9013899 -0.4899383 0.01285076 0.8716624 -0.3813319 0.01084291 0.9243746 -0.340137 -0.01196205 0.9402998 -0.2466273 0.008943796 0.9690691 -0.2477306 0.009788751 0.9687795 -0.1936902 0.002319455 0.98106 -0.1683437 -0.01205801 0.9856547 -0.1024764 0.001559197 0.9947342 -0.06734812 -0.01555204 0.9976084 -0.001847147 0.00946778 0.9999535 0.04738289 -0.009750425 0.9988293 0.102586 0.01412826 0.9946238 0.1534749 -0.004444539 0.9881426 0.1987079 0.01985794 0.9798576 0.2338883 0.02373188 0.9719738 0.2714096 -4.56898e-4 0.9624638 0.3540964 0.002459108 0.9352057 0.3441305 -0.005560994 0.9389054 0.4301465 -0.02256888 0.902477 0.4765993 0.004559457 0.8791089 0.5078623 -0.008267283 0.8613986 0.6089411 -0.016101 0.793052 0.5623892 0.01854699 0.8266648 0.686116 3.53552e-4 0.7274922 0.6804242 0.007599115 0.7327792 0.7797475 -2.49139e-4 0.6260942 0.7760489 -0.005531311 0.6306485 0.8388224 -0.008649349 0.5443365 0.8466181 0.00555998 0.5321718 0.9103183 -0.02267736 0.4132876 0.9267514 0.01033747 0.3755329 0.9503503 -0.01642626 0.3107484 0.967301 0.003291606 0.25361 0.9731088 -0.004943132 0.2302935 0.9918079 -7.41079e-4 0.1277372 0.9836872 0.01459223 0.1792945 0.9963265 0.01452416 0.08439642 0.9996564 -0.01396471 0.0221824 0.8887025 0.4584225 -0.007527589 0.8013387 0.597117 -0.03616124 0.3807107 0.9238885 -0.03859639 0.8271929 0.5488699 -0.1203905 0.7802429 0.6186628 -0.0920729 0.4676308 0.8813434 -0.06749451 0.8884024 0.4106262 -0.2052494 0.854251 0.4852124 -0.1866127 0.9162777 0.2616143 -0.3033041 0.6482305 0.731346 -0.2119675 0.5137223 0.8408791 -0.1703291 0.4565965 0.8784746 -0.1407192 0.774469 0.554503 -0.304507 0.8272016 0.3682875 -0.4243843 0.7612534 0.5394132 -0.3598983 0.572574 0.7593274 -0.3091617 0.4759998 0.8469175 -0.2369705 0.826331 0.3057786 -0.4729446 0.05078041 0.9983901 -0.02527409 0.7678656 0.4041026 -0.497075 0.1566486 0.9828516 -0.09728312 0.5801272 0.7196467 -0.3815247 0.7657451 0.3228092 -0.5562633 0.5438573 0.7463752 -0.3835927 0.7272813 0.3813027 -0.5706752 0.3006143 0.9244961 -0.234389 0.5992811 0.6407843 -0.4798517 0.7191612 0.2621561 -0.6434916 0.6595644 0.3846573 -0.6457659 0.5427627 0.6585791 -0.5212315 0.4553183 0.7504776 -0.4790288 0.6178215 0.3107831 -0.7222954 0.5770496 0.3978755 -0.7132384 0.2914416 0.9105058 -0.2933279 0.4642605 0.6968672 -0.546661 0.532512 0.3381321 -0.7759495 0.1312327 0.9765284 -0.1707934 0.3167893 0.8154022 -0.4845243 0.4662109 0.4437066 -0.7653573 0.2080619 0.9247723 -0.318601 0.3555514 0.7150551 -0.6018966 0.4507197 0.3410294 -0.8249551 0.2890273 0.7162314 -0.6351975 0.373691 0.4065334 -0.8337181 0.3001145 0.60297 -0.7391607 0.1593638 0.911011 -0.3803451 0.2342015 0.4489384 -0.8623247 0.2582485 0.6132485 -0.7464812 0.2022084 0.4676188 -0.8604909 0.1083678 0.943138 -0.3142409 0.1240832 0.8589433 -0.4968098 0.1482646 0.5681279 -0.8094741 0.1129412 0.7638759 -0.6354039 0.1171146 0.8541668 -0.5066394 0.09213191 0.4211542 -0.9022976 0.0148679 0.9693794 -0.2451171 0.02784848 0.8048997 -0.5927571 0.02077716 0.522845 -0.8521746 0.007319509 0.9414267 -0.3371383 -7.56195e-4 0.6273517 -0.7787357 -0.116162 0.362268 -0.9248072 -0.07506024 0.6249011 -0.7770873 -0.1011687 0.7256575 -0.6805778 -0.05770248 0.9187061 -0.390704 -0.2144112 0.3571561 -0.9091025 -0.2253819 0.4656913 -0.8557655 -0.05930286 0.9533984 -0.2958292 -0.1639698 0.6567823 -0.7360373 -0.3041728 0.2871302 -0.9083145 -0.241009 0.4586384 -0.8553161 -0.2717354 0.6436638 -0.7154418 -0.2212028 0.7850899 -0.5785356 -0.1880248 0.8260119 -0.5313671 -0.3722864 0.4309234 -0.8220145 -0.1161155 0.928102 -0.3537567 -0.3766788 0.4259855 -0.822587 -0.08169502 0.9828833 -0.1651254 -0.4016603 0.5676109 -0.7186703 -0.3157699 0.7599971 -0.5680615 -0.2733498 0.8150319 -0.5108845 -0.1767509 0.9352918 -0.3065753 -0.4678412 0.4721597 -0.7471211 -0.5805312 0.3464618 -0.7368499 -0.5176409 0.4955348 -0.6974908 -0.4462106 0.6950026 -0.5637975 -0.4352336 0.7251761 -0.5335649 -0.3223214 0.8667337 -0.3806336 -0.6570419 0.3378455 -0.6739113 -0.6008145 0.562368 -0.5681233 -0.2780279 0.9169794 -0.2860932 -0.5993889 0.5844722 -0.5469233 -0.1295747 0.9844189 -0.1188694 -0.4568791 0.7950246 -0.3989956 -0.6782326 0.4917846 -0.5460298 -0.7803051 0.3977213 -0.4826403 -0.6855157 0.5612487 -0.4637545 -0.5843932 0.7198945 -0.3744818 -0.4776974 0.8169463 -0.3231161 -0.3235347 0.924104 -0.2033648 -0.8180364 0.3928139 -0.4201354 -0.8015428 0.4515116 -0.3920033 -0.643317 0.6874576 -0.336965 -0.2810971 0.9480125 -0.1491874 -0.8934241 0.2945183 -0.3391937 -0.4676136 0.8617104 -0.1969585 -0.843637 0.4100624 -0.3465912 -0.684308 0.6954762 -0.21917 -0.4834071 0.8552993 -0.186496 -0.8840376 0.4048636 -0.2335871 -0.7325835 0.6510867 -0.1985135 -0.9221702 0.3181601 -0.2199464 -0.6701125 0.729101 -0.1391444 -0.38252 0.9204607 -0.08019244 -0.3243268 0.9421923 -0.08417767 -0.9194329 0.37467 -0.1194385 -0.8708809 0.48312 -0.09034144 -0.7316777 0.6741563 -0.1008028 -0.4402791 0.8976842 -0.01782226 -0.8917998 0.4511218 -0.03438532 -0.3567281 0.9337898 -0.02795886 -0.8231322 0.5673605 0.0235731 -0.533907 0.8452191 0.02340668 -0.490158 0.8714805 0.01633995 -0.8970274 0.4334659 0.08630764 -0.8758354 0.4563763 0.1569498 -0.8972755 0.4154376 0.1493602 -0.6894815 0.7114298 0.1359516 -0.2020123 0.9787191 0.0360586 -0.8773157 0.3853216 0.2860847 -0.5758236 0.8013073 0.1622778 -0.8751106 0.3924334 0.2831566 -0.3615608 0.9267916 0.101643 -0.5970181 0.7819823 0.1790897 -0.7582877 0.5558291 0.3406668 -0.6099342 0.7448992 0.2703807 -0.8243048 0.3804567 0.4192547 -0.2733306 0.9541282 0.1221881 -0.4962599 0.8313603 0.2501323 -0.8126593 0.334127 0.4774349 -0.4820104 0.8297463 0.2814022 -0.768468 0.4131302 0.4886518 -0.110616 0.9919686 0.06133967 -0.6390658 0.6378374 0.4298354 -0.3415939 0.9119375 0.2273404 -0.7673683 0.2319561 0.5977813 -0.5798574 0.6689193 0.4650941 -0.6580056 0.4741076 0.585022 -0.3845593 0.8572888 0.342301 -0.6452584 0.4629999 0.607678 -0.3730066 0.8630642 0.3405677 -0.5647909 0.5661715 0.6003842 -0.4307849 0.7680979 0.4737616 -0.5836498 0.3784503 0.7184207 -0.40354 0.7877447 0.4654179 -0.09054321 0.9898071 0.1099268 -0.5331535 0.4086076 0.7408018 -0.2394856 0.9151756 0.3241919 -0.4394171 0.5845916 0.6820303 -0.04033523 0.9977861 0.05287814 -0.4558952 0.5680825 0.6851583 -0.3152796 0.7718656 0.5521072 -0.4382906 0.3212471 0.8394651 -0.3068014 0.7743614 0.5533872 -0.3989439 0.3756002 0.8365216 -0.3168423 0.6796391 0.6615902 -0.3690637 0.3119378 0.8754925 -0.1502059 0.9265868 0.3447831 -0.3143681 0.4172218 0.8527008 -0.2482945 0.6802315 0.6896629 -0.1977999 0.7529259 0.6276764 -0.2576598 0.3081709 0.9157741 -0.123407 0.9192407 0.3738548 -0.1621176 0.621499 0.7664574 -0.05931657 0.9680335 0.2437064 -0.1139215 0.5023956 0.8571001 -0.1521232 0.6228141 0.7674381 -0.04677844 0.8932673 0.4470854 -0.07667177 0.4704573 0.8790856 -0.06114888 0.488508 0.8704141 -0.01453578 0.8826646 0.4697788 -3.21919e-4 0.4232692 0.906004 -0.002202987 0.8926575 0.4507305 0.02228623 0.4526939 0.8913875 0.04568392 0.8336351 0.5504232 0.08065867 0.3922144 0.9163308 0.05111467 0.8326998 0.5513604 0.1130654 0.4680289 0.8764504 0.1338524 0.6514073 0.746828 0.2336993 0.5084502 0.8287721 0.1711148 0.6433214 0.7462288 0.0629884 0.9695864 0.2365056 0.3393028 0.3300617 0.8808706 0.289815 0.4881452 0.8232384 0.2709801 0.6803331 0.6809676 0.170009 0.8521308 0.4949445 0.1500962 0.8920777 0.4262259 0.4278423 0.3785786 0.8207492 0.4165561 0.5122094 0.751081 0.3464408 0.6546893 0.6718339 0.1965337 0.9184034 0.3433801 0.2007408 0.9105892 0.3612901 0.5443823 0.3332483 0.769801 0.4815766 0.4963297 0.7223163 0.4335851 0.6897723 0.5798432 0.2335712 0.8987462 0.3710792 0.4579344 0.699957 0.5480477 0.6433952 0.2993493 0.7045798 0.6170657 0.4559771 0.6413384 0.3051834 0.9005064 0.3097601 0.198234 0.9555637 0.2181777 0.639737 0.5068544 0.5777848 0.4379798 0.8223908 0.3631076 0.7189555 0.3781525 0.5831841 0.8265114 0.2464302 0.5061138 0.4418643 0.8327313 0.3336384 0.741276 0.4400781 0.5067951 0.659365 0.6150483 0.4323812 0.3615712 0.9022246 0.2350685 0.1848936 0.9767926 0.108123 0.8251734 0.3783657 0.4194381 0.6386966 0.6943857 0.3315045 0.6069694 0.7333361 0.3062785 0.8944359 0.2420256 0.3760427 0.5860674 0.77118 0.2486091 0.493095 0.8504748 0.1831667 0.8334038 0.4738409 0.284452 0.4847337 0.8580119 0.1698499 0.8406311 0.4725989 0.2645556 0.743528 0.6450049 0.176451 0.312 0.9462204 0.08557456 0.7551305 0.6428655 0.1284599 0.7623085 0.6326909 0.1363379 0.9030721 0.4260697 0.05408704 0.3802597 0.9230276 0.05850356 0.7922171 0.6035689 0.08998203 0.6582362 0.7527343 0.01078224 0.4266921 0.9043929 0.002728402 0.3203368 0.9469577 0.0256015 -0.002193272 0.9999959 0.001886188 -9.34413e-4 0.9999948 0.003081858 -0.001882076 0.999995 0.002547919 -0.002206146 0.9999976 4.26835e-4 -7.44286e-4 0.9999997 3.99911e-4 -3.04288e-4 0.9999997 7.78352e-4 -8.41566e-4 0.9999997 1.61822e-5 8.27316e-4 0.9999985 0.001591324 -9.76596e-4 0.9999996 2.69025e-4 4.03583e-4 0.9999981 0.001923799 -2.44681e-4 0.9999985 0.001787602 -9.22691e-4 0.9999996 1.91983e-5 -0.001389026 0.999997 -0.002028465 2.29038e-4 0.999998 0.001967966 -0.001815259 0.9999983 -4.63282e-4 -0.002514064 0.9999902 -0.00365889 0.001772642 0.999996 0.002221882 -0.004471063 0.9999861 0.002807378 0.00111097 0.9999958 0.002717673 -0.001461803 0.9999933 0.00337094 -6.02916e-4 0.9999998 -4.06186e-4 7.86104e-4 0.9999992 0.001120507 -9.06874e-5 0.9999973 -0.002314627 0.004491984 0.9999899 -3.41297e-4 0.003168225 0.999992 0.002486348 -0.00127387 0.9999976 -0.001796662 0.002014338 0.9999929 0.003210186 -0.001904129 0.9999979 -9.22901e-4 -3.26102e-4 0.9999996 -9.44488e-4 0.002054691 0.9999933 0.003027498 0.001332461 0.9999991 4.00971e-4 7.77086e-4 0.9999986 -0.001499354 0.001929342 0.9999971 -0.001469135 -5.37623e-5 0.9999988 -0.001596271 0.001180291 0.9999971 -0.002145886 0.00254625 0.9999968 -1.11724e-4 0.002142846 0.9999975 -5.99507e-4 0.002363324 0.999997 -7.35361e-4 7.52424e-4 0.9999971 -0.002301931 8.40934e-4 0.999997 -0.002333581 0.002222836 0.9999976 1.92675e-4 6.80841e-4 0.9999997 -4.67791e-4 -2.56771e-7 0.9999966 -0.002666532 5.23367e-4 0.9999997 -6.53327e-4 0.9955738 0.03516322 -0.08715772 0.9853239 -0.02509957 -0.1688396 0.9766631 0.02712166 -0.2130576 0.9299682 -0.03310042 -0.3661468 0.9524506 0.03907376 -0.3021776 0.906756 0.03410297 -0.4202745 0.8430165 0.01825571 -0.5375779 0.8047558 -0.06827914 -0.5896663 0.7749038 0.01744699 -0.6318384 0.6784312 0.06870985 -0.7314439 0.5934275 -0.02392596 -0.8045318 0.5750575 -0.07346892 -0.8148075 0.4367362 0.07322973 -0.8966041 0.3174549 -0.0416395 -0.9473587 0.3027974 -0.01613086 -0.9529184 0.1916567 0.03526186 -0.9808284 0.09030443 -0.0224986 -0.9956601 0.1121702 -0.06312936 -0.9916816 -0.01281481 0.05688726 -0.9982984 -0.1980062 -0.0837388 -0.9766174 -0.1589743 -0.001590967 -0.9872815 -0.3244807 0.07438218 -0.9429633 -0.4484188 0.0324915 -0.8932328 -0.5000569 -0.03916275 -0.8651066 -0.5141773 -0.01603889 -0.857534 -0.641863 0.05304378 -0.7649825 -0.7200385 -0.07630926 -0.6897256 -0.7571272 0.02365303 -0.6528393 -0.8604499 0.0632525 -0.5055938 -0.8967638 -0.04372686 -0.440344 -0.926739 0.03704828 -0.3738748 -0.9785277 -0.01803398 -0.2053251 -0.9763965 -0.03700929 -0.2127918 -0.9939574 0.07678836 -0.07843589 -0.9970906 -0.01395267 0.07493811 -0.9949428 -0.04056251 0.09188878 -0.982335 0.04855537 0.1807222 -0.9440144 -0.04399132 0.3269582 -0.9292209 0.03814727 0.3675505 -0.8298673 -0.03047186 0.5571282 -0.8468967 0.01859617 0.5314323 -0.7776058 0.02904468 0.628081 -0.6968699 -0.0353803 0.7163245 -0.6797385 0.01256132 0.7333469 -0.5928544 0.07973456 0.8013527 -0.5261345 0.04298841 0.8493142 -0.4524148 -0.0718922 0.8889053 -0.417724 -0.002487957 0.9085706 -0.3021729 0.05297213 0.9517802 -0.1970161 -0.02089679 0.9801776 -0.1930907 -0.02898657 0.9807527 -0.05575776 0.04747313 0.9973151 0.07146388 -0.06742942 0.9951614 0.03972136 -0.01282137 0.9991285 0.1624342 0.05188524 0.9853544 0.2760988 0.05311828 0.9596604 0.3846841 -0.08146429 0.9194465 0.3290932 0.01696544 0.9441451 0.4354615 0.009084224 0.9001616 0.5182548 0.07448041 0.8519769 0.6102176 0.05112707 0.7905825 0.6742616 -0.07140892 0.735032 0.7167106 0.02048265 0.6970698 0.8123394 0.06163167 0.5799192 0.8606937 -0.07936608 0.5028991 0.9097233 0.068663 0.4094986 0.9459133 0.04605293 0.3211343 0.9687978 -0.0461629 0.2435156 0.978087 0.006033122 0.2081091 0.9884559 0.04591906 0.1443833 0.9993817 -0.001978933 0.03510779 0.999511 -0.02189463 0.02232891 0.9987375 -0.04490536 -0.0225197 0.9924926 0.007319509 -0.1220858 0.9865338 0.05474579 -0.1541236 0.9694017 -0.05875259 -0.2383455 0.94563 -0.07945483 -0.3153902 0.8854805 0.06704896 -0.4598138 0.9015216 -0.00528264 -0.4327018 0.8242768 -0.02142453 -0.5657817 0.7864837 0.05291187 -0.6153404 0.7240185 -0.06906777 -0.6863141 0.6473873 -0.05578273 -0.7601172 0.5583392 0.07852911 -0.8258877 0.5624996 0.06754356 -0.8240341 0.4271377 -0.07250005 -0.9012753 0.3115715 0.04412454 -0.9491977 0.2595362 -0.02918756 -0.9652922 0.1412571 -0.004309058 -0.9899637 0.1256391 0.01811146 -0.9919108 -0.00764358 -0.05790132 -0.9982931 -0.1171622 0.027969 -0.9927189 -0.09851539 -0.005737364 -0.995119 -0.2483569 -0.0449478 -0.9676252 -0.3172019 0.05739659 -0.9466196 -0.4096099 -0.05412441 -0.9106539 -0.5104742 -0.03226977 -0.8592875 -0.5552445 0.03734177 -0.8308485 -0.6042265 -0.02717465 -0.7963491 -0.7251081 0.004336476 -0.6886214 -0.7379162 0.0292958 -0.6742562 -0.7766548 -0.04016995 -0.6286444 -0.8660108 -0.06127554 -0.4962567 -0.902166 0.06599801 -0.4263107 -0.943127 -0.05281001 -0.3282112 -0.9701289 -0.01894664 -0.2418493 -0.9798476 0.05172634 -0.1929333 -0.9916349 -0.03745776 -0.1235204 -0.9973836 -0.0648216 -0.03200113 -0.9964262 0.01416814 0.08327156 -0.9873497 0.1024046 0.1210536 -0.9585083 -0.09556555 0.2685688 -0.8967409 0.04405903 0.4403575 -0.888768 0.07547509 0.4521008 -0.836169 -0.04563194 0.5465706 -0.7589697 -0.02892482 0.6504832 -0.6751446 -0.02751058 0.7371723 -0.7215136 0.04727625 0.6907845 -0.5487989 0.009214043 0.8359037 -0.5523523 0.003178179 0.8336048 -0.4667277 -0.04993593 0.8829902 -0.3384666 0.05796235 0.9391916 -0.3091444 -0.005575835 0.9509989 -0.1990588 -0.05552715 0.9784132 -0.08176034 0.01705545 0.9965061 -0.06569695 0.05118703 0.996526 0.09376269 -0.05774343 0.9939187 0.2416558 -0.01635879 0.9702242 0.1928514 0.05749797 0.9795419 0.352706 -0.05084455 0.9343518 0.4380778 0.04124993 0.8979902 0.48267 -0.03127628 0.8752437 0.6399701 0.00343877 0.7683922 0.6352567 -0.005828499 0.7722791 0.7100874 -0.03560602 0.7032127 0.7650095 0.02172434 0.6436524 0.7910669 -0.03083246 0.6109523 0.8839306 -0.00390172 0.467602 0.8883038 0.01117712 0.4591203 0.9314481 -0.04004609 0.3616641 0.9730535 -0.02703124 0.2289896 0.9608896 0.02963405 0.2753415 0.9922292 -0.02095168 0.1226478 0.9961115 0.03791457 0.07952564 0.6785736 -0.734047 0.02670025 0.931972 -0.3490245 0.09803068 0.8681936 -0.4823529 0.1165144 0.7225046 -0.6872164 0.07563745 0.1987646 -0.980017 0.007708191 0.9170101 -0.3307701 0.2228981 0.8877107 -0.416132 0.1969869 0.4855241 -0.8668841 0.1130419 0.3355011 -0.9390952 0.07442557 0.7020437 -0.6747069 0.227827 0.8815473 -0.3420959 0.325338 0.5865389 -0.7881909 0.1863533 0.8123368 -0.4841477 0.3251307 0.1365346 -0.9891999 0.05330991 0.8316843 -0.320598 0.4533411 0.7764365 -0.5118332 0.3676591 0.6056055 -0.72523 0.3275417 0.4782741 -0.8500382 0.2206557 0.2908504 -0.9456549 0.1454055 0.7390024 -0.4500836 0.5012986 0.6000749 -0.6898496 0.404991 0.578409 -0.7238699 0.3761056 0.3391256 -0.9105446 0.2364369 0.7583308 -0.297943 0.579797 0.6593841 -0.4329605 0.61462 0.579537 -0.5791435 0.5733496 0.2444203 -0.9462491 0.2118292 0.5306189 -0.6918215 0.489721 0.2965778 -0.9094252 0.291526 0.5828761 -0.3214502 0.7462744 0.5278477 -0.5788564 0.6215321 0.4327087 -0.7062125 0.5603812 0.2772122 -0.9061168 0.3195402 0.1246444 -0.9730986 0.1937601 0.3652362 -0.697952 0.6160078 0.4716181 -0.3208602 0.8213557 0.420463 -0.4724388 0.7746046 0.2263277 -0.8590092 0.4592157 0.1859786 -0.9078174 0.3758718 0.3068404 -0.4262977 0.850952 0.3102957 -0.4843 0.8180282 0.2275052 -0.7443348 0.6278591 0.21396 -0.3803671 0.8997455 0.06738293 -0.9639014 0.2575923 0.2052347 -0.3960339 0.8950061 0.1421751 -0.8132529 0.5642749 0.1255364 -0.7013615 0.7016642 0.03542715 -0.9836142 0.1767712 0.09091413 -0.2595797 0.9614329 0.06507658 -0.3702672 0.926643 0.06564021 -0.6932055 0.7177447 0.03068214 -0.7620333 0.6468107 0.009620189 -0.9032545 0.4289975 -0.07704067 -0.3466338 0.9348315 -0.08732932 -0.3913109 0.9161056 -0.06541645 -0.683243 0.7272549 -0.09236454 -0.7835547 0.6144192 -0.1795321 -0.3408597 0.9228125 -0.05518871 -0.9253982 0.3749566 -0.2254338 -0.4689723 0.8539583 -0.05531555 -0.9491466 0.309937 -0.2032933 -0.6309261 0.748735 -0.3051918 -0.2720482 0.9126049 -0.227261 -0.7329991 0.6411433 -0.1292307 -0.9245697 0.3584276 -0.3893748 -0.4115675 0.8240143 -0.1283834 -0.950534 0.2828481 -0.3663682 -0.5775919 0.7294943 -0.3319856 -0.645739 0.6876095 -0.2100419 -0.8995369 0.383035 -0.4138384 -0.5697665 0.7100029 -0.5428109 -0.365361 0.7562195 -0.5508088 -0.3932696 0.7361717 -0.5174177 -0.568788 0.6393428 -0.3980848 -0.7356919 0.5479836 -0.2884906 -0.8723468 0.3946952 -0.6645523 -0.1656473 0.7286503 -0.565532 -0.5754642 0.5907746 -0.6560762 -0.3955003 0.6427625 -0.2579196 -0.9174815 0.3028287 -0.1108509 -0.9879395 0.1081095 -0.4709678 -0.764946 0.4393711 -0.7173348 -0.3172201 0.6203244 -0.4891764 -0.7698324 0.409957 -0.7138036 -0.4828654 0.5072727 -0.6613207 -0.5809544 0.4744964 -0.7750986 -0.3839771 0.5017805 -0.3680282 -0.8921582 0.2619333 -0.4765903 -0.8411604 0.25556 -0.8489255 -0.3282403 0.4142268 -0.8137235 -0.4019371 0.4198817 -0.4734091 -0.83991 0.265396 -0.6617992 -0.6812767 0.3128641 -0.3466711 -0.9251093 0.1548937 -0.8579957 -0.4188297 0.2973635 -0.6935979 -0.6711599 0.2616608 -0.9220305 -0.2893798 0.2571364 -0.5408214 -0.8264976 0.15625 -0.9056022 -0.3612518 0.2222206 -0.7356476 -0.6623805 0.1416856 -0.07971817 -0.9964394 0.02745097 -0.5399854 -0.8284603 0.1485576 -0.3837861 -0.920437 0.07418864 -0.9265022 -0.3641219 0.09491556 -0.764976 -0.6379802 0.08827918 -0.9357472 -0.3410119 0.08993458 -0.6945725 -0.7172974 0.05525827 -0.2981488 -0.9540723 0.02921366 -0.4278936 -0.9037123 0.01452946 -0.930757 -0.3648294 -0.02431011 -0.7167924 -0.6966243 -0.03038507 -0.8610128 -0.504716 -0.06260049 -0.8955019 -0.4262773 -0.1279228 -0.5156833 -0.8556109 -0.04472959 -0.8780999 -0.4491471 -0.1649476 -0.4802935 -0.8733677 -0.08091354 -0.7476011 -0.6334943 -0.1994432 -0.8732134 -0.3599673 -0.3285151 -0.7466052 -0.6316335 -0.2088536 -0.205987 -0.9762664 -0.06688368 -0.7853916 -0.47773 -0.3936165 -0.5875434 -0.7740012 -0.2360404 -0.404335 -0.8958742 -0.1841817 -0.8143535 -0.3443478 -0.4671756 -0.7850379 -0.4519626 -0.4236099 -0.5635051 -0.7361062 -0.3749799 -0.4227401 -0.8672778 -0.2629073 -0.7352334 -0.4010189 -0.5464574 -0.6143602 -0.6108003 -0.4994843 -0.5836965 -0.6317707 -0.5100629 -0.6559482 -0.3335483 -0.6771097 -0.5864678 -0.5743864 -0.5710832 -0.2285896 -0.9543454 -0.19228 -0.2840979 -0.9184412 -0.275235 -0.4916844 -0.6562319 -0.572369 -0.5849502 -0.3199214 -0.7453077 -0.5435111 -0.4282304 -0.7219519 -0.2964577 -0.8833062 -0.363157 -0.2740353 -0.9054495 -0.3241387 -0.4967927 -0.5656662 -0.6581937 -0.4142735 -0.6678287 -0.6183707 -0.4878656 -0.3071107 -0.817111 -0.3145986 -0.8215097 -0.4755518 -0.3853281 -0.5326316 -0.7535423 -0.06930696 -0.9912887 -0.1119967 -0.2365994 -0.8675978 -0.4373726 -0.3694328 -0.5425887 -0.7543984 -0.3389596 -0.4815919 -0.8081929 -0.1611739 -0.9258173 -0.3418853 -0.325457 -0.4920284 -0.8074564 -0.1810411 -0.7875243 -0.5890923 -0.1481083 -0.919789 -0.3633901 -0.2525164 -0.3440759 -0.9043491 -0.1363788 -0.6071338 -0.7828086 -0.1271919 -0.7756356 -0.6182329 -0.1070896 -0.5456766 -0.8311251 -0.03056329 -0.9830219 -0.1809253 -0.06037139 -0.9046642 -0.4218271 -0.03187948 -0.9780003 -0.2061536 0.02019834 -0.4319199 -0.9016858 -0.005958378 -0.5639039 -0.825819 0.02182191 -0.781884 -0.6230419 0.1260317 -0.3774264 -0.9174233 0.04340761 -0.8162019 -0.5761339 0.1697259 -0.5144479 -0.8405573 0.04217863 -0.8636292 -0.5023601 0.1615708 -0.6152852 -0.7715694 0.1345146 -0.7105833 -0.6906354 0.2561965 -0.2782014 -0.9257254 0.1227194 -0.8738146 -0.4705188 0.06664502 -0.9499697 -0.3051494 0.04463291 -0.9868046 -0.155643 0.3502319 -0.444809 -0.8243075 0.2861598 -0.678036 -0.6770375 0.2929557 -0.6668781 -0.6851647 0.4138781 -0.2697528 -0.8694472 0.2095162 -0.8263379 -0.5227511 0.1477604 -0.9354768 -0.321014 0.5127186 -0.3718796 -0.773838 0.5105021 -0.4216111 -0.749421 0.3879764 -0.6993615 -0.6003065 0.3457899 -0.7983439 -0.4930279 0.1802582 -0.9457419 -0.2703318 0.5813661 -0.3794767 -0.7197297 0.1546767 -0.9633993 -0.2189451 0.5809152 -0.5459613 -0.6037085 0.4702572 -0.7259358 -0.5018718 0.6650212 -0.4288429 -0.6114252 0.2822065 -0.9232041 -0.2608711 0.3695436 -0.8670431 -0.3341763 0.7372768 -0.4401856 -0.5125033 0.6950959 -0.5091298 -0.5075713 0.1296285 -0.9868925 -0.09612387 0.5286968 -0.7631935 -0.3715043 0.8262879 -0.3783968 -0.4172101 0.4896002 -0.8198553 -0.2968655 0.8210798 -0.4014775 -0.4057633 0.344446 -0.9192786 -0.1904838 0.6640205 -0.6831679 -0.3039053 0.6388021 -0.7261792 -0.254157 0.8816294 -0.3402368 -0.3270608 0.4137905 -0.8975788 -0.1520851 0.330582 -0.9348624 -0.1294138 0.755549 -0.6113195 -0.235445 0.1814906 -0.9815301 -0.0604971 0.8805604 -0.4425175 -0.1696816 0.7590971 -0.6226019 -0.1901013 0.6361121 -0.7596352 -0.1353352 0.9002778 -0.4179407 -0.12176 0.9648983 -0.2625287 -0.007066726 0.5873956 -0.8052107 -0.08125531 0.3906161 -0.919884 -0.03510677 0.8577703 -0.5100194 -0.06411302 0.7623138 -0.6456336 -0.04510957 0.3393612 -0.9405843 -0.01162797 0.002415657 -0.9999936 0.002663552 0.002238452 -0.9999939 0.002705752 0.002480924 -0.999994 0.002426683 0.002413392 -0.999996 0.001533508 9.77345e-4 -0.9999973 0.00214672 0.00217694 -0.9999963 0.001654267 0.001474142 -0.9999989 5.16825e-4 -2.06912e-5 -0.9999954 0.003077387 8.79255e-4 -0.9999913 0.004084527 0.001502513 -0.9999989 1.69772e-4 0.00191766 -0.9999982 -1.55594e-4 -2.82742e-4 -0.9999935 0.003618061 2.05682e-4 -0.9999947 0.003278255 0.001785755 -0.9999984 -3.41981e-4 -8.55588e-4 -0.9999967 0.002471864 -0.004180073 -0.9999863 0.003145754 0.00277388 -0.999994 -0.002093374 0.003173351 -0.9999934 -0.001792252 -0.003149986 -0.9999824 0.005046069 0.00323832 -0.9999923 -0.00227797 -0.003914833 -0.9999804 0.004903316 0.00241357 -0.9999941 -0.002469301 -0.003371238 -0.9999897 0.003062903 0.00276345 -0.9999955 -0.001152098 -0.003798902 -0.9999912 0.001806199 4.63286e-4 -0.9999995 -0.001000106 -0.003373682 -0.9999925 0.001909434 -1.91678e-4 -0.9999965 -0.002637088 -0.002707302 -0.9999964 2.36997e-4 2.18622e-4 -0.9999959 -0.002885043 -0.006281554 -0.9999749 -0.003292798 -5.80829e-4 -0.9999944 -0.00330609 -0.00666058 -0.9999766 -0.001549541 3.01784e-4 -0.9999976 -0.002149283 -0.005316913 -0.9999859 1.23143e-4 -6.91063e-4 -0.9999987 -0.001464843 -0.002459585 -0.9999958 -0.001560628 -0.002371132 -0.9999954 -0.001920104 -0.002194523 -0.999994 -0.002713263 -0.002591788 -0.9999934 -0.00256735 0.9227706 0.3839743 -0.03253185 0.9321066 0.3561546 -0.06581348 0.1635754 0.9863327 -0.01977413 0.8408889 0.5215563 -0.1445167 0.8012278 0.5792505 -0.1500102 0.6488116 0.7535743 -0.1056852 0.4149732 0.904286 -0.1003201 0.7950385 0.5666492 -0.2163853 0.8937078 0.3298994 -0.3040606 0.6489787 0.7199369 -0.2460032 0.8235184 0.4149662 -0.3868082 0.485218 0.8545668 -0.1851463 0.8180815 0.4322988 -0.3792896 0.741639 0.580545 -0.3360645 0.3743143 0.9093113 -0.1817741 0.5297821 0.7861091 -0.3183764 0.7892605 0.3498449 -0.5046548 0.4104021 0.8822455 -0.2306794 0.7207264 0.4647092 -0.5143917 0.7334188 0.3130776 -0.6033899 0.5962768 0.6789624 -0.4283271 0.2674862 0.940175 -0.2110032 0.4864531 0.7732623 -0.4067294 0.309563 0.9122668 -0.2682164 0.6335859 0.413423 -0.6539499 0.5869599 0.5044677 -0.633238 0.5103548 0.6823159 -0.5234339 0.3159404 0.8717787 -0.3744109 0.2662491 0.9217054 -0.2820829 0.543889 0.3501616 -0.7626085 0.5247101 0.4914119 -0.6951214 0.3974782 0.7005116 -0.5927013 0.3043841 0.8577347 -0.4142965 0.4079563 0.368756 -0.8352191 0.4074954 0.3595547 -0.8394451 0.1585935 0.9458317 -0.283285 0.3448175 0.6606097 -0.6668551 0.1057385 0.9725351 -0.2073523 0.2790601 0.7543992 -0.5941443 0.2974232 0.4037393 -0.8651786 0.2814803 0.3111576 -0.9077168 0.2004457 0.7202907 -0.6640804 0.1954499 0.7795318 -0.5950879 0.1200132 0.908801 -0.399597 0.1999075 0.3498495 -0.915228 0.1545267 0.4893111 -0.85831 0.1586407 0.659779 -0.7345236 0.06444984 0.9433532 -0.3254705 0.07507926 0.3677558 -0.9268867 0.08763188 0.4624473 -0.8823056 0.04788821 0.8588775 -0.5099375 -0.009470105 0.2308596 -0.9729411 0.02312505 0.7125199 -0.7012708 0.0325489 0.8468816 -0.5307844 -0.004856646 0.9058478 -0.4235756 -0.08186537 0.4504901 -0.8890202 -0.06959933 0.6025677 -0.7950271 -0.01449942 0.9880685 -0.1533318 -0.1511136 0.2849639 -0.9465517 -0.1001493 0.7247418 -0.6817033 -0.08731329 0.8303117 -0.5504171 -0.2193176 0.483371 -0.8474977 -0.09635454 0.8810614 -0.463084 -0.2169036 0.50377 -0.8361631 -0.3123859 0.2444057 -0.9179765 -0.2392994 0.7178223 -0.6538096 -0.1621304 0.8673563 -0.4705392 -0.3700014 0.4349691 -0.8209146 -0.1513653 0.9101693 -0.3855912 -0.3493676 0.5714851 -0.7425276 -0.07350814 0.9853968 -0.1535903 -0.4854982 0.4862346 -0.7265448 -0.3825771 0.6305146 -0.6753416 -0.2865269 0.8316625 -0.4756468 -0.2693865 0.8746418 -0.4030292 -0.5163757 0.4918259 -0.7010445 -0.633838 0.203112 -0.746321 -0.471831 0.6912314 -0.5473342 -0.2931814 0.8731741 -0.3893734 -0.5020208 0.678552 -0.5362299 -0.6651197 0.4053477 -0.6271437 -0.2097758 0.953513 -0.2163497 -0.7023252 0.356828 -0.6159652 -0.4223912 0.8208063 -0.3845294 -0.1162934 0.9876561 -0.1049345 -0.6997938 0.4767777 -0.5319508 -0.557967 0.734473 -0.3862932 -0.5567195 0.7373027 -0.3826857 -0.8201415 0.2881894 -0.4942823 -0.3954485 0.8879222 -0.2349784 -0.7332638 0.5607655 -0.3845339 -0.4010654 0.8917676 -0.2095164 -0.7331239 0.5767068 -0.36047 -0.6044267 0.7507595 -0.266512 -0.8616743 0.3906492 -0.3238992 -0.8535262 0.4291043 -0.2955719 -0.7224102 0.6556338 -0.2196999 -0.6215275 0.7548664 -0.2094768 -0.2580926 0.9610399 -0.09894847 -0.9400694 0.2616686 -0.2186301 -0.3932529 0.9127129 -0.1109387 -0.7773062 0.61405 -0.136886 -0.8168612 0.5621081 -0.1295077 -0.3953029 0.9167515 -0.05746668 -0.9530537 0.2973751 -0.05706834 -0.8391416 0.53569 -0.09422093 -0.3601124 0.9309241 -0.06082242 -0.7343149 0.6786655 -0.01395916 -0.9354721 0.3524082 0.02646714 -0.8758249 0.480574 0.04449027 -0.511542 0.8592018 0.00985825 -0.4515658 0.8922373 0.001025676 -0.5584608 0.8275837 0.056804 -0.8212537 0.5585279 0.1165719 -0.9427248 0.2770851 0.1857258 -0.8214042 0.5582653 0.11677 -0.145316 0.9891371 0.02216231 -0.8593474 0.4359703 0.2673052 -0.3951404 0.9139654 0.09236615 -0.7246395 0.6533188 0.2192536 -0.6478006 0.7311251 0.2140339 -0.9073281 0.2157574 0.3608387 -0.4856491 0.8605397 0.1536763 -0.7852402 0.4708243 0.4021472 -0.6996912 0.6188916 0.356939 -0.6881029 0.6369265 0.3476193 -0.3080562 0.9386655 0.1549476 -0.8166717 0.2754239 0.5071381 -0.4031013 0.884621 0.234425 -0.5777397 0.7003942 0.419124 -0.4241694 0.8518841 0.3072035 -0.7259175 0.351208 0.5913518 -0.7104305 0.433158 0.5546735 -0.6504786 0.5606487 0.5123969 -0.3747136 0.8778358 0.2983186 -0.5142064 0.6870996 0.5133088 -0.6595473 0.3233588 0.6785547 -0.4146425 0.8115439 0.4116652 -0.5638924 0.534143 0.6298546 -0.1085436 0.9879102 0.1106879 -0.2735484 0.9018616 0.3343902 -0.5144623 0.52988 0.6742075 -0.4339537 0.6283107 0.6456856 -0.28371 0.8691924 0.4049854 -0.4336031 0.4134007 0.8006799 -0.4180676 0.5789686 0.7000107 -0.4047266 0.3620672 0.8397046 -0.1805818 0.9260912 0.3312783 -0.3169845 0.5080302 0.8008909 -0.2650501 0.7453115 0.6117672 -0.2226539 0.8127299 0.5384192 -0.1780047 0.8898991 0.4199926 -0.2713826 0.4479121 0.8518958 -0.113379 0.9383127 0.3266717 -0.2286663 0.5037819 0.833016 -0.180617 0.6717564 0.7184156 -0.1708391 0.3428776 0.9237148 -0.1079093 0.4418843 0.8905581 -0.09091597 0.69744 0.7108529 -0.1165236 0.7567209 0.6432697 -0.09263736 0.852411 0.5146008 -0.06046789 0.3467372 0.9360113 -0.01956218 0.7718873 0.6354584 -0.02165734 0.9294354 0.3683488 0.05928796 0.3764351 0.924544 0.02391022 0.4549549 0.8901935 0.002108991 0.9745092 0.2243377 0.01445817 0.7126616 0.701359 0.09415394 0.3860959 0.9176411 0.1413013 0.2962049 0.9446145 0.09936541 0.7819586 0.6153595 0.09375637 0.7675474 0.6340984 0.07315444 0.8900558 0.4499435 0.2018706 0.4243944 0.8826877 0.2025603 0.6269937 0.752229 0.317409 0.5340855 0.7835844 0.1149423 0.9238899 0.3649875 0.2397271 0.6549988 0.7165944 0.1819609 0.8479764 0.4978214 0.3685845 0.5095724 0.7774841 0.3879817 0.5622267 0.7303228 0.2540535 0.8487859 0.4637018 0.4510516 0.5153647 0.7286643 0.04716783 0.994899 0.08916997 0.2395982 0.8876752 0.3932243 0.4563277 0.5245159 0.7187824 0.1404436 0.9669564 0.2127696 0.3943352 0.7356226 0.5507805 0.561712 0.3944348 0.7272558 0.5524573 0.6383537 0.5359997 0.5160607 0.6019908 0.6093345 0.634904 0.4520485 0.6265373 0.3986619 0.8344935 0.3803804 0.2983332 0.9095141 0.2894504 0.646289 0.5469706 0.5321031 0.7895149 0.2716918 0.5503181 0.5382174 0.7304362 0.420458 0.5324 0.7701731 0.3512603 0.7717018 0.4534195 0.4459678 0.1640582 0.9787986 0.1226304 0.4439541 0.8585589 0.2564787 0.8187128 0.4133077 0.3986052 0.4534639 0.8576462 0.2425148 0.7587956 0.5637221 0.3262619 0.4076098 0.8952911 0.1797444 0.4576076 0.8732367 0.1674906 0.7493637 0.6140395 0.2478096 0.8761088 0.4148887 0.2455622 0.8023527 0.5532833 0.2238478 0.7720728 0.6161042 0.155947 0.8613128 0.5001594 0.08933711 0.3462854 0.9364658 0.05584144 0.3833284 0.9207932 0.07210606 0.9495661 0.313207 0.01502889 0.865781 0.4871144 0.1146416 0.711737 0.7022293 0.01745575 0.5651726 0.8249692 -0.002412617 0.4376495 0.8990666 0.01192897 -0.004250764 0.9999744 0.005769371 -0.004070758 0.9999871 0.0030393 -0.003796517 0.999976 0.005805671 -0.005378246 0.999984 0.001832604 -0.007499158 0.9999711 0.001282632 -0.007701277 0.9999675 0.002419173 -0.001100242 0.9999931 0.003574073 -0.005395233 0.9999777 0.00393933 0.00172013 0.9999431 0.01053154 -0.003373205 0.9999563 0.008735537 -6.44965e-5 0.9999964 0.002690255 -0.002443909 0.999997 -1.32431e-4 -0.004176318 0.999987 -0.002935945 4.61911e-4 0.9999973 0.002272784 -0.005073308 0.9999871 -3.76388e-4 -0.002736449 0.9999957 -0.001026093 6.62973e-4 0.9999977 0.002072334 0.001107633 0.9999966 0.002394974 -0.002335131 0.999996 -0.00163412 7.95466e-4 0.9999992 0.00101459 -0.002523124 0.9999929 -0.002794146 -0.003299534 0.9999837 -0.004660308 0.004095733 0.9999915 -6.00296e-4 0.005050301 0.9999825 0.003090322 -0.002723574 0.9999834 -0.005077004 -0.002686202 0.9999827 -0.005257546 0.007553696 0.999971 9.56504e-4 0.0074656 0.9999707 0.001673102 -0.001125812 0.9999859 -0.005198001 0.003125071 0.9999876 0.003892064 6.22609e-4 0.9999743 -0.007144153 1.05528e-4 0.9999719 -0.007496654 0.004045724 0.9999912 -0.001143217 -0.002263009 0.9999738 -0.006869852 0.00525254 0.9999861 -6.74817e-4 9.30377e-4 0.9999946 -0.003142416 0.004517078 0.9999877 -0.002093434 0.004552423 0.9999839 -0.003413438 0.004397332 0.9999881 -0.002122402 0.003875672 0.9999707 -0.006600558 8.49468e-4 0.999965 -0.008333742 0.003828167 0.9999868 -0.003448247 0.002942144 0.9999957 -3.57904e-4 0.9966389 -0.06444841 -0.05057126 0.9906267 0.04257082 -0.1297944 0.9643097 -0.02060371 -0.263974 0.960885 0.004934668 -0.2769038 0.8802716 -0.05745279 -0.4709787 0.9114296 0.0421831 -0.4092882 0.8624373 0.004965305 -0.5061396 0.8055568 0.07862305 -0.5872791 0.7437745 0.03880363 -0.6673034 0.7029731 -0.04550766 -0.7097591 0.6840043 -0.004448771 -0.7294645 0.6252757 0.03429234 -0.7796502 0.5132889 -0.02890968 -0.8577288 0.5260027 -0.069552 -0.8476343 0.4274161 0.05883777 -0.9021384 0.3366069 0.04335528 -0.9406467 0.2455742 -0.07065439 -0.9667995 0.25006 -0.08207213 -0.9647457 0.1402279 0.06318902 -0.988101 0.008859753 0.04993379 -0.9987133 -0.07498812 -0.08386129 -0.9936519 -0.1120429 -0.009499251 -0.993658 -0.1722807 0.03628462 -0.9843794 -0.2968891 0.01394695 -0.9548102 -0.3346762 -0.04328787 -0.9413385 -0.3895071 0.0338627 -0.9204008 -0.5182061 0.02282536 -0.8549512 -0.5497553 -0.04617655 -0.8340485 -0.6365938 0.04711502 -0.7697587 -0.7065068 -0.02060562 -0.7074062 -0.7147741 -0.004499733 -0.6993409 -0.7949597 0.0312823 -0.6058552 -0.8229131 -0.01775592 -0.5678899 -0.8452806 0.02643245 -0.5336686 -0.9308501 -0.05025196 -0.3619295 -0.9135975 0.02476966 -0.4058647 -0.9507386 0.02395975 -0.3090664 -0.9751977 0.06547635 -0.2114292 -0.9930273 -0.08454155 -0.08215582 -0.9915543 0.01253277 -0.1290857 -0.9991742 0.04035109 0.004789113 -0.9915401 0.05845922 0.1158908 -0.9842686 0.005563497 0.1765909 -0.9764429 -0.06256932 0.2065055 -0.9449031 0.05925464 0.3219425 -0.8853836 -0.02753925 0.4640448 -0.8932682 -0.09768104 0.4387829 -0.8329488 0.06551432 0.5494582 -0.7471238 0.04574662 0.6631088 -0.6948008 -0.09372729 0.7130688 -0.6365029 0.04300874 0.7700743 -0.5625576 0.05684947 0.8248013 -0.4686344 -0.08394318 0.8793948 -0.4266702 0.02509975 0.9040589 -0.2604528 0.06399291 0.9633636 -0.1809513 -0.04871571 0.9822848 -0.1523233 -0.001741051 0.9883292 -0.05648875 0.04546433 0.9973676 0.04278695 -0.02262467 0.9988281 0.04769206 -0.01468318 0.9987542 0.1626568 0.04297405 0.9857465 0.2498387 -0.04615491 0.9671869 0.2864119 0.01638555 0.9579666 0.3976462 0.04971021 0.9161913 0.4866166 -0.07259917 0.870594 0.5161817 -0.005073547 0.8564642 0.6069077 0.06188076 0.7923597 0.7167316 -0.06015074 0.6947502 0.7014468 -0.1101143 0.7041642 0.7849994 0.06135904 0.6164504 0.8583089 0.05518126 0.5101579 0.8953279 -0.07152843 0.4396268 0.9162896 0.005298912 0.4004815 0.9359237 0.03912693 0.3500227 0.9768579 -0.01395839 0.2134335 0.9692969 -0.07039415 0.2356018 0.9912046 0.06194353 0.116947 0.998553 0.04990595 0.02003616 0.996881 -6.65748e-4 -0.0789169 0.9957638 0.017304 -0.09030479 0.9857494 -0.04300892 -0.1626299 0.9560458 -0.01341325 -0.2929104 0.9343412 -1.66398e-4 -0.35638 0.9420004 0.03905063 -0.3333324 0.8630776 -0.07134163 -0.5000075 0.8217359 0.01974415 -0.5695264 0.8167216 0.03816032 -0.5757687 0.7369872 -0.04792398 -0.6742057 0.649534 -0.01148754 -0.7602459 0.668334 0.03038549 -0.7432405 0.5571791 -0.05223292 -0.828748 0.4403109 0.007861733 -0.897811 0.4631834 0.06499123 -0.8838763 0.3329225 -0.07026833 -0.9403325 0.2071392 0.03794682 -0.9775753 0.2070657 0.03812402 -0.977584 0.08248466 -0.04740399 -0.9954643 -0.0156303 0.02854597 -0.9994704 -0.04886543 -0.02710419 -0.9984376 -0.114132 -0.05785626 -0.9917795 -0.2454894 0.04443645 -0.9683803 -0.2857766 -0.03522944 -0.9576485 -0.4311984 -0.004103362 -0.9022478 -0.4476611 0.03307557 -0.8935914 -0.5544171 -0.05133634 -0.8306542 -0.6504995 0.03823411 -0.7585437 -0.6481951 0.03108602 -0.7608397 -0.7413169 -0.05442583 -0.6689448 -0.8144004 0.02701818 -0.5796742 -0.8158646 0.03220725 -0.5773456 -0.8631138 -0.04357689 -0.5031259 -0.9145991 -0.02137273 -0.4037967 -0.9436197 0.01687598 -0.3306012 -0.9352685 0.0529164 -0.3499611 -0.9719023 -0.06178563 -0.2271315 -0.9929173 -0.01183086 -0.1182178 -0.9936357 0.0907309 -0.06675404 -0.9991161 -0.03896367 0.01578187 -0.9890958 -0.05447673 0.1368276 -0.9780383 0.0132215 0.2080057 -0.9741729 0.04348433 0.2215768 -0.9458832 -0.04991567 0.3206454 -0.894856 0.01633822 0.446056 -0.8759376 0.07588618 0.4764186 -0.8384685 -0.05337351 0.54233 -0.7525635 -0.06417518 0.6553852 -0.6820257 0.06635254 0.728312 -0.680743 0.07058912 0.7291132 -0.5667248 -0.06632339 0.8212335 -0.4701353 0.001471877 0.8825932 -0.4348185 0.08198225 0.8967787 -0.3475312 -0.05074542 0.9362943 -0.2410913 -0.05078572 0.9691728 -0.1534915 0.05377244 0.9866858 -0.1520177 0.05722951 0.9867196 -0.03298193 -0.05770421 0.9977888 0.1044656 0.05434304 0.9930427 0.1379204 -0.01591283 0.9903155 0.2499122 -0.0419926 0.9673575 0.3621694 0.03209221 0.9315598 0.3522019 0.05734115 0.9341658 0.4166523 -0.04935222 0.9077253 0.518599 -0.07518041 0.851706 0.6154531 0.04635637 0.7868091 0.612338 0.03563183 0.7897927 0.7105453 -0.03237241 0.7029065 0.7619488 0.03431153 0.6467278 0.7855815 -0.02153789 0.6183832 0.8648622 -0.02905404 0.5011681 0.8797838 0.02278536 0.4748277 0.9304403 -0.03859806 0.3644052 0.9594221 -0.03561496 0.2797157 0.9491429 0.00396955 0.3148206 0.9912635 -0.004194974 0.1318297 0.9926994 0.01623988 0.1195164 0.9986419 -0.04921227 0.01710391 0.8620683 -0.5058193 0.03139007 0.8422411 -0.538776 0.01871669 0.5831314 -0.8123633 0.004858493 0.5499687 -0.8351125 0.01102554 0.3429976 -0.9393289 0.003761649 0.9558196 -0.2605203 0.1361546 0.8587499 -0.5052312 0.08538234 0.2202102 -0.9753116 0.0165745 0.7557884 -0.6445384 0.1155608 0.6019683 -0.7938197 0.0865128 0.463124 -0.881648 0.09062492 0.8569142 -0.46178 0.2290359 0.8560033 -0.4717438 0.2114623 0.7218971 -0.6430895 0.2555396 0.8340498 -0.4212335 0.3562632 0.4431858 -0.886729 0.1315221 0.7232429 -0.6399169 0.2596654 0.2919364 -0.9500077 0.1107185 0.7959359 -0.4209464 0.4350752 0.09945988 -0.9938717 0.04823786 0.5418487 -0.7930445 0.2783534 0.8149251 -0.3297365 0.4766246 0.5465805 -0.780849 0.3025306 0.5007052 -0.8089848 0.3079581 0.7144041 -0.4590696 0.5280929 0.2695065 -0.9463923 0.1780675 0.563691 -0.7101052 0.421904 0.7360814 -0.3401635 0.5852121 0.5007321 -0.760303 0.4137714 0.6701514 -0.3456202 0.6568438 0.319643 -0.9047463 0.2815361 0.6137367 -0.4576298 0.6433524 0.5175016 -0.652193 0.5539282 0.5171725 -0.652879 0.5534271 0.2369254 -0.9389911 0.2493235 0.5913107 -0.2663978 0.7611727 0.3002715 -0.8859384 0.3534831 0.5431095 -0.3661317 0.7556319 0.4604245 -0.6263729 0.6290202 0.3462045 -0.763417 0.5452861 0.5034918 -0.303855 0.8088067 0.283055 -0.8701058 0.4034795 0.4272062 -0.4606019 0.7780365 0.3512252 -0.7804259 0.5172778 0.3981056 -0.4629521 0.7919517 0.3255811 -0.6027519 0.7284829 0.2655825 -0.8008725 0.5367208 0.0673809 -0.9878169 0.1402768 0.1472443 -0.9189092 0.3659576 0.272301 -0.4182539 0.866554 0.270105 -0.5906193 0.7604027 0.1686239 -0.7851524 0.5959041 0.2375296 -0.3596841 0.9023343 0.1861928 -0.4379901 0.8794867 0.1226779 -0.7562853 0.6426374 0.1248754 -0.2918995 0.9482621 0.1213644 -0.7573439 0.6416394 0.04331433 -0.8998986 0.4339429 0.1003242 -0.363816 0.9260525 0.07861894 -0.6692219 0.7388918 -0.008587718 -0.3760263 0.9265692 0.02373367 -0.9143175 0.4043023 0.01757085 -0.7197301 0.6940316 -8.37369e-4 -0.7886874 0.6147938 -0.02878934 -0.3239221 0.9456456 -0.07208865 -0.3908223 0.917639 -0.006770372 -0.9882924 0.1524218 -0.07258594 -0.7581409 0.6480384 -0.06213223 -0.7860327 0.6150547 -0.130769 -0.3519259 0.9268483 -0.1765958 -0.5033349 0.8458535 -0.05904543 -0.92799 0.3678972 -0.1647484 -0.5983736 0.7840963 -0.2434147 -0.3195482 0.915772 -0.1830714 -0.7231435 0.6659943 -0.323467 -0.315759 0.8920009 -0.1433818 -0.8719267 0.4681728 -0.11584 -0.9091059 0.4001345 -0.3338727 -0.4262362 0.8407448 -0.3167586 -0.541379 0.7788278 -0.3171211 -0.6657248 0.6754589 -0.07170462 -0.9829345 0.1694054 -0.445635 -0.2684887 0.8540043 -0.2336645 -0.8211399 0.5207017 -0.170489 -0.9314549 0.3214426 -0.4288935 -0.5465185 0.7192829 -0.4086552 -0.5315877 0.7418999 -0.3907799 -0.7127894 0.582428 -0.5477377 -0.320252 0.772931 -0.5561023 -0.390776 0.7335151 -0.2263841 -0.910521 0.3459795 -0.4396305 -0.6762681 0.5910893 -0.6244061 -0.350234 0.6981785 -0.2106435 -0.942108 0.2608866 -0.6076191 -0.4881781 0.6264832 -0.480268 -0.7170249 0.5051912 -0.4339311 -0.7655433 0.4750235 -0.3186944 -0.8814361 0.3485749 -0.7045998 -0.3706161 0.6051304 -0.3291703 -0.9117652 0.2456241 -0.6958026 -0.4872505 0.5276797 -0.5740205 -0.7054259 0.4157823 -0.565894 -0.7142149 0.4118994 -0.8006137 -0.2956 0.5211895 -0.7611587 -0.4922263 0.4223158 -0.2352504 -0.959465 0.1551911 -0.6556581 -0.6506674 0.3830723 -0.8441819 -0.3585871 0.3984625 -0.819247 -0.4164339 0.3942298 -0.5208284 -0.8193838 0.2394742 -0.4049155 -0.8949028 0.1875965 -0.7020379 -0.6621755 0.2620429 -0.9102256 -0.2617759 0.3208784 -0.8243756 -0.5048189 0.2560524 -0.7097351 -0.6560288 0.2567147 -0.2461922 -0.9662337 0.07603871 -0.8504748 -0.4801542 0.2148133 -0.517394 -0.8470879 0.1214311 -0.3572813 -0.9299075 0.0873056 -0.7468129 -0.6559455 0.1095719 -0.9327447 -0.3486388 0.09186106 -0.7454734 -0.6571666 0.111363 -0.675855 -0.7355526 0.04671722 -0.9533543 -0.3014973 0.01466852 -0.9042489 -0.4265757 -0.01915848 -0.3337199 -0.9426708 0.001688003 -0.8152758 -0.578687 -0.02113968 -0.3217343 -0.9468291 -0.001372158 -0.9661082 -0.2316364 -0.113928 -0.7145732 -0.6944622 -0.08430546 -0.889962 -0.4264178 -0.1616648 -0.4112659 -0.9103508 -0.04606294 -0.7660417 -0.6296873 -0.1291282 -0.9202823 -0.3286749 -0.2122578 -0.3665634 -0.9280903 -0.06542021 -0.6593641 -0.7331199 -0.1666563 -0.8695248 -0.4093463 -0.2763372 -0.7997766 -0.5317011 -0.2786601 -0.2034012 -0.9774298 -0.05708825 -0.6735888 -0.7108908 -0.2022681 -0.829526 -0.3979468 -0.3918228 -0.4463012 -0.8754482 -0.185488 -0.7823057 -0.5315865 -0.324675 -0.4979419 -0.8278243 -0.2583811 -0.533756 -0.8141173 -0.2287306 -0.8004816 -0.404347 -0.4424169 -0.7019459 -0.5578987 -0.4427427 -0.3224585 -0.9235237 -0.2076642 -0.7239797 -0.5408927 -0.4281221 -0.5031099 -0.7866824 -0.3577864 -0.7435612 -0.3886954 -0.5440888 -0.3446298 -0.9096016 -0.2320676 -0.6766368 -0.4741795 -0.5633086 -0.5730524 -0.6597131 -0.4861992 -0.6965091 -0.3463454 -0.6284266 -0.4447672 -0.7690725 -0.4590311 -0.604056 -0.3429375 -0.7193819 -0.5933237 -0.4146849 -0.6899301 -0.2491731 -0.931693 -0.2643123 -0.5004901 -0.6282198 -0.5956926 -0.2199741 -0.9448723 -0.2425443 -0.5318908 -0.284622 -0.797548 -0.4061703 -0.7013882 -0.5857306 -0.4807232 -0.4116082 -0.7742636 -0.248788 -0.8905751 -0.3807632 -0.4382779 -0.5501757 -0.7107878 -0.2470291 -0.891627 -0.3794442 -0.4251164 -0.2093423 -0.8805975 -0.3267608 -0.5073974 -0.7973552 -0.3136751 -0.6338526 -0.7069929 -0.104788 -0.9735924 -0.2028235 -0.2442978 -0.7868249 -0.5667673 -0.1866129 -0.8544034 -0.484944 -0.3072694 -0.4832427 -0.8197939 -0.2795665 -0.1702244 -0.944916 -0.1910499 -0.6565624 -0.7296752 -0.1303228 -0.8471712 -0.5150893 -0.1302319 -0.8485869 -0.5127767 -0.1698004 -0.4650222 -0.8688626 -0.1492716 -0.46186 -0.8743017 -0.09987545 -0.5819107 -0.8070967 -0.08426946 -0.8002385 -0.5937316 -0.01881575 -0.5394029 -0.8418377 -0.009986758 -0.9970447 -0.07617211 0.008041679 -0.5883918 -0.8085361 -0.01902818 -0.8727807 -0.4877414 6.8786e-4 -0.9245399 -0.3810846 0.03611648 -0.5790881 -0.8144648 0.09677714 -0.309542 -0.9459483 0.07113373 -0.7171053 -0.6933254 0.03736633 -0.9086724 -0.4158346 0.1892567 -0.3229748 -0.9272913 0.05548268 -0.9319764 -0.3582481 0.2047504 -0.4358893 -0.8764005 0.1633811 -0.67896 -0.7157654 0.1653721 -0.7532854 -0.6365638 0.1167954 -0.8748346 -0.4701312 0.3096915 -0.3473817 -0.8851086 0.3214277 -0.4383482 -0.839366 0.2478305 -0.7023804 -0.6672645 0.1204946 -0.9395146 -0.320614 0.01179856 -0.9994041 -0.03244042 0.2476625 -0.8134613 -0.5262547 0.4133069 -0.3728414 -0.8307629 0.2663997 -0.8032827 -0.5326991 0.4190264 -0.4221752 -0.8038563 0.2854577 -0.8325217 -0.474786 0.5047906 -0.398496 -0.7657594 0.5024234 -0.4975619 -0.7071089 0.2310729 -0.9167007 -0.3259837 0.5556201 -0.4922375 -0.6700661 0.5483363 -0.5711322 -0.610848 0.3715016 -0.8425834 -0.3899231 0.6951227 -0.387326 -0.6056264 0.699818 -0.4354609 -0.5662407 0.3503652 -0.8797371 -0.3214139 0.6625079 -0.5542403 -0.5038859 0.4767739 -0.7978238 -0.3690038 0.1283851 -0.9867643 -0.09906327 0.8161513 -0.3589581 -0.4528203 0.7457366 -0.5046939 -0.4349263 0.004868745 -0.99998 -0.00403887 0.4249385 -0.8741475 -0.2351456 0.4479367 -0.8584649 -0.2497816 0.594426 -0.7451867 -0.3022492 0.8424225 -0.4035042 -0.357084 0.7423195 -0.6057081 -0.2864952 0.2922709 -0.9489599 -0.1185448 0.9191898 -0.317187 -0.233415 0.7278622 -0.6446734 -0.2336941 0.6712354 -0.7151785 -0.1948406 0.4378306 -0.8910374 -0.1198196 0.9286778 -0.3183795 -0.1902421 0.7834883 -0.6122645 -0.1061995 0.3690229 -0.9268728 -0.06876713 0.3002086 -0.9526322 -0.04864877 0.7875718 -0.6058192 -0.1127563 0.6309569 -0.7725287 -0.07136601 0.8671231 -0.4932677 -0.06917065 0.00334227 -0.9999905 0.002810597 0.003449678 -0.9999853 0.004183948 0.00694704 -0.9999054 0.0118708 0.006447732 -0.9998946 0.0130077 0.005008518 -0.9999842 0.002577543 0.009314775 -0.9999502 0.003608405 0.006204962 -0.9999 0.01271468 0.003536581 -0.9999306 0.01123976 0.008286416 -0.9999628 0.002391338 0.001852393 -0.999954 0.009413421 0.008872389 -0.9999595 0.001580119 0.006611645 -0.999978 5.27048e-4 6.24482e-4 -0.999942 0.01076507 -3.96686e-4 -0.9999822 0.005967378 0.006067454 -0.9999812 -9.49753e-4 0.005601525 -0.9999841 -6.89823e-4 -0.001934885 -0.9999846 0.005193471 -0.001981973 -0.9999828 0.005519688 0.005631923 -0.9999806 -0.002711236 0.01143628 -0.9999024 -0.008024573 -0.002450227 -0.9999902 0.003699362 0.009242832 -0.9999312 -0.007230043 -0.005944848 -0.9999712 0.004733383 -0.006073951 -0.9999647 0.005819022 0.008977651 -0.9998732 -0.01315486 0.004055678 -0.9999451 -0.009667932 -0.01132607 -0.9999194 0.005759894 -0.006666302 -0.9999689 0.004237592 0.00720185 -0.999858 -0.01523822 0.001776993 -0.9999839 -0.005411982 -0.008416116 -0.999957 0.003914594 5.13456e-4 -0.9999917 -0.004052281 -0.004765093 -0.9999885 5.85497e-4 -0.005691468 -0.9999838 1.8415e-4 -0.001609563 -0.9998666 -0.01625907 -0.002830922 -0.9999737 -0.006678879 -0.004607975 -0.999989 -9.06379e-4 -0.003855347 -0.9999266 -0.01149684 -0.009428322 -0.9999446 -0.004701614 -0.009747743 -0.999942 -0.004610419 -0.004702925 -0.9999171 -0.01199573 -0.004773795 -0.9999631 -0.007145941 -0.005459606 -0.9999589 -0.007241189 -0.009245216 -0.9999506 -0.003659725 -0.004534065 -0.9999812 -0.004131257 0.9611887 0.2452159 -0.1264336 0.9231177 0.3717956 -0.09809112 0.7417948 0.6646535 -0.08930939 0.7801321 0.6202222 -0.08196491 0.5558748 0.8278002 -0.07583028 0.8773684 0.4194189 -0.2330507 0.504285 0.8547692 -0.1227445 0.485411 0.867654 -0.1074838 0.8771569 0.4194683 -0.2337568 0.8395951 0.4864207 -0.2418161 0.7954378 0.5313314 -0.2914887 0.7013874 0.6514472 -0.289262 0.8893356 0.2236707 -0.3988156 0.4925633 0.8511336 -0.1815302 0.764576 0.5026233 -0.4034767 0.6991772 0.6204923 -0.355163 0.305662 0.9399152 -0.1520857 0.5554611 0.7649347 -0.3260951 0.7848975 0.3753527 -0.4929972 0.4052451 0.8807444 -0.2450832 0.7480162 0.4089702 -0.5227 0.7051571 0.4870033 -0.5153459 0.3460245 0.9037989 -0.2518224 0.6398795 0.5418204 -0.5449634 0.1949864 0.9658405 -0.1706825 0.6318612 0.5530943 -0.54299 0.5176692 0.7195348 -0.462913 0.5986875 0.4496916 -0.6628354 0.4052293 0.810355 -0.4232187 0.2708531 0.9220123 -0.2766442 0.5523769 0.5103992 -0.6590694 0.4304004 0.7333706 -0.5262349 0.5556761 0.3794158 -0.7397756 0.3753335 0.7753455 -0.5079017 0.4815016 0.3990383 -0.7803363 0.4818075 0.3870547 -0.7861617 0.2147859 0.9263175 -0.3095204 0.3867167 0.6657512 -0.6381423 0.4211753 0.310762 -0.8520789 0.1292968 0.9652351 -0.2271646 0.2443181 0.8039832 -0.5421438 0.3187271 0.507244 -0.8006975 0.2460587 0.8316973 -0.4977297 0.3002017 0.4808131 -0.8238312 0.1796864 0.8296536 -0.5285715 0.2492694 0.5309992 -0.8098794 0.196959 0.6957582 -0.6907442 0.01328104 0.9993207 -0.03437691 0.2170043 0.3976639 -0.8915002 0.1200128 0.7424046 -0.6591148 0.1217535 0.3743339 -0.9192662 0.1296854 0.4565675 -0.8801862 0.1026057 0.6284527 -0.7710508 0.04746997 0.9562888 -0.2885451 0.05949211 0.9440209 -0.324477 0.03790473 0.7112582 -0.7019082 0.006386756 0.2655843 -0.9640666 0.02430927 0.9243292 -0.3808212 -0.03242367 0.4128045 -0.9102424 -0.01456385 0.6405634 -0.7677673 -0.07790571 0.3508003 -0.9332041 -0.004572093 0.9475217 -0.319659 -0.08057862 0.8116573 -0.5785496 -0.1437243 0.4827641 -0.8638763 -0.1180877 0.6979335 -0.7063598 -0.06023782 0.8213889 -0.5671787 -0.1878309 0.3802603 -0.9056056 -0.2514924 0.3846141 -0.8881575 -0.09873896 0.9189575 -0.3817956 -0.2615828 0.5076813 -0.8208741 -0.196141 0.7053287 -0.681205 -0.1664276 0.8473657 -0.5042551 -0.3702543 0.4103818 -0.8333659 -0.3392145 0.499259 -0.7972918 -0.306947 0.6742751 -0.6716672 -0.2011998 0.8398428 -0.5041655 -0.49759 0.2994807 -0.8140735 -0.1657699 0.9397006 -0.2991377 -0.3554432 0.7209551 -0.5948815 -0.4975125 0.4381653 -0.7486605 -0.1941664 0.9245006 -0.3280214 -0.4265772 0.6378945 -0.6411884 -0.407727 0.7573391 -0.5100944 -0.6119064 0.2640589 -0.7455492 -0.2616831 0.9087716 -0.325048 -0.6123179 0.4603706 -0.6427487 -0.2339028 0.9331568 -0.2729613 -0.5499567 0.5982502 -0.5827902 -0.6838829 0.330877 -0.6502497 -0.7304784 0.3357508 -0.594704 -0.4876397 0.7767136 -0.3986523 -0.3352056 0.9012303 -0.2746291 -0.6495458 0.6010704 -0.465623 -0.2544062 0.95017 -0.1801515 -0.7513864 0.5033752 -0.426652 -0.6934724 0.5883637 -0.4158416 -0.4653679 0.8504471 -0.2453007 -0.7483602 0.5068113 -0.4279011 -0.8793228 0.2557273 -0.4017399 -0.7809818 0.5541593 -0.2880539 -0.4625725 0.8670777 -0.1849411 -0.7706938 0.5765799 -0.2712689 -0.8266242 0.5072345 -0.2437328 -0.3291398 0.9386904 -0.1026037 -0.8347645 0.5086187 -0.2108914 -0.05766814 0.9982417 -0.01371043 -0.4795768 0.8717436 -0.1003462 -0.7863574 0.5984097 -0.1534537 -0.9081119 0.4091155 -0.08920389 -0.8043577 0.5825639 -0.1167398 -0.538225 0.8427308 -0.01090079 -0.9170246 0.3986852 -0.01078355 -0.5591781 0.8286339 -0.02618974 -0.8440172 0.5354046 0.03125542 -0.4474528 0.8942897 -0.005664944 -0.852097 0.5186103 0.07052671 -0.390832 0.9193065 0.04610806 -0.7821913 0.6113139 0.1202994 -0.6083543 0.7860555 0.1096439 -0.8842539 0.4212118 0.2016823 -0.2018914 0.9785959 0.03987592 -0.8578677 0.4350389 0.2735037 -0.78765 0.5491661 0.2793281 -0.5847125 0.7901138 0.1839338 -0.4336258 0.8871008 0.1581804 -0.02772986 0.9995706 0.009475231 -0.7643108 0.551805 0.333677 -0.8266388 0.3747701 0.4197806 -0.4008266 0.9004011 0.1691626 -0.2108727 0.9719616 0.1040354 -0.5777539 0.7601469 0.2972831 -0.7846384 0.3247737 0.5280764 -0.7475753 0.4668241 0.4724473 -0.6407116 0.6436153 0.4186264 -0.5780155 0.7325987 0.3594401 -0.3253028 0.9145558 0.2403457 -0.7037555 0.3347125 0.6266544 -0.7007765 0.3544406 0.6190996 -0.3002682 0.9236093 0.2382962 -0.5774509 0.6417618 0.5046705 -0.5782979 0.6398607 0.5061126 -0.354403 0.8817422 0.311335 -0.06533557 0.9957231 0.06531959 -0.6231441 0.3403633 0.7041621 -0.4970093 0.6174972 0.6096549 -0.480165 0.6742336 0.5611156 -0.2989196 0.8928472 0.3368547 -0.2316393 0.9307064 0.2830708 -0.5025153 0.3554215 0.7881333 -0.4518061 0.6234049 0.6381518 -0.4088997 0.6819123 0.6064625 -0.2498423 0.8878656 0.3863593 -0.404223 0.2962066 0.8653702 -0.4122754 0.3782698 0.828819 -0.1903409 0.9147472 0.3563817 -0.3427361 0.6608956 0.6676444 -0.2823534 0.7498335 0.5983531 -0.346055 0.378047 0.8586772 -0.09458035 0.9715728 0.2170274 -0.2288129 0.6963868 0.6802133 -0.2368921 0.690218 0.683726 -0.2652288 0.2653374 0.9269573 -0.1165866 0.9010068 0.4178449 -0.1956381 0.5556008 0.808105 -0.1665076 0.5788985 0.7982178 -0.08545577 0.899048 0.4294301 -0.1321354 0.5124427 0.8484944 -0.04389989 0.9328518 0.3575756 -0.02706342 0.4551037 0.8900271 -0.06613188 0.5468178 0.8346359 -0.02012592 0.8891966 0.4570825 0.05547165 0.3934891 0.9176543 0.02622908 0.4699587 0.8822987 0.0462535 0.8056505 0.5905826 0.01932001 0.8796434 0.4752413 0.1445596 0.3490122 0.9259012 0.1343468 0.3832039 0.9138413 0.1335362 0.7235214 0.6772628 0.1407866 0.7325478 0.6659978 0.2789965 0.3508766 0.893894 0.260049 0.4071419 0.8755628 0.09804648 0.9320523 0.3488059 0.2158925 0.6309658 0.7451663 0.03690421 0.9807308 0.1918471 0.2542051 0.7329919 0.6309537 0.3750834 0.3312523 0.8657855 0.3676894 0.3515583 0.8609363 0.2940179 0.6826877 0.6689477 0.1457115 0.9093872 0.3895937 0.4795868 0.3516787 0.8039394 0.4792481 0.3715501 0.7951552 0.1207547 0.9714289 0.2043145 0.3618307 0.7028321 0.6124588 0.3548693 0.7336596 0.5794923 0.1172084 0.9735655 0.1960422 0.5647357 0.3678228 0.7387692 0.5640491 0.3799777 0.7331205 0.4561851 0.6701647 0.5854695 0.444499 0.7370545 0.5090889 0.6683934 0.341905 0.6605688 0.6643279 0.3807063 0.6432194 0.2842965 0.9093423 0.3037636 0.5772998 0.594224 0.5600205 0.7463842 0.3012799 0.5934149 0.254482 0.9393782 0.2297989 0.5519914 0.7049126 0.4454256 0.7282132 0.4288123 0.5346266 0.350895 0.8952547 0.274576 0.6590231 0.5819548 0.4764633 0.8256469 0.2901613 0.4838528 0.8145193 0.3571383 0.4571767 0.3645579 0.9009324 0.2354114 0.6563264 0.6416574 0.3968774 0.5717682 0.7566174 0.317193 0.8403669 0.3543622 0.4101354 0.7849791 0.5239872 0.3305228 0.6030895 0.7477283 0.2778229 0.1835727 0.9785037 0.09397655 0.4862386 0.8550449 0.1801956 0.8352602 0.4643804 0.2944337 0.8240106 0.5076871 0.2515165 0.610211 0.7757756 0.1606703 0.5142027 0.8436362 0.1545112 0.906539 0.3663781 0.2096527 0.882488 0.4440655 0.1549863 0.6475111 0.7492066 0.1393521 0.9002937 0.4158715 0.128539 0.9453344 0.3261017 7.91152e-4 0.8129708 0.5807437 0.04260593 0.8196066 0.5716775 0.03781718 0.1461513 0.9891566 0.01446622 0.5819495 0.8117398 0.0491259 0.3637752 0.9314444 0.008900761 -0.004917562 0.9999743 0.005229949 -0.004589319 0.9999784 0.004712224 -0.004158616 0.9999874 0.002804815 -0.002236843 0.9999823 0.005524337 -0.003864645 0.9999637 0.007594168 -0.005745351 0.9999803 0.002550959 -0.001616775 0.9999986 5.67434e-4 -0.001279056 0.9999781 0.006513237 -9.00024e-4 0.9999996 8.55541e-5 -0.001747131 0.9999856 0.005081474 2.51061e-4 0.9999939 0.003500878 -0.001237332 0.9999993 -2.70845e-4 -0.01040041 0.9999377 -0.004087567 0.001456677 0.9999834 0.005586743 0.001833975 0.9999888 0.004378676 -0.009063839 0.999949 -0.004455745 0.002196133 0.9999866 0.004709959 -0.01037979 0.9999211 -0.007086932 0.001915991 0.999996 0.002094566 -0.006959736 0.9999536 -0.006652772 -0.007001578 0.9999517 -0.00691092 0.007505536 0.999965 0.003732562 -0.004176795 0.9999653 -0.007219374 0.007455468 0.9999628 0.004352629 -0.005669534 0.9998201 -0.01810765 0.01058244 0.9999328 0.004734814 -0.007574796 0.9998207 -0.01735454 -0.002088129 0.9999451 -0.01028341 0.01006883 0.9999462 0.002530157 0.01857584 0.9998275 4.15372e-4 0.01191455 0.9999283 0.001217663 -0.003597557 0.9999588 -0.00833863 3.05754e-4 0.9999943 -0.003378868 0.009993135 0.9999487 -0.001724064 0.001642107 0.9999867 -0.004890263 0.01390719 0.9998866 -0.00579667 0.002086162 0.9999814 -0.005758166 0.01413732 0.9998846 -0.005562365 0.01396244 0.9998883 -0.005340754 0.001302421 0.9999975 -0.001841783 0.01130336 0.9999179 -0.006044328 0.002547562 0.9999951 -0.001868844 0.9963712 -0.01380741 -0.08398777 0.9965028 -0.04317331 -0.07154142 0.9729807 0.07846474 -0.2171445 0.9376326 -0.06148898 -0.3421465 0.9478188 6.05061e-4 -0.3188093 0.8982958 0.03865504 -0.4376876 0.8663091 0.03098303 -0.4985465 0.8337746 -0.05334138 -0.5495222 0.8123009 0.01697856 -0.5829915 0.7470079 0.06865841 -0.6612603 0.6729211 -0.0124554 -0.7396094 0.6601528 -0.05221426 -0.7493143 0.5651821 0.04941433 -0.823485 0.491339 -0.01069533 -0.8709027 0.4766178 0.01482838 -0.8789855 0.3404427 0.005103766 -0.9402514 0.3527626 -0.02469003 -0.9353871 0.2481043 0.04169547 -0.9678357 0.1559252 -0.03441333 -0.9871693 0.1422637 -0.006997108 -0.9898041 0.04828363 0.04038155 -0.9980171 -0.04276496 -0.03173637 -0.998581 -0.05924957 6.91105e-5 -0.9982433 -0.1435896 0.0452553 -0.9886021 -0.2398076 -0.02842158 -0.9704044 -0.2462917 -0.01568424 -0.969069 -0.3460491 0.03950393 -0.9373844 -0.4345843 -0.03515535 -0.8999449 -0.4311136 -0.04333549 -0.9012565 -0.5245131 0.05177581 -0.8498268 -0.6026433 0.009718 -0.7979515 -0.6298476 -0.05318152 -0.774896 -0.6833457 0.03701913 -0.7291559 -0.7820282 -0.03467243 -0.6222779 -0.7543937 0.02478319 -0.6559543 -0.8154085 0.04364532 -0.5772384 -0.838591 0.05523598 -0.5419541 -0.9023141 -0.01164579 -0.4309218 -0.9011478 -0.006692349 -0.4334605 -0.929769 0.03565955 -0.3664124 -0.9701033 -0.05828893 -0.2355885 -0.9628021 -0.00271213 -0.2701943 -0.9838163 0.05360561 -0.1709734 -0.9932824 0.08268916 -0.08094847 -0.9996722 -0.0155189 0.02036386 -0.9961736 -0.07512205 0.04466646 -0.9916242 0.02867347 0.1259337 -0.9719182 0.01719909 0.2346897 -0.9622153 -0.01579791 0.2718315 -0.9643084 -0.03267437 0.2627582 -0.9275785 0.06110692 0.3685975 -0.8691251 -0.03781789 0.4931443 -0.8659815 -0.01906746 0.4997125 -0.7792365 0.06484603 0.6233662 -0.7259127 -0.04654443 0.6862102 -0.7129126 -0.01649945 0.7010589 -0.63572 0.04281115 0.7707318 -0.5756211 -0.013206 0.8176099 -0.5691108 -0.001385152 0.8222597 -0.4301552 -0.03537994 0.9020614 -0.4697803 0.0250855 0.882427 -0.3396117 0.06405675 0.938382 -0.2440499 -0.04020035 0.9689292 -0.1985636 0.03339505 0.9795189 -0.05462253 -0.03681886 0.9978281 -0.1066217 0.03001153 0.9938467 0.005590915 0.0403378 0.9991706 0.1360368 -0.01140844 0.9906381 0.1381213 -0.007176578 0.9903894 0.2538831 0.03676468 0.9665361 0.3070307 -0.03871119 0.9509121 0.3850886 0.05079096 0.9214809 0.489529 -0.03327488 0.871352 0.4806176 -0.0089069 0.8768852 0.5964554 0.05209726 0.8009538 0.6715439 -0.04007238 0.7398805 0.6785202 -0.02188915 0.7342557 0.7479596 0.04714667 0.6620677 0.8157612 -0.01795613 0.5781102 0.8134266 -0.008045613 0.581612 0.8869042 0.0322777 0.4608244 0.9146879 -0.05721437 0.4000907 0.9316745 0.0187934 0.3628078 0.9608959 0.08003532 0.2650914 0.987325 -0.0573455 0.1479901 0.9917542 -0.01134282 0.1276518 0.9984655 0.05079597 0.02205884 0.9974256 0.003403365 -0.07162863 0.9937767 0.05175733 -0.09863603 0.9815577 -0.06415736 -0.1800787 0.9624657 -0.07316768 -0.2613549 0.9366675 0.02572011 -0.3492745 0.9332541 0.04556363 -0.3563154 0.886663 -0.04815638 -0.4599018 0.8544803 -0.01434844 -0.5192857 0.8354652 0.04130035 -0.5479893 0.7848439 -0.04642659 -0.617952 0.7074776 0.02473998 -0.7063027 0.6978504 0.05275994 -0.7142978 0.6015115 -0.08234095 -0.7946093 0.5242508 -0.03667849 -0.8507737 0.4776691 0.07181435 -0.8755999 0.4063625 -0.04297035 -0.9127011 0.3416728 -0.06035751 -0.9378789 0.2625721 0.002714455 -0.9649087 0.2476161 0.03662431 -0.9681658 0.1452901 -0.04626202 -0.988307 0.06218552 -0.003855168 -0.9980572 0.02568024 0.06785577 -0.9973646 -0.06207197 -0.06500649 -0.9959525 -0.1850197 -0.03782939 -0.9820065 -0.2372758 0.06354105 -0.9693621 -0.3017237 -0.03246718 -0.9528424 -0.4219774 -0.008029222 -0.9065709 -0.4323533 0.0142073 -0.9015924 -0.5266588 -0.03234004 -0.8494615 -0.5752522 0.03829538 -0.8170793 -0.6344773 -0.04806268 -0.7714459 -0.7213625 0.02160757 -0.6922206 -0.7261728 0.03810483 -0.6864554 -0.8023483 -0.05783432 -0.5940476 -0.8542319 -0.00618577 -0.5198555 -0.8608492 0.02467501 -0.5082617 -0.9118552 -0.030245 -0.4093967 -0.9495639 -0.03358322 -0.3117699 -0.9359514 0.02549141 -0.3512056 -0.9852346 0.009321391 -0.170956 -0.9858826 0.01598846 -0.166673 -0.9948641 -0.05391168 -0.08566915 -0.9998604 -0.005084037 0.01591575 -0.9982941 0.04204726 0.04050898 -0.9889326 -0.05976599 0.1357955 -0.9646505 0.02457511 0.2623845 -0.9649837 0.02214646 0.2613736 -0.9306824 -0.03068894 0.3645389 -0.904913 0.02640622 0.4247767 -0.8869115 -0.03194415 0.4608338 -0.8453835 -0.04169297 0.5325304 -0.8125219 0.03117597 0.5820964 -0.7732045 -0.04094743 0.6328335 -0.6769617 -0.03721171 0.735077 -0.7007303 0.02359229 0.7130362 -0.5903224 -0.0428642 0.8060287 -0.5317132 0.05966663 0.8448202 -0.4796712 -0.03307884 0.8768246 -0.3957979 -0.03022694 0.9178401 -0.3461876 0.0465539 0.9370096 -0.2897276 -0.03563064 0.9564458 -0.1914252 -0.03713011 0.9808047 -0.1442215 0.01768207 0.9893875 -0.1024327 -0.03714358 0.9940463 0.04725801 -8.78353e-4 0.9988824 0.05465489 0.01269584 0.9984247 0.1440643 -0.04076671 0.9887284 0.2461948 0.04566848 0.9681439 0.2498009 0.03726583 0.96758 0.3422405 -0.05283707 0.9381257 0.4323551 -0.01140731 0.9016314 0.5259471 -0.0262537 0.8501121 0.4724399 0.07554996 0.878119 0.6062102 -0.05438917 0.7934426 0.6861055 0.05558472 0.7253755 0.6759009 0.01430571 0.7368538 0.7760215 -0.03191572 0.6298986 0.8096056 0.04454672 0.5852816 0.8421691 -0.03390383 0.5381466 0.8899553 -0.03380042 0.4547936 0.9184902 0.06234318 0.3904986 0.9308252 0.006864666 0.3654001 0.9602306 -0.06888335 0.2705776 0.9834775 -0.02565139 0.179204 0.9974468 -0.03319114 0.06323093 0.9889054 0.06563878 0.1332584 0.5384187 -0.8424409 0.01996642 0.9375338 -0.3426522 0.06016713 0.1927099 -0.9812546 -0.00149393 0.9045439 -0.4160763 0.09317135 0.650472 -0.7545566 0.08677929 0.9411419 -0.2974495 0.1605492 0.8498075 -0.4814282 0.2146025 0.6978377 -0.6961396 0.1685594 0.6188103 -0.776997 0.1155406 0.4375236 -0.8940204 0.09643965 0.8886381 -0.3753492 0.2635059 0.5833576 -0.7857441 0.2056696 0.3533482 -0.9294794 0.1058917 0.8548538 -0.4043223 0.3251898 0.8316242 -0.4475853 0.328738 0.6173965 -0.748521 0.241946 0.8159964 -0.4049354 0.4125257 0.7735206 -0.4772629 0.4169965 0.1366508 -0.9889183 0.05802875 0.5471621 -0.7937861 0.2655515 0.4613388 -0.8527503 0.2449159 0.3001173 -0.9404765 0.159479 0.7728 -0.3732338 0.5132997 0.7462791 -0.4800719 0.4610841 0.539168 -0.7608246 0.3611702 0.7218711 -0.375796 0.5811019 0.7379503 -0.3399316 0.5829889 0.5416411 -0.7131165 0.4450728 0.4822249 -0.7918731 0.3746951 0.3953179 -0.8623675 0.3163008 0.6418074 -0.4353643 0.6313012 0.5632403 -0.6072561 0.5603576 0.6583706 -0.2943841 0.6927382 0.2334978 -0.9460184 0.2247841 0.1193844 -0.9846604 0.1272449 0.4416356 -0.7378571 0.5104166 0.5630617 -0.3731009 0.7373991 0.5361179 -0.4363353 0.7226265 0.431315 -0.71372 0.5518798 0.2877525 -0.8452368 0.4503037 0.4855201 -0.3471374 0.8023503 0.2852925 -0.8451725 0.4519864 0.4591532 -0.38873 0.7987912 0.3807554 -0.6020596 0.7018188 0.4233857 -0.262233 0.8671669 0.1943141 -0.9087842 0.3692607 0.3433684 -0.428174 0.8359218 0.3087471 -0.6043717 0.7344455 0.3197163 -0.2917197 0.9014883 0.2096462 -0.7853779 0.5824347 0.1836521 -0.8525644 0.4892913 0.2592121 -0.3443931 0.9023317 0.2351989 -0.2940115 0.9264119 0.1930497 -0.728516 0.6572642 0.1866734 -0.3630793 0.9128671 0.05993521 -0.9694526 0.2378433 0.1386167 -0.7300167 0.6692243 0.1596263 -0.3220316 0.9331747 0.1111478 -0.7673425 0.6315314 0.07023996 -0.8743866 0.4801192 0.06941562 -0.5232845 0.8493261 0.02879875 -0.4597669 0.8875726 0.03855258 -0.5071321 0.8610058 0.005303859 -0.9994547 0.03259164 0.01338994 -0.7404143 0.6720174 0.03449141 -0.893727 0.4472834 0.004008591 -0.9476419 0.3193101 -0.06734472 -0.4145903 0.9075129 -0.05181825 -0.819279 0.571049 -0.03700083 -0.907531 0.4183523 -0.1098352 -0.6478903 0.7537735 -0.1902782 -0.5060349 0.8412626 -0.1248238 -0.6432657 0.7553994 -0.05645579 -0.9518875 0.3012029 -0.1332296 -0.8535901 0.5036208 -0.2873288 -0.3868578 0.8762325 -0.1078477 -0.9066432 0.4078814 -0.2479289 -0.5060018 0.8261316 -0.2259009 -0.6953952 0.6821982 -0.3609576 -0.3275727 0.8731585 -0.1138435 -0.9498346 0.291297 -0.3756549 -0.4958684 0.7829418 -0.2841825 -0.7329263 0.6181095 -0.2592313 -0.814525 0.5189878 -0.4561303 -0.3906289 0.7995963 -0.266015 -0.8152494 0.5143973 -0.4667039 -0.4348163 0.7701444 -0.3691931 -0.7216467 0.5855959 -0.5395419 -0.334657 0.7725927 -0.382068 -0.7776148 0.4993388 -0.2383216 -0.9239385 0.2992334 -0.1670719 -0.9594799 0.226904 -0.5348432 -0.5610145 0.6318271 -0.4781463 -0.6681715 0.5700203 -0.6323192 -0.3773934 0.6765699 -0.6676324 -0.4703442 0.5770992 -0.4410974 -0.8040835 0.3986013 -0.7434968 -0.3001056 0.5976195 -0.2888327 -0.9220896 0.2575393 -0.2720464 -0.9327518 0.2365689 -0.56712 -0.6753138 0.4715148 -0.7659659 -0.386469 0.513749 -0.7102994 -0.5395507 0.4520617 -0.6118746 -0.6729401 0.4156454 -0.4160071 -0.8728458 0.2551048 -0.4140222 -0.8748825 0.2513292 -0.8294466 -0.382525 0.4070544 -0.7373533 -0.5560898 0.3835026 -0.657615 -0.6833208 0.3171991 -0.1800337 -0.9801815 0.08265668 -0.8992898 -0.2699623 0.3440906 -0.6459981 -0.7172628 0.261191 -0.8724359 -0.3896221 0.2950426 -0.7442183 -0.616472 0.2571021 -0.9205427 -0.2972375 0.253478 -0.384548 -0.9141925 0.1279646 -0.4081957 -0.9057844 0.1137151 -0.8849164 -0.4209513 0.1993067 -0.7518324 -0.638711 0.1636961 -0.7102587 -0.6824004 0.1728069 -0.9633229 -0.2318525 0.135105 -0.7153428 -0.6917074 0.09912407 -0.424112 -0.9048284 0.03760981 -0.8775508 -0.4755824 0.06104189 -0.3062064 -0.9507247 0.04858291 -0.8871614 -0.4599902 0.03679329 -0.4237173 -0.9056991 0.01314324 -0.3562011 -0.9343909 -0.005878448 -0.8104053 -0.5852409 -0.02714031 -0.8222861 -0.5659613 -0.05944234 -0.7878002 -0.6102876 -0.08318626 -0.4956834 -0.8654024 -0.07332772 -0.8889005 -0.4124735 -0.1993024 -0.8285927 -0.5317302 -0.1752068 -0.6968169 -0.6945663 -0.1789525 -0.4851022 -0.8708397 -0.07946234 -0.9239239 -0.2423417 -0.2960328 -0.63873 -0.7361838 -0.2237355 -0.2793947 -0.9546031 -0.1033042 -0.8058736 -0.4951048 -0.3247137 -0.1936849 -0.9791559 -0.06115525 -0.7109604 -0.6429906 -0.284778 -0.8690915 -0.2833853 -0.4054292 -0.8306115 -0.2931489 -0.473443 -0.5829412 -0.7434314 -0.3278557 -0.3853684 -0.8943426 -0.2272499 -0.6843402 -0.5857141 -0.4343013 -0.7057061 -0.4412765 -0.554305 -0.2742537 -0.9421797 -0.192568 -0.6596106 -0.5712001 -0.4885125 -0.4272055 -0.8255966 -0.3686272 -0.6761649 -0.3428536 -0.6521138 -0.4163221 -0.8220484 -0.3884745 -0.6121735 -0.4557047 -0.6462019 -0.5358163 -0.6187255 -0.5745256 -0.03752416 -0.9987378 -0.03338956 -0.6119427 -0.2695826 -0.7435398 -0.2377527 -0.9306104 -0.2782768 -0.4085701 -0.7360229 -0.53976 -0.3785423 -0.7711924 -0.5118281 -0.2547439 -0.9123699 -0.3204478 -0.5175318 -0.4278956 -0.7409901 -0.4788022 -0.4096421 -0.7764934 -0.4793575 -0.3784567 -0.7918251 -0.3426268 -0.7543125 -0.5600175 -0.2705598 -0.824923 -0.4962857 -0.4006667 -0.3636376 -0.8409721 -0.1671717 -0.9438364 -0.2850029 -0.2553941 -0.7937157 -0.5520772 -0.3630264 -0.4496464 -0.8161066 -0.06949836 -0.9872517 -0.1431924 -0.1893067 -0.8449941 -0.5001479 -0.2612909 -0.4654358 -0.8456339 -0.260714 -0.4523684 -0.8528723 -0.1780092 -0.7800313 -0.5998867 -0.1282432 -0.8221855 -0.5545852 -0.1848807 -0.3625453 -0.9134441 -0.09188616 -0.8080405 -0.5819171 -0.08476138 -0.5933551 -0.8004657 -0.01478123 -0.9917497 -0.1273342 -0.0808553 -0.6318296 -0.7708786 -0.04169404 -0.3388976 -0.939899 -0.01834392 -0.954383 -0.298021 0.008073568 -0.7866048 -0.6174042 0.03135174 -0.3411529 -0.939485 -0.002157628 -0.9299032 -0.3677979 0.08056026 -0.5718699 -0.8163791 0.05647456 -0.7159292 -0.695885 0.153022 -0.4115701 -0.89844 0.11815 -0.518141 -0.8470954 0.07306659 -0.859691 -0.5055618 0.03917169 -0.9425682 -0.3317091 0.2141959 -0.3836508 -0.8982942 0.03146624 -0.9910655 -0.1296115 0.1373141 -0.830052 -0.5405172 0.1552705 -0.7939689 -0.5877963 0.2443099 -0.5915976 -0.7683261 0.2024654 -0.7275756 -0.6554706 0.08817261 -0.956647 -0.2775829 0.2907482 -0.5202095 -0.8030241 0.3627428 -0.5327835 -0.7645649 0.364812 -0.5560329 -0.7468197 0.2391007 -0.8284397 -0.5064765 0.2294108 -0.8479804 -0.4778075 0.4327319 -0.500597 -0.7497639 0.2255439 -0.8897575 -0.3968144 0.1176683 -0.9784141 -0.1698822 0.4304103 -0.6678241 -0.6072546 0.5730872 -0.4060008 -0.7118529 0.4377762 -0.664649 -0.60547 0.4016709 -0.7793318 -0.4809393 0.3023328 -0.8899475 -0.3414506 0.6540424 -0.3917934 -0.6470909 0.654903 -0.3846775 -0.6504809 0.5650797 -0.6132568 -0.5519067 0.5103884 -0.7468478 -0.4262889 0.324691 -0.8958409 -0.303389 0.7348342 -0.3434928 -0.5848345 0.7106147 -0.4587562 -0.5334506 0.5208454 -0.7398281 -0.425881 0.7490243 -0.4531193 -0.4833691 0.4513669 -0.8467617 -0.2815362 0.7258964 -0.5386406 -0.4277158 0.1609929 -0.9794906 -0.121159 0.4974427 -0.818846 -0.2864297 0.8328109 -0.3737516 -0.408333 0.4783451 -0.844972 -0.2391827 0.835771 -0.4264761 -0.3458397 0.7948209 -0.5234199 -0.307069 0.5833388 -0.7756454 -0.2410187 0.1801254 -0.9814414 -0.06578552 0.8079847 -0.5379638 -0.2403245 0.7513465 -0.6310675 -0.1929569 0.524606 -0.8358195 -0.1618472 0.3657918 -0.9254899 -0.098311 0.8853812 -0.444318 -0.1366815 0.7604578 -0.6337009 -0.14187 0.6730264 -0.7325984 -0.1016623 0.4016796 -0.9127953 -0.07388037 0.9355267 -0.3491104 -0.05396169 0.8848831 -0.4654688 -0.01790755 0.7158244 -0.6978138 -0.02552294 0.1929721 -0.9812033 -0.001445412 0.005943953 -0.9999618 0.006406545 0.00495404 -0.9999789 0.004215538 0.004190623 -0.9999766 0.005400002 0.00597155 -0.9999771 0.00323081 0.00329107 -0.9999681 0.007286965 0.006516993 -0.9999734 0.003281235 0.002592444 -0.999973 0.006888806 0.004124224 -0.9999907 0.001377403 0.002032935 -0.9999424 0.01054751 0.004003107 -0.9999919 4.78291e-4 6.87006e-4 -0.9999785 0.006539106 0.004971325 -0.9999877 1.48593e-4 0.003319025 -0.9999945 -2.94331e-4 -7.96546e-4 -0.9999864 0.005174756 -0.001695036 -0.9999762 0.006692111 0.003261327 -0.9999941 -0.001156449 0.01380139 -0.9998693 -0.008422136 -0.006826162 -0.9999588 0.005990564 -0.0067932 -0.9998787 0.01402205 -0.007218778 -0.999874 0.01413881 0.008852362 -0.9999567 -0.002874076 0.0130214 -0.9998732 -0.009176015 -0.005737483 -0.9999648 0.00613892 -0.009356737 -0.99993 0.007258653 0.00334376 -0.9999875 -0.003729939 0.003607332 -0.99997 -0.00686264 0.004150092 -0.999965 -0.007272958 -0.004680871 -0.9999858 0.002549946 -0.009328246 -0.9999377 0.006144642 -0.00373739 -0.9999927 8.46688e-4 0.00228095 -0.9999395 -0.01076453 -0.004696071 -0.9999889 6.31572e-4 0.002130389 -0.9999862 -0.004805266 -5.96772e-5 -0.9999927 -0.003837406 -0.004400372 -0.9999903 -2.94021e-4 -0.01191794 -0.9999241 -0.003122746 -0.004921495 -0.9998912 -0.01391094 -0.004117608 -0.9998596 -0.01624715 -0.004308462 -0.9999895 -0.001613378 -0.01110166 -0.9999364 -0.001996159 -0.002818822 -0.9999802 -0.00565195 -0.004823088 -0.9998518 -0.01652514 -0.003864109 -0.9999887 -0.002756237 -0.003683507 -0.9999838 -0.00433886 -0.0060817 -0.9999659 -0.005603492 0.7706269 0.6372677 0.004919409 0.4898633 0.8712279 -0.03155946 0.3406431 0.9401757 -0.005665779 0.8957527 0.4360778 -0.08639025 0.5120527 0.8566351 -0.06307476 0.8389284 0.5266022 -0.1374385 0.8597115 0.4758012 -0.1857675 0.4205504 0.9027741 -0.09020119 0.7913858 0.5679649 -0.2261072 0.7059161 0.6770287 -0.2081219 0.8673623 0.3877359 -0.3119996 0.3114858 0.946693 -0.08215385 0.4785637 0.8554024 -0.1981509 0.8292675 0.4222704 -0.3660646 0.3754575 0.9150133 -0.1475887 0.7619965 0.5301969 -0.3718235 0.5419146 0.7999577 -0.2576753 0.7686318 0.45447 -0.4501803 0.1222422 0.9902265 -0.06714361 0.702611 0.5369418 -0.4669381 0.5655666 0.7298684 -0.3839617 0.4573923 0.8413223 -0.2880434 0.7393876 0.3944507 -0.5456323 0.2993308 0.932154 -0.2036911 0.6876789 0.3962562 -0.608341 0.4570199 0.7915073 -0.4057698 0.2893712 0.9224502 -0.2556368 0.6426727 0.4723083 -0.6032386 0.5405803 0.657066 -0.5253925 0.644138 0.2845476 -0.7100133 0.2121867 0.9545813 -0.2091683 0.5471515 0.4765444 -0.6881357 0.4828485 0.6877622 -0.5420706 0.2782932 0.8924816 -0.3550062 0.5196015 0.4449566 -0.7294025 0.4746052 0.5132032 -0.715103 0.2489056 0.9023277 -0.3519245 0.2682465 0.8618023 -0.430512 0.4295948 0.3805568 -0.8189168 0.421171 0.4849562 -0.7664415 0.3098284 0.7230345 -0.6174364 0.251632 0.8591883 -0.4455075 0.142884 0.9397415 -0.3105963 0.3250052 0.3634805 -0.8730713 0.3093242 0.407446 -0.8592475 0.2494181 0.6981062 -0.6711472 0.1756148 0.81266 -0.5556466 0.1461156 0.876252 -0.4591653 0.2291473 0.3278105 -0.9165326 0.1932343 0.399545 -0.8961163 0.1477162 0.6873333 -0.7111631 0.145125 0.3120046 -0.9389312 0.05925369 0.9586301 -0.2784195 0.07734811 0.441064 -0.8941364 0.0589717 0.7051885 -0.7065631 0.0700286 0.7680247 -0.63658 0.05798733 0.8446944 -0.5320987 0.04019653 0.3260525 -0.9444968 0.005030632 0.9984834 -0.0548228 -0.03158152 0.381352 -0.9238903 -0.0123052 0.9522141 -0.3051832 -0.05587255 0.5303154 -0.8459573 -0.039213 0.6743317 -0.7373867 -0.0552932 0.8485053 -0.5262904 -0.149542 0.4099934 -0.8997458 -0.0385195 0.9064375 -0.4205797 -0.1658365 0.436715 -0.8841823 -0.2429721 0.2547296 -0.9359902 -0.1703721 0.6514754 -0.7392923 -0.1436592 0.7738975 -0.6168022 -0.2939558 0.3964281 -0.8697326 -0.1523718 0.854042 -0.4973883 -0.3099279 0.3956418 -0.8645302 -0.3121716 0.4073233 -0.8582755 -0.08361619 0.9620081 -0.2599014 -0.221141 0.7784327 -0.5874856 -0.06290733 0.9840015 -0.1666846 -0.4190807 0.3295357 -0.8460364 -0.3854239 0.4199041 -0.8216624 -0.2978014 0.7548128 -0.5844416 -0.2962264 0.772205 -0.5620938 -0.2139695 0.8976343 -0.3853179 -0.4952114 0.2891464 -0.8192436 -0.5022327 0.4541003 -0.7359043 -0.4247766 0.6555074 -0.6243997 -0.5731152 0.3209795 -0.7539967 -0.3973249 0.7508658 -0.5275734 -0.3461648 0.8287754 -0.4396607 -0.2164392 0.9307449 -0.2947338 -0.1358898 0.9759348 -0.1705442 -0.6195387 0.3839181 -0.6846742 -0.6094444 0.4426754 -0.6577355 -0.6066002 0.5279216 -0.59442 -0.4254495 0.8001287 -0.4228321 -0.6545333 0.4798356 -0.5842465 -0.3909151 0.8463726 -0.3617169 -0.647345 0.5797909 -0.4947597 -0.3998524 0.8496092 -0.343922 -0.6603031 0.5692322 -0.489872 -0.6553909 0.6342232 -0.4101509 -0.2875361 0.9383363 -0.1919584 -0.8062076 0.3815876 -0.4521285 -0.292039 0.9360984 -0.1960436 -0.6685124 0.6217293 -0.408098 -0.8390418 0.3232726 -0.4376114 -0.6256225 0.7448353 -0.2319849 -0.6757546 0.6721448 -0.3026172 -0.4120582 0.8921455 -0.1851604 -0.8280076 0.4887689 -0.2747876 -0.7697973 0.5790215 -0.2686007 -0.8841931 0.3931975 -0.252187 -0.2933439 0.9503175 -0.1041452 -0.5388306 0.8339738 -0.1189506 -0.890283 0.4212886 -0.1729512 -0.802488 0.5847917 -0.1184559 -0.546482 0.8301946 -0.1101567 -0.4173848 0.9070982 -0.05443418 -0.9102198 0.4107605 -0.05268502 -0.8446412 0.5313395 -0.06526726 -0.4412611 0.8972126 -0.01727718 -0.9545727 0.2965587 0.02905386 -0.6745243 0.7382345 0.005192458 -0.9059975 0.4168964 0.07325232 -0.265338 0.9640995 0.01038753 -0.7066137 0.7066063 0.03747814 -0.9306041 0.3477715 0.1141534 -0.528158 0.8447303 0.08648741 -0.9077008 0.3902782 0.1541504 -0.7754857 0.6042541 0.1830271 -0.5326113 0.8391997 0.1098591 -0.4679722 0.8765597 0.1124501 -0.8257766 0.5026901 0.2557259 -0.8312584 0.4372204 0.3432897 -0.7858684 0.5366755 0.3072302 -0.6607702 0.6985917 0.274504 -0.481801 0.8550262 0.191828 -0.4787213 0.8568872 0.191234 -0.8252118 0.3079759 0.4734725 -0.6970992 0.5531457 0.4561609 -0.1214517 0.9904324 0.06552314 -0.625151 0.6762752 0.3896642 -0.4075607 0.8772141 0.2537515 -0.3202638 0.9229397 0.2135733 -0.6961253 0.5457876 0.4663963 -0.761319 0.22878 0.6066738 -0.6486669 0.485665 0.58597 -0.5632103 0.6586404 0.4989859 -0.5565183 0.6671888 0.4951227 -0.3160374 0.9129248 0.2582415 -0.6585969 0.3092484 0.6860143 -0.2271527 0.9497495 0.2153546 -0.4656082 0.7314705 0.4981567 -0.3378332 0.8596162 0.383313 -0.6149872 0.3470842 0.708042 -0.547025 0.5043468 0.6681302 -0.03992199 0.9980776 0.04740852 -0.5083645 0.3744091 0.7754891 -0.489285 0.5302942 0.6923788 -0.428017 0.648017 0.6299805 -0.2794675 0.8819492 0.3795571 -0.199837 0.9319713 0.302481 -0.4513683 0.3206733 0.8327277 -0.3196547 0.7270575 0.6076251 -0.2032573 0.8978378 0.3906071 -0.4073443 0.4265472 0.8075446 -0.3413216 0.6145393 0.711225 -0.3272938 0.2813264 0.9020723 -0.3095316 0.3608934 0.8797421 -0.157873 0.9230539 0.3507815 -0.2819818 0.63082 0.7228779 -0.1862248 0.7953793 0.5767947 -0.2009854 0.4606545 0.8645244 -0.157193 0.7844689 0.5999159 -0.1582036 0.7980337 0.5814758 -0.191768 0.4248207 0.8847329 -0.04630076 0.9636492 0.2631288 -0.08027547 0.3767089 0.9228468 -0.1029412 0.519156 0.8484576 -0.0629878 0.7545648 0.6531957 -0.07481646 0.7312121 0.6780349 -0.03247445 0.8630851 0.5040134 0.004850983 0.3541455 0.9351778 0.03098362 0.4776969 0.8779782 7.14024e-4 0.8846196 0.466313 0.01372611 0.9093934 0.4157108 0.04837113 0.5129242 0.8570701 0.04678404 0.4983386 0.8657193 0.06162655 0.8658028 0.4965761 0.1366035 0.1617957 0.9773238 0.1059238 0.6820449 0.7235987 0.2278112 0.4538615 0.8614591 0.2278974 0.3190337 0.9199349 0.1807259 0.5970981 0.7815447 0.09374552 0.925813 0.3661726 0.1958789 0.7445922 0.6381332 0.3159101 0.4200903 0.8507204 0.2393988 0.7085854 0.6637733 0.3520115 0.3493362 0.8683618 0.0518189 0.9891692 0.1373287 0.2600069 0.7392784 0.6211795 0.3864631 0.5258794 0.757692 0.4632042 0.3664243 0.8069543 0.1775204 0.9214823 0.345481 0.3858249 0.5263208 0.7577108 0.2954813 0.8453917 0.4449762 0.5233102 0.4037827 0.7504041 0.562978 0.3141248 0.7644485 0.3898891 0.7652335 0.5122542 0.3205155 0.8381384 0.4413547 0.6236497 0.3913068 0.6767127 0.2218738 0.9391413 0.2622705 0.622523 0.3996044 0.6728904 0.5187672 0.6412497 0.5654021 0.6899331 0.3799065 0.6161683 0.6688027 0.4949226 0.5547564 0.5029785 0.7175258 0.4818395 0.3502275 0.8817714 0.3159433 0.6798197 0.4993484 0.5371187 0.6127318 0.6526067 0.4457179 0.03050303 0.9991542 0.02757918 0.7848716 0.2782214 0.5536872 0.3161379 0.9167584 0.2441537 0.2955923 0.9258449 0.2354497 0.6125041 0.7006977 0.365871 0.472716 0.8408145 0.2637622 0.808868 0.4110463 0.4204446 0.789533 0.4419559 0.4258084 0.8053107 0.4770066 0.3520503 0.4409437 0.8725645 0.2102379 0.448458 0.867144 0.2166721 0.8230872 0.4570252 0.3371284 0.1113083 0.9927775 0.04475933 0.806785 0.517233 0.2856012 0.5113906 0.8432807 0.1654009 0.8916677 0.3868935 0.2350366 0.4835596 0.8639743 0.1404225 0.8820941 0.4179379 0.2173427 0.7373902 0.6591251 0.1476814 0.4903022 0.8609066 0.1358073 0.9322392 0.3372565 0.1311035 0.8829312 0.4585148 0.1009786 0.7436791 0.660452 0.1036568 0.6489151 0.7575925 0.07044672 0.3997229 0.9149408 0.05572223 0.8926064 0.4488419 0.04236429 0.369341 0.928074 0.04760116 0.7455658 0.6660899 -0.02135342 -0.003467857 0.9999877 0.003564298 -0.004800498 0.9999703 0.006039619 -0.006512641 0.9999779 0.001335442 -0.00260806 0.9999847 0.004895925 -0.01204234 0.9999075 0.006324291 -0.00215429 0.9998007 0.01985245 -0.01215505 0.999912 0.005323112 -0.007508039 0.9999706 0.001587748 -0.003659188 0.9997963 0.01984864 -0.005382597 0.9999424 0.009295701 4.22046e-4 0.9999514 0.009847104 -0.01166301 0.9999315 -0.001056611 -0.01110053 0.9999381 -9.27032e-4 0.001268088 0.9999305 0.01173043 -0.008321702 0.9999646 0.001252293 0.002941727 0.999931 0.01137155 0.003416538 0.9999215 0.01206356 -0.00844717 0.9999589 -0.003292977 -0.008736073 0.9999558 -0.003486573 0.002655923 0.9999853 0.004740655 -0.00694853 0.9999687 -0.003790736 -0.008533358 0.9999464 -0.005879282 -0.004790902 0.9999771 -0.004791617 0.00505948 0.9999752 0.004899919 0.01128184 0.9998949 0.009107887 -0.005675315 0.999947 -0.008591175 -0.005668342 0.9999467 -0.008627116 0.01070362 0.999929 0.005255043 -0.005268573 0.9999399 -0.009614527 0.01133882 0.9999218 0.005276024 -0.001281797 0.9999926 -0.003618121 0.01043319 0.999938 0.003922462 0.004960238 0.9999871 0.001092493 -2.45191e-4 0.9999948 -0.003242611 0.004162013 0.9999877 -0.002729177 0.001070916 0.9999656 -0.008234083 0.01039659 0.9999459 -5.25748e-4 0.001333832 0.9999856 -0.005215704 0.0110253 0.9999347 -0.003020167 0.006773412 0.9999771 -1.50865e-4 0.005120754 0.9999651 -0.006610035 0.006466031 0.9999748 -0.002951383 0.004604458 0.9999864 -0.002458751 0.004926502 0.9999539 -0.008239388 0.005225837 0.9999515 -0.008358418 0.001890599 0.9999893 -0.004238426 0.006503462 0.9999573 -0.006558299 0.9097244 -0.4151481 0.007324278 0.8388909 -0.5428649 0.03949499 0.5858927 -0.810374 0.004883289 0.4591376 -0.8872848 0.04380053 0.9299461 -0.342179 0.1345884 0.8518269 -0.5158271 0.09117859 0.6568105 -0.7452084 0.115172 0.5009199 -0.8622166 0.07524532 0.8909594 -0.4085325 0.198224 0.7112077 -0.6836056 0.1639118 0.9278953 -0.2755749 0.2511351 0.3517969 -0.9323272 0.08369565 0.6720695 -0.7174724 0.183183 0.4640108 -0.8734402 0.1476354 0.8673534 -0.4007789 0.2950835 0.802675 -0.5232384 0.286242 0.7088338 -0.6341719 0.3088378 0.4503412 -0.8788222 0.1576845 0.7083737 -0.6425859 0.2920446 0.8516678 -0.2877101 0.4380465 0.2505366 -0.9613398 0.1142683 0.6102885 -0.7197695 0.3308776 0.3800306 -0.8987839 0.2185509 0.7756131 -0.4318518 0.4603568 0.6860817 -0.6004581 0.4107823 0.8070412 -0.2766155 0.5216977 0.740251 -0.3495205 0.574338 0.3085386 -0.9242423 0.2249006 0.6640445 -0.5200937 0.5371662 0.5950589 -0.6661028 0.44968 0.3974242 -0.8604049 0.3189945 0.6207234 -0.4709739 0.6268063 0.6084104 -0.5416095 0.5800828 0.3944585 -0.8412446 0.3697434 0.5745956 -0.4753942 0.6662133 0.5446373 -0.5229617 0.6556534 0.3468007 -0.833198 0.4307092 0.2941866 -0.8971709 0.3294523 0.5050351 -0.4061408 0.7615703 0.495432 -0.5105713 0.7027546 0.3229692 -0.8056011 0.4966869 0.2987457 -0.822929 0.4832585 0.2323774 -0.8827833 0.4082823 0.4304794 -0.4052982 0.8064868 0.4315935 -0.4126656 0.8021436 0.04236567 -0.9972435 0.06091576 0.3369268 -0.4988858 0.7984944 0.2109138 -0.8177949 0.5354688 0.3258879 -0.4040318 0.8547253 0.18787 -0.8373786 0.5133246 0.2148978 -0.4272337 0.8782314 0.0784198 -0.9617118 0.2626041 0.2251862 -0.5055426 0.8328974 0.1801821 -0.7171551 0.6732184 0.1290921 -0.4959293 0.8587138 0.1169356 -0.4500223 0.8853282 0.1047013 -0.7958758 0.5963383 0.0642547 -0.8885291 0.454299 0.05271643 -0.9420698 0.3312483 0.06195944 -0.4736629 0.8785241 0.04195606 -0.3450028 0.9376635 0.009597003 -0.992483 0.1220064 0.009449899 -0.6850146 0.7284681 0.007243692 -0.8448173 0.5350061 -0.01059609 -0.8822567 0.4706493 -0.03502106 -0.3276737 0.9441418 -0.06213974 -0.530049 0.8456872 -0.07460635 -0.5486747 0.8327004 -0.0661 -0.8177453 0.5717721 -0.04197013 -0.8706482 0.4901126 -0.1350467 -0.4568015 0.879258 -0.1770342 -0.6010062 0.7793912 -0.1238834 -0.7902325 0.6001548 -0.1078913 -0.9159921 0.386417 -0.2641559 -0.3735574 0.8892 -0.04360926 -0.9830088 0.1783034 -0.2346015 -0.5134917 0.825402 -0.330453 -0.2259693 0.9163727 -0.01708388 -0.9985092 0.05184239 -0.3615765 -0.4315063 0.8264773 -0.2720615 -0.6551181 0.7048425 -0.2312061 -0.7898547 0.5680436 -0.4058226 -0.3769973 0.832575 -0.418887 -0.4768916 0.7727279 -0.3743004 -0.6544067 0.6570016 -0.2418924 -0.8392403 0.4869947 -0.1905934 -0.9182159 0.3472084 -0.5485076 -0.2342243 0.8026697 -0.4075853 -0.6986638 0.5879994 -0.3534226 -0.7957596 0.4917917 -0.2524135 -0.896434 0.3642714 -0.5246359 -0.4874368 0.6979703 -0.1794795 -0.959391 0.2176145 -0.6346591 -0.3536357 0.6871315 -0.5783891 -0.4781389 0.6609458 -0.4691969 -0.7319509 0.4940669 -0.4590669 -0.7556951 0.4671001 -0.3044034 -0.9035879 0.3014425 -0.6716505 -0.4249975 0.6068467 -0.6224271 -0.5784403 0.527249 -0.6228063 -0.5793652 0.5257837 -0.2576715 -0.942328 0.2135963 -0.759638 -0.3733704 0.5324891 -0.1022993 -0.9920559 0.07321298 -0.4909135 -0.7983373 0.3488 -0.7586722 -0.4343755 0.485525 -0.5316174 -0.7760887 0.3392189 -0.806672 -0.3630436 0.4663472 -0.510645 -0.8088771 0.2914783 -0.3004451 -0.940725 0.1573826 -0.7910044 -0.4648935 0.3977264 -0.6543915 -0.6840361 0.322283 -0.8614111 -0.3311745 0.3850901 -0.8642696 -0.4116218 0.2891461 -0.2681584 -0.9571925 0.1089663 -0.8464376 -0.4557373 0.2754036 -0.642513 -0.7292279 0.2353804 -0.5096502 -0.8439974 0.1671084 -0.8445452 -0.4821229 0.2330259 -0.7051029 -0.6927025 0.151635 -0.5389299 -0.8320413 0.1313846 -0.9586157 -0.2274453 0.1712447 -0.8918304 -0.4370907 0.1165771 -0.7682728 -0.6316136 0.104025 -0.6815022 -0.7287802 0.06659126 -0.3950131 -0.9166522 0.06093907 -0.2129713 -0.9768171 0.02171707 -0.9521301 -0.3044331 0.02772885 -0.8992877 -0.4373466 0.003111481 -0.6994638 -0.7137808 0.03560131 -0.5682835 -0.8226891 -0.01538103 -0.86596 -0.496412 -0.06073313 -0.715762 -0.6955032 -0.06292921 -0.40643 -0.9135515 -0.01544553 -0.9364243 -0.3342839 -0.1066017 -0.6154223 -0.7802879 -0.111384 -0.434661 -0.896963 -0.08079177 -0.3233026 -0.9450088 -0.04933607 -0.8721706 -0.445834 -0.2013713 -0.866782 -0.4558376 -0.2022401 -0.7573341 -0.6281643 -0.1784795 -0.9034592 -0.2981126 -0.3080428 -0.8381813 -0.430585 -0.334737 -0.04330515 -0.9989568 -0.01449131 -0.6173273 -0.7491925 -0.2400367 -0.6446506 -0.7239388 -0.2456384 -0.8660359 -0.2970829 -0.4021488 -0.3292672 -0.935086 -0.131139 -0.3685504 -0.9171736 -0.1515363 -0.7633054 -0.4786586 -0.433879 -0.6175546 -0.7042338 -0.3502587 -0.5049261 -0.8051985 -0.3109742 -0.7937087 -0.3269168 -0.5129834 -0.5367596 -0.7866524 -0.3050693 -0.7342968 -0.4204097 -0.5329765 -0.5855609 -0.6883671 -0.4280996 -0.7383183 -0.3150246 -0.5963603 -0.4364854 -0.8127079 -0.3859879 -0.3289846 -0.9152016 -0.232756 -0.6794264 -0.4001712 -0.6150146 -0.5410363 -0.6762428 -0.4999756 -0.4534202 -0.8162927 -0.3578779 -0.6844043 -0.3064768 -0.661561 -0.2491204 -0.9343189 -0.254926 -0.4627196 -0.7236053 -0.5121387 -0.2633891 -0.922195 -0.2831654 -0.5890348 -0.4056025 -0.6989454 -0.5839121 -0.4175251 -0.6962181 -0.4828508 -0.6689966 -0.5650652 -0.5303568 -0.3995436 -0.747721 -0.4317001 -0.5967954 -0.6763656 -0.3704986 -0.7497535 -0.5482704 -0.2646091 -0.8732533 -0.4091588 -0.1936486 -0.9439966 -0.267153 -0.4068148 -0.4770584 -0.7790488 -0.3921297 -0.4909669 -0.7779369 -0.1849719 -0.9023259 -0.3893502 -0.366732 -0.2729333 -0.8893903 -0.2815102 -0.7021328 -0.6540348 -0.189054 -0.8926883 -0.4091041 -0.2778245 -0.5129522 -0.8122153 -0.2566457 -0.6425356 -0.7219979 -0.1622929 -0.803225 -0.5731412 -0.1222287 -0.8978603 -0.4229741 -0.2274194 -0.3359161 -0.9140245 -0.08977514 -0.9340924 -0.3455604 -0.1820195 -0.4572151 -0.8705304 -0.1455647 -0.6727545 -0.7254049 -0.09185683 -0.2276353 -0.9694043 -0.1052106 -0.4032557 -0.909019 -0.07376611 -0.5924773 -0.8022028 -0.08129048 -0.7367328 -0.67128 -0.05008661 -0.8534677 -0.5187335 -0.04502743 -0.9181114 -0.3937565 0.009358465 -0.4343992 -0.9006719 -0.009855508 -0.5756687 -0.8176237 0.0168932 -0.7915197 -0.6109102 0.04193705 -0.3539583 -0.9343206 -0.004941701 -0.9851096 -0.1718562 0.03280854 -0.8146772 -0.5789858 0.02700328 -0.9259312 -0.376726 0.07999682 -0.4194549 -0.9042445 0.07985436 -0.7148415 -0.6947121 0.1401003 -0.3086349 -0.9408062 0.1763408 -0.4094532 -0.8951268 0.1251849 -0.7080276 -0.6950006 0.2360249 -0.3298256 -0.914061 0.06042349 -0.9549807 -0.2904498 0.1432621 -0.7968758 -0.5869114 0.1010084 -0.9074297 -0.4078834 0.2544748 -0.4676214 -0.8465062 0.2087571 -0.6961594 -0.6868644 0.3449348 -0.4432784 -0.8273598 0.3687647 -0.3818841 -0.8474534 0.2636007 -0.7119067 -0.6509252 0.1280786 -0.9437165 -0.304951 0.2295985 -0.8475152 -0.4785422 0.4241529 -0.443422 -0.7896021 0.4240896 -0.4748956 -0.7711176 0.2692329 -0.8251627 -0.4966088 0.2792879 -0.8483455 -0.4497867 0.5449592 -0.3286902 -0.771351 0.4822028 -0.4895581 -0.7265077 0.4191325 -0.6805127 -0.6010246 0.1781398 -0.9542994 -0.2399565 0.6113103 -0.2785967 -0.7407318 0.5937322 -0.4799165 -0.6458811 0.4868304 -0.6756405 -0.5536301 0.3801391 -0.8349937 -0.3978438 0.6638743 -0.3958842 -0.6344658 0.6571775 -0.4789612 -0.5819913 0.397165 -0.84487 -0.3584057 0.3615173 -0.8838361 -0.2968825 0.7235108 -0.435381 -0.5357009 0.7087036 -0.4957898 -0.5019279 0.4186508 -0.8554379 -0.3048894 0.7539872 -0.4827373 -0.4454975 0.7317877 -0.5434302 -0.4113035 0.4051678 -0.8806453 -0.2455667 0.3853377 -0.8948357 -0.225353 0.8142226 -0.4649615 -0.3476386 0.07643914 -0.9964495 -0.03529435 0.7451784 -0.5703043 -0.345633 0.5324674 -0.8143486 -0.2308999 0.8296453 -0.4450232 -0.3371099 0.4752072 -0.8640703 -0.1660138 0.360695 -0.9249736 -0.1196789 0.8953022 -0.3782478 -0.2352926 0.8065118 -0.5395341 -0.2417474 0.6606951 -0.727258 -0.1859514 0.886491 -0.4352862 -0.1570343 0.750853 -0.650001 -0.1171264 0.6547238 -0.7457554 -0.1232308 0.9654698 -0.2306492 -0.1211154 0.3303126 -0.9428947 -0.04293429 0.330908 -0.9426739 -0.04319411 0.8795274 -0.4721694 -0.05905783 0.780293 -0.6215806 -0.06914103 0.5748964 -0.818181 -0.008610963 0.9922904 -0.004514157 -0.1238522 0.9979616 0.004777193 -0.06363904 0.9838536 0.005002319 -0.1789048 0.9627231 -0.00472784 -0.2704475 0.9787957 0.006010472 -0.2047512 0.9376824 -0.001608908 -0.3474901 0.9446886 0.001567244 -0.3279653 0.9042418 -0.001546621 -0.4270182 0.8697311 -1.28278e-4 -0.4935261 0.8959057 0.001323997 -0.4442424 0.865117 0.001697301 -0.5015675 0.8086014 -0.004407405 -0.5883404 0.7848476 0.003451347 -0.6196792 0.7229945 -0.002635359 -0.6908487 0.7056378 0.002377927 -0.7085688 0.6460846 -0.003106534 -0.7632597 0.5557464 -0.002501487 -0.8313481 0.607734 0.004577159 -0.7941275 0.4825248 -0.001082003 -0.8758817 0.510403 0.002501785 -0.8599317 0.3813293 -0.004614889 -0.9244278 0.4449544 0.003177225 -0.8955476 0.3276237 0.004217147 -0.944799 0.258022 -0.004755556 -0.9661275 0.1473119 -6.294e-4 -0.9890899 0.1975793 0.00464797 -0.9802759 0.04279965 -0.003841757 -0.9990764 0.09743726 0.004811465 -0.99523 -0.09667229 -0.004865586 -0.9953044 -0.05191355 0.005310833 -0.9986374 -0.1913976 0.003966987 -0.9815047 -0.2441707 -0.005454778 -0.969717 -0.3120581 0.00502187 -0.9500498 -0.3789681 -0.005335986 -0.9253944 -0.3230889 0.004540264 -0.9463579 -0.4892862 -0.004122197 -0.8721137 -0.4343133 0.001677989 -0.9007603 -0.5557022 -0.003055095 -0.8313758 -0.5300186 0.001491367 -0.8479847 -0.6433289 0.00312519 -0.7655836 -0.644599 0.003578305 -0.7645125 -0.7132907 -3.21975e-5 -0.7008683 -0.7260953 0.002962827 -0.6875877 -0.7804015 -0.002583265 -0.6252736 -0.8428555 -0.003869354 -0.5381262 -0.812025 0.005051255 -0.5836009 -0.8838133 0.004125773 -0.4678217 -0.9048478 -0.004034817 -0.4257161 -0.9330927 0.003083646 -0.3596228 -0.9478964 -0.002450406 -0.3185696 -0.9624163 0.002364397 -0.2715682 -0.9755573 -0.002859652 -0.2197268 -0.9933661 -0.002386748 -0.1149702 -0.9860306 0.00349164 -0.1665277 -0.9966124 0.002571463 -0.08220112 -0.9996727 -0.002904117 0.02542328 -0.9995598 -0.001763463 0.02961605 -0.9922977 0.003580391 0.1238253 -0.9839493 -0.005345046 0.1783686 -0.970827 0.00504285 0.2397283 -0.9501984 8.79338e-4 0.3116443 -0.9510283 3.53692e-4 0.309104 -0.9111839 8.89687e-4 0.4119991 -0.9084458 0.002289116 0.4179965 -0.8676338 0.00190401 0.4972002 -0.8672667 0.002055704 0.4978396 -0.8064501 5.49492e-4 0.5913019 -0.8060824 6.76805e-4 0.5918029 -0.7547023 -0.003726363 0.6560568 -0.6768911 -0.003813803 0.7360733 -0.7211335 0.003116309 0.6927891 -0.6392833 0.004009127 0.768961 -0.5658485 -0.005805015 0.8244888 -0.5326809 0.003053903 0.8463107 -0.4428908 -0.0018664 0.8965737 -0.4318308 7.81254e-4 0.9019544 -0.3431234 2.62144e-4 0.9392904 -0.337609 0.001552045 0.9412853 -0.2444168 0.001954674 0.9696684 -0.2394806 6.45321e-4 0.970901 -0.1596518 -0.006586432 0.9871515 -0.1050885 0.002493143 0.9944598 -0.05596125 -0.002864003 0.9984289 0.002797245 0.00354135 0.9999898 0.05576676 -0.001243054 0.9984431 0.1025637 0.004231393 0.9947175 0.1472755 -0.003241658 0.9890903 0.2476332 5.67111e-4 0.9688538 0.2433059 -5.7224e-4 0.9699495 0.3444481 -1.65832e-4 0.9388054 0.3537126 0.002488493 0.9353508 0.4485635 0.00333327 0.8937448 0.4701963 -0.001808702 0.8825601 0.5688727 -0.004162728 0.8224151 0.5235537 0.001599311 0.8519912 0.6135761 0.002051711 0.789633 0.6395184 -0.001725077 0.7687739 0.7192416 -4.45911e-4 0.69476 0.6834674 0.003663301 0.7299719 0.7134522 -0.001452922 0.7007025 0.7757222 -0.002481758 0.6310698 0.7894743 0.002294719 0.6137794 0.8415545 -0.00262767 0.540166 0.8672452 0.00497204 0.4978564 0.897907 -0.002130866 0.4401801 0.9063968 5.97716e-4 0.4224268 0.9295804 -0.003049492 0.3686069 0.9654017 -0.002478659 0.2607556 0.9485098 0.003529489 0.3167283 0.9751687 0.003960311 0.2214281 0.9921703 -0.002067148 0.1248746 0.9946357 0.002348423 0.1034131 0.9997814 2.75388e-4 0.02091091 0.9995968 0.001776099 0.0283426 0.00812608 -0.9999277 0.008868813 0.008898019 -0.9999255 0.008361935 0.006726205 -0.9999656 0.004856348 0.01218098 -0.9997438 0.01908493 0.008653819 -0.9998332 0.01608395 0.008146166 -0.9999609 0.003467798 0.0104041 -0.9998536 0.01359087 0.0134713 -0.9999001 0.004301249 5.40707e-4 -0.9999977 0.002098977 0.01515179 -0.9998811 0.002881765 0.0141226 -0.9998986 0.001903772 -0.001000225 -0.9999903 0.004296302 0.01612561 -0.9998696 9.73027e-4 4.50244e-4 -0.999966 0.008244216 0.01589059 -0.9998725 -0.001577556 -0.001090109 -0.9999714 0.007483422 0.006837189 -0.999974 0.002353131 -0.002865493 -0.9999425 0.01034384 -0.001596748 -0.9999894 0.004332244 0.00492537 -0.9999861 -0.001881659 0.009269595 -0.9999435 -0.005211114 -0.001592457 -0.9999955 0.0025388 0.007921278 -0.9999552 -0.005202412 -0.005016922 -0.9999811 0.003554403 0.008388757 -0.9999282 -0.008564174 0.008370935 -0.9999282 -0.00857681 -0.005369901 -0.9999706 0.005469262 -0.005329132 -0.9999709 0.005470752 0.009369432 -0.9998735 -0.01285213 -0.001471519 -0.9999985 0.001043915 0.00595057 -0.9999229 -0.01090323 -0.001328408 -0.9999989 6.20033e-4 0.005623638 -0.9998622 -0.0156207 -0.01322638 -0.9999114 -0.001520991 0.0038262 -0.9998811 -0.01493984 -0.01715594 -0.9998421 0.004648566 0.005203068 -0.999954 -0.008062183 -0.01549816 -0.9998655 0.005387306 1.72777e-4 -0.9999776 -0.006697475 -0.001843631 -0.9999984 6.90098e-5 -4.67297e-4 -0.9999611 -0.008801937 -0.0019055 -0.9999982 -3.25913e-4 -0.001766443 -0.9999724 -0.007224202 -0.006354033 -0.9998889 -0.01349186 -0.0124911 -0.9999054 -0.005763351 -0.01655697 -0.9998437 -0.006207704 -0.006144285 -0.9998993 -0.01279824 -0.00616616 -0.9998885 -0.01360434 -0.01310926 -0.9998884 -0.007165968 -0.01122874 -0.9999151 -0.006633579 -0.00393182 -0.9999768 -0.005570054 -0.005722999 -0.999899 -0.0130127 -0.006359696 -0.9999738 -0.003463625 -0.008078992 -0.9999382 -0.007637381 0.367465 0.929984 -0.009953856 0.8491638 0.5223162 -0.07814568 0.3880115 0.9209514 -0.03599637 0.8381432 0.5378941 -0.09047615 0.7246254 0.6780937 -0.1229101 0.744861 0.6553708 -0.125185 0.8721674 0.4321688 -0.2292476 0.2215772 0.9737885 -0.05137664 0.4535332 0.8809738 -0.1348811 0.8533736 0.4342806 -0.2883642 0.8472272 0.4454824 -0.2893989 0.539326 0.8178721 -0.2005312 0.8183885 0.4377195 -0.3723468 0.7280886 0.5761311 -0.3714299 0.4893378 0.8369474 -0.2450869 0.489557 0.8368013 -0.2451483 0.7834758 0.3896377 -0.4840953 0.7567922 0.4302489 -0.492089 0.4489969 0.8539417 -0.2630311 0.5265775 0.765073 -0.3706474 0.7290053 0.3676069 -0.5774223 0.7291309 0.3670247 -0.577634 0.1699534 0.9771448 -0.1276863 0.5816111 0.6566374 -0.4801622 0.5129479 0.7649676 -0.3894984 0.2986981 0.9189861 -0.2573796 0.6806193 0.2795423 -0.6772102 0.526849 0.6855922 -0.5023878 0.3299964 0.88134 -0.3381455 0.5963976 0.4860495 -0.6388002 0.5519605 0.5080177 -0.6612547 0.4164741 0.7338499 -0.5366691 0.2994792 0.8950481 -0.330456 0.5671467 0.3511844 -0.7449927 0.3729746 0.740525 -0.5590285 0.4844959 0.4264819 -0.7637912 0.09638422 0.9859232 -0.1366223 0.4210791 0.568629 -0.7066494 0.4046792 0.579437 -0.7074515 0.1959959 0.9164012 -0.3489907 0.3890764 0.3455173 -0.853954 0.2592703 0.7925198 -0.5519885 0.2069616 0.8842746 -0.4185996 0.3576622 0.3871092 -0.8498377 0.2593489 0.7304244 -0.6318374 0.3216375 0.2857788 -0.9027069 0.2403782 0.4879663 -0.839111 0.2082876 0.7450984 -0.6335965 0.07634139 0.9685637 -0.2367622 0.1125187 0.8826086 -0.4564447 0.1144527 0.884616 -0.4520566 0.1927498 0.4372456 -0.878444 0.1455786 0.5437746 -0.8265084 0.06581538 0.8971191 -0.4368591 0.07577335 0.353583 -0.9323291 0.1042888 0.5591842 -0.8224579 0.05095481 0.7494384 -0.6601104 0.03826963 0.7503418 -0.6599415 -0.006998777 0.4460825 -0.8949645 -0.04518336 0.3832902 -0.9225222 0.004163503 0.9873683 -0.1583878 -0.03453791 0.8891409 -0.4563285 -0.02712917 0.8971025 -0.4409888 -0.08137154 0.4893422 -0.8682874 -0.1763552 0.404939 -0.8971751 -0.1555528 0.4712462 -0.8681765 -0.1360911 0.8019987 -0.5816162 -0.0738992 0.8906581 -0.4486281 -0.2449393 0.4169152 -0.8753208 -0.2476773 0.6319993 -0.7343249 -0.1646589 0.7952039 -0.5835566 -0.3732058 0.3416358 -0.8625558 -0.2822071 0.6131117 -0.7378707 -0.408371 0.2926652 -0.8646273 -0.1324818 0.9366958 -0.3241137 -0.2841801 0.7639018 -0.5793926 -0.2763257 0.7805742 -0.5606675 -0.4301831 0.4091843 -0.8046805 -0.04327028 0.9953851 -0.08565247 -0.3728489 0.6141769 -0.6955361 -0.5011798 0.2874504 -0.8162053 -0.2613826 0.869919 -0.4182345 -0.1494429 0.9622325 -0.2275424 -0.489551 0.5499357 -0.6766909 -0.4896568 0.5512465 -0.6755469 -0.4584335 0.6507574 -0.6052715 -0.4008755 0.7448856 -0.5333334 -0.629881 0.1890757 -0.7533262 -0.3082662 0.8779584 -0.3662802 -0.564682 0.5702446 -0.5966201 -0.5709697 0.6005651 -0.5597458 -0.3163001 0.8925901 -0.3213056 -0.6356008 0.5194085 -0.5711624 -0.2590899 0.9354492 -0.2404314 -0.6541159 0.5307198 -0.5389518 -0.7573435 0.358516 -0.5457994 -0.4774915 0.8108072 -0.3385168 -0.3332232 0.909279 -0.2493472 -0.7445539 0.4757853 -0.4682604 -0.2110055 0.9689339 -0.1290112 -0.6007397 0.7175326 -0.3525035 -0.5845043 0.7344149 -0.3449487 -0.8586751 0.2511955 -0.4467416 -0.4051524 0.8903716 -0.2075816 -0.8312357 0.4035978 -0.382304 -0.7366285 0.5848713 -0.3395646 -0.8890245 0.2921177 -0.3525659 -0.6273451 0.7419379 -0.2365722 -0.4703282 0.8604905 -0.195825 -0.8351226 0.4838083 -0.2617247 -0.6533333 0.7211249 -0.2305093 -0.8746658 0.4200665 -0.2418757 -0.8698383 0.4528186 -0.1957976 -0.5357099 0.8367596 -0.1133518 -0.9205084 0.3512876 -0.1710597 -0.1523066 0.9878077 -0.03222799 -0.6034603 0.7895321 -0.1116905 -0.1759013 0.9837831 -0.03506386 -0.9251046 0.3769307 -0.0458787 -0.8645172 0.4973136 -0.07272696 -0.6487976 0.7582427 -0.06426328 -0.5280091 0.8490602 -0.01741826 -0.9269404 0.3749402 0.01419281 -0.9099375 0.4139871 0.02507281 -0.6511226 0.7583019 0.03190106 -0.5297864 0.8480635 0.01071989 -0.3673972 0.929619 0.02877444 -0.9235487 0.3638367 0.1211638 -0.9007061 0.4215894 0.1048378 -0.7604005 0.6424443 0.09516566 -0.9041261 0.3816112 0.1921693 -0.790256 0.5806904 0.1956894 -0.6739071 0.7258353 0.1378859 -0.4538802 0.8856769 0.09782332 -0.348664 0.9318948 0.1000275 -0.850021 0.4286404 0.3061566 -0.7772144 0.5785184 0.2474962 -0.5810056 0.7819616 0.2257625 -0.4815955 0.8557567 0.1890673 -0.8310682 0.4236924 0.3602923 -0.7563434 0.5488998 0.3558844 -0.3799266 0.904102 0.19559 -0.76644 0.4550693 0.4533011 -0.7174162 0.5770087 0.3903523 -0.564922 0.7562966 0.3299679 -0.196609 0.9733435 0.1180997 -0.7307918 0.4108208 0.5451328 -0.7103322 0.4842649 0.510799 -0.5535221 0.7317087 0.3977634 -0.4344336 0.8301188 0.3495284 -0.6497796 0.4394614 0.6202098 -0.6544414 0.4172868 0.630538 -0.4657515 0.7566506 0.4588635 -0.4104984 0.8301755 0.3772266 -0.1321516 0.9802834 0.1469032 -0.5871036 0.3926043 0.7079344 -0.5633474 0.4454224 0.6958727 -0.4499855 0.7242097 0.5225259 -0.497052 0.4777601 0.7243512 -0.3834788 0.7056435 0.5958283 -0.3261573 0.8329539 0.4470002 -0.2370893 0.9118061 0.3352589 -0.5074006 0.2823569 0.8141372 -0.3248945 0.7392526 0.5898721 -0.2692106 0.8088592 0.5227548 -0.1662558 0.9424804 0.2899826 -0.4047988 0.3917379 0.8262441 -0.137841 0.9591485 0.247051 -0.400601 0.4043055 0.8222262 -0.3314602 0.4853319 0.8090656 -0.245255 0.7752776 0.5820608 -0.3139725 0.4247762 0.8491093 -0.1675335 0.8513121 0.4971925 -0.2178424 0.3412123 0.9143954 -0.2269029 0.5149157 0.8266662 -0.06271868 0.9756563 0.210146 -0.1800302 0.6784 0.7122939 -0.05518257 0.9794474 0.1940041 -0.1319412 0.4037485 0.9053059 -0.1070052 0.7296853 0.6753587 -0.1096264 0.7405484 0.6630009 -0.05413085 0.9305104 0.3622436 -0.1065384 0.3151242 0.9430516 -0.03128772 0.4837557 0.8746436 -0.05033928 0.7201722 0.6919668 -0.003965914 0.9524847 0.304561 -0.009913921 0.4593597 0.8881951 4.52646e-4 0.8500361 0.5267243 -0.001285016 0.9451936 0.3265081 0.02491855 0.5223864 0.8523448 0.04380702 0.7164686 0.6962425 0.1092281 0.2957815 0.9489904 0.1334875 0.400366 0.9065805 0.1083137 0.7203503 0.6851012 0.1071698 0.7237852 0.6816521 0.07778471 0.9280147 0.3643327 0.06612658 0.9463108 0.3164226 0.2188901 0.3391106 0.914927 0.22793 0.5108824 0.8288831 0.2419565 0.5287542 0.8135577 0.3183871 0.3649351 0.8749012 0.03467583 0.9923962 0.1180999 0.2164004 0.757913 0.6154177 0.3568315 0.5852727 0.7280984 0.2491617 0.7842266 0.5682494 0.1891115 0.9018186 0.3885355 0.3900233 0.5361021 0.7486497 0.4311526 0.5487055 0.716261 0.5171434 0.3608858 0.7760954 0.2015479 0.9259381 0.3194013 0.3572974 0.7734899 0.5234996 0.5625955 0.317223 0.76345 0.1890322 0.9326122 0.307411 0.5326644 0.5840201 0.6125268 0.4215316 0.7392457 0.5251923 0.234049 0.9368021 0.2600441 0.5554859 0.5653628 0.6097545 0.2375457 0.9337321 0.2677994 0.5669271 0.6068941 0.5570217 0.4467832 0.796587 0.4072274 0.6827344 0.4177029 0.5994982 0.08141487 0.9935292 0.07919174 0.7354023 0.3566299 0.5761933 0.4345075 0.8400334 0.3248803 0.7118849 0.490606 0.5025193 0.4339497 0.8403254 0.3248707 0.771675 0.4294962 0.4690957 0.3905926 0.8907121 0.2325285 0.7056187 0.6098753 0.3607693 0.4266833 0.8729861 0.2362978 0.8428488 0.4008269 0.3590874 0.741182 0.5766844 0.343634 0.3890455 0.9050239 0.171975 0.6409776 0.7235002 0.2563109 0.8911161 0.3364903 0.3044446 0.2970545 0.9479508 0.1146646 0.8350119 0.4961512 0.2378851 0.7222548 0.6598199 0.2073302 0.9171528 0.3431847 0.2026205 0.5844398 0.8002054 0.134542 0.4530456 0.8854956 0.1031852 0.3477497 0.9355034 0.06247812 0.8944031 0.4274336 0.1316956 0.8044683 0.5857415 0.09867954 0.7804151 0.6251735 0.0105111 0.7418276 0.6701868 0.0232715 0.474921 0.8799651 0.01056319 -0.009270191 0.9999314 0.007165908 -0.003341853 0.9999895 0.003155946 -0.002026319 0.9999958 0.00208199 -0.001906096 0.9999946 0.002693712 -0.01153439 0.999912 0.006547808 -0.00812155 0.999952 0.00547558 -6.2748e-4 0.999999 0.001312553 1.63444e-4 0.999993 0.003760278 -0.009369671 0.9999526 0.002650082 -0.001788258 0.9999733 0.007097959 -0.01250886 0.9999186 0.002537071 -0.01295584 0.999916 5.82788e-4 -3.6766e-4 0.9999775 0.006713986 -0.009768664 0.9999516 0.001294374 -0.001719713 0.9999933 0.003244459 -0.01301676 0.9999132 -0.002040386 2.27156e-4 0.9999986 0.001654744 -0.007776081 0.9999681 -0.001887619 7.66438e-4 0.999997 0.00238502 0.002568662 0.9999789 0.005975723 -0.00605303 0.9999776 -0.002893626 0.002891838 0.9999826 0.00514847 0.00362569 0.9999776 0.005631923 -0.006185531 0.9999762 -0.003068864 -0.003771126 0.9999884 -0.003010988 0.004270851 0.9999799 0.004695713 0.009769916 0.9999231 0.00763905 -0.004668891 0.9999725 -0.005762577 -0.003376781 0.9999879 -0.003600537 0.009538114 0.9999314 0.006809055 0.009703397 0.9999299 0.006787478 -0.004104137 0.9999554 -0.008514046 -0.007677972 0.9997873 -0.01914328 0.009397745 0.9999474 0.004115045 0.01180124 0.9999217 0.004175007 -0.01034826 0.9997336 -0.02063596 -0.001782894 0.9999726 -0.007196784 0.01192939 0.9999269 0.002027988 0.01398104 0.9998972 0.003205835 0.004650831 0.999989 6.91874e-4 -3.09905e-4 0.9999736 -0.007256448 7.00022e-4 0.9999468 -0.0102899 0.002714991 0.9999963 -2.23412e-4 0.001369774 0.9999614 -0.008689105 0.001962661 0.9999572 -0.009043097 0.008789896 0.9999482 -0.005157768 0.002036571 0.999982 -0.005641818 0.01450914 0.9998851 -0.004412233 0.01078045 0.9999341 -0.00393778 0.002868533 0.9999831 -0.005075931 0.004321932 0.9999717 -0.006163179 0.00824207 0.9999513 -0.005443572 0.007074594 0.9999678 -0.003813922 0.003612637 0.9999851 -0.004094481 -0.09614819 -0.5531353 -0.8275246 -0.09380656 -0.5342782 -0.8400877 -0.05502098 -0.8344125 -0.5483873 -0.04973417 -0.7143391 -0.6980302 -0.2023906 -0.2819988 -0.9378244 -0.1426731 -0.8159334 -0.5602654 -0.2269166 -0.4801105 -0.8473505 -0.2034283 -0.7376824 -0.6437714 -0.3568723 -0.4613868 -0.8122588 -0.1725714 0.8758955 -0.4505842 -0.2127509 -0.7648828 -0.6080225 -0.3809456 -0.6244459 -0.6818709 -0.3789215 -0.6411603 -0.6673321 -0.1904056 -0.9048647 -0.3807435 -0.5714362 -0.3085342 -0.760439 -0.515703 -0.6047943 -0.6068562 -0.281619 -0.9084234 -0.3089624 -0.373167 -0.8189405 -0.4359853 -0.5466319 -0.6127832 -0.5706928 -0.5957736 -0.6402969 -0.4848442 -0.3624569 -0.8407791 -0.4021387 -0.6323149 -0.6777598 -0.3752593 -0.6655676 -0.620281 -0.4150558 -0.4349722 -0.855305 -0.2815183 -0.6885873 -0.6532526 -0.3148154 -0.8552815 -0.4190177 -0.3048241 -0.3271493 -0.9363421 -0.1274249 -0.7791354 -0.5902304 -0.2111306 -0.6190621 -0.7703347 -0.1527965 -0.8125151 -0.5690122 -0.1266671 -0.9293658 -0.3577226 -0.09117966 -0.7692037 -0.6328914 -0.08817261 -0.3619176 -0.9319041 -0.02388197 -0.8841423 -0.4642205 0.05283689 -0.6490525 -0.7606716 -0.01047241 -0.8905136 -0.4513841 0.05690449 -0.8924834 -0.4198954 0.1648071 -0.538205 -0.8407563 0.05885905 -0.807968 -0.5592682 0.1854913 -0.8907225 -0.3315621 0.3109344 -0.6484127 -0.7247824 0.2329195 -0.5305644 -0.8310983 0.166665 -0.7701909 -0.5399061 0.3395696 -0.8132058 -0.3947491 0.4276326 -0.5207362 -0.7992348 0.3000963 -0.450244 -0.8586781 0.2448521 -0.6466882 -0.619632 0.444804 -0.6963914 -0.4088805 0.5897931 -0.3938377 -0.8583146 0.3289193 -0.3940574 -0.858094 0.3292319 -0.5652943 -0.5969568 0.5692846 -0.2561802 -0.9171036 0.3054388 -0.5790776 -0.406965 0.7064339 -0.297087 -0.839733 0.4545195 -0.4340313 -0.5686704 0.6987352 -0.442156 -0.4746984 0.7610254 -0.1988196 -0.9114555 0.3601661 -0.3230249 -0.6392928 0.697825 -0.3030753 -0.5143429 0.8022448 -0.1717425 -0.8310616 0.5290004 -0.2121303 -0.4251706 0.8799038 -0.09766733 -0.7846525 0.6121942 -0.07013881 -0.307197 0.9490577 -0.03013485 -0.801889 0.5967128 -0.05270159 -0.74657 0.6632163 -0.02400958 -0.4974293 0.8671723 0.08228403 -0.5361731 0.840088 0.09068375 -0.8152765 0.5719274 0.1001624 -0.4789307 0.8721199 0.09841507 -0.7954252 0.5980079 0.1700281 -0.6359237 0.7527893 0.2876889 -0.4307849 0.855371 0.2879909 -0.5365648 0.7931959 0.1080334 -0.9291281 0.3536239 0.373743 -0.5423312 0.7524581 0.4351727 -0.4310934 0.7904323 0.2970314 -0.8150599 0.4974432 0.1906035 -0.9177759 0.3483644 0.4756789 -0.5721601 0.6681036 0.535826 -0.5203698 0.6649104 0.5522445 -0.5868617 0.5921313 0.1795416 -0.9466694 0.2675482 0.6651018 -0.4455582 0.5992641 0.6613805 -0.4600507 0.5923928 0.2692976 -0.9286072 0.2552791 0.5141831 -0.7586672 0.4000498 0.6662751 -0.5704829 0.4802362 0.8721244 -0.2150222 0.4395048 0.4606035 -0.834529 0.3023342 0.6437233 -0.7016185 0.3055354 0.8721631 -0.3678225 0.3225495 0.553163 -0.8215575 0.1380359 0.7742799 -0.619095 0.1311947 0.6883555 -0.7117276 0.1400378 0.860351 -0.5009709 0.093939 0.8455104 -0.5267109 0.08768182 0.3666341 -0.9297367 0.03419166 0.7817363 -0.6234449 -0.01432126 0.8957169 -0.418763 -0.1494284 0.7784989 -0.6211411 -0.09012913 0.4400914 -0.8952807 -0.06922614 0.8378168 -0.4993084 -0.2208032 0.724034 -0.6470718 -0.2388994 0.8613678 -0.3016676 -0.4087079 0.5186207 0.843824 -0.1378173 0.709054 -0.666357 -0.2306748 0.8636716 -0.2990086 -0.4057896 0.8583024 -0.3153923 -0.4047775 0.3350415 -0.9284829 -0.1602089 0.6681199 -0.6212133 -0.4095242 0.7324452 -0.3828353 -0.5629931 0.6637243 -0.5240893 -0.5336672 0.3389817 -0.9023018 -0.266351 0.578367 -0.5448924 -0.6071112 0.4522696 -0.797907 -0.3984931 0.5933505 -0.4605919 -0.6601442 0.2145206 -0.9354887 -0.2807881 0.420444 -0.6443057 -0.6388247 0.3868499 -0.4794859 -0.7876806 0.3643469 -0.6609185 -0.6560778 0.2758543 -0.8102771 -0.5170643 0.3294289 -0.4784071 -0.8140046 0.1223088 -0.8557501 -0.5027249 0.1756558 -0.6204492 -0.7643219 0.1114474 -0.816346 -0.5667086 0.1005951 -0.4320524 -0.8962207 0.1082934 -0.5112893 -0.8525585 0.04272413 -0.9296143 -0.3660491 0.03791522 -0.6553793 -0.7543478 -0.04500812 5.40114e-4 0.9989866 -0.1420858 -4.0453e-4 0.9898543 -0.2168222 7.16366e-4 0.9762108 -0.2524341 -9.48327e-5 0.9676141 -0.3755766 -1.94462e-4 0.9267914 -0.3984166 4.22459e-4 0.9172046 -0.5584138 -7.63817e-4 0.8295622 -0.5449634 -1.50284e-4 0.8384599 -0.6856149 6.91811e-4 0.7279642 -0.6960341 1.89067e-4 0.7180088 -0.7719061 -5.36381e-4 0.6357365 -0.8272929 7.34853e-4 0.5617703 -0.8511049 -2.49723e-4 0.5249957 -0.9086095 -2.62935e-4 0.417647 -0.9195639 4.43348e-4 0.3929404 -0.9532928 -1.16537e-4 0.3020477 -0.9698224 8.92494e-4 0.2438108 -0.9885173 -4.96819e-4 0.1511077 -0.9994937 1.12063e-4 0.03182178 -0.9988898 5.18258e-4 0.0471062 -0.9986416 -2.52136e-4 -0.05210429 -0.9912049 0.00104314 -0.1323318 -0.9731335 -4.13918e-4 -0.2302412 -0.963236 1.82969e-4 -0.2686567 -0.9229467 -3.95825e-4 -0.3849278 -0.9249353 -2.18418e-4 -0.3801246 -0.8589448 -6.00369e-4 -0.5120677 -0.8493723 -2.30008e-4 -0.5277942 -0.8148727 -5.28247e-4 -0.5796399 -0.7620487 6.06698e-4 -0.6475194 -0.7277949 -5.55497e-5 -0.685795 -0.6717165 6.94482e-4 -0.740808 -0.6381124 1.85244e-4 -0.7699432 -0.6151459 4.57006e-4 -0.7884132 -0.5344247 -1.88337e-4 -0.8452162 -0.5069714 4.13506e-4 -0.8619629 -0.4094644 4.75716e-4 -0.9123261 -0.3719729 -7.85034e-4 -0.9282433 -0.2941753 -2.85227e-4 -0.9557515 -0.2550556 4.27627e-4 -0.9669263 -0.1636937 -1.01709e-4 -0.9865113 -0.1292408 5.70586e-4 -0.9916131 -0.007273375 -5.38113e-4 -0.9999734 0.005140542 -2.65592e-4 -0.9999868 0.1415888 -2.69262e-4 -0.9899256 0.158401 -5.78899e-4 -0.9873747 0.2334971 4.22952e-4 -0.9723574 0.3163877 -3.91326e-4 -0.9486299 0.3440759 4.64048e-6 -0.9389419 0.40341 -6.00634e-4 -0.9150192 0.4717544 3.55077e-4 -0.88173 0.5591816 -1.93305e-4 -0.8290453 0.5559705 -6.73886e-5 -0.831202 0.6915563 -1.56231e-4 -0.7223225 0.6727407 6.3326e-4 -0.7398781 0.7779432 -3.539e-4 -0.6283345 0.7588656 5.93547e-4 -0.651247 0.8338704 -9.2199e-4 -0.5519596 0.8889692 4.35628e-4 -0.4579669 0.8950573 9.89524e-5 -0.4459511 0.9465239 -2.23938e-4 -0.3226339 0.9537642 3.57144e-4 -0.3005558 0.9893695 -6.59579e-4 -0.1454229 0.9877063 -3.58713e-4 -0.1563207 0.9988734 5.97887e-4 -0.04745304 0.9993166 -6.0196e-4 0.03695839 0.9967558 -2.80611e-5 0.0804854 0.990569 -5.66685e-4 0.1370143 0.9748056 5.88833e-4 0.2230554 0.9519997 -1.72707e-4 0.3060991 0.9462729 7.5283e-5 0.3233693 0.9225906 -7.57241e-4 0.3857798 0.8783773 2.94628e-4 0.4779681 0.8573559 -9.87553e-5 0.5147241 0.8314414 5.60214e-4 0.5556125 0.7857865 -4.70975e-4 0.6184978 0.748191 3.63306e-4 0.6634834 0.6675897 -1.04706e-4 0.7445294 0.6589516 -4.17195e-4 0.7521852 0.5760706 4.42253e-4 0.8173998 0.550122 -1.2134e-4 0.8350843 0.4667042 5.65903e-4 0.8844133 0.4586446 3.55087e-4 0.8886197 0.338007 1.1586e-4 0.9411437 0.3290457 2.6625e-4 0.944314 0.2581431 -2.48428e-4 0.9661067 0.2106185 4.74041e-4 0.9775682 0.1091985 -2.75715e-4 0.99402 0.07738739 1.62765e-4 0.9970011 0.01160335 -4.39891e-4 0.9999327 -3.24955e-4 -0.999997 0.002412319 0.002260744 -0.9999952 -0.002129375 0.002014696 -0.9999979 4.26231e-4 -4.01463e-4 -0.9999999 2.34528e-4 -8.95839e-4 -0.9999966 0.002482533 0.001128017 -0.9999992 -6.91791e-4 -0.00417304 -0.9999912 6.63561e-4 0.001009464 -0.9999995 4.94153e-4 -0.001864194 -0.9999981 -5.80564e-4 -4.88602e-4 -0.9999948 -0.00319004 0.006010711 -0.9999819 -3.9361e-4 0.001433134 -0.9999986 9.26977e-4 -4.60918e-4 -0.9999958 -0.002853631 -0.001967132 -0.9999952 0.00243479 0.001768648 -0.999998 9.71856e-4 -0.003518581 -0.9999922 -0.001840174 -0.001566946 -0.9999934 0.003295302 0.001173019 -0.9999988 -0.00108093 0.002735078 -0.999996 7.335e-4 -0.001940488 -0.9999974 0.001218378 -0.002174973 -0.9999971 0.001058459 -0.003878653 -0.9999898 -0.00235331 0.001440227 -0.9999865 0.004998147 -0.001102149 -0.9999983 0.001474499 -0.002384364 -0.9999914 -0.003387868 0.001069307 -0.9999958 0.002716779 0.002222657 -0.9999976 -3.63883e-4 -0.004872739 -0.999988 -5.24227e-4 -0.003760516 -0.999993 -1.8974e-4 5.49795e-5 -1 -2.7736e-4 1.4096e-4 -1 -4.92128e-4 -0.001183927 -0.999998 0.001635372 0.003238379 -0.9999918 0.002450525 -0.00248593 -0.9999969 -3.17963e-4 0.00562936 -0.9999821 -0.002064943 0.003319442 -0.9999945 -3.63267e-4 -1.83368e-4 -0.9999976 -0.002224683 6.02582e-4 -0.999989 -0.004653036 0.001119375 -0.9999977 0.001875877 -9.43805e-5 -1 -3.29902e-4 9.30933e-4 -0.9999974 0.002104938 -0.004435896 -0.9999899 -6.88741e-4 0.001022219 -0.9999977 0.001886188 -0.002753734 -0.9999841 0.004940092 0.002948105 -0.99998 -0.005606174 -0.04371076 0.354649 0.9339773 0.003816545 0.8051243 0.5930939 -0.1295875 0.4379879 0.8895919 -0.14292 0.3963951 0.9068875 -0.1268526 0.7915269 0.5978241 -0.1092671 0.827241 0.5511198 -0.2378014 0.5840067 0.7761357 -0.295842 0.6216935 0.7252413 -0.2940196 0.524948 0.7987378 -0.1436677 0.9414609 0.3049771 -0.3849297 0.7139084 0.5849478 -0.4119572 0.6291134 0.6591719 -0.5146608 0.438296 0.7368996 -0.4583716 0.6425415 0.6140325 -0.3799288 -0.7356563 0.5607708 -0.4122387 0.7168735 0.5622738 -0.2803187 0.9230778 0.263342 -0.5692497 0.5703108 0.5921996 -0.5439147 0.6012142 0.5854044 -0.6067606 0.6137784 0.5050918 -0.7079187 0.4800553 0.5180714 -0.2855055 0.9249565 0.250883 -0.720699 0.5224347 0.455692 -0.7605373 0.4645963 0.4535785 -0.4603795 0.8314773 0.3109602 -0.3637689 0.9103979 0.1970987 -0.7458234 0.5655653 0.3519709 -0.9251751 0.2652642 0.2714517 -0.6506165 0.7154494 0.2546181 -0.4288047 0.8921286 0.1422433 -0.6131119 0.7887217 0.0448566 -0.7506633 0.6461735 0.1377124 -0.8024607 0.5966694 0.006523847 -0.8719479 0.4866611 0.0535528 -0.7035064 0.7101618 0.02736926 -0.9590976 0.2702175 -0.08434629 -0.6252192 0.7804192 -0.00685811 -0.7128722 0.7007086 0.0286501 -0.6861181 0.7159479 -0.1290756 -0.9310079 0.3088318 -0.1945441 -0.5295876 0.8337385 -0.1562601 -0.5273642 0.8160363 -0.2365841 -0.800395 0.4992335 -0.3318641 -0.84166 0.4298608 -0.3268455 -0.5717517 0.7739008 -0.2723557 -0.7926623 0.4277493 -0.4344158 -0.3597292 0.9060994 -0.2226633 -0.7147461 0.5480585 -0.4344766 -0.6064054 0.60727 -0.5133184 -0.4188261 0.8314307 -0.3651134 -0.4904492 0.741707 -0.4575263 -0.5996043 0.6330429 -0.4896237 -0.3529355 0.7858453 -0.5078225 -0.4375281 0.7179268 -0.5414337 -0.3885586 0.6965826 -0.6031542 -0.4912248 0.430418 -0.7572573 -0.3693485 0.676297 -0.6373415 -0.1658001 0.9424169 -0.2904495 -0.3148704 0.6793461 -0.6628314 -0.2117496 0.6037088 -0.7685688 -0.269584 0.4528973 -0.8498286 -0.06461185 0.9714717 -0.2281842 -0.1091561 0.6708218 -0.7335415 -0.0270698 0.5182232 -0.8548169 -0.1058666 -0.1129608 -0.9879435 -0.01221811 0.5758482 -0.8174654 -0.02364319 0.8590301 -0.5113789 0.1170087 0.4778678 -0.8706041 0.1481506 0.5954647 -0.7896032 0.04446208 0.9034279 -0.4264286 0.1630337 0.7837591 -0.5992845 0.2682237 0.4409979 -0.856491 0.2681294 0.4387941 -0.8576517 0.1433438 0.889294 -0.434291 0.3597239 0.5939202 -0.7196232 0.3701903 0.5807247 -0.7250641 0.2696446 0.8446219 -0.4624993 0.463786 0.4914874 -0.7371178 0.3494765 0.8222801 -0.4491342 0.6336061 0.373438 -0.67756 0.5731771 0.5055509 -0.6448925 0.4005188 0.8150829 -0.4185985 0.4087077 0.8074714 -0.4253798 0.583191 0.6357815 -0.5056385 0.6748573 0.556712 -0.484396 0.2948527 0.930302 -0.2181746 0.7618573 0.4153109 -0.4970819 0.8133057 0.4338532 -0.3876922 0.8076866 0.4436706 -0.3883281 0.5361579 0.8060213 -0.2507281 0.5889042 0.7625698 -0.2677298 0.7875897 0.5457265 -0.2861556 0.932902 0.2893579 -0.2143965 0.4490293 0.8816759 -0.1449841 0.8224918 0.5587137 -0.1065191 0.7232267 0.6871235 -0.06931412 0.8141242 0.5705105 -0.1082569 0.8887389 0.4579001 0.02169787 0.4513564 -0.8922686 -0.0115841 0.7445282 0.6647958 0.06102776 0.5981244 0.8006311 0.03517484 0.7964479 0.5830252 0.1604759 0.6094127 0.7922161 0.03177928 0.8830205 0.401132 0.2436552 0.599353 0.7675604 0.2272158 0.7372164 0.5837457 0.340225 0.7789122 0.5330934 0.3303139 0.1335768 -0.98857 0.06990438 0.7267213 0.6091173 0.3175725 0.7072908 0.5682311 0.4205393 0.5659856 0.7252616 0.3919897 0.5739948 0.687471 0.4448749 0.5649815 0.5725331 0.5941396 0.4061726 0.8305685 0.3810247 0.5188847 0.6265213 0.5815754 0.5157125 0.4789934 0.7103562 0.1860384 0.9378951 0.2928183 0.4298563 0.6178928 0.6583557 0.2927549 0.7086344 0.6419749 0.4304271 -0.157489 0.8887799 0.3385955 0.3729295 0.8638731 0.2507231 0.6234618 0.7405629 0.1113956 0.9483104 0.2971503 0.1618081 0.6748763 0.7199723 0.1394657 0.3849215 0.9123513 0.06813102 0.6542039 0.7532434 0.005632877 0.4963575 0.8681001 0.06103736 0.9300809 0.3622485 0.02120548 0.7566959 0.653423 0.003336548 0.9999924 0.002076685 -0.001472294 0.9999988 4.98748e-4 2.89029e-4 1 -2.89799e-4 8.16928e-4 0.9999997 2.63484e-4 -0.003647327 0.9999898 -0.002695143 0.003132939 0.999995 3.88642e-4 -0.001323282 0.9999968 -0.002192199 -0.00483632 0.9999871 -0.001634061 0.001011729 0.9999983 0.001525163 -2.80212e-4 0.9999997 -7.84921e-4 0.001339852 0.9999991 -5.73895e-5 5.51789e-4 0.9999998 -1.89973e-4 0.001526474 0.9999988 4.43878e-4 6.1662e-4 0.999998 0.001961827 -1.17953e-4 1 -3.8692e-5 0.004667758 0.9999891 -2.27043e-4 0.001610159 0.9999954 -0.002569913 0.002949357 0.999993 0.002351641 6.65666e-4 0.9999978 -0.002004027 -1.26742e-4 1 -6.92879e-5 -0.008922457 0.9999438 0.005726814 -0.001239776 0.9999984 0.001284241 -8.39362e-4 0.9999995 -7.32141e-4 -7.90316e-5 0.9999999 5.29279e-4 4.08201e-4 0.9999998 4.83785e-4 -0.001949131 0.9999974 0.001190543 -0.002396047 0.9999964 -0.001292109 0.002105295 0.9999976 -7.08186e-4 0.004377067 0.9999905 -2.63288e-4 -0.002545833 0.9999966 7.46448e-4 0.002776622 0.9999962 3.88426e-5 -0.001277267 0.9999967 -0.002232432 0.00221771 0.9999896 0.004010915 -0.005208432 0.999983 -0.00264132 -0.00796473 0.9999648 -0.002654373 0.001214027 0.9999986 -0.00119543 -3.2889e-5 1 2.13268e-4 5.56857e-5 1 3.51987e-4 0.001400113 0.9999986 -9.68626e-4 0.002278625 0.9999964 0.001395046 -0.996231 0.009355425 -0.08623474 -0.9365804 -0.003541767 -0.350435 -0.9370734 -0.002940297 -0.3491204 -0.8162819 0.002424597 -0.5776487 -0.8075432 -0.002430438 -0.5898034 -0.6358355 0.002770483 -0.7718196 -0.6238817 -0.003276467 -0.781512 -0.349406 0.003637015 -0.9369645 -0.3346038 -0.003635585 -0.9423519 -0.007880151 0.003637492 -0.9999623 0.00787729 -0.003636956 -0.9999625 0.3112187 0.003102719 -0.9503332 0.3414763 -0.008402884 -0.9398529 0.5222975 0.009628236 -0.852709 0.6098952 -0.01387751 -0.7923606 0.7277773 0.01699823 -0.6856029 0.8113934 -0.01655274 -0.584266 0.92153 0.01169568 -0.3881312 0.941458 -0.007977366 -0.3370362 0.9965131 0.01290196 -0.08243358 0.9995058 -0.02221113 0.02224773 0.9781904 0.01845967 0.2068887 0.9194704 -0.01334375 0.3929327 0.8804863 0.01334702 0.4738838 0.7837984 -0.01533508 0.620826 0.6515895 -0.001730382 0.7585698 0.6253657 0.01586657 0.7801705 0.4049218 0.005272567 0.9143362 0.3449524 -0.01317369 0.9385278 0.2097634 0.0114566 0.977685 0.02522802 -0.01872378 0.9995064 -0.07781815 0.01455092 0.9968614 -0.3272788 -0.006496548 0.9449055 -0.3336333 -0.009146332 0.9426587 -0.5292943 0.01036119 0.8483752 -0.6231357 -0.01899802 0.781883 -0.7499826 0.02125 0.6611162 -0.855807 -0.01821768 0.5169747 -0.9225221 0.01397603 0.3856911 -0.9618473 -0.01071143 0.2733774 -0.9914673 0.009553194 0.1300053 -0.9998881 -0.01391208 -0.005507647 0.9764488 0.01553225 0.2151897 0.9339485 -0.0171929 0.3569942 0.8856309 0.01374626 0.4641865 0.7928435 -0.01236039 0.6093 0.7036547 0.00896871 0.7104855 0.6498489 -0.007362604 0.7600278 0.4990922 0.01562976 0.866408 0.3810563 -0.022475 0.9242787 0.1733115 0.01982831 0.9846675 0.04195636 -0.01845991 0.9989489 -0.1332171 0.0157206 0.9909623 -0.2860811 -0.01342731 0.9581114 -0.389095 0.01154357 0.9211253 -0.5469132 -0.01562881 0.8370436 -0.6240779 0.01176828 0.7812735 -0.7839763 -0.001725852 0.6207885 -0.8038024 -0.01417231 0.5947275 -0.9125145 0.01332098 0.4088275 -0.9587169 -0.01579725 0.2839235 -0.9842864 0.01099503 0.1762371 -0.9992912 -0.01111376 -0.03596991 -0.996075 0.006983518 -0.088238 -0.9386132 -0.004962742 -0.3449358 -0.9225652 0.01074534 -0.3856917 -0.819608 -0.01369464 -0.5727611 -0.7405632 0.01264721 -0.6718677 -0.6531966 -0.01265102 -0.7570827 -0.5379377 0.0172047 -0.8428091 -0.3547585 -0.0205841 -0.9347314 -0.2416047 0.01786899 -0.9702102 -0.01364207 -0.01652383 -0.9997705 0.1026014 0.01970797 -0.9945274 0.2892595 -0.01779437 -0.9570853 0.4586831 0.01591116 -0.8884574 0.5170972 -0.004882276 -0.8559128 0.7075842 0.002178847 -0.7066257 0.7048653 8.91297e-4 -0.7093406 0.8450218 -0.002129197 -0.5347277 0.8559041 0.004594862 -0.5171145 0.9678064 0.004568576 -0.2516547 0.9588431 -0.006983637 -0.283851 0.9997146 -0.001132905 -0.0238685 0.9999247 -0.01097249 0.005507886 0.8906052 0.4545885 -0.01309919 0.5473348 0.8368625 -0.009263873 0.9051415 0.4189648 -0.0720238 0.3040053 0.9526687 -0.001755177 0.8626174 0.4961268 -0.09874045 0.6678748 0.7385423 -0.09218764 0.1245834 0.9920769 -0.01620602 0.6274843 0.7711341 -0.1077769 0.9219281 0.325621 -0.2098082 0.2913337 0.9545107 -0.063515 0.8687196 0.4379357 -0.2313843 0.6803532 0.7090019 -0.185569 0.5689985 0.7961034 -0.2060587 0.8818497 0.3168854 -0.3491774 0.900674 0.2665258 -0.3431479 0.6700659 0.687237 -0.2805655 0.571448 0.7994949 -0.1850817 0.8262135 0.3655846 -0.4286249 0.6596446 0.6838026 -0.3119023 0.8323624 0.2810909 -0.4776617 0.2665473 0.9550696 -0.1295943 0.5071093 0.8048358 -0.3083497 0.774679 0.3970333 -0.4921758 0.5869968 0.7117147 -0.3858718 0.5058721 0.809197 -0.2988207 0.746766 0.3260429 -0.5796867 0.7073075 0.4116515 -0.5746818 0.5796871 0.6732898 -0.4589595 0.28675 0.9293339 -0.2326225 0.4916141 0.7548155 -0.4342455 0.4110475 0.8334118 -0.3694115 0.6594914 0.4175381 -0.6250866 0.5902199 0.5453859 -0.5951427 0.1009946 0.9906034 -0.09222346 0.5899934 0.3202318 -0.7411879 0.5393831 0.5602787 -0.6286126 0.4493869 0.6876646 -0.5702358 0.3149467 0.8656322 -0.3892166 0.2551213 0.9084749 -0.3310387 0.4861621 0.3661934 -0.7934411 0.4855918 0.3800151 -0.787267 0.4254145 0.5974417 -0.6797691 0.3409776 0.7199898 -0.6044411 0.216809 0.9243965 -0.3138233 0.09651243 0.9801368 -0.173255 0.4146868 0.2993068 -0.8593313 0.2957919 0.7302101 -0.6158736 0.3655179 0.4241936 -0.8285268 0.3103333 0.6012923 -0.7363021 0.1533522 0.9107709 -0.3833792 0.2846207 0.2277094 -0.9312033 0.2866061 0.2653313 -0.9205739 0.2358947 0.6236959 -0.7452229 0.213889 0.6605647 -0.7196568 0.1367551 0.868571 -0.4763219 0.1285732 0.9055284 -0.4043357 0.167097 0.4328629 -0.8858377 0.1595773 0.549051 -0.8204134 0.1388474 0.2692426 -0.9530109 0.08326637 0.707308 -0.7019845 0.0637539 0.8604134 -0.505593 0.03971046 0.4614402 -0.8862822 0.04858303 0.6268932 -0.777589 -0.003968477 0.3512986 -0.9362552 0.02675008 0.919855 -0.3913454 -0.03479802 0.8306992 -0.5556331 -0.06230044 0.4691424 -0.8809224 -0.004174113 0.8396951 -0.5430422 -0.04383403 0.8735522 -0.484753 -0.1177534 0.4485791 -0.8859521 -0.1312994 0.497049 -0.8577313 -0.08972805 0.8187535 -0.5670907 -0.2399336 0.3879635 -0.8898968 -0.1975457 0.4984459 -0.8441135 -0.02614742 0.9924979 -0.1194337 -0.1532329 0.8351446 -0.5282548 -0.1502515 0.8198678 -0.5524865 -0.3095166 0.3667476 -0.877323 -0.3217087 0.4474024 -0.8344667 -0.07637906 0.9646371 -0.252273 -0.2312455 0.7487611 -0.6211944 -0.3808483 0.4420397 -0.8121303 -0.3862072 0.5508409 -0.7398773 -0.2667135 0.7791471 -0.5672688 -0.4949769 0.3645998 -0.7887109 -0.1593917 0.9422806 -0.2944517 -0.1841009 0.9252578 -0.3316701 -0.4211876 0.5245413 -0.7399037 -0.5384689 0.4478756 -0.7137637 -0.2512425 0.8979548 -0.3613232 -0.570301 0.3994867 -0.7177515 -0.4129149 0.6989836 -0.5838865 -0.3164987 0.8469642 -0.427177 -0.5827057 0.4689974 -0.6636984 -0.5434626 0.6400177 -0.5431628 -0.3734499 0.8290176 -0.416251 -0.7008531 0.4009879 -0.5899268 -0.2141493 0.9568294 -0.1965136 -0.1011441 0.9893243 -0.1049169 -0.5665332 0.6299782 -0.5311946 -0.5230291 0.7415626 -0.4201496 -0.7443368 0.3994502 -0.5351657 -0.7409441 0.4171577 -0.5262903 -0.2819015 0.9321962 -0.2270285 -0.6088923 0.6689769 -0.4262865 -0.8355896 0.2805498 -0.4723155 -0.2756665 0.9441592 -0.1804761 -0.6141653 0.7179284 -0.3276889 -0.5684479 0.7492754 -0.3397844 -0.8287328 0.3544682 -0.4330756 -0.8706666 0.2936443 -0.3946046 -0.1881145 0.9766703 -0.1035761 -0.5917504 0.758215 -0.2737545 -0.3848743 0.9097967 -0.155376 -0.8411136 0.443104 -0.3101401 -0.7456476 0.6073334 -0.2741459 -0.8955424 0.3321307 -0.2961301 -0.385997 0.9129626 -0.1323095 -0.6073353 0.7788154 -0.1568135 -0.9309179 0.298478 -0.2104824 -0.6192387 0.7715318 -0.1458837 -0.9016519 0.3979285 -0.1693419 -0.8209424 0.5509749 -0.1499341 -0.9606007 0.2496399 -0.1221734 -0.1208258 0.992479 -0.01966017 -0.4707328 0.8795532 -0.06926041 -0.1988238 0.979749 -0.02369058 -0.9409739 0.334739 -0.05017757 -0.7503744 0.6609634 -0.008110582 -0.7900914 0.6125288 -0.02375119 -0.6217481 0.7829635 -0.01994097 -0.4775742 0.8784999 0.01268053 -0.9066287 0.4120368 0.09082943 -0.8283418 0.5584694 0.04429578 -0.4659833 0.8823083 0.06627053 -0.4769813 0.8768206 0.06061887 -0.9031586 0.4096422 0.128444 -0.8027996 0.5731436 0.1643753 -0.5004442 0.8621416 0.07916796 -0.8011802 0.5538499 0.2266289 -0.8196219 0.5174649 0.2458659 -0.4695981 0.8740571 0.1245067 -0.3923425 0.91082 0.1283528 -0.8425689 0.4145639 0.3438233 -0.8037767 0.512503 0.3021323 -0.5618551 0.7887101 0.24951 -0.7992545 0.4227585 0.4271623 -0.0920785 0.9949277 0.04050302 -0.8243414 0.3131525 0.4715899 -0.5751823 0.748749 0.3294547 -0.5361234 0.7891558 0.299675 -0.4103857 0.8775252 0.2480589 -0.7451158 0.400424 0.533351 -0.7449899 0.4013014 0.5328669 -0.6542997 0.6022725 0.4573399 -0.7002193 0.321224 0.63758 -0.6912705 0.4216054 0.5868508 -0.4870455 0.7604714 0.4294999 -0.4839466 0.7634615 0.4276943 -0.6715992 0.3318871 0.6624239 -0.3532854 0.8874356 0.2960531 -0.1902716 0.964408 0.1836139 -0.5430255 0.5725183 0.6142852 -0.4763605 0.7180181 0.5074747 -0.5310446 0.527108 0.6634372 -0.3044237 0.8779948 0.3693933 -0.4731136 0.5745226 0.6678978 -0.2769075 0.8655198 0.4173703 -0.468122 0.4550403 0.7574959 -0.2457922 0.8840342 0.39758 -0.4416868 0.4719066 0.7630314 -0.3286258 0.6887856 0.6462039 -0.2483878 0.8636931 0.4385632 -0.4190912 0.3013426 0.8564784 -0.3541784 0.4066978 0.8421131 -0.3065009 0.6227455 0.7198926 -0.3239358 0.2757486 0.9050019 -0.1327946 0.9239545 0.3587113 -0.1991634 0.7565834 0.6228287 -0.1696778 0.8144344 0.554893 -0.2233967 0.4658064 0.8562234 -0.1878081 0.4080432 0.8934366 -0.04289895 0.9891624 0.1404193 -0.112722 0.8426936 0.5264611 -0.0663942 0.917035 0.3932412 -0.1364789 0.4864732 0.8629701 -0.1028792 0.6549307 0.7486533 -0.08791559 0.3057677 0.9480386 -0.04227209 0.9227648 0.3830381 -0.02430617 0.7441532 0.6675668 -0.00455743 0.3703607 0.9288768 5.71218e-4 0.3920326 0.9199512 -0.01827186 0.738107 0.6744363 0.0332843 0.8046203 0.5928561 0.08455574 0.381532 0.9204802 0.1004686 0.4394002 0.8926554 0.01032358 0.9894649 0.1444047 0.08361244 0.6969828 0.7121967 0.03178274 0.9648742 0.2607831 0.1717665 0.3894594 0.9048854 0.2074292 0.6033724 0.7700097 0.1545218 0.7317786 0.6637945 0.2905616 0.3897576 0.8738782 0.1147714 0.8841302 0.4529253 0.230206 0.5850136 0.7776659 0.2521256 0.7078505 0.6598337 0.1451786 0.8904827 0.4312353 0.3738509 0.3180805 0.8712407 0.3896381 0.4416247 0.8081768 0.3006197 0.6780883 0.6706892 0.4295933 0.3980228 0.8105725 0.2890138 0.7920037 0.5377743 0.1118159 0.9696162 0.2175816 0.1207493 0.9657111 0.2298295 0.4359866 0.6341186 0.6385996 0.4168527 0.6362077 0.6492101 0.5586371 0.3603227 0.7470557 0.3681344 0.8068742 0.4619861 0.6097605 0.3176157 0.7261627 0.2646837 0.9047423 0.3337426 0.4500527 0.7354453 0.5065302 0.6003456 0.4592065 0.6547631 0.6870186 0.3905982 0.6127303 0.1580157 0.9748646 0.1570672 0.6773635 0.4671204 0.568311 0.5471044 0.716955 0.432033 0.4814258 0.7824262 0.395017 0.7890064 0.2767378 0.5485302 0.33156 0.9041867 0.2692852 0.772834 0.4126755 0.4821065 0.6130834 0.6718397 0.4156444 0.2601537 0.9535892 0.151617 0.8176721 0.3780822 0.4341269 0.8141019 0.3948783 0.425804 0.627461 0.7170039 0.3036417 0.5412467 0.7934733 0.2783026 0.4201552 0.882606 0.2108939 0.8626634 0.3728408 0.3417625 0.845298 0.4301028 0.3169904 0.7198653 0.6369363 0.2758737 0.8984915 0.3568257 0.2557119 0.5992047 0.7819396 0.1718267 0.5557752 0.8167811 0.1548639 0.3882563 0.9128186 0.1265676 0.8647473 0.4596895 0.2022324 0.1671763 0.9850883 0.04066121 0.8982891 0.4119805 0.1528037 0.5137026 0.8537372 0.08510166 0.8695644 0.4792857 0.1189244 0.3260406 0.9440955 0.04879885 0.6372733 0.767472 0.06978207 0.9371305 0.347841 0.02816182 0.619127 0.7852253 0.0101509 0.9934858 -0.00876367 -0.113619 0.9962729 0.0133571 -0.08521765 0.9731344 0.01149046 -0.2299513 0.9758958 6.62439e-5 -0.2182374 0.9479393 -0.0160157 -0.3180482 0.924966 0.01889079 -0.3795802 0.9327399 -0.005943834 -0.3605012 0.8709402 -0.003709256 -0.4913752 0.8655538 0.006788432 -0.5007702 0.8064938 -0.01901489 -0.5909369 0.7584153 -0.0117852 -0.6516652 0.7849402 0.002155661 -0.6195678 0.6838006 8.33486e-4 -0.7296684 0.7068242 0.01518839 -0.7072262 0.5940468 -0.01744151 -0.8042414 0.6407752 0.02007812 -0.7674661 0.5220568 -0.00500375 -0.8528961 0.5286638 -0.01383459 -0.8487186 0.3887112 -0.02284216 -0.9210765 0.4255648 0.007714688 -0.9048951 0.2929136 0.01713764 -0.9559854 0.2627404 -0.009060204 -0.9648241 0.1378981 0.004963636 -0.9904341 0.1433106 7.59794e-4 -0.9896776 0.0538184 -0.02648818 -0.9981995 -0.003782689 0.002829134 -0.9999889 -0.0442748 -0.02055752 -0.9988079 -0.2064483 -0.01551508 -0.9783346 -0.1472754 0.01857966 -0.9889211 -0.2375305 -0.001831948 -0.9713784 -0.2880942 -0.01561814 -0.9574747 -0.3437239 0.01047444 -0.9390124 -0.3894012 -0.007150709 -0.9210406 -0.4362004 0.01430982 -0.8997358 -0.4843918 -0.004311263 -0.8748407 -0.5177552 0.01733523 -0.8553532 -0.5928035 -0.007547676 -0.8053118 -0.609391 -5.08062e-4 -0.7928698 -0.6316878 -0.01159089 -0.7751362 -0.6918494 0.01868265 -0.7218002 -0.7225587 0.003292918 -0.6913017 -0.7386784 0.01186823 -0.6739537 -0.7763771 -0.009616017 -0.6301955 -0.8108935 0.01121729 -0.5850865 -0.8466892 -0.01532536 -0.5318671 -0.8642361 -0.003708124 -0.5030728 -0.8852611 -0.02324986 -0.4645132 -0.9143687 0.0130546 -0.4046722 -0.9463123 -0.01161807 -0.3230451 -0.947754 -0.009098529 -0.3188724 -0.9701128 -0.01834815 -0.2419601 -0.9741526 -0.004990458 -0.2258358 -0.9924871 -0.005038321 -0.1222457 -0.9923379 -0.006222367 -0.1233971 -0.9998769 0.01373732 -0.007584512 -0.9997546 -0.002649188 0.02200007 -0.9983179 0.01618343 0.05567371 -0.9855922 -0.008882999 0.1689059 -0.9822565 0.006525993 0.1874293 -0.9662958 0.01207262 0.2571511 -0.9616498 -5.23091e-4 0.2742796 -0.9291784 0.01675993 0.3692514 -0.9163952 -0.01036608 0.4001405 -0.8642138 0.008303165 0.5030563 -0.8706238 -0.004477918 0.491929 -0.8124163 -0.004147469 0.583063 -0.8088452 6.2162e-4 0.5880213 -0.7509975 3.43106e-4 0.660305 -0.7538184 -0.002929151 0.6570764 -0.6758462 -0.002432405 0.7370387 -0.6760225 -0.002640426 0.7368763 -0.6009016 -0.002520978 0.799319 -0.6154145 0.007123112 0.7881715 -0.5287059 -0.01668703 0.8486411 -0.5585289 0.005516111 0.8294669 -0.4508888 -0.01384985 0.8924728 -0.4429729 -0.005742728 0.8965166 -0.3411153 -0.00562191 0.9400047 -0.3324222 0.00382936 0.943123 -0.2061498 2.02774e-4 0.9785204 -0.2051112 0.001195609 0.978738 -0.1039925 3.19797e-4 0.9945781 -0.08255451 -0.0175991 0.9964311 0.001805186 0.00294584 0.9999941 0.04453092 -0.01818001 0.9988426 0.1521683 -0.0127049 0.988273 0.102348 0.005836308 0.9947316 0.2098735 0.01962816 0.9775316 0.2839013 1.11814e-4 0.9588536 0.2898821 0.004414916 0.9570522 0.385736 -3.71118e-4 0.9226092 0.3890727 0.002313137 0.9212043 0.4806828 5.304e-4 0.8768944 0.4950705 0.0137425 0.8687441 0.5745161 -0.01329272 0.8183854 0.5539633 0.006421864 0.8325164 0.6448416 -0.01197004 0.7642225 0.6548088 8.74797e-5 0.7557946 0.738739 -1.27022e-4 0.6739917 0.7441943 -0.008197128 0.667913 0.8090204 -0.001113057 0.5877796 0.8165456 0.009185135 0.5772081 0.8656323 -0.01205742 0.5005351 0.9138249 -0.01253247 0.4059152 0.8874871 0.01235055 0.4606671 0.9295757 0.01027524 0.3684881 0.9568575 0.007224142 0.2904679 0.9620046 -0.01121139 0.2728031 0.9757009 -0.01536279 0.2185677 0.9915861 -0.01660019 0.1283809 0.9863237 0.004410266 0.1647607 0.9997374 -0.004907965 0.02238458 0.9994394 0.003398895 0.03330844 0.9379331 -0.346803 0.003033339 0.839468 -0.5414059 0.04661911 0.6868091 -0.7268129 0.006025373 0.4439468 -0.8952995 0.03674346 0.8565073 -0.5063297 0.1001277 0.7828392 -0.6041864 0.1487338 0.5379513 -0.8363274 0.1056643 0.8354197 -0.5126816 0.1980701 0.4084728 -0.9050418 0.1185305 0.831919 -0.4830504 0.2730812 0.8014456 -0.5230337 0.290036 0.5101146 -0.8339374 0.2105503 0.8525355 -0.3514816 0.3868386 0.4938947 -0.8422467 0.2160754 0.8032228 -0.4173468 0.4250349 0.5755432 -0.7502549 0.3253732 0.8180427 -0.3197157 0.4781088 0.1210342 -0.9897665 0.07558369 0.5361378 -0.7688985 0.3483555 0.7583943 -0.3753235 0.5328887 0.7253009 -0.4423074 0.5275442 0.6288834 -0.6272872 0.4593653 0.3009625 -0.9265572 0.2256403 0.7041099 -0.3298178 0.6288478 0.5861389 -0.5578531 0.5875724 0.5192518 -0.7055256 0.482298 0.3654714 -0.8609567 0.3538142 0.5518214 -0.5330897 0.6413335 0.5117669 -0.5852681 0.6289323 0.2903574 -0.8973981 0.3322187 0.2646762 -0.9126141 0.3115801 0.5031726 -0.4012597 0.765381 0.4803583 -0.563991 0.6716919 0.2270033 -0.9169722 0.3280724 0.3205566 -0.7706836 0.5507181 0.4405487 -0.3760985 0.8151484 0.4402021 -0.37098 0.8176773 0.3158228 -0.7588547 0.5695575 0.2738069 -0.7803034 0.562278 0.3628153 -0.3762545 0.8525244 0.3420684 -0.4223787 0.8393959 0.04977178 -0.9934298 0.1030542 0.2700329 -0.7167589 0.6429145 0.2664718 -0.3611707 0.8936155 0.1254224 -0.9405409 0.3156774 0.1554648 -0.8152968 0.5577829 0.228774 -0.4488533 0.8638248 0.1571699 -0.8171849 0.5545329 0.1070862 -0.8502101 0.5154372 0.14968 -0.4197498 0.8952129 0.1147274 -0.5083141 0.8534955 0.09318804 -0.7961311 0.5979058 0.02561604 -0.9775241 0.2092624 0.0458222 -0.4717646 0.8805332 0.01057684 -0.5559449 0.8311519 -0.004849076 -0.6916261 0.7222395 0.01539874 -0.8319935 0.5545718 -6.9831e-4 -0.9158868 0.4014362 -0.08947861 -0.3273607 0.9406533 -0.01731359 -0.9257233 0.3778049 -0.07395607 -0.7315146 0.677803 -0.07341283 -0.795548 0.6014265 -0.1326534 -0.4745195 0.8701921 -0.1980529 -0.3477557 0.9164283 -0.1760749 -0.4261026 0.8873749 -0.02603107 -0.9891011 0.1449188 -0.1240679 -0.8658618 0.484655 -0.09014385 -0.9418706 0.3236572 -0.204951 -0.7221422 0.6606859 -0.3067556 -0.3500782 0.8850686 -0.3075817 -0.4588593 0.8335717 -0.2315285 -0.691825 0.6839392 -0.3751313 -0.4721529 0.7977144 -0.3684077 -0.5662869 0.737289 -0.2673993 -0.7749985 0.5726038 -0.2266079 -0.865059 0.4475731 -0.131232 -0.9465882 0.294532 -0.2641722 -0.8554231 0.4454936 -0.4523313 -0.5549266 0.6981782 -0.4531515 -0.6091651 0.6508238 -0.5375332 -0.4948033 0.6828088 -0.4532429 -0.6091246 0.6507982 -0.3413854 -0.8518942 0.3971552 -0.6435743 -0.3676964 0.6712761 -0.2162296 -0.9369251 0.2746199 -0.5732179 -0.5001058 0.6490882 -0.4476651 -0.7708824 0.4531406 -0.06822627 -0.9950346 0.0724675 -0.6911727 -0.3746138 0.6180168 -0.6817112 -0.443659 0.5817531 -0.4696056 -0.773353 0.4259057 -0.5172575 -0.7298919 0.4468808 -0.2234901 -0.9586027 0.1764454 -0.7526828 -0.3558301 0.5539439 -0.2885224 -0.9391646 0.1863454 -0.7433025 -0.4682642 0.4777342 -0.5459955 -0.7554031 0.3622915 -0.8329225 -0.2846997 0.474538 -0.6226374 -0.6819328 0.3837845 -0.2551254 -0.9567095 0.1400643 -0.8698348 -0.3201047 0.3753938 -0.8319441 -0.4056957 0.3785239 -0.6430858 -0.7054279 0.2980138 -0.652657 -0.6967535 0.297613 -0.1224419 -0.9913234 0.04781299 -0.6325168 -0.7441975 0.2146924 -0.8933882 -0.3597647 0.2691228 -0.8637174 -0.4397435 0.2462068 -0.2428327 -0.9674935 0.07063138 -0.6969839 -0.6860215 0.2087777 -0.9191518 -0.365891 0.1458898 -0.8977919 -0.4126056 0.154034 -0.6883652 -0.7140446 0.1276473 -0.3582171 -0.9319505 0.05611401 -0.5827854 -0.8090081 0.07659733 -0.9132207 -0.4024121 0.0639736 -0.9719312 -0.2344695 0.01933729 -0.7377429 -0.67472 0.02210217 -0.6254941 -0.7793374 0.03728914 -0.9161821 -0.3987767 -0.03984433 -0.7837051 -0.6206784 -0.02376633 -0.4230856 -0.9060263 -0.01072067 -0.288282 -0.9574729 -0.01180827 -0.1895056 -0.9818795 4.6376e-4 -0.6786314 -0.7313935 -0.06725311 -0.9462109 -0.3055416 -0.1064395 -0.8773965 -0.4567468 -0.1468256 -0.7024514 -0.7018931 -0.117933 -0.6737018 -0.7282955 -0.1253467 -0.911 -0.3599928 -0.2012068 -0.3556157 -0.9307996 -0.08455604 -0.2958371 -0.9530829 -0.06413608 -0.742878 -0.6267864 -0.2350981 -0.7385753 -0.6296355 -0.2409685 -0.8440973 -0.4201148 -0.333172 -0.5336069 -0.8204708 -0.2051622 -0.437636 -0.8837421 -0.165755 -0.8232003 -0.4109358 -0.3917567 -0.6744083 -0.635336 -0.3761938 -0.2468342 -0.9610256 -0.1245102 -0.6563813 -0.650055 -0.3828737 -0.7693528 -0.3594632 -0.5280933 -0.3003267 -0.9379935 -0.1731247 -0.6563739 -0.6497324 -0.3834335 -0.5420981 -0.7420279 -0.3943657 -0.7319579 -0.3745357 -0.5691755 -0.3330893 -0.9059498 -0.2613554 -0.6543135 -0.5177258 -0.5512114 -0.6496506 -0.3856182 -0.6551738 -0.2932355 -0.9236965 -0.2465719 -0.6214216 -0.5139455 -0.5913504 -0.4417835 -0.7574685 -0.4806964 -0.3562729 -0.8531112 -0.3811443 -0.6197566 -0.3294047 -0.7123162 -0.4732388 -0.5901157 -0.6540708 -0.4866635 -0.4565733 -0.7447816 -0.2203903 -0.9321448 -0.2872879 -0.4772343 -0.5896593 -0.6515746 -0.02260607 -0.9992383 -0.03180789 -0.2576856 -0.8744007 -0.4111222 -0.4428853 -0.4121068 -0.7962542 -0.4384554 -0.4188624 -0.79518 -0.2343722 -0.8822343 -0.4083289 -0.1436759 -0.9472606 -0.2864518 -0.3055954 -0.7132738 -0.6307551 -0.3727243 -0.3262187 -0.8687105 -0.2952882 -0.4746531 -0.8291619 -0.2779656 -0.5317324 -0.7999973 -0.2608882 -0.7059103 -0.6585044 -0.1519747 -0.8794068 -0.4511623 -0.1778795 -0.6187674 -0.7651705 -0.1112638 -0.8950299 -0.4319051 -0.1668597 -0.3622823 -0.9170111 -0.1644425 -0.5715897 -0.8038931 -0.09326303 -0.9148538 -0.3928671 -0.07005745 -0.331926 -0.9407004 -0.03952485 -0.9139347 -0.4039322 -0.02152568 -0.6987975 -0.7149957 -0.04825234 -0.6293494 -0.7756232 -0.009153544 -0.9538004 -0.3003017 0.01803338 -0.6431593 -0.76552 0.04866063 -0.5790877 -0.8138117 0.03798019 -0.8678733 -0.4953318 0.1079993 -0.6013919 -0.7916212 0.08740162 -0.8512494 -0.5174317 0.1762086 -0.4397395 -0.8806701 0.2207814 -0.4302186 -0.8753101 0.2336666 -0.5000094 -0.8339008 0.1838365 -0.7528662 -0.6319783 0.09567368 -0.8674244 -0.4882842 0.07055467 -0.9611969 -0.2666885 0.2125157 -0.8395068 -0.5000656 0.3602073 -0.400328 -0.842608 0.3666961 -0.4955082 -0.7874043 0.2330218 -0.8309521 -0.5051925 0.2325685 -0.8362723 -0.4965489 0.1232643 -0.9661887 -0.2264622 0.4600056 -0.4185985 -0.7830517 0.4576624 -0.59157 -0.6637697 0.3197817 -0.8105306 -0.4906935 0.2872883 -0.8624017 -0.4168078 0.5750501 -0.3973014 -0.7151707 0.5211269 -0.5223141 -0.6749925 0.6498454 -0.2853543 -0.7044672 0.280106 -0.8985021 -0.3379864 0.4517334 -0.752064 -0.479934 0.3775363 -0.835267 -0.3997443 0.06433224 -0.9959824 -0.06229358 0.6617624 -0.4287475 -0.6150172 0.6351989 -0.5164397 -0.5742929 0.3469642 -0.8885241 -0.3002346 0.6367195 -0.5783736 -0.5099729 0.7480589 -0.413342 -0.5191881 0.4602292 -0.8194672 -0.3415593 0.7618678 -0.4534077 -0.4625787 0.8024488 -0.3899469 -0.4516829 0.4477436 -0.8532004 -0.2675347 0.4621992 -0.8445405 -0.2704131 0.7680573 -0.5380211 -0.347306 0.7891675 -0.5110877 -0.3405941 0.5034813 -0.8272658 -0.2492749 0.8107118 -0.5196192 -0.269708 0.3953526 -0.9076232 -0.1411263 0.799144 -0.546667 -0.2500483 0.6643476 -0.7260674 -0.1773934 0.9247591 -0.3256157 -0.1969647 0.2290685 -0.9711117 -0.06685644 0.9001026 -0.4133576 -0.1376627 0.6553764 -0.7434235 -0.1334289 0.5340248 -0.8423286 -0.07280296 0.9241045 -0.367577 -0.1044907 0.9068717 -0.4139463 -0.07894432 0.6802374 -0.7324007 -0.02943527 0.5339489 -0.8429179 -0.06624358 0.2322871 -0.9726414 0.003403007 0.001268625 -0.9999985 0.001277744 0.001977324 -0.9999981 -5.29297e-5 5.40022e-4 -0.9999995 9.34099e-4 -0.001106142 -0.9999917 0.003931224 0.002952873 -0.9999955 5.85312e-4 0.00176078 -0.999998 9.28014e-4 0.003497064 -0.9999939 8.43564e-5 0.00292474 -0.9999956 6.48625e-4 0.004215896 -0.9999858 0.003279089 1.66719e-4 -0.9999997 9.48724e-4 0.003551661 -0.9999937 -7.98622e-5 0.003311753 -0.9999946 2.61841e-4 1.52757e-4 -0.9999997 9.47165e-4 -8.99317e-5 -0.9999998 6.73103e-4 0.003120601 -0.9999949 -6.3427e-4 0.003174304 -0.9999946 -8.27424e-4 -2.47224e-4 -0.9999998 5.84811e-4 -0.005607724 -0.9999843 4.07178e-4 0.002583205 -0.9999955 -0.001563489 0.002143025 -0.9999805 -0.005878806 -0.002044856 -0.9999946 0.002555966 8.51336e-4 -0.9999951 0.003025949 0.001469612 -0.9999979 -0.001464843 0.005300104 -0.9999857 -7.94548e-4 -6.81556e-6 -1 5.43381e-6 9.26507e-4 -0.999998 -0.001803338 -8.16512e-6 -1 7.7882e-6 -1.66469e-4 -0.9999929 -0.00379908 -4.7521e-4 -1 -2.75649e-4 -5.08833e-4 -0.9999999 9.07418e-5 0.001482307 -0.9999951 -0.002774417 2.64956e-4 -0.9999967 -0.002571821 -6.94597e-4 -0.9999998 -4.53364e-4 -8.67921e-4 -0.9999997 -7.66583e-5 0.002315521 -0.9999961 -0.001626253 -2.19352e-4 -0.9999996 -8.78955e-4 -9.85657e-4 -0.9999941 -0.00330764 -0.002260625 -0.9999971 -9.39459e-4 -6.90492e-4 -0.9999993 -0.001008808 -0.002167046 -0.9999974 7.48544e-4 -6.46682e-4 -0.9999994 -0.001010477 -0.004562616 -0.9999883 -0.001641511 3.66182e-4 -0.9999735 -0.007274031 -9.23783e-4 -0.9999993 -8.47873e-4 0.9336306 -0.351116 0.0710743 0.9288839 -0.3628804 0.07411301 0.6875964 -0.724467 0.0485661 0.6794465 -0.7320504 0.04954439 0.5136623 -0.857437 0.03086638 0.9251969 -0.3485794 0.1500104 0.8345707 -0.5215325 0.1774704 0.712233 -0.691325 0.1216308 0.3348698 -0.9408323 0.05193203 0.4371675 -0.8937932 0.1000919 0.8366873 -0.5035603 0.2153638 0.7429803 -0.6179618 0.2571062 0.8518584 -0.3885834 0.3511981 0.4487187 -0.8829423 0.1380739 0.7427921 -0.6183367 0.2567484 0.8562871 -0.3467435 0.3828076 0.3218149 -0.9379677 0.1290417 0.6995777 -0.5944081 0.3965731 0.6098711 -0.7343946 0.2978621 0.3825938 -0.9048774 0.1865985 0.7010421 -0.5954511 0.3924003 0.7832201 -0.3586078 0.5079044 0.5196432 -0.7779176 0.353292 0.3357551 -0.9208663 0.1981768 0.1600065 -0.9807208 0.1121823 0.7360042 -0.3865091 0.5557956 0.5989664 -0.6224461 0.5037858 0.5154628 -0.7528343 0.4093152 0.357885 -0.8789919 0.3151057 0.5972263 -0.5456172 0.5878969 0.5945729 -0.3090639 0.7422686 0.5252357 -0.609025 0.5943198 0.463641 -0.6926169 0.5525568 0.2958238 -0.8853344 0.3587079 0.3409981 -0.8525627 0.3960518 0.5170078 -0.3974084 0.7581356 0.4715834 -0.5483995 0.6905556 0.5001152 -0.1906902 0.8447024 0.2463929 -0.8955065 0.3706193 0.4321481 -0.3708776 0.8220086 0.3665562 -0.6624427 0.6533041 0.1082465 -0.9738253 0.1998678 0.3332638 -0.7172114 0.6119993 0.3685151 -0.3796699 0.8485562 0.2760292 -0.6860921 0.6731162 0.2597585 -0.7573351 0.5991403 0.3507658 -0.2656748 0.8979868 0.1853071 -0.8670758 0.4624293 0.271469 -0.4022434 0.8743597 0.2407193 -0.5675256 0.7873811 0.2378021 -0.2816826 0.9295727 0.1435818 -0.5934364 0.7919707 0.159226 -0.6764363 0.7190836 0.1010289 -0.8974275 0.4294382 0.08507227 -0.9155747 0.3930467 0.08828794 -0.5586447 0.8246948 0.0985561 -0.6069881 0.7885761 0.03534889 -0.8679451 0.4954006 0.004076361 -0.3787458 0.9254919 0.01647782 -0.5160906 0.8563756 0.002729177 -0.8945726 0.4469146 4.86565e-4 -0.9007211 0.4343976 -0.0283789 -0.6557811 0.7544175 -0.09347444 -0.22936 0.9688429 -0.1086536 -0.3617975 0.9259034 -0.070921 -0.627842 0.775103 -0.1060318 -0.7837014 0.6120207 -0.06291532 -0.8993486 0.4326822 -0.05880779 -0.9442597 0.3239067 -0.2361811 -0.3947184 0.8879278 -0.2156062 -0.4483499 0.8674655 -0.1604259 -0.7211447 0.673954 -0.3158326 -0.4114597 0.8549566 -0.3141556 -0.4157907 0.8534778 -0.1900926 -0.8310776 0.5226613 -0.1122428 -0.9424672 0.3148925 -0.2437438 -0.7608813 0.6013723 -0.4044769 -0.3380047 0.8497949 -0.07831376 -0.9805345 0.1800535 -0.4235231 -0.4720824 0.7731536 -0.3455312 -0.7005423 0.6243786 -0.5063699 -0.313241 0.8034113 -0.3389033 -0.7410464 0.5796507 -0.2118377 -0.9197732 0.3303666 -0.5472795 -0.4575543 0.7008062 -0.4713072 -0.6253344 0.6219537 -0.5732003 -0.4141029 0.7070788 -0.2103901 -0.9393107 0.2709825 -0.3412496 -0.8586312 0.3824933 -0.6154621 -0.5186042 0.5935118 -0.6889842 -0.3792351 0.6176419 -0.4330226 -0.8086008 0.3983167 -0.7308955 -0.3403468 0.5915707 -0.4237734 -0.8305158 0.3614689 -0.7261052 -0.4367116 0.5310878 -0.5906684 -0.6913035 0.4161855 -0.7988809 -0.3226078 0.5076549 -0.7825447 -0.4295055 0.4507204 -0.182695 -0.9751427 0.1253766 -0.6385258 -0.6815434 0.3574684 -0.6115937 -0.7097515 0.3495799 -0.8806625 -0.2549791 0.3992733 -0.3785371 -0.904641 0.1957921 -0.8032828 -0.5090116 0.3092635 -0.7560005 -0.5828244 0.2979581 -0.3772407 -0.9149963 0.143078 -0.5343715 -0.8258743 0.1799412 -0.8819537 -0.3893483 0.2656424 -0.9380081 -0.2904304 0.1891854 -0.8724564 -0.4436474 0.2049315 -0.1653053 -0.9852303 0.04467087 -0.7234735 -0.6768046 0.1360951 -0.6305573 -0.7664477 0.122293 -0.4755827 -0.8772304 0.06548345 -0.9416461 -0.3269926 0.07986611 -0.9019585 -0.4276781 0.05968403 -0.8934919 -0.4468446 0.04474675 -0.8058165 -0.5921653 -7.28514e-6 -0.4847467 -0.8741624 0.02933859 -0.9604303 -0.2593786 -0.1014711 -0.3652807 -0.9308372 -0.01059013 -0.8026074 -0.5937516 -0.0572772 -0.7985234 -0.5994642 -0.05479925 -0.4859551 -0.8723742 -0.05301862 -0.4817519 -0.871624 -0.09048116 -0.9080707 -0.3623527 -0.2100199 -0.7655979 -0.6240348 -0.1563344 -0.6116196 -0.7776436 -0.1455749 -0.9298411 -0.2768405 -0.2423941 -0.8822612 -0.3615773 -0.3014583 -0.1556687 -0.9864714 -0.05139696 -0.7284162 -0.6171936 -0.2974591 -0.5888447 -0.7819314 -0.2045612 -0.3126942 -0.9408348 -0.1305844 -0.7280783 -0.6131074 -0.3065963 -0.8334003 -0.3322777 -0.4416282 -0.5677375 -0.7591571 -0.3183627 -0.8078727 -0.3621392 -0.4649699 -0.3477686 -0.9190122 -0.1856708 -0.8076192 -0.2720433 -0.5232053 -0.6033088 -0.701756 -0.3788893 -0.7261523 -0.4423429 -0.5263418 -0.6355367 -0.60861 -0.4750653 -0.5842842 -0.7077198 -0.3971711 -0.3124101 -0.9193044 -0.2393316 -0.2428414 -0.955881 -0.1652868 -0.738165 -0.1920956 -0.646693 -0.5766013 -0.6369405 -0.5117009 -0.4794309 -0.7598553 -0.4390513 -0.6403071 -0.4443135 -0.6265719 -0.3130379 -0.9153509 -0.2532591 -0.6454371 -0.266889 -0.7156684 -0.6269237 -0.4072792 -0.6641463 -0.3311815 -0.8574813 -0.3937571 -0.2051081 -0.9557408 -0.2109273 -0.4770498 -0.6307156 -0.6120632 -0.3512054 -0.8150262 -0.4608547 -0.5419856 -0.3151842 -0.7790446 -0.5141808 -0.3990684 -0.7591854 -0.3029521 -0.8416525 -0.447036 -0.4656856 -0.4432051 -0.7659675 -0.3132814 -0.7977572 -0.5152071 -0.4441407 -0.3809636 -0.8109289 -0.08103096 -0.9854191 -0.1496101 -0.3850481 -0.4423484 -0.8099789 -0.3649751 -0.3131703 -0.8767655 -0.2646561 -0.740733 -0.6174721 -0.2412026 -0.8057407 -0.5409284 -0.1763278 -0.8871103 -0.4265488 -0.2536203 -0.4761158 -0.8420158 -0.2239871 -0.5742397 -0.7874507 -0.1956218 -0.6159343 -0.7631232 -0.1114467 -0.8923675 -0.4373328 -0.1226403 -0.4087877 -0.9043517 -0.136638 -0.547617 -0.8254974 -0.05837708 -0.9418198 -0.3310099 -0.03294456 -0.8327817 -0.5526205 -0.008623838 -0.418544 -0.9081556 0.004485726 -0.4683686 -0.8835218 -0.01726579 -0.8226681 -0.5682598 0.01878619 -0.8629705 -0.5049049 0.07598257 -0.4701427 -0.8793137 0.1017389 -0.5835778 -0.8056589 0.03524839 -0.9288436 -0.3687913 0.1456215 -0.6104075 -0.7785868 0.1357638 -0.8085691 -0.5725246 0.2197092 -0.411338 -0.8846066 0.098185 -0.8945591 -0.4360319 0.2720156 -0.3718259 -0.8875546 0.2908893 -0.4199704 -0.8596559 0.0866248 -0.9506208 -0.2980203 0.2597497 -0.6691563 -0.6962471 0.3754415 -0.2816652 -0.8830111 0.4051473 -0.3637644 -0.8387677 0.280127 -0.7297123 -0.6237378 0.2687472 -0.7817566 -0.5627002 0.4560762 -0.3030785 -0.8367425 0.1693935 -0.9126817 -0.3719112 0.4699496 -0.5014871 -0.7264008 0.113109 -0.9734393 -0.1990535 0.3157783 -0.7653617 -0.560808 0.4876055 -0.494325 -0.7196413 0.5977371 -0.1827684 -0.7805806 0.2805631 -0.8701092 -0.4052091 0.4613656 -0.6626712 -0.5899227 0.2986341 -0.8605615 -0.4126155 0.6061076 -0.456327 -0.6514593 0.5219703 -0.6252368 -0.5801948 0.483473 -0.7214688 -0.4957183 0.6741572 -0.3389247 -0.6562334 0.2851252 -0.9059103 -0.3130977 0.6842414 -0.4161024 -0.5988928 0.2033656 -0.9591022 -0.1968895 0.5623163 -0.6789697 -0.4720177 0.7615532 -0.2531479 -0.596618 0.5466938 -0.716046 -0.4340555 0.3111898 -0.9206589 -0.2356868 0.7805801 -0.3246537 -0.5341298 0.6899042 -0.5714666 -0.4443626 0.2764033 -0.9442038 -0.1791105 0.7961957 -0.4636384 -0.3887311 0.1415751 -0.9870219 -0.07579243 0.6853833 -0.6204245 -0.381213 0.5683591 -0.7689955 -0.2925987 0.8519482 -0.407851 -0.3283929 0.8233079 -0.4635787 -0.3275039 0.7083448 -0.6555345 -0.2617675 0.5564032 -0.7968741 -0.2353876 0.3921669 -0.9085913 -0.1437609 0.9261381 -0.2856534 -0.2463141 0.6992055 -0.6894156 -0.1892563 0.6192036 -0.7702908 -0.1524433 0.8801743 -0.4305834 -0.1997282 0.4098607 -0.9042943 -0.1194408 0.8942766 -0.4265117 -0.1354888 0.800295 -0.5939794 -0.08195316 0.6097512 -0.7884806 -0.08063554 0.4125418 -0.910159 -0.03768062 0.9275036 -0.3737686 -0.005838394 0.2465645 -0.9684549 -0.03607171 0.8358219 -0.5479309 -0.0342611 0.9989914 0.01666873 -0.04169279 0.9998921 -0.01130545 -0.009384751 0.992945 -0.0157507 -0.1175253 0.990336 0.004385054 -0.1386204 0.9654329 -9.03556e-4 -0.2606505 0.9663263 -0.00425148 -0.2572848 0.9302638 -0.003555476 -0.3668742 0.9298323 -0.00262326 -0.3679744 0.8840222 -0.002684652 -0.4674373 0.8902055 -0.01284933 -0.4553781 0.8513498 -0.01302015 -0.524437 0.8359211 0.008991062 -0.5487763 0.7820628 -0.01248544 -0.6230747 0.744001 0.02238339 -0.6678036 0.7129528 -0.006207585 -0.7011846 0.6491517 0.01718902 -0.7604649 0.6074634 -0.01653856 -0.7941756 0.5693183 0.01023012 -0.8220536 0.4899406 -0.009892821 -0.8716997 0.4640976 0.01421684 -0.88567 0.3842712 0.008149921 -0.9231843 0.381714 0.0100848 -0.9242256 0.2937843 -0.009755671 -0.955822 0.1900492 -0.01474934 -0.9816638 0.241848 0.02002513 -0.9701076 0.114715 -0.01254487 -0.9933193 0.1014683 -1.86597e-4 -0.9948388 -0.005787849 -0.004145085 -0.9999747 -0.0221771 0.01082605 -0.9996954 -0.1542636 -0.02333486 -0.9877541 -0.1116064 0.01237648 -0.9936755 -0.2559399 0.006124317 -0.9666734 -0.2416264 -0.01068538 -0.9703106 -0.3806385 -0.01123315 -0.9246558 -0.3446643 0.01048928 -0.9386675 -0.4773783 -0.001612186 -0.8786964 -0.4498669 0.01743459 -0.8929255 -0.5675027 0.01374971 -0.8232567 -0.5605158 0.00465846 -0.8281308 -0.6719135 8.7028e-4 -0.7406292 -0.6772362 0.007821381 -0.7357241 -0.7546259 -0.01052957 -0.6560709 -0.7080066 0.01846957 -0.7059643 -0.780375 0.01169931 -0.6252024 -0.8330492 -0.01029002 -0.5531033 -0.8466191 0.009512424 -0.5321144 -0.8993327 -0.01480311 -0.4370145 -0.9117081 0.004458487 -0.4108144 -0.9270828 -0.004987597 -0.3748235 -0.9456534 0.01485478 -0.3248368 -0.9668164 -0.01644152 -0.254943 -0.9775785 0.02257746 -0.2093581 -0.9969393 0.003600835 -0.07809722 -0.9967805 0.001806437 -0.08015865 -0.9994169 -0.009550511 -0.03278231 -0.9971615 0.01402908 0.07397443 -0.9965825 0.0054183 0.08242577 -0.9783541 -0.003348231 0.2069107 -0.9744628 0.009815335 0.2243348 -0.9578384 -0.002144157 0.2872996 -0.9442415 0.02293097 0.3284542 -0.9115763 -0.003199875 0.4111188 -0.9165951 -0.01339167 0.3995925 -0.867627 0.01158541 0.4970807 -0.8441452 -0.01577639 0.5358825 -0.8084483 0.009534657 0.58849 -0.7842159 -0.007094621 0.6204476 -0.7524026 0.01177912 0.6585983 -0.7118223 -0.01319158 0.7022357 -0.6488363 -0.005380988 0.760909 -0.6643065 0.003939509 0.7474499 -0.6102638 0.02165699 0.7919021 -0.528607 0.002793073 0.8488622 -0.5312075 5.34494e-4 0.8472416 -0.4362203 -0.002357244 0.8998369 -0.4350395 -0.001300394 0.9004105 -0.3387337 -9.82709e-5 0.9408823 -0.3331799 0.004635393 0.9428519 -0.2367184 0.002827405 0.9715743 -0.2405474 0.006489872 0.9706157 -0.1063413 0.003803431 0.9943224 -0.101068 -0.002928137 0.9948753 0.04220306 1.46898e-4 0.9991092 0.04667514 -0.004280745 0.998901 0.1274036 -0.0177291 0.9916925 0.1653903 0.005466461 0.986213 0.230866 -0.01690363 0.9728387 0.3549537 -0.01430588 0.9347745 0.2796251 0.01358014 0.9600132 0.3857582 0.01299464 0.9225084 0.4845358 0.01342338 0.8746684 0.5133327 -0.02201223 0.8579075 0.6418555 -0.02049124 0.7665519 0.5973678 0.01532262 0.8018211 0.6832784 -0.001178979 0.7301571 0.7182255 -0.01909351 0.6955484 0.7738725 -0.01959091 0.6330385 0.7442163 -0.003967642 0.667927 0.8189765 0.0130589 0.5736786 0.8491241 -0.002183556 0.5281891 0.8652733 0.016007 0.5010448 0.9033106 0.00134772 0.4289851 0.907056 0.007907509 0.4209358 0.9515522 0.005705595 0.3074343 0.9468894 -1.54359e-4 0.3215599 0.9607001 -0.01622068 0.2771142 0.9838532 -0.0160849 0.1782529 0.973938 0.002583563 0.2267996 0.9975733 -0.006513893 0.06931948 0.9940326 0.01550769 0.1079761 0.9582549 0.2845538 -0.02787065 0.686539 0.7253107 -0.05087906 0.9238744 0.3656152 -0.1130564 0.9121282 0.3930852 -0.1162167 0.2393644 0.9705127 -0.02845746 0.5520332 0.8289963 -0.08957982 0.381694 0.9216331 -0.07001513 0.8437318 0.5039691 -0.1847484 0.7396763 0.6482867 -0.1805642 0.7857346 0.5852116 -0.2003709 0.9358865 0.240169 -0.2577508 0.3811997 0.9201716 -0.08928245 0.8802437 0.3350319 -0.3360427 0.8345092 0.4370865 -0.3354845 0.7286261 0.631884 -0.2642475 0.2972186 0.9482379 -0.1118308 0.4992542 0.8363246 -0.2265098 0.8287888 0.3581217 -0.4299513 0.8098333 0.4314343 -0.3975358 0.6262759 0.7009059 -0.3413348 0.5071715 0.8256421 -0.2471687 0.7858955 0.3313786 -0.5220695 0.7775607 0.3839182 -0.4980024 0.6334922 0.662131 -0.4003377 0.09243261 0.9946764 -0.04555404 0.3102667 0.9286739 -0.2032231 0.5387489 0.7490161 -0.3856482 0.7188851 0.3932477 -0.573202 0.3345673 0.9123196 -0.2360886 0.5719618 0.6786003 -0.4608268 0.7224347 0.2858536 -0.6295838 0.2679774 0.9356578 -0.229636 0.5828067 0.5506377 -0.5976074 0.5046086 0.7228429 -0.4720894 0.3839514 0.8417202 -0.37959 0.5407698 0.5411877 -0.6439596 0.5456767 0.5041732 -0.6693627 0.3491671 0.8459542 -0.4030432 0.05618292 0.9964945 -0.06198602 0.5061752 0.3903692 -0.7690244 0.4988276 0.5166402 -0.6958836 0.220476 0.9256511 -0.3075069 0.295962 0.810233 -0.5058943 0.4563307 0.3778823 -0.8055851 0.2283728 0.9039761 -0.3614875 0.3588985 0.5748733 -0.7353317 0.3114241 0.710003 -0.6315939 0.3007394 0.5178744 -0.8008508 0.3150628 0.3915426 -0.8645403 0.06903749 0.9830027 -0.170116 0.2090612 0.8016558 -0.560037 0.2190693 0.6696307 -0.7096502 0.2383921 0.1431921 -0.9605547 0.1041563 0.9418568 -0.3194639 0.1754261 0.6902642 -0.7019694 0.08533924 0.9099798 -0.405776 0.1467789 0.4576467 -0.8769352 0.1406524 0.584653 -0.798998 0.09822189 0.316766 -0.9434044 0.05177831 0.9236294 -0.3797734 0.0743528 0.7195129 -0.6904875 0.03986257 0.8815029 -0.470493 0.01805335 0.4639856 -0.8856588 0.01226282 0.4613165 -0.8871509 3.10914e-4 0.8878844 -0.4600664 -0.0522862 0.6201592 -0.7827317 -0.1269024 0.502457 -0.8552386 -0.02823084 0.9608857 -0.2755025 -0.109127 0.5831757 -0.804983 -0.1330662 0.7922787 -0.5954728 -0.2329346 0.2925876 -0.9274342 -0.06952905 0.9299539 -0.3610424 -0.1932315 0.7378512 -0.6467127 -0.2905784 0.4672126 -0.8350309 -0.3058072 0.4451466 -0.8416213 -0.05906242 0.9848833 -0.1628395 -0.2095563 0.8910188 -0.4027055 -0.3993565 0.4006763 -0.8246048 -0.3489826 0.4688075 -0.8114376 -0.2198488 0.8591172 -0.4621517 -0.4252596 0.5725703 -0.7009405 -0.2359756 0.8524932 -0.4664449 -0.2328871 0.9049715 -0.3560762 -0.5168388 0.4421612 -0.7330561 -0.4624207 0.5460568 -0.6985622 -0.3363634 0.8310754 -0.4429145 -0.5691348 0.4481795 -0.6893625 -0.09576374 0.9879068 -0.1219413 -0.5375393 0.6309723 -0.5593975 -0.3671711 0.8342205 -0.4114142 -0.3027624 0.8971269 -0.3217116 -0.6316252 0.5263625 -0.5692031 -0.6171197 0.5242478 -0.5867942 -0.7448443 0.3289471 -0.5805178 -0.7521057 0.4130829 -0.5135169 -0.6281993 0.6509165 -0.4262317 -0.535553 0.7501559 -0.3878778 -0.8083122 0.2961848 -0.5088282 -0.3712304 0.8908204 -0.2619678 -0.3015522 0.9257447 -0.2281731 -0.6304747 0.708619 -0.3167976 -0.5158717 0.818646 -0.2523792 -0.3949447 0.893221 -0.2148838 -0.8274462 0.4013429 -0.3927552 -0.7951697 0.4859041 -0.3627706 -0.8790394 0.388057 -0.2769505 -0.8042249 0.5154506 -0.2958601 -0.1839007 0.9798859 -0.07748532 -0.5236138 0.8354653 -0.1668133 -0.5195761 0.8385918 -0.1637214 -0.892526 0.396624 -0.2146784 -0.8090708 0.5676125 -0.1523829 -0.5320079 0.8335559 -0.1488366 -0.8110855 0.5701383 -0.1307002 -0.9461205 0.3160691 -0.07040268 -0.3607344 0.9311674 -0.05289763 -0.6499037 0.7587859 -0.04323607 -0.8765252 0.4812607 -0.009585678 -0.1805403 0.9834536 -0.0149756 -0.6718999 0.7405078 -0.01410198 -0.9516196 0.2975092 0.07686769 -0.6002964 0.7996272 0.01551109 -0.3604874 0.9325074 0.02188187 -0.8974015 0.4256761 0.1160625 -0.7285812 0.6780282 0.09719693 -0.3058146 0.9509313 0.04698097 -0.9010057 0.3917758 0.1862812 -0.8250406 0.5268533 0.2042882 -0.6614308 0.7376772 0.1354317 -0.4810174 0.8688071 0.1174582 -0.8109986 0.5206843 0.2667757 -0.7526448 0.5985262 0.2743943 -0.4732933 0.8672229 0.1546545 -0.3744358 0.9156605 0.1461638 -0.8024481 0.4340199 0.4095165 -0.7461611 0.5545159 0.3684505 -0.832288 0.2694593 0.4844465 -0.6039275 0.7210566 0.3396309 -0.4875868 0.8301168 0.2704911 -0.08748292 0.9950286 0.04759126 -0.7670751 0.3461276 0.5401773 -0.7399558 0.4083241 0.5345436 -0.2819624 0.9400453 0.1918651 -0.6254906 0.6500496 0.4315056 -0.483197 0.7819938 0.3937085 -0.7024784 0.3208159 0.6352963 -0.3650155 0.8828201 0.2956222 -0.689204 0.4197772 0.5905802 -0.5430006 0.6844857 0.486446 -0.6625124 0.31862 0.6779075 -0.4848102 0.6648478 0.568275 -0.4957038 0.654634 0.5707294 -0.3276262 0.8584125 0.3947014 -0.2211629 0.9429799 0.2487486 -0.4987506 0.5449737 0.6739818 -0.1137927 0.9831333 0.1431784 -0.4555866 0.4236741 0.7829056 -0.4423616 0.5703125 0.6921416 -0.2929939 0.8136202 0.5021723 -0.2560075 0.8460606 0.4675915 -0.3970131 0.3758347 0.8373344 -0.235947 0.8517777 0.4677647 -0.3447457 0.4563187 0.8203194 -0.2994889 0.6008758 0.7411172 -0.3323821 0.3124324 0.8898923 -0.136943 0.9327315 0.3335546 -0.2254953 0.3306105 0.9164326 -0.1689014 0.7392635 0.651891 -0.1339458 0.8425852 0.5216406 -0.1619046 0.5693114 0.8060221 -0.141076 0.5574687 0.8181236 -0.09250044 0.2084387 0.9736514 -0.05915158 0.9250447 0.3752245 -0.03934043 0.3499284 0.9359501 -0.04580748 0.6883667 0.7239151 -0.0371226 0.6676604 0.7435399 -0.03378432 0.8937184 0.4473549 0.03993111 0.3141488 0.9485337 0.04782527 0.2827026 0.9580147 0.02931916 0.6622509 0.7487084 0.04489517 0.7061556 0.706632 0.0457884 0.8751951 0.4815985 0.007412552 0.933308 0.3590003 0.1353609 0.3185078 0.9382058 0.1508236 0.489489 0.8588672 0.07222503 0.887702 0.4547184 0.1774556 0.5425735 0.8210503 0.1643112 0.7436478 0.6480662 0.277354 0.3396259 0.8987375 0.3046299 0.4033271 0.8628603 0.05623251 0.9768052 0.2066146 0.2507522 0.7111745 0.6567756 0.2087799 0.7813076 0.5881918 0.3680576 0.3054115 0.8782128 0.1544822 0.9036828 0.3993656 0.3978503 0.4035874 0.8239129 0.3585085 0.587566 0.7254226 0.4732376 0.2083007 0.8559538 0.1695271 0.9401155 0.2957084 0.3742602 0.6951252 0.6137837 0.5080574 0.4419584 0.7392905 0.2090951 0.9165945 0.3407841 0.4561415 0.5843316 0.6711866 0.573072 0.2895491 0.7666484 0.6246827 0.3663244 0.6896217 0.6095997 0.4556545 0.6486657 0.4863609 0.6942152 0.530583 0.4581493 0.7437332 0.4867854 0.2774558 0.9088799 0.3113768 0.7101249 0.3444852 0.614046 0.7076776 0.4311963 0.5596984 0.683196 0.5033528 0.5290362 0.1509913 0.9788832 0.1378021 0.5438474 0.711215 0.445425 0.408824 0.8660406 0.2878136 0.7096372 0.5669523 0.4183064 0.6723662 0.6396166 0.372578 0.4649333 0.8408777 0.2770596 0.8119314 0.4679865 0.3489357 0.7381652 0.585497 0.3351201 0.3192437 0.9362822 0.1464891 0.888855 0.3571977 0.2869612 0.3689292 0.9176529 0.1476637 0.6237527 0.7479177 0.2270503 0.8500251 0.4758821 0.2258175 0.7280876 0.6574916 0.1938899 0.9255309 0.3218297 0.1995457 0.3021239 0.949772 0.08157521 0.618928 0.7759498 0.1217795 0.9446784 0.3046502 0.1215361 0.6216889 0.7775167 0.09471362 0.1516578 0.988112 0.02519321 0.8268936 0.5595188 0.05644398 0.8243178 0.5649167 0.03700667 0.6745944 0.7380915 -0.01197642 0.4152302 0.9095556 0.01710826 0.4015892 0.9154797 0.02496206 -8.14158e-4 0.9999992 0.001026272 -1.7796e-4 0.9999928 0.00379002 -0.00130999 0.9999991 4.58076e-4 -0.001428604 0.9999987 8.65432e-4 -0.002165734 0.999994 0.002717673 -9.1765e-4 0.9999963 0.002592861 -0.00339359 0.9999934 0.00138688 -0.001464545 0.9999989 4.22159e-4 -8.49123e-4 0.9999985 0.001535117 -7.4843e-4 0.9999998 -7.49437e-6 2.87614e-5 0.9999994 0.001140534 0.002446293 0.9999942 0.002394199 -0.002433717 0.9999917 -0.003315985 -6.64253e-4 0.999997 0.002405345 -0.004171073 0.9999908 0.001046478 4.97089e-4 0.9999991 0.001355171 -0.001435577 0.9999988 -5.29388e-4 6.4252e-4 0.999999 0.001317858 -0.001200258 0.9999989 -8.75795e-4 -7.55914e-4 0.9999951 -0.003058791 8.57902e-4 0.9999992 0.001073837 0.002757012 0.9999963 2.58295e-4 -0.001671791 0.9999964 -0.00209558 0.002393424 0.9999954 0.001899123 -0.001860678 0.9999971 -0.001510202 4.81174e-4 0.9999877 0.004939973 4.22009e-4 0.9999999 1.84628e-4 -7.49727e-4 0.9999975 -0.002113223 -0.001725614 0.9999984 -6.18359e-4 0.001514911 0.9999976 -0.001620113 0.00163865 0.9999969 -0.001885175 0.002332329 0.9999973 5.59305e-5 1.726e-5 0.9999976 -0.00219357 0.001485586 0.9999952 0.002738714 -0.002095639 0.9999963 -0.001739859 3.73332e-4 0.9999995 -0.001030683 2.90907e-4 1 -1.05873e-4 5.23955e-4 0.9999994 -0.001057744 4.06075e-4 0.9999994 -0.001103579 9.39858e-4 0.9999994 -6.6943e-4 7.13517e-4 0.9999994 -9.2612e-4 8.32366e-4 0.9999993 -9.13547e-4 0.9950943 0.04421716 -0.08849954 0.9845063 -0.01862722 -0.1743578 0.9861751 -0.04335516 -0.1599347 0.9418029 0.07307666 -0.3281267 0.8864628 -0.08408969 -0.4550964 0.8725297 -0.008052527 -0.4884947 0.8088553 0.0678938 -0.584075 0.7508064 0.03638714 -0.6595195 0.6963012 -0.06722265 -0.7145948 0.672447 -0.008228421 -0.7400996 0.5708861 0.04482245 -0.8198049 0.4697363 -0.04861634 -0.8814671 0.4637664 -0.03303062 -0.8853417 0.3886784 0.06646716 -0.918973 0.2704878 0.05693328 -0.9610385 0.1564571 -0.06872355 -0.985291 0.1602247 -0.07753157 -0.984031 0.09707295 0.01578694 -0.9951521 -0.005352497 0.07474541 -0.9971883 -0.1035096 0.04218333 -0.9937335 -0.1737924 -0.06446689 -0.98267 -0.2358094 0.02204084 -0.9715493 -0.3408708 0.03952598 -0.9392789 -0.4342479 -0.03729325 -0.9000211 -0.4387089 -0.02809339 -0.89819 -0.4987812 0.0326299 -0.8661136 -0.6091342 0.04325127 -0.7918869 -0.6621033 -0.02476006 -0.7490035 -0.6809549 0.007644951 -0.7322855 -0.7519975 0.04459428 -0.6576558 -0.8209372 -0.05250984 -0.5685992 -0.840735 0.01046818 -0.5413457 -0.9080945 0.06918996 -0.4130098 -0.9540497 -0.05915802 -0.293751 -0.9510784 -0.02314788 -0.3080815 -0.9901378 0.05549132 -0.1286385 -0.9978225 -0.0613783 -0.02414828 -0.9995797 0.01734042 0.02323204 -0.9881582 0.06234693 0.140201 -0.9685129 -0.0275191 0.247438 -0.9632632 0.005290508 0.2685074 -0.8805149 -0.05234175 0.47112 -0.9176543 0.03481525 0.3958518 -0.8562111 0.03332996 0.5155499 -0.7561212 0.0517587 0.6523817 -0.6968032 -0.05545437 0.7151155 -0.6793676 -0.01410269 0.7336626 -0.5632342 0.04810404 0.8248959 -0.4913213 -0.04904347 0.8695966 -0.4288504 0.03767549 0.9025896 -0.2858523 -0.01394981 0.9581722 -0.2985996 -0.04249089 0.9534322 -0.144847 0.06525576 0.9872999 -0.00519216 -0.06478202 0.997886 0.005855679 -0.03970849 0.9991942 0.1568483 0.07116955 0.9850552 0.2407513 0.03297311 0.9700266 0.288834 -0.05787217 0.9556285 0.3946462 0.05108284 0.9174121 0.5322068 -0.06613123 0.8440276 0.5493717 -0.01968568 0.8353462 0.6455808 0.07534372 0.7599664 0.722514 0.0502336 0.689529 0.7705579 -0.07932686 0.6324143 0.827752 0.03767859 0.5598278 0.8865393 0.03433835 0.4613774 0.9140005 -0.06862545 0.3998671 0.9471275 0.05812984 0.3155482 0.9850032 0.03854531 0.1681753 0.9920859 -0.07752883 0.09876698 0.9993569 0.02296417 0.02754157 0.997102 -0.04596781 -0.06061965 0.9841047 0.003578782 -0.1775536 0.9817016 0.02349156 -0.1889711 0.9459363 -0.05212503 -0.3201366 0.8953558 0.03170764 -0.4442215 0.8997405 0.05666464 -0.4327311 0.8317025 -0.07169187 -0.5505735 0.7900058 -0.06564056 -0.6095755 0.6975673 0.08819937 -0.7110702 0.7279539 0.01371806 -0.6854889 0.644892 -0.04973757 -0.7626537 0.5335037 0.02021878 -0.8455561 0.5359184 0.02610576 -0.8438661 0.4413101 -0.07773089 -0.8939818 0.2960199 -0.009773612 -0.9551318 0.2382946 0.08307129 -0.9676336 0.2009412 0.0153234 -0.9794835 0.05433928 -0.07695227 -0.9955529 -0.1187224 0.07530879 -0.9900675 -0.08205771 0.003910601 -0.99662 -0.1810506 -0.04359072 -0.9825073 -0.2979163 0.001250207 -0.9545913 -0.3014937 0.0075984 -0.953438 -0.4295483 -0.03355252 -0.9024204 -0.4918758 0.01156669 -0.8705887 -0.5072747 -0.01303124 -0.8616859 -0.5862385 -0.0470494 -0.8087712 -0.6789895 0.03483515 -0.7333211 -0.7100028 -0.03155857 -0.7034915 -0.8164079 2.61859e-4 -0.5774757 -0.8160422 -6.34812e-4 -0.5779922 -0.871831 -0.04534196 -0.4877037 -0.9223577 0.06666821 -0.3805415 -0.946378 -0.05879491 -0.3176665 -0.9819996 -0.06204193 -0.1784029 -0.9956107 0.04909986 -0.07967936 -0.9956336 0.03600931 -0.08612245 -0.9983447 -0.04858016 0.03078699 -0.9956056 -0.04059904 0.08438789 -0.9833338 0.06257998 0.1706997 -0.9686211 -0.04263097 0.2448589 -0.9297468 -0.03573304 0.3664617 -0.9089299 0.05699169 0.4130358 -0.8489314 -0.04811996 0.526308 -0.7711172 0.003109633 0.6366856 -0.7829055 0.03880494 0.6209294 -0.6503421 -0.04329925 0.7584065 -0.6060761 0.0395888 0.794421 -0.5346192 -0.03504872 0.844366 -0.446506 -0.01735132 0.8946124 -0.4217712 0.0285058 0.9062542 -0.2922214 -0.05201154 0.9549353 -0.1923831 0.04367393 0.9803476 -0.179259 0.02107965 0.9835761 -0.06968265 -0.06125694 0.9956867 0.008112192 -0.05391281 0.9985127 0.08547377 0.04408401 0.9953647 0.1379729 -0.01665771 0.990296 0.2548345 -0.02137988 0.9667484 0.3054057 0.04926353 0.9509471 0.3856032 -0.04816657 0.9214068 0.4813317 -0.04222643 0.8755208 0.5357245 0.0212292 0.844126 0.5428401 0.03805464 0.8389735 0.6496752 -0.04573565 0.758835 0.698401 0.06724309 0.7125409 0.7240343 0.007153451 0.6897269 0.7896389 -0.06511592 0.610107 0.8849515 0.02438014 0.4650446 0.8832721 0.01500725 0.4686207 0.9510402 -0.02718067 0.3078699 0.9632561 0.04322576 0.2650834 0.9901648 -0.06559062 0.1235789 0.9982329 0.05223131 0.02834272 0.8903355 -0.455205 0.009545207 0.6750599 -0.7377631 1.88431e-4 0.9539734 -0.2737492 0.1224587 0.9200469 -0.3798828 0.09593152 0.7147843 -0.6909351 0.1081302 0.6105226 -0.7890561 0.06820964 0.480766 -0.8746825 0.06160092 0.888103 -0.4104066 0.2069773 0.748126 -0.6410096 0.1715061 0.9237715 -0.2374831 0.3004134 0.3173438 -0.9444848 0.08509659 0.6323998 -0.7469519 0.2052645 0.8663364 -0.3727401 0.3324548 0.4584461 -0.8747316 0.157073 0.7404088 -0.605171 0.2925116 0.8676052 -0.2122071 0.4496995 0.7913681 -0.4078314 0.4554232 0.6428137 -0.6733852 0.3651615 0.6183609 -0.7098198 0.3373215 0.4336857 -0.8691115 0.2378274 0.7393454 -0.40882 0.535009 0.2954375 -0.9358633 0.1920328 0.6176165 -0.6443979 0.4508895 0.7518111 -0.3301693 0.5707612 0.5340403 -0.7245744 0.4356522 0.3937618 -0.8593845 0.3262053 0.6645727 -0.4239454 0.6153158 0.584388 -0.5753741 0.5722197 0.566927 -0.3891749 0.7260419 0.5203154 -0.6186233 0.5887081 0.4277508 -0.7412211 0.5173206 0.2749482 -0.9076373 0.3171719 0.2616402 -0.9155471 0.3054801 0.5230557 -0.3896963 0.7579905 0.4648537 -0.4853183 0.7405251 0.3932615 -0.6771004 0.6219972 0.4332379 -0.4018741 0.8067232 0.200057 -0.9248546 0.3234521 0.2999173 -0.7791703 0.5504029 0.3691738 -0.4744936 0.7991036 0.2868161 -0.7565615 0.587666 0.3403005 -0.3976872 0.8520801 0.1951 -0.8253644 0.5298205 0.3110252 -0.4238769 0.850642 0.09885859 -0.9756919 0.195582 0.2453716 -0.2985835 0.9223019 0.1802843 -0.8031618 0.5678279 0.1536328 -0.4505807 0.8794169 0.1259639 -0.8206934 0.5573109 0.140487 -0.4251253 0.8941656 0.08802598 -0.87072 0.4838371 0.03848022 -0.4836179 0.874433 -8.55522e-4 -0.6150332 0.7885007 0.001476407 -0.8067677 0.590867 -0.1017922 -0.4753838 0.87387 -0.1459947 -0.4962065 0.8558415 -0.0288276 -0.8714503 0.489636 -0.0271129 -0.9722076 0.2325453 -0.1601065 -0.5434313 0.8240439 -0.1183841 -0.7690089 0.6281805 -0.2142225 -0.5089367 0.8337219 -0.2950407 -0.2130526 0.9314289 -0.1449267 -0.8717927 0.4679462 -0.09627884 -0.9412338 0.3237428 -0.2543694 -0.644403 0.7211387 -0.2062662 -0.8030738 0.559041 -0.3688049 -0.3990734 0.8394781 -0.3872853 -0.3818853 0.8391507 -0.2586196 -0.8208133 0.5092952 -0.4146823 -0.5598341 0.7173733 -0.05833375 -0.9905842 0.123856 -0.4946464 -0.4780981 0.7257735 -0.201879 -0.9211543 0.3327457 -0.4785522 -0.5109854 0.7140601 -0.6175261 -0.3225361 0.7173787 -0.392756 -0.7902904 0.4703019 -0.6168091 -0.4072722 0.6735547 -0.2954513 -0.8843855 0.361346 -0.4979391 -0.6874009 0.5287123 -0.2471313 -0.9296963 0.2731133 -0.6822175 -0.419668 0.5987138 -0.5636073 -0.6677652 0.4862474 -0.7394486 -0.2956286 0.6048303 -0.5605343 -0.6750568 0.4796872 -0.3610059 -0.8887602 0.2824541 -0.3053916 -0.9195056 0.2474783 -0.808942 -0.3149052 0.4964349 -0.7771238 -0.3782615 0.5029881 -0.6454727 -0.6286131 0.4338325 -0.1442698 -0.9847517 0.09721243 -0.5231983 -0.7941952 0.3090594 -0.5179451 -0.8072141 0.2830873 -0.8308042 -0.3942192 0.3928811 -0.3675799 -0.9122019 0.1810325 -0.6958521 -0.6516171 0.3019689 -0.8975802 -0.2413775 0.3688998 -0.8246347 -0.5032777 0.258243 -0.7012838 -0.673451 0.2338052 -0.6182225 -0.764635 0.1820284 -0.3567997 -0.9255047 0.1270238 -0.9241117 -0.31563 0.2153958 -0.6233022 -0.7655059 0.1596729 -0.8983053 -0.4191747 0.1316819 -0.8248944 -0.5568839 0.09710645 -0.1262918 -0.9917578 0.02160894 -0.4963563 -0.8663257 0.05576974 -0.7914862 -0.6077635 0.06460058 -0.6921031 -0.7200495 0.05022192 -0.8728544 -0.4879807 2.17285e-4 -0.2945705 -0.9553893 0.02143824 -0.8598957 -0.507506 -0.05492931 -0.824222 -0.5613363 -0.07456302 -0.660786 -0.7491496 -0.04622429 -0.8362354 -0.5281496 -0.1475408 -0.4408539 -0.8959769 -0.05360448 -0.4174606 -0.9062541 -0.06656002 -0.7934168 -0.5839332 -0.1717901 -0.571413 -0.8068408 -0.1499832 -0.8751404 -0.3681945 -0.313946 -0.5526615 -0.8137143 -0.1800956 -0.8693645 -0.379487 -0.3165362 -0.6976046 -0.6556007 -0.2890255 -0.6802959 -0.6569132 -0.3250578 -0.8217199 -0.3785923 -0.4259631 -0.7417394 -0.532651 -0.4075605 -0.3174039 -0.936199 -0.1509509 -0.3934266 -0.8922647 -0.2215386 -0.7088268 -0.5620692 -0.4261957 -0.7612597 -0.3121811 -0.5683543 -0.5764461 -0.7078108 -0.4083061 -0.3907084 -0.8800473 -0.2699329 -0.4134917 -0.8618904 -0.2935465 -0.7102169 -0.4111586 -0.5714374 -0.6135765 -0.6156142 -0.494513 -0.6893904 -0.245516 -0.6815151 -0.5346913 -0.6751941 -0.5081519 -0.3796648 -0.8524037 -0.359531 -0.569527 -0.5154183 -0.6402993 -0.06399559 -0.9958453 -0.06478327 -0.5597479 -0.5202823 -0.6449719 -0.5475783 -0.4268521 -0.7196912 -0.2283905 -0.933496 -0.2764471 -0.3860414 -0.7623159 -0.5194675 -0.2693542 -0.8877484 -0.3732976 -0.4559297 -0.4991604 -0.736863 -0.4480339 -0.5148868 -0.7308607 -0.2323419 -0.8854614 -0.4024616 -0.3573768 -0.6124532 -0.7051121 -0.3328526 -0.483937 -0.8093295 -0.3268218 -0.5787449 -0.7471559 -0.1340085 -0.9417812 -0.3083667 -0.2403305 -0.7373059 -0.6313647 -0.2874444 -0.3651847 -0.8854467 -0.08327573 -0.9703863 -0.22675 -0.204169 -0.4702228 -0.8586068 -0.1322853 -0.6689237 -0.7314655 -0.1300286 -0.7479984 -0.6508387 -0.08844721 -0.882668 -0.4615999 -0.06555998 -0.3395539 -0.938299 -0.09401392 -0.6240131 -0.7757378 0.05103498 -0.328935 -0.9429726 0.04307281 -0.3650667 -0.9299845 -0.001393795 -0.9422624 -0.3348726 0.04468542 -0.6923523 -0.7201747 0.02344018 -0.7512476 -0.6596041 0.01057463 -0.9146183 -0.4041799 0.1199716 -0.6527062 -0.7480518 0.1695398 -0.3517793 -0.9206019 0.1815153 -0.4877596 -0.8538986 0.2907684 -0.4008693 -0.8687679 0.23386 -0.5091314 -0.8283084 0.1507957 -0.8487856 -0.5067779 0.1801088 -0.8107803 -0.5569527 0.1195108 -0.9015366 -0.4158714 0.3442203 -0.4315201 -0.8338483 0.2545622 -0.7661616 -0.5900802 0.3849692 -0.3734711 -0.8439894 0.06915187 -0.9810898 -0.1807788 0.4037327 -0.6186779 -0.6739714 0.2820565 -0.8033957 -0.5244041 0.228286 -0.890003 -0.39469 0.4739198 -0.5347293 -0.6996175 0.2260878 -0.9141924 -0.3363578 0.1304835 -0.9784688 -0.1599149 0.5276486 -0.5456588 -0.6510326 0.513535 -0.6420592 -0.5692468 0.476608 -0.7058166 -0.5240876 0.6533633 -0.4712703 -0.5924701 0.3768742 -0.8611682 -0.3411087 0.6735047 -0.4719164 -0.5689344 0.6337829 -0.6223975 -0.4592828 0.406436 -0.8582237 -0.313468 0.783348 -0.4255809 -0.4530417 0.7127793 -0.5521351 -0.4325422 0.3539276 -0.9021896 -0.2465546 0.8410537 -0.3313202 -0.4276162 0.5932703 -0.7490085 -0.2949859 0.4360222 -0.8718134 -0.2232176 0.3658702 -0.9163578 -0.1625654 0.822277 -0.4597588 -0.3353841 0.7090327 -0.6443306 -0.28655 0.8983029 -0.3221125 -0.2988235 0.8684497 -0.4375756 -0.2330726 0.3858845 -0.9136753 -0.127635 0.6693729 -0.7134084 -0.2073363 0.5813274 -0.7972859 -0.1624615 0.9049816 -0.3855466 -0.1798956 0.8682245 -0.4789724 -0.129505 0.6321382 -0.7704485 -0.08252704 0.143757 -0.9894 -0.02053248 0.944949 -0.3237556 -0.04747205 0.5784524 -0.814162 -0.05032962 0.2783485 -0.9602986 -0.01867485 0.01074522 -0.9999368 0.003317534 0.001361727 -0.9999979 0.001582801 0.008434832 -0.999952 0.004998147 0.008259475 -0.999956 0.004456818 -4.71789e-4 -0.9999445 0.0105257 9.3804e-4 -0.9999973 0.002125501 0.006903707 -0.9999585 0.005953371 0.002111971 -0.9999493 0.009849011 0.003152728 -0.9999948 6.72431e-4 2.15744e-4 -0.9999185 0.01277548 0.003299415 -0.9999946 2.95756e-5 0.006502687 -0.9998944 0.01299369 0.002525329 -0.9999969 -2.08882e-4 -4.13565e-5 -1 5.41565e-4 -1.66332e-4 -0.9999999 4.83942e-4 0.003599166 -0.9999755 -0.0060153 0.001855552 -0.999998 -7.71697e-4 -0.003279626 -0.9999931 0.001788139 -0.002549827 -0.9999884 0.004092931 -0.003390192 -0.9999873 0.003733754 0.0041278 -0.999984 -0.003881812 0.004015743 -0.9999855 -0.003601133 -0.003255426 -0.9999858 0.004237234 -0.001844286 -0.999997 0.001618683 0.002147495 -0.9999916 -0.003493964 0.004038035 -0.9999862 -0.003373444 -0.001759588 -0.9999982 7.31846e-4 0.001446127 -0.9999892 -0.00442475 0.001217663 -0.9999824 -0.005819082 -0.002433657 -0.9999971 2.9904e-4 -0.002467393 -0.9999969 3.21504e-4 0.001063406 -0.9999825 -0.005838513 -3.33152e-5 -0.9999911 -0.004226565 -0.002210736 -0.9999976 -1.89632e-4 -0.007030844 -0.9999189 -0.01062268 -0.01128643 -0.9999275 -0.004216909 -0.001557409 -0.9999902 -0.004172682 -0.009394407 -0.9999549 0.001382529 -0.001392602 -0.9999908 -0.004045069 -0.004212915 -0.9999868 -0.002981841 -0.002609014 -0.9999917 -0.003168225 -0.004219591 -0.9999849 -0.003540754 0.9026411 0.4283964 -0.04142171 0.3123393 0.9499707 -1.05008e-4 0.7552308 0.6504856 -0.08059114 0.6579022 0.7525342 -0.02927726 0.1911829 0.9814625 -0.01344078 0.9187545 0.3471736 -0.1880443 0.7429803 0.658505 -0.1197983 0.748255 0.6517071 -0.1240661 0.3762129 0.9221014 -0.09051471 0.8891273 0.3323842 -0.3146002 0.8853648 0.3473064 -0.3090431 0.7382568 0.6338599 -0.2306483 0.5102485 0.8334811 -0.2120277 0.8115261 0.4359184 -0.3891022 0.3764639 0.9176109 -0.1275351 0.6011717 0.73541 -0.3126735 0.515561 0.8213473 -0.2441014 0.8292049 0.310817 -0.464556 0.7576867 0.4336788 -0.4876821 0.6368374 0.6625937 -0.3942179 0.751695 0.3845172 -0.5358182 0.3158686 0.9281736 -0.1967763 0.692665 0.4554921 -0.5592335 0.5321218 0.7246703 -0.4378349 0.09288054 0.9931417 -0.07101345 0.498355 0.7735086 -0.3915696 0.4687308 0.8031418 -0.36777 0.6932219 0.3670058 -0.6202824 0.6459607 0.4042108 -0.6475712 0.6395865 0.3212062 -0.6983951 0.249999 0.9356912 -0.2489628 0.5131501 0.6773152 -0.5271822 0.4438109 0.7368758 -0.5099472 0.3267124 0.851001 -0.4111647 0.5495103 0.4403153 -0.7100429 0.5247394 0.3918294 -0.7557238 0.4711945 0.4573478 -0.7541941 0.2979062 0.8620659 -0.4099934 0.4078145 0.5797246 -0.7054125 0.1936251 0.9290739 -0.3151685 0.3442786 0.6168579 -0.7077844 0.3247216 0.5319176 -0.7820612 0.2067924 0.8602575 -0.4660408 0.02209752 0.9984326 -0.05141991 0.1681386 0.8771675 -0.4497849 0.2166323 0.4830306 -0.848382 0.2384847 0.6038435 -0.7605907 0.1742894 0.7881488 -0.590292 0.1706851 0.4688782 -0.8666141 0.05829483 0.9762772 -0.2085294 0.09937155 0.846691 -0.5227234 0.05870729 0.9458188 -0.3193438 0.07652246 0.5114034 -0.8559271 0.09482818 0.567485 -0.817905 0.07456904 0.7435044 -0.6645606 -1.94146e-4 0.4901589 -0.8716332 -1.85664e-4 0.8159813 -0.5780784 -0.008799254 0.8500443 -0.5266379 -0.03209316 0.5569962 -0.8298948 0.01077979 0.9636489 -0.2669543 -0.1063781 0.5096802 -0.8537622 -0.04849952 0.8671682 -0.495648 -0.1254891 0.5433272 -0.8300892 -0.1215474 0.6854598 -0.7178936 -0.008886158 0.9932704 -0.1154775 -0.05544644 0.9492033 -0.3097401 -0.2261526 0.3751167 -0.8989676 -0.09841114 0.9247709 -0.3675787 -0.1750831 0.7892622 -0.588567 -0.2962574 0.4775121 -0.8271723 -0.2936149 0.4525547 -0.8420123 -0.2492215 0.6933244 -0.6761583 -0.3991151 0.3577871 -0.844213 -0.2808498 0.7390205 -0.6123498 -0.4225625 0.5384969 -0.7290145 -0.09742939 0.9739158 -0.2049283 -0.4674187 0.4711694 -0.7480102 -0.4295736 0.5344499 -0.7278941 -0.1669352 0.9380518 -0.3036305 -0.5268759 0.4200187 -0.7389087 -0.3065115 0.87238 -0.3807938 -0.2727276 0.8971565 -0.3474621 -0.3116426 0.8691263 -0.3840553 -0.5797479 0.5323723 -0.6168243 -0.5429905 0.5707231 -0.6159843 -0.7142266 0.3685819 -0.5950023 -0.4000115 0.8380469 -0.3710367 -0.6134754 0.5694682 -0.5471326 -0.5732989 0.6569846 -0.4895914 -0.8091639 0.2846013 -0.5140582 -0.04052758 0.9986135 -0.03359603 -0.5986799 0.6996075 -0.3900408 -0.7876895 0.4022492 -0.4666274 -0.2414818 0.9573581 -0.1585935 -0.4978306 0.8173385 -0.2900387 -0.2975661 0.9374485 -0.1806786 -0.8335462 0.3831288 -0.3980113 -0.8104246 0.465837 -0.3552578 -0.5997328 0.7519192 -0.2737483 -0.9143442 0.2948793 -0.2775267 -0.8372243 0.4688356 -0.2815115 -0.712554 0.6696114 -0.2094933 -0.5657131 0.7969333 -0.2118163 -0.3371496 0.9330705 -0.1253386 -0.6897001 0.7115812 -0.1340374 -0.9417164 0.311184 -0.1278074 -0.9142943 0.3892951 -0.1118724 -0.3786978 0.9239727 -0.053501 -0.7972736 0.5943868 -0.1051627 -0.2142795 0.9754695 -0.05043578 -0.6795998 0.73348 -0.01229476 -0.9430878 0.3323475 0.01143074 -0.4275965 0.9038162 -0.0166608 -0.8596104 0.5074599 0.05961936 -0.7527134 0.6571169 0.04024946 -0.8953418 0.4303902 0.1145752 -0.3168308 0.9480951 0.02709299 -0.1445148 0.9892765 0.02115845 -0.5438968 0.835295 0.08036518 -0.8067132 0.5580008 0.194548 -0.6290176 0.7630928 0.148413 -0.8559316 0.4550042 0.245667 -0.4647877 0.8671475 0.1789625 -0.7950405 0.486957 0.3616399 -0.819011 0.4493483 0.3568013 -0.4494696 0.8762929 0.1734589 -0.5762934 0.7726791 0.2661826 -0.8045464 0.3392611 0.4874496 -0.7623443 0.4181849 0.4939155 -0.6086533 0.6780366 0.4120773 -0.5156898 0.7943465 0.3210574 -0.1779755 0.9785172 0.1040614 -0.32509 0.9173615 0.2297049 -0.713774 0.3623411 0.5993627 -0.6352501 0.5099096 0.5800428 -0.5763933 0.6448779 0.5018997 -0.6196974 0.3725492 0.6907839 -0.6096066 0.4800284 0.6308348 -0.3347451 0.8846922 0.3244467 -0.3205422 0.8963063 0.3064113 -0.4153285 0.7529103 0.5105177 -0.5526685 0.4103235 0.7253911 -0.3656111 0.8221613 0.436325 -0.4448608 0.6402043 0.6262886 -0.5416801 0.2432236 0.8046272 -0.06697916 0.9938781 0.08786553 -0.469122 0.3731752 0.8004155 -0.212002 0.921534 0.3253158 -0.4000265 0.6458623 0.6502621 -0.1549964 0.9554405 0.2512166 -0.3374965 0.7259645 0.5992259 -0.42203 0.2835619 0.8610942 -0.3431763 0.4582093 0.8199234 -0.2700772 0.7415037 0.6141911 -0.2700358 0.7375441 0.6189584 -0.1557306 0.9239996 0.3492462 -0.2676524 0.3433421 0.9002658 -0.2673984 0.3980326 0.8775354 -0.2060423 0.6148051 0.7612892 -0.2033446 0.7334017 0.6486701 -0.08260518 0.9288808 0.3610498 -0.06961005 0.9650581 0.2526209 -0.1418529 0.1942763 0.9706362 -0.1175583 0.6343868 0.7640245 -0.0973227 0.382787 0.9186961 -0.04744905 0.8230428 0.5659941 -0.05608743 0.8857403 0.4607802 0.004029512 0.2785826 0.9604039 -0.01508957 0.3688806 0.9293543 0.02396106 0.6458802 0.7630627 -0.01235198 0.8058162 0.592037 0.1115788 0.3313512 0.9368866 0.1133305 0.5891809 0.8000138 0.134734 0.6363137 0.7595734 0.05413758 0.931627 0.3593609 0.2616015 0.3562923 0.8970065 0.07892096 0.9021465 0.42415 0.2048427 0.5874149 0.7829326 0.2249979 0.7251515 0.6507927 0.386165 0.2701933 0.8819707 0.01464456 0.9981814 0.05847668 0.1646389 0.8601312 0.4827716 0.3947393 0.3781284 0.8373767 0.1523268 0.922574 0.3544768 0.3424807 0.622815 0.7034263 0.3588297 0.5902813 0.7230556 0.2129915 0.8899818 0.4031962 0.5289325 0.2246431 0.8183923 0.5262062 0.3893823 0.7559686 0.4363579 0.5955696 0.6744543 0.2307683 0.9066153 0.353263 0.3858688 0.7648857 0.5158054 0.5767958 0.3875088 0.719127 0.5633028 0.5315496 0.6325702 0.1476733 0.9701341 0.1924383 0.4301522 0.7369159 0.5214634 0.6748536 0.4022075 0.6187097 0.6184739 0.5025179 0.604124 0.3830754 0.8495539 0.3626451 0.2697514 0.9274034 0.2591469 0.4556307 0.7952474 0.3999779 0.720949 0.4538455 0.5236954 0.6923449 0.5395883 0.4790649 0.143222 0.9846175 0.1000792 0.5166193 0.7636014 0.3873209 0.7175221 0.5594052 0.4150035 0.6853689 0.6284664 0.3678308 0.8716562 0.2142899 0.4407895 0.4338186 0.8594232 0.2705427 0.3268881 0.9256816 0.1904146 0.8311048 0.4537799 0.3214787 0.7289789 0.6198617 0.2904502 0.6955154 0.6682862 0.2639166 0.9156415 0.2670456 0.3004787 0.4557995 0.8746283 0.1651435 0.3644296 0.9261445 0.09719711 0.9437345 0.2876303 0.1631996 0.9094226 0.3743306 0.1811826 0.7563052 0.6370289 0.1489857 0.6833069 0.7220748 0.108166 0.4671235 0.880353 0.0823062 0.917108 0.3956005 0.04912465 0.9267678 0.3734841 0.04013973 0.7617066 0.6453877 0.05725306 -0.002140164 0.9999957 0.002060532 -0.002228677 0.9999962 0.001651287 -0.001024365 0.9999983 0.001570701 -0.001881062 0.9999969 0.001697778 -5.26286e-4 0.9999983 0.001764774 -0.001846015 0.9999982 5.49855e-4 0.001566052 0.9999718 0.00735253 -0.00403887 0.9999917 -6.59503e-4 -0.00288695 0.9999706 0.007108032 -0.004417598 0.9999902 -1.56702e-4 2.40897e-4 0.9999836 0.005726516 -0.004060745 0.9999917 5.23601e-4 9.67533e-4 0.9999794 0.006361544 -0.001743614 0.9999983 -6.43978e-4 0.001651227 0.9999906 0.004009664 -0.001677632 0.999998 -0.001167237 -0.00167495 0.999998 -0.001178622 0.002728879 0.9999902 0.003504633 0.003111124 0.9999886 0.003643929 -9.20567e-4 0.9999991 -0.001066446 0.003574073 0.9999896 0.002848863 0.003488123 0.9999903 0.002709031 -3.91545e-4 0.9999986 -0.001650094 0.003379523 0.9999935 0.001293599 -6.80887e-4 0.9999982 -0.001788735 0.004350244 0.9999903 7.67136e-4 -3.17208e-5 0.9999973 -0.002326846 -8.07592e-4 0.9999997 -3.96757e-4 0.004351019 0.9999903 8.19097e-4 0.002304255 0.9999974 1.37642e-5 1.04859e-4 1 -3.44176e-4 0.001795828 0.9999983 -5.26479e-4 0.004468441 0.9999401 -0.01000148 0.001535296 0.9999977 -0.001499712 0.001403629 0.9999964 -0.002313137 0.00799185 0.9999634 -0.003064513 0.00297898 0.9999938 -0.001880288 0.00188452 0.9999964 -0.001902997 0.9975327 0.06908619 -0.0124821 0.9894319 -0.021227 -0.1434358 0.9862231 -0.04991817 -0.1577091 0.9711498 0.03385114 -0.2360559 0.9467886 0.04537028 -0.3186424 0.9135938 -0.04590541 -0.4040288 0.9082 -0.01710325 -0.4181867 0.8430708 0.05051136 -0.5354254 0.785883 -0.03887134 -0.6171522 0.7873965 -0.04422211 -0.6148587 0.7160543 0.04355055 -0.6966847 0.651089 0.0306825 -0.758381 0.6025037 -0.04859644 -0.7966353 0.5708337 0.01693379 -0.8208912 0.4811897 0.06997233 -0.8738195 0.3906413 0.02213788 -0.9202767 0.3565239 -0.0508756 -0.9329 0.259491 0.05183261 -0.9643536 0.1150197 -0.0393638 -0.992583 0.1493513 0.0119518 -0.988712 0.04115593 0.04105007 -0.9983092 -0.09252136 -0.02695804 -0.9953458 -0.03862094 0.03557348 -0.9986205 -0.1407617 0.02567213 -0.9897107 -0.2472171 0.02038902 -0.9687457 -0.2956501 -0.02810388 -0.9548829 -0.326197 0.0184412 -0.9451219 -0.4353811 0.04158532 -0.8992853 -0.5077105 -0.03566598 -0.8607892 -0.5364531 0.0199722 -0.8436939 -0.6170641 0.04014343 -0.7858882 -0.6922037 -0.04613888 -0.720226 -0.6778528 -0.08382821 -0.730403 -0.759921 0.07384902 -0.6458068 -0.8105768 0.07208865 -0.5811785 -0.8740153 -0.06083416 -0.4820753 -0.8706033 -0.03961175 -0.4903886 -0.9253178 0.04519522 -0.3764896 -0.965903 -0.02324616 -0.2578586 -0.9657082 -0.02201646 -0.2586951 -0.9805617 0.04878509 -0.1900493 -0.9983035 0.01857322 -0.05518352 -0.9993354 -0.03459429 -0.01149076 -0.999762 -0.02161103 -0.003004312 -0.9893416 0.05903857 0.1331079 -0.9721097 -0.003986716 0.2344929 -0.9676996 -0.03374892 0.2498369 -0.9284056 0.06201565 0.3663566 -0.8927706 -0.02606427 0.449757 -0.8632486 0.04682064 0.502603 -0.7690238 -0.06705152 0.6356937 -0.8186181 0.03590267 0.5732151 -0.7419567 0.01832622 0.6701974 -0.6457818 0.07751297 0.7595773 -0.5412266 -0.05688112 0.8389508 -0.545542 -0.04572391 0.8368353 -0.4406605 0.05252325 0.8961359 -0.3368772 0.009430885 0.9415014 -0.2850154 -0.08749121 0.9545217 -0.208622 0.04724389 0.9768546 -0.1013298 0.07289004 0.9921792 0.02781367 -0.05837726 0.9979072 0.02085119 -0.04120022 0.9989333 0.1594279 0.06122487 0.9853093 0.2738758 -6.55221e-4 0.9617649 0.2913169 -0.02925807 0.9561791 0.340063 0.01796364 0.9402312 0.4481945 0.02198207 0.8936658 0.4963144 -0.05674546 0.8662864 0.5574885 0.04295808 0.8290725 0.6544083 0.04210293 0.7549684 0.7157169 -0.08016717 0.6937741 0.7457357 0.00362271 0.6662321 0.8107467 0.08486747 0.5792127 0.8897598 -0.01398462 0.4562147 0.9007605 -0.09367352 0.4240942 0.9460178 0.06902801 0.3166791 0.9750874 0.03792136 0.2185558 0.988164 -0.07883095 0.1315973 0.9942729 -0.01801216 0.1053422 0.9963246 -0.05300271 -0.06729048 0.9835469 -0.05301171 -0.1726996 0.9597749 0.07062685 -0.2717425 0.9677903 0.01912099 -0.2510308 0.9317165 -0.02715033 -0.3621702 0.8826178 -0.03220683 -0.4689868 0.9010285 0.03394842 -0.4324297 0.792065 0.002518057 -0.6104318 0.7762067 0.04890561 -0.628579 0.7153886 -0.04456549 -0.6973041 0.6413296 -0.02715027 -0.766785 0.572008 0.01709407 -0.8200699 0.5900102 0.05759435 -0.805339 0.4757704 -0.0621829 -0.8773688 0.3769863 -0.01028174 -0.9261618 0.2917011 -0.02530425 -0.9561748 0.3423439 0.04735696 -0.9383805 0.211938 -0.05641102 -0.9756537 0.110001 0.01677834 -0.9937899 0.07505613 0.07191902 -0.9945825 0.0226463 -0.01835697 -0.9995751 -0.08698791 -0.08625227 -0.9924685 -0.2129909 0.01820343 -0.9768847 -0.2375174 0.06326925 -0.9693207 -0.2945321 -0.02307927 -0.955363 -0.4426254 -0.03107529 -0.896168 -0.4986491 0.05999714 -0.8647252 -0.5380057 -0.01890468 -0.8427293 -0.6043994 -0.07578605 -0.7930686 -0.7107185 -0.01751083 -0.7032587 -0.7462294 0.09203225 -0.6592964 -0.7800441 0.008502662 -0.6256667 -0.8349195 -0.06084287 -0.5469987 -0.8805813 -0.04108113 -0.4721111 -0.9304841 -0.01108103 -0.3661647 -0.9091154 0.06762069 -0.4110192 -0.962861 -0.0521962 -0.264904 -0.9910187 -0.003638982 -0.1336737 -0.9844053 0.05830281 -0.1659734 -0.998326 -0.04911446 -0.03054666 -0.9966952 0.03487563 0.07336544 -0.9934462 0.0698921 0.09044158 -0.9834209 -0.04388672 0.1759468 -0.9601261 -0.05553704 0.2739958 -0.9360976 0.02385085 0.3509311 -0.933566 0.0373423 0.3564549 -0.8907746 -0.0370897 0.4529295 -0.8334025 0.02402633 0.5521442 -0.831017 0.03161871 0.5553477 -0.7453147 -0.06599086 0.663439 -0.6821985 0.01736718 0.7309608 -0.6692495 0.05474835 0.7410181 -0.5688818 -0.06306397 0.8199979 -0.4656024 0.01153558 0.8849189 -0.4012197 -7.65327e-4 0.9159816 -0.4354249 0.06305116 0.8980144 -0.2946097 -0.06612521 0.9533271 -0.1943053 -0.01394128 0.9808421 -0.1521277 0.04347258 0.9874044 -0.1009464 -0.03708827 0.9942004 0.009692311 -0.0519821 0.9986011 0.1044721 0.05024445 0.9932579 0.1518118 -0.03111708 0.9879195 0.2370878 -0.04974597 0.9702138 0.3502553 -0.01267766 0.9365686 0.3218896 0.02942264 0.94632 0.4769243 0.03156369 0.8783775 0.488886 -9.50906e-5 0.8723477 0.6057965 -0.06127607 0.7932566 0.6705963 9.0342e-4 0.7418221 0.6758568 0.018085 0.7368111 0.7812083 -0.03340542 0.6233761 0.810296 0.01683741 0.585779 0.840896 -0.04255914 0.5395209 0.9197061 0.02735894 0.3916535 0.8877542 -0.04041355 0.4585404 0.9097647 -0.01822471 0.4147242 0.9533827 -0.03079473 0.3001883 0.9678395 0.02518838 0.2503043 0.9833262 -0.057949 0.1723707 0.9958289 -0.03649485 0.08362412 0.9965116 0.08122199 0.01917213 0.9457664 -0.3220734 0.04236537 0.4442983 -0.8958131 0.01086449 0.8303222 -0.5549322 0.0511409 0.7631304 -0.6395453 0.0928114 0.5306454 -0.8446932 0.0700646 0.8399233 -0.514629 0.1722964 0.4356504 -0.8949168 0.09660631 0.4058911 -0.9090303 0.09442776 0.7857859 -0.574187 0.2298909 0.7877346 -0.5716059 0.2296543 0.3560061 -0.9245017 0.1362223 0.7811992 -0.5285059 0.3322792 0.7514641 -0.6001273 0.2741333 0.4684544 -0.8579146 0.2110282 0.7425146 -0.5519501 0.3795041 0.6926258 -0.6120859 0.3816024 0.4869167 -0.8374065 0.2483191 0.03543311 -0.9991542 0.02086842 0.700589 -0.5484587 0.4564737 0.7242451 -0.3229038 0.6092636 0.2944949 -0.9330615 0.2065652 0.6371519 -0.6007391 0.4828562 0.5502973 -0.7066723 0.4447329 0.3821452 -0.8707935 0.3093283 0.6558001 -0.3529013 0.6673732 0.5491051 -0.5884339 0.5934891 0.2817213 -0.907731 0.3108981 0.4826681 -0.658706 0.5771812 0.5474489 -0.3276657 0.7700228 0.3550755 -0.8300409 0.4300623 0.492273 -0.5541979 0.6712168 0.06241017 -0.9940688 0.08906388 0.4689353 -0.2114847 0.8575395 0.2340518 -0.8887247 0.3941931 0.1678578 -0.9378197 0.3038388 0.358628 -0.6746122 0.645201 0.4174058 -0.3848399 0.8232077 0.3613201 -0.6068907 0.7079064 0.3343409 -0.2978494 0.8941487 0.3106372 -0.369888 0.875607 0.2787322 -0.6522942 0.7048552 0.2300083 -0.7333307 0.639783 0.1478939 -0.9056923 0.3973021 0.2551196 -0.3739417 0.8916735 0.1704519 -0.5996142 0.7819266 0.170884 -0.7218124 0.6706605 0.08358192 -0.9461627 0.3127142 0.0944584 -0.9019018 0.4214864 0.1198801 -0.3799229 0.9172172 0.1474846 -0.5789771 0.801894 0.01326823 -0.9961604 0.08653599 0.04243594 -0.4467394 0.8936572 0.01376777 -0.5992102 0.8004733 0.0517053 -0.7327403 0.6785413 0.03921252 -0.8715851 0.4886735 0.01142305 -0.9245057 0.3809972 -0.008075118 -0.6126775 0.7902917 -0.08828097 -0.4231413 0.9017527 -0.05452758 -0.8610327 0.5056179 -0.06027543 -0.8636472 0.5004804 -0.05972027 -0.9401748 0.3354176 -0.1705291 -0.6318512 0.7560979 -0.2208335 -0.4745396 0.8520825 -0.1782346 -0.6237273 0.7610498 -0.2854707 -0.3462477 0.893655 -0.2048591 -0.7419508 0.6383901 -0.3424243 -0.3850571 0.8570162 -0.1461833 -0.9135437 0.3795635 -0.1337245 -0.927058 0.3502589 -0.3404515 -0.5115078 0.7889567 -0.08157354 -0.980126 0.1808286 -0.4595727 -0.3936761 0.7961232 -0.3708825 -0.5628699 0.7386634 -0.324856 -0.7266832 0.60531 -0.5130562 -0.3884683 0.7654187 -0.5396503 -0.3343299 0.7726585 -0.359021 -0.7789559 0.5141321 -0.3556348 -0.7892583 0.500595 -0.587678 -0.4018176 0.7022658 -0.2403764 -0.9163125 0.3202978 -0.5368419 -0.6035556 0.5895094 -0.2084445 -0.9462666 0.2472456 -0.5388416 -0.6099104 0.5810844 -0.7132539 -0.3449926 0.6101222 -0.4184125 -0.8315708 0.3652685 -0.4047425 -0.8271526 0.3898746 -0.7047109 -0.4642617 0.5365108 -0.5197166 -0.7519503 0.4055433 -0.7896726 -0.345586 0.5069396 -0.7911694 -0.3949185 0.4670016 -0.458563 -0.8438807 0.2785417 -0.2292032 -0.9594727 0.1639452 -0.6527643 -0.6705418 0.3525232 -0.8543967 -0.2711432 0.4432694 -0.4423598 -0.8521358 0.2796113 -0.8545643 -0.3814074 0.3524889 -0.8020301 -0.5093019 0.3120245 -0.6944953 -0.6572898 0.2926541 -0.5488649 -0.8109915 0.2025838 -0.3494746 -0.9261004 0.1421464 -0.1859819 -0.980652 0.0610938 -0.8870478 -0.3983004 0.2334591 -0.8221757 -0.5175039 0.237101 -0.6956915 -0.6957125 0.1788788 -0.9366788 -0.3145134 0.153994 -0.6529688 -0.7475582 0.1216084 -0.9183402 -0.375589 0.1248373 -0.7597827 -0.6427672 0.09788089 -0.9578599 -0.2782912 0.07112276 -0.436151 -0.8972848 0.06820839 -0.9219732 -0.3871392 0.009427726 -0.7476466 -0.663209 0.03432899 -0.938572 -0.3446475 -0.0173465 -0.5533215 -0.8328632 -0.0131942 -0.3823091 -0.9240178 -0.005565226 -0.9385214 -0.318898 -0.1322184 -0.8897874 -0.4449147 -0.1016324 -0.3393657 -0.940602 -0.009946823 -0.7613971 -0.6398802 -0.1040568 -0.6800932 -0.716588 -0.1548388 -0.9151957 -0.320246 -0.2446621 -0.3824543 -0.9194427 -0.09139949 -0.8677882 -0.4289637 -0.2508664 -0.3760644 -0.9220923 -0.09122222 -0.7495161 -0.6282573 -0.2086103 -0.8747462 -0.3361698 -0.3490117 -0.8115354 -0.4514321 -0.3709712 -0.6497941 -0.7095744 -0.2725287 -0.5090743 -0.8276095 -0.2364445 -0.8164116 -0.4059183 -0.4107339 -0.3543582 -0.9231085 -0.1493355 -0.7016641 -0.5609825 -0.4392791 -0.1177343 -0.9908721 -0.06566041 -0.5146986 -0.8087384 -0.2846536 -0.7042217 -0.4962712 -0.5077272 -0.6936606 -0.5297179 -0.4880922 -0.3582361 -0.8953561 -0.2645838 -0.3669334 -0.8906734 -0.2684417 -0.7004984 -0.451501 -0.5526743 -0.6593574 -0.4838596 -0.575437 -0.690057 -0.2071201 -0.6934859 -0.5510666 -0.6455182 -0.5288023 -0.4157845 -0.8113212 -0.4109514 -0.3605241 -0.8687483 -0.3395568 -0.5958829 -0.3747925 -0.7102494 -0.5593002 -0.4778091 -0.6774081 -0.1538349 -0.9709739 -0.183152 -0.4701329 -0.6174275 -0.6306809 -0.3951407 -0.7597646 -0.5163543 -0.441537 -0.5504016 -0.7085924 -0.2752637 -0.872883 -0.4028714 -0.4065623 -0.5843657 -0.702299 -0.325924 -0.7194651 -0.6133054 -0.2545719 -0.8599179 -0.4424187 -0.3952059 -0.3364907 -0.8547435 -0.3477959 -0.4215406 -0.8374614 -0.1429179 -0.9393474 -0.3117706 -0.2860355 -0.6868807 -0.6681157 -0.1938415 -0.8012573 -0.5660498 -0.2976288 -0.3289325 -0.8962258 -0.1450704 -0.912253 -0.3830784 -0.1960963 -0.5587978 -0.8057863 -0.1642405 -0.7340271 -0.6589608 -0.1601487 -0.3662477 -0.9166325 -0.02656918 -0.985692 -0.1664494 -0.09906417 -0.3559843 -0.9292263 -0.08209824 -0.8382968 -0.5389978 -0.03195708 -0.9632434 -0.2667226 -0.03922247 -0.5487887 -0.8350406 -0.03967034 -0.6958175 -0.7171223 0.01981061 -0.4680132 -0.8834994 0.08577984 -0.544097 -0.8346258 0.05055403 -0.8466597 -0.5297281 0.050112 -0.8475843 -0.5282894 0.04762566 -0.8597865 -0.5084282 0.1183938 -0.4775505 -0.8705909 0.1556932 -0.4635093 -0.8723065 0.2100045 -0.630787 -0.746998 0.1526595 -0.778894 -0.6082921 0.2411652 -0.5970665 -0.7650823 0.24085 -0.5970152 -0.7652216 0.0373581 -0.9883952 -0.1472394 0.3642812 -0.4344018 -0.8237683 0.1003931 -0.951732 -0.2900471 0.3897004 -0.4834831 -0.7838225 0.2966679 -0.7597127 -0.5786405 0.2516658 -0.8109343 -0.5282517 0.4585316 -0.3521029 -0.8159487 0.1589952 -0.9221119 -0.3527467 0.5123194 -0.3536373 -0.7826045 0.1014192 -0.9837116 -0.1484104 0.5086693 -0.5329081 -0.6762135 0.3642922 -0.7705657 -0.5229912 0.5726741 -0.4684372 -0.6727637 0.2574566 -0.912637 -0.3175055 0.5854652 -0.4962738 -0.6410483 0.6777862 -0.3494402 -0.6469138 0.4575695 -0.7739765 -0.4377107 0.3562539 -0.8627431 -0.3588282 0.7568722 -0.3096017 -0.5755792 0.7084914 -0.4131417 -0.5721485 0.5620406 -0.6947022 -0.4488868 0.5318139 -0.7570454 -0.3795474 0.7895992 -0.4003461 -0.4650335 0.3079355 -0.930046 -0.2004747 0.2288165 -0.9602593 -0.1598292 0.6428637 -0.6661404 -0.3781314 0.8457913 -0.2829746 -0.452286 0.5892332 -0.7514017 -0.2969844 0.4144411 -0.8844202 -0.214568 0.8413633 -0.3919817 -0.3720997 0.6370027 -0.7135629 -0.2916429 0.8750513 -0.3402465 -0.3442637 0.333311 -0.9345915 -0.1242685 0.8583799 -0.4332864 -0.2746762 0.6948371 -0.6861522 -0.2153989 0.6195472 -0.7536638 -0.2194358 0.9116369 -0.3237357 -0.2532062 0.2866358 -0.9528666 -0.0994246 0.9280999 -0.33179 -0.1689557 0.3555763 -0.9320936 -0.0690453 0.6524236 -0.7462675 -0.1320163 0.860245 -0.4981217 -0.1088727 0.4789333 -0.8741012 -0.08105671 0.8602709 -0.4980744 -0.1088848 0.9715437 -0.2292242 -0.05965995 0.7212963 -0.6922485 -0.02288442 0.5555477 -0.8313001 -0.01752585 0.1248288 -0.9921482 -0.007725119 0.007062017 -0.9999525 0.006720483 0.007231533 -0.9999424 0.007947087 0.002238333 -0.9999915 0.003477096 0.007406115 -0.9999595 0.005117237 0.01281684 -0.9998949 0.006794929 0.00105983 -0.999994 0.003317236 0.006264865 -0.9999789 0.001730442 3.24821e-4 -0.9999732 0.007314801 0.01252996 -0.9999215 -3.69874e-4 7.06263e-4 -0.999966 0.008230924 0.01270437 -0.9999192 3.60116e-4 0.01007711 -0.9999479 0.001658558 -6.454e-4 -0.9999687 0.007887184 0.004161298 -0.999991 -8.00427e-4 -0.001157402 -0.9999821 0.005895853 -0.001623392 -0.9999805 0.006036996 0.006542444 -0.9999603 -0.006058335 0.01104974 -0.9999248 -0.005323708 -0.001152813 -0.9999963 0.002463936 0.01062333 -0.9999338 -0.004418492 -0.00145936 -0.9999971 0.001907706 0.003445446 -0.9999889 -0.003247797 -0.009709298 -0.9999372 0.005601108 -0.009313941 -0.9999295 0.007376551 0.00236386 -0.9999904 -0.003721773 0.003491282 -0.9999831 -0.004655539 -0.01239645 -0.9998918 0.007928311 -0.01261997 -0.9999039 0.005734086 -0.009758055 -0.9999353 0.005846321 0.001090288 -0.9999896 -0.00442177 0.001084983 -0.999993 -0.003590583 -0.003398478 -0.9999941 5.93566e-4 -0.004535853 -0.9999896 -7.1144e-4 -0.005242288 -0.9999862 -4.53291e-4 -2.77903e-4 -0.9999945 -0.003348767 -0.001522243 -0.9999808 -0.006017804 -0.007185578 -0.9999667 -0.003871738 -0.001716196 -0.9999839 -0.005416333 -0.007971048 -0.9999628 -0.003332257 -0.008362054 -0.9999591 -0.003445386 -0.003260254 -0.9999781 -0.005758285 -0.009087383 -0.999893 -0.01147222 -0.003701448 -0.9999898 -0.002616822 -0.003067672 -0.9999899 -0.003308475 -0.00581175 -0.9999216 -0.0110926 0.9574748 0.2874618 -0.02465587 0.7325708 0.6802597 -0.02422583 0.9180767 0.3891953 -0.07524853 0.5462841 0.836236 -0.04778289 0.9306152 0.3488587 -0.1106936 0.4229625 0.9059276 -0.01995205 0.8093931 0.5580512 -0.1829259 0.6014695 0.7866108 -0.1395636 0.6659831 0.7341669 -0.1321576 0.8386365 0.505001 -0.2041151 0.8768993 0.3652921 -0.3124248 0.3522256 0.9296939 -0.107734 0.8279604 0.4041246 -0.3887996 0.8106932 0.463788 -0.3573198 0.3756297 0.9150363 -0.1470075 0.6327577 0.7257059 -0.2701274 0.5513663 0.7966123 -0.2477988 0.7732145 0.4252747 -0.470405 0.7740092 0.4151378 -0.4780904 0.160618 0.9823318 -0.09605324 0.5099686 0.8127374 -0.2817627 0.3637224 0.8977467 -0.2485094 0.7164378 0.4740214 -0.5118795 0.7273073 0.3430557 -0.5944215 0.4364791 0.8281306 -0.3516898 0.6917803 0.3750251 -0.6170868 0.4334887 0.8251803 -0.3621672 0.5888077 0.5537816 -0.5887542 0.5526472 0.5482874 -0.627664 0.5114784 0.597191 -0.6178615 0.3285391 0.8472148 -0.4174796 0.2520503 0.9240093 -0.287537 0.493421 0.491598 -0.7175425 0.06747484 0.9936428 -0.09011864 0.4153341 0.5610695 -0.7160298 0.3758328 0.6236781 -0.6854016 0.2738479 0.8293972 -0.4869369 0.1935154 0.9029549 -0.3836983 0.3187934 0.5140074 -0.7963462 0.2606257 0.5885953 -0.7652646 0.1586109 0.9103485 -0.382241 0.08503997 0.9563428 -0.2796009 0.248174 0.5831527 -0.7735261 0.2277969 0.373863 -0.8990745 0.1493826 0.7449728 -0.6501541 0.0895372 0.9212813 -0.3784493 0.1422816 0.4041542 -0.9035571 0.1358928 0.4227756 -0.8959877 0.1090832 0.6954274 -0.7102687 0.07442528 0.7481203 -0.6593762 0.04922264 0.8811632 -0.4702432 0.06492328 0.4166683 -0.9067374 0.0109573 0.6070774 -0.7945672 -0.004194498 0.6162505 -0.7875391 -0.0595656 0.4483382 -0.8918771 -0.03878068 0.8521859 -0.5218002 0.001526892 0.9336279 -0.358241 -0.1452129 0.4166387 -0.8973993 -0.06879609 0.8493149 -0.5233846 -0.1723259 0.4844651 -0.8576698 -0.1754844 0.5231568 -0.8339737 -0.09034341 0.9277831 -0.3620174 -0.2323434 0.5903252 -0.7730025 -0.2248774 0.6812368 -0.6966682 -0.3304944 0.3305618 -0.8840262 -0.1391908 0.8843992 -0.4454929 -0.4012176 0.3481686 -0.8472326 -0.2936657 0.7327172 -0.6139105 -0.01980948 0.9982244 -0.0561757 -0.2454957 0.8429455 -0.4787222 -0.190472 0.8929046 -0.4079731 -0.4089775 0.4661151 -0.7845216 -0.4674499 0.4216379 -0.7769892 -0.4714277 0.5843491 -0.6605241 -0.2844426 0.8545179 -0.4346166 -0.2412675 0.913102 -0.3286864 -0.5393332 0.5191423 -0.6630317 -0.5613852 0.5507342 -0.6176881 -0.314337 0.889209 -0.3324151 -0.6480916 0.3980675 -0.6492453 -0.437467 0.789508 -0.4304649 -0.6949727 0.353275 -0.6262665 -0.6341782 0.6066194 -0.479407 -0.5266515 0.7438338 -0.4115212 -0.1478982 0.9814614 -0.1219009 -0.7600975 0.4315946 -0.4857755 -0.7887511 0.4185641 -0.4501953 -0.4007142 0.8763962 -0.2671293 -0.7701727 0.4954136 -0.4017454 -0.5757899 0.7675331 -0.2817074 -0.439756 0.8646581 -0.24286 -0.8766948 0.3261501 -0.353599 -0.1825602 0.9806782 -0.07030069 -0.8637431 0.4129821 -0.2887799 -0.581155 0.78904 -0.1991856 -0.3735681 0.9208254 -0.111927 -0.7528691 0.6227282 -0.213068 -0.7620859 0.6208033 -0.1839248 -0.9123899 0.3806405 -0.1505243 -0.6405517 0.7606565 -0.1053345 -0.4809156 0.8736121 -0.07431101 -0.9019619 0.4216055 -0.09334707 -0.8099648 0.5838238 -0.05573987 -0.9569005 0.2861972 0.04932165 -0.3562603 0.9342337 -0.01691251 -0.3884086 0.9212144 -0.02242666 -0.7722434 0.6353206 -0.002799749 -0.7301284 0.6832492 0.009115397 -0.950618 0.2917748 0.1057966 -0.8650031 0.4834833 0.1342151 -0.6960079 0.7134454 0.08104705 -0.6198787 0.7801059 0.08476567 -0.3503209 0.9361655 0.02948737 -0.2410014 0.9699984 0.03196072 -0.8851168 0.4181219 0.2043093 -0.5341479 0.8326077 0.1464604 -0.7957254 0.5539394 0.2448928 -0.5467129 0.8200906 0.1689871 -0.8588495 0.3840025 0.338998 -0.5121603 0.8413502 0.1726897 -0.1929287 0.9770444 0.09034776 -0.7206295 0.5794726 0.3806637 -0.5728018 0.7691612 0.2833536 -0.728861 0.5533026 0.4032592 -0.3734935 0.9012319 0.2197357 -0.7281671 0.3914362 0.5626281 -0.3871899 0.8876139 0.2494506 -0.6631568 0.6048702 0.4408572 -0.5304562 0.7569247 0.3816821 -0.7078268 0.3024866 0.6383441 -0.6983711 0.3971242 0.595458 -0.5078466 0.7186383 0.4750273 -0.4694896 0.7817214 0.4104769 -0.2622717 0.93846 0.2247366 -0.6043739 0.4162157 0.6793355 -0.1614505 0.9744957 0.1558588 -0.4959293 0.6981558 0.5163649 -0.6029506 0.3640331 0.7098807 -0.3838418 0.7991651 0.4626021 -0.5263651 0.4191829 0.739747 -0.5226909 0.3743096 0.7659548 -0.1583085 0.9658271 0.2052235 -0.2926641 0.8593086 0.4194481 -0.3900831 0.7253361 0.5672061 -0.3426452 0.7643079 0.5462853 -0.2451232 0.8778891 0.41137 -0.3813194 0.545737 0.7461681 -0.3897669 0.4183478 0.8204066 -0.3866226 0.552469 0.738445 -0.2378087 0.7676869 0.5950664 -0.3039079 0.4151133 0.8575087 -0.3027851 0.403707 0.8633319 -0.1860197 0.8881482 0.4202255 -0.2319531 0.7346246 0.6375927 -0.01574748 0.9991647 0.03770983 -0.06545734 0.9779922 0.1981074 -0.1924293 0.3720253 0.9080574 -0.1776161 0.4091283 0.8950233 -0.1212318 0.7418794 0.6594831 -0.1280499 0.8088896 0.5738475 -0.07944577 0.9291573 0.3610472 -0.09975582 0.3402531 0.9350277 -0.06473791 0.7384311 0.6712142 -0.04925858 0.4492955 0.8920242 -0.04355961 0.5308465 0.8463479 0.009473681 0.2607276 0.965366 -0.00977081 0.9581185 0.2862055 -0.005393445 0.8716058 0.4901779 0.001641154 0.9161897 0.4007416 0.03404504 0.6720512 0.7397217 0.0962699 0.5751615 0.8123556 0.1056962 0.5759236 0.810642 0.1136538 0.7213671 0.6831635 0.1472762 0.4492771 0.8811696 0.04645168 0.9124189 0.4066132 0.1623908 0.7684692 0.6189382 0.2307602 0.4395411 0.8680746 0.1194048 0.9078785 0.4018696 0.0632103 0.9580818 0.2794348 0.2498391 0.5826215 0.7733904 0.3639656 0.3784009 0.8510828 0.2996771 0.5589014 0.7731901 0.4181586 0.2974696 0.8582863 0.1602711 0.9087625 0.38531 0.007705748 0.9997851 0.01924818 0.2773934 0.7642411 0.5822273 0.4455395 0.4191012 0.7911062 0.1048119 0.9731139 0.2050948 0.33159 0.7362447 0.5899083 0.5345269 0.3106012 0.7860077 0.3389925 0.8012046 0.493108 0.5453917 0.4109007 0.7305536 0.2478511 0.900339 0.3577144 0.3915438 0.7514053 0.5311155 0.6029731 0.3411942 0.7211172 0.5824947 0.5653811 0.58399 0.1625031 0.9706462 0.1773096 0.4764428 0.7201611 0.5043514 0.6504588 0.486275 0.5834723 0.3252744 0.897176 0.2987842 0.7754539 0.3373028 0.5337586 0.6689615 0.5504486 0.4994968 0.6017873 0.6775124 0.422882 0.398538 0.872298 0.2833085 0.3620582 0.9003052 0.2415871 0.8361672 0.3332704 0.4356094 0.8206056 0.3909925 0.416811 0.7264671 0.57874 0.3705479 0.4424349 0.8694953 0.2196124 0.6272468 0.7267712 0.2799377 0.65543 0.7100188 0.2574586 0.8961148 0.3174279 0.31019 0.8741735 0.3659471 0.3192235 0.8231993 0.531946 0.1984348 0.6236857 0.7567942 0.1956494 0.5009849 0.8549718 0.1343042 0.202925 0.9774047 0.05917418 0.1452575 0.988697 0.0371297 0.9038896 0.3952882 0.1634962 0.8427751 0.5096099 0.1732858 0.6746582 0.7321151 0.0940417 0.9385437 0.3239346 0.1191728 0.8228409 0.5676436 0.02671617 0.8082016 0.5855039 0.06320971 0.6658653 0.7425469 0.07244056 0.4154385 0.9093953 0.02027505 -3.31868e-4 0.9999999 3.21198e-4 -0.008022189 0.9999587 0.004291415 -2.51276e-4 0.9999999 4.29813e-4 -0.008018076 0.9999587 0.004293441 -0.01230949 0.9999133 0.004690825 -8.14963e-4 0.9999938 0.003442287 -0.001182258 0.9999915 0.003940463 -0.01140749 0.9999307 0.002921521 -0.01004481 0.9999436 0.003468155 -2.16246e-5 0.9999913 0.004177629 -0.007208406 0.9999741 -1.77293e-4 -0.008276522 0.9999655 -7.78584e-4 -1.2516e-4 0.999993 0.003765106 -0.007477045 0.9999694 -0.002307951 0.001343786 0.9999893 0.004439413 0.003890812 0.9999537 0.008805096 -0.0126596 0.9999001 -0.006299376 0.003791391 0.9999747 0.006020128 -0.0104503 0.9999192 -0.007239282 -0.009674847 0.9999366 -0.005765676 0.00589025 0.9999611 0.006569385 -0.004563212 0.9999764 -0.005153 0.005146145 0.9999779 0.004222631 -0.004911482 0.9998896 -0.01402342 0.01032274 0.9999382 0.004125177 -0.006836771 0.9998763 -0.01416486 0.01035946 0.9999361 0.0045349 -0.006770551 0.9998544 -0.01567101 0.01034641 0.9999363 0.004537284 -0.001635253 0.999956 -0.009237766 0.002282679 0.9999974 2.27191e-4 -9.05938e-4 0.9999479 -0.01017206 0.008661687 0.9999054 -0.01068943 0.001057147 0.9999772 -0.006672799 0.01944768 0.999805 -0.003446221 0.01169478 0.9999192 0.004983425 7.23498e-4 0.9999804 -0.006231248 0.001753509 0.9999932 -0.003270208 0.003388702 0.9999928 -0.001736581 0.008198738 0.9999364 -0.007755219 0.009653747 0.9999171 -0.00852704 0.008526623 0.9999254 -0.008740961 0.9969526 0.04606628 -0.06295585 0.9834547 0.007441282 -0.1810017 0.97361 -0.07055175 -0.2170394 0.9458056 0.0657804 -0.3180012 0.8962841 -0.0368787 -0.4419444 0.8937114 -0.02180039 -0.4481124 0.8387676 0.04076218 -0.5429617 0.7908496 -0.02544957 -0.6114811 0.7705203 0.02665627 -0.636858 0.7232401 0.03621649 -0.6896464 0.6660253 -0.05136257 -0.7441587 0.6456396 0.003851771 -0.7636327 0.5596228 0.07201147 -0.825613 0.5259985 0.05664134 -0.8485972 0.454409 -0.06902438 -0.888115 0.4125903 0.02415901 -0.9105963 0.3402132 0.0467025 -0.9391879 0.261228 -0.02147227 -0.9650383 0.2478848 -9.77417e-4 -0.9687891 0.0897684 -0.04288023 -0.9950392 0.1425804 0.03114187 -0.9892932 0.001632332 0.06630891 -0.9977978 -0.1496473 -0.04076611 -0.9878988 -0.1518665 -0.03446394 -0.9878 -0.2844378 0.07748121 -0.9555584 -0.3958986 -0.01679003 -0.9181407 -0.4181151 -0.07966631 -0.9048939 -0.5178626 0.06435149 -0.85304 -0.5913961 0.03441089 -0.8056467 -0.6370251 -0.07637304 -0.7670505 -0.6863053 0.03342735 -0.726545 -0.7484173 0.06230753 -0.660295 -0.8080422 -0.03671139 -0.5879797 -0.8026396 -0.01213115 -0.5963411 -0.8668252 0.03663086 -0.4972648 -0.9091678 -0.0274142 -0.4155268 -0.9170128 0.008298337 -0.3987717 -0.9709009 -0.03447592 -0.2369874 -0.9567852 0.03968226 -0.2880758 -0.9841456 0.03076201 -0.1746751 -0.9972192 -0.01471984 -0.07305783 -0.9975751 -0.007352709 -0.06920963 -0.998224 0.04986751 0.03258925 -0.9931493 -0.04120564 0.109346 -0.9824714 0.0473718 0.1802937 -0.95993 -6.5633e-4 0.2802391 -0.9649052 -0.04132246 0.2593269 -0.9266797 0.0561493 0.3716343 -0.8885555 0.01356375 0.4585686 -0.8683785 -0.05617064 0.4927106 -0.8411666 0.02299755 0.540287 -0.7821128 0.04793244 0.6212908 -0.7259592 -0.04487931 0.686272 -0.7128062 -0.005825161 0.701337 -0.6357851 0.04963958 0.7702683 -0.554663 -0.05906802 0.8299759 -0.5269343 0.015105 0.8497719 -0.4193782 0.07359588 0.9048235 -0.3515883 0.01645833 0.9360101 -0.3171097 -0.06138473 0.9464002 -0.2422289 0.03349411 0.9696408 -0.09838896 -0.05086636 0.9938472 -0.1519099 0.02311807 0.988124 -0.05305534 0.02246874 0.9983388 0.04690462 0.04969149 0.9976626 0.127446 -0.04423457 0.9908587 0.1550811 0.003558337 0.9878954 0.2628496 0.03478258 0.9642097 0.307157 -0.02576214 0.9513102 0.3771348 0.04670971 0.9249799 0.4960535 -0.06508982 0.865849 0.4733605 -0.01114481 0.8807984 0.5654292 0.05077594 0.8232324 0.6396083 0.05212241 0.766932 0.6956314 -0.04339814 0.7170869 0.7152674 0.001196146 0.6988499 0.780688 0.03819811 0.6237525 0.8238826 -0.03548586 0.5656484 0.8371994 0.002948164 0.54689 0.8897379 0.05643606 0.4529699 0.9274299 -0.02311998 0.3732817 0.926412 -0.01634514 0.3761565 0.9621042 0.02713418 0.2713288 0.9757844 -0.0291565 0.2167829 0.9850903 0.03719681 0.1679688 0.9968268 0.03647536 0.07075417 0.9982922 -0.05673241 0.01393026 0.9993919 -0.03018647 -0.01745814 0.989417 -0.02616518 -0.142722 0.9834291 0.03266561 -0.178326 0.9610316 -0.05762243 -0.2703666 0.9136022 0.01693332 -0.4062564 0.9196299 0.06849509 -0.3867676 0.8605239 -0.07405 -0.5039992 0.7873206 0.03643542 -0.6154664 0.7744144 0.08135193 -0.6274267 0.714416 -0.04784119 -0.6980839 0.6458976 -0.06229877 -0.7608779 0.5802493 0.01035636 -0.8143731 0.5779988 0.01745229 -0.815851 0.4722211 -0.03090369 -0.8809382 0.3848877 -0.02995651 -0.9224771 0.4202337 0.02169042 -0.9071568 0.2619157 -0.007512092 -0.9650615 0.2397198 0.03913021 -0.9700533 0.1478312 -0.0398736 -0.9882086 0.04938101 0.01439982 -0.9986763 0.02570033 0.05700248 -0.9980432 -0.0555194 -0.06150442 -0.9965616 -0.1904081 -0.02659571 -0.9813448 -0.2371927 0.06886529 -0.9690186 -0.2960824 -0.01949107 -0.9549636 -0.3862331 -0.0274614 -0.9219924 -0.4321419 0.03442281 -0.9011484 -0.4715626 -0.01765078 -0.881656 -0.5386538 -0.02383726 -0.84219 -0.5892745 0.03090226 -0.8073417 -0.5920095 0.02457547 -0.8055563 -0.6793452 -0.07352954 -0.7301258 -0.7534769 -0.01473855 -0.6573092 -0.7790077 0.0776214 -0.6221913 -0.8314545 -0.04700499 -0.553601 -0.8903509 -0.0291031 -0.4543437 -0.9304286 -0.03031963 -0.3652169 -0.9070578 0.02931976 -0.4199842 -0.9629254 -0.004466474 -0.2697307 -0.9682874 0.03073787 -0.2479408 -0.9833189 -0.04655128 -0.1758322 -0.9974087 -0.02228206 -0.0684061 -0.9961506 0.08720195 -0.00892812 -0.9952836 -0.06388294 0.07300412 -0.9844886 -0.07128131 0.1603166 -0.9597222 0.07439392 0.270922 -0.9640031 0.0475741 0.2616006 -0.9297497 -0.04111617 0.3658894 -0.8858406 0.01878625 0.4636095 -0.8773885 0.05280357 0.4768661 -0.8165432 -0.07311409 0.5726356 -0.7504712 -0.01994144 0.6606022 -0.6790016 0.02036583 0.7338543 -0.7024101 0.1051499 0.7039629 -0.5925773 -0.08676344 0.8008273 -0.5195252 -0.05983138 0.8523578 -0.4450761 0.01814377 0.895309 -0.4602147 0.04672437 0.8865773 -0.3386031 -0.04239964 0.9399735 -0.2350941 0.04382467 0.9709842 -0.2444661 0.06992691 0.9671332 -0.1503456 -0.0597108 0.9868287 -0.03546702 -0.06047922 0.9975392 0.03851145 0.04160636 0.9983917 0.03578078 0.03423213 0.9987733 0.1509702 -0.03895616 0.9877705 0.2550626 0.02148127 0.9666859 0.2498312 0.03330689 0.9677163 0.3413714 -0.05846834 0.9381083 0.4494165 -0.002476572 0.893319 0.5204299 -0.04456186 0.8527409 0.457374 0.01195162 0.8891941 0.6065481 0.03267174 0.7943752 0.6430155 -0.04484319 0.7645393 0.7552792 0.02611029 0.654883 0.7136261 -0.04059845 0.6993495 0.7628389 0.05671083 0.6440969 0.832751 -0.0731368 0.5487959 0.8904608 -0.0109241 0.4549288 0.9051086 0.05912494 0.4210495 0.9330669 -0.03261119 0.358222 0.9716278 0.02706187 0.2349622 0.9738063 0.008878827 0.2272054 0.9918349 -0.04920387 0.1176543 0.9984316 0.04743719 0.0297321 0.7561756 -0.6543374 -0.006407916 0.9105535 -0.4070814 0.07195252 0.4363488 -0.8996785 0.01336205 0.801026 -0.5957934 0.05820512 0.02287912 -0.9997383 1.64934e-4 0.9569044 -0.2662099 0.1160441 0.4164559 -0.9089245 0.02051264 0.7157465 -0.692489 0.09036552 0.6013685 -0.7943204 0.08608788 0.8968945 -0.4090815 0.1680256 0.1459525 -0.9891052 0.01920115 0.9024101 -0.3738095 0.2142957 0.5304565 -0.8394162 0.1183068 0.349614 -0.932788 0.08761644 0.8483183 -0.4729076 0.2381482 0.6693775 -0.7161382 0.1976867 0.8766957 -0.3427878 0.3374924 0.6073058 -0.7610564 0.2279759 0.342 -0.9284754 0.144809 0.8198489 -0.447074 0.3577325 0.6973386 -0.6451076 0.3123381 0.8436862 -0.3113036 0.4373601 0.3252926 -0.9346724 0.143431 0.6018481 -0.7309221 0.3217638 0.4820765 -0.836303 0.2611507 0.788773 -0.4003505 0.46643 0.6635228 -0.6391885 0.388813 0.7986518 -0.299505 0.5219695 0.1059598 -0.9926123 0.05910527 0.3469077 -0.9030202 0.2533962 0.6891465 -0.4763503 0.5460471 0.6778097 -0.4978482 0.5410372 0.2579025 -0.9476176 0.1884336 0.577928 -0.6880201 0.4388936 0.4487248 -0.819542 0.3563664 0.6091489 -0.5313243 0.5887548 0.5732851 -0.5815098 0.5772266 0.4402965 -0.7887855 0.4289016 0.5800891 -0.3851581 0.7177395 0.5461679 -0.5383269 0.6417981 0.286515 -0.8966564 0.3375153 0.1930078 -0.9515351 0.2394351 0.104148 -0.9872438 0.1204277 0.4136696 -0.7325742 0.540567 0.5006483 -0.3864915 0.7745809 0.3830848 -0.6483669 0.6579259 0.3727715 -0.6587716 0.6534993 0.2048229 -0.9051437 0.3725082 0.3660671 -0.4677001 0.8045195 0.3532916 -0.5985308 0.7189896 0.3194956 -0.3951634 0.8612599 0.1225407 -0.9503726 0.285965 0.1235229 -0.9496479 0.2879429 0.1961932 -0.8136153 0.5473011 0.2502341 -0.5161123 0.8191527 0.193822 -0.7845122 0.5890448 0.2142582 -0.3960861 0.8928657 0.2176529 -0.4678654 0.85658 0.1250065 -0.7222871 0.680202 0.1210637 -0.8160942 0.5650963 0.1467556 -0.3076144 0.9401257 0.04680025 -0.960988 0.272602 0.08454841 -0.4674238 0.8799811 0.06218463 -0.606942 0.7923097 0.03672122 -0.9687136 0.2454497 0.06254905 -0.6063805 0.7927109 0.007590353 -0.885547 0.464488 -0.05728906 -0.4436974 0.8943437 -0.02847731 -0.5781186 0.8154557 -0.04577142 -0.7785869 0.6258653 -0.02715009 -0.881894 0.4706655 -0.1397475 -0.3900634 0.9101215 -0.165917 -0.4715508 0.8660898 -0.04075586 -0.9463409 0.3205899 -0.1458434 -0.6639074 0.7334553 -0.2291842 -0.3774062 0.8972398 -0.1587915 -0.7881913 0.5945922 -0.2680753 -0.4526786 0.8504222 -0.2365632 -0.6427348 0.7286494 -0.1630368 -0.7873241 0.5945922 -0.3204463 -0.3280266 0.8886579 -0.1562015 -0.9007912 0.4051868 -0.3815521 -0.3763341 0.8442693 -0.3525055 -0.6249974 0.6965042 -0.306543 -0.7005387 0.6444199 -0.2045863 -0.8682703 0.4519416 -0.4118204 -0.596288 0.6890897 -0.176243 -0.9447512 0.276376 -0.4204413 -0.6792389 0.6015512 -0.5779944 -0.370527 0.727071 -0.4209364 -0.6788091 0.60169 -0.1069217 -0.9837177 0.1444549 -0.6302912 -0.3598754 0.6879119 -0.6243863 -0.4246808 0.6555823 -0.463077 -0.7212835 0.5150824 -0.6510587 -0.4246471 0.6291244 -0.4150218 -0.8081926 0.4178297 -0.7176364 -0.2827057 0.6364555 -0.3198124 -0.8926678 0.3175915 -0.5339183 -0.704191 0.468024 -0.7545864 -0.3903528 0.5274696 -0.7337336 -0.4284656 0.5273067 -0.5689064 -0.6983919 0.4342746 -0.4858222 -0.8070381 0.335658 -0.2783536 -0.9383918 0.2047934 -0.7729572 -0.4611518 0.4357479 -0.5750071 -0.7548496 0.3155456 -0.8325335 -0.3481546 0.4309019 -0.130841 -0.9883414 0.07785975 -0.5793 -0.7489373 0.3217214 -0.3505616 -0.9226369 0.1607726 -0.8674678 -0.3715357 0.3308492 -0.8379858 -0.4241271 0.3433602 -0.6645365 -0.6898222 0.2872919 -0.4985853 -0.8497542 0.1712623 -0.8731751 -0.3920564 0.289581 -0.9350417 -0.2429452 0.2582148 -0.6818646 -0.7089126 0.1802879 -0.5069964 -0.8473998 0.1576964 -0.9323719 -0.3079363 0.1893619 -0.3560954 -0.9309999 0.08022004 -0.7748587 -0.6184489 0.1308242 -0.7384744 -0.6681249 0.09091097 -0.9373687 -0.3453379 0.04562532 -0.7454279 -0.6625761 0.07300817 -0.1380969 -0.99031 0.01467776 -0.6610782 -0.7498927 0.02523273 -0.2796099 -0.9601134 8.84162e-4 -0.9365504 -0.3439845 -0.06744068 -0.9163307 -0.3966575 -0.05478167 -0.7425338 -0.6682749 -0.04530286 -0.6956099 -0.7152918 -0.06696712 -0.9193329 -0.3625339 -0.1529583 -0.4188613 -0.905674 -0.06564873 -0.8473631 -0.5022374 -0.1724338 -0.402057 -0.9127647 -0.072187 -0.8390063 -0.5126965 -0.1822386 -0.5497422 -0.8229928 -0.1430609 -0.8784856 -0.4101111 -0.2450958 -0.8182533 -0.4814335 -0.314139 -0.8198329 -0.4788318 -0.3139975 -0.1157619 -0.9926701 -0.03472018 -0.6882613 -0.6689266 -0.2807734 -0.5470175 -0.8104395 -0.2096656 -0.4266269 -0.8861125 -0.1810919 -0.8460972 -0.2995385 -0.4409041 -0.7637172 -0.4605678 -0.452342 -0.6485064 -0.6635941 -0.3729376 -0.5987502 -0.7186062 -0.3536995 -0.391821 -0.8919283 -0.2256993 -0.3303661 -0.921911 -0.2023326 -0.7815315 -0.3510795 -0.5157051 -0.6792734 -0.4919422 -0.5445922 -0.5781449 -0.6786553 -0.4529631 -0.6851164 -0.4261274 -0.5907886 -0.4288746 -0.8236614 -0.3710104 -0.3646911 -0.87743 -0.3116359 -0.6163474 -0.5069621 -0.6025822 -0.5107522 -0.6853318 -0.5190882 -0.638656 -0.3142367 -0.7024059 -0.1818217 -0.9646744 -0.1906418 -0.4165067 -0.7540003 -0.5079428 -0.5688722 -0.3807517 -0.7289805 -0.5305535 -0.4701625 -0.7053086 -0.1002511 -0.9882038 -0.1157713 -0.4183377 -0.7430406 -0.5223833 -0.4485639 -0.550864 -0.7038035 -0.4468221 -0.4698945 -0.7612813 -0.3262627 -0.8008594 -0.5021724 -0.2413123 -0.8800102 -0.4090849 -0.3985783 -0.4076717 -0.8215469 -0.3947019 -0.5040434 -0.7682126 -0.2574297 -0.7764737 -0.5751685 -0.2233411 -0.8837068 -0.4113164 -0.3660115 -0.3396584 -0.866411 -0.3093068 -0.4136414 -0.8562885 -0.1008688 -0.966797 -0.2347959 -0.2389381 -0.6657732 -0.7068625 -0.2195397 -0.7795668 -0.5865817 -0.1549564 -0.8737022 -0.4611216 -0.2835013 -0.2747154 -0.9187811 -0.1808333 -0.3672495 -0.9123745 -0.1840953 -0.3532887 -0.917222 -0.1449949 -0.6647428 -0.7328666 -0.1447637 -0.6566652 -0.7401584 -0.09115403 -0.8892692 -0.4482089 -0.09053617 -0.8901805 -0.4465218 -0.05856275 -0.3333142 -0.9409953 -0.04306405 -0.420823 -0.9061201 -0.04180204 -0.6202939 -0.7832548 -0.004558086 -0.9991146 -0.04182648 -0.02028971 -0.9028598 -0.4294561 -0.01834744 -0.7102732 -0.7036871 0.05497395 -0.3306349 -0.9421563 0.001452565 -0.9507698 -0.309895 0.08457958 -0.4284842 -0.899582 0.03014725 -0.9197949 -0.3912397 0.07844883 -0.635603 -0.76802 0.05314373 -0.6943936 -0.7176303 0.1546066 -0.2506991 -0.9556396 0.195776 -0.3170076 -0.9279968 0.1263086 -0.6888787 -0.7137873 0.1368988 -0.7720839 -0.6206008 0.2408657 -0.2628536 -0.9342867 0.07293832 -0.9147654 -0.3973469 0.2657779 -0.4080969 -0.8733952 0.05584526 -0.9764319 -0.2084758 0.2114399 -0.7142325 -0.6672071 0.1961442 -0.7448722 -0.6377249 0.1625985 -0.8797563 -0.4467557 0.3510873 -0.3614608 -0.8637614 0.3499646 -0.516184 -0.7817153 0.3678471 -0.5433304 -0.7546393 0.1988039 -0.88714 -0.416485 0.4538436 -0.3514561 -0.8188435 0.1270643 -0.965748 -0.2262421 0.3155909 -0.7483016 -0.5834786 0.5245575 -0.3389129 -0.7810105 0.350656 -0.7725921 -0.5292843 0.2344271 -0.913614 -0.3321949 0.4741507 -0.6129325 -0.6320561 0.5936851 -0.4773123 -0.6478512 0.5223627 -0.6023973 -0.6035353 0.4589411 -0.7441522 -0.4853973 0.1661319 -0.9674071 -0.1911123 0.2123934 -0.9503417 -0.2274641 0.6620942 -0.3917899 -0.6388521 0.6671701 -0.4366003 -0.6035431 0.4983433 -0.7364739 -0.4574497 0.46036 -0.8003744 -0.3840176 0.723782 -0.3701143 -0.5823702 0.7522377 -0.2953894 -0.5889683 0.3503684 -0.8911089 -0.2883867 0.6292151 -0.6389839 -0.4424794 0.7682614 -0.4322947 -0.4721185 0.6502212 -0.6289048 -0.4262524 0.8133378 -0.3472647 -0.4667857 0.4833613 -0.8369125 -0.2567871 0.8234289 -0.3771667 -0.4239227 0.2802142 -0.9424447 -0.1824227 0.8857483 -0.2521553 -0.389702 0.6489985 -0.706706 -0.2817226 0.510352 -0.8253854 -0.2414122 0.8723552 -0.345655 -0.3457156 0.7279697 -0.6254974 -0.2807369 0.9367352 -0.2169675 -0.274686 0.3215209 -0.9397766 -0.1159493 0.755348 -0.6318269 -0.1739087 0.7780674 -0.5966113 -0.1966371 0.4395977 -0.8915284 -0.1092283 0.8144261 -0.5616213 -0.1459167 0.9429327 -0.3099979 -0.1215701 0.3591812 -0.9320362 -0.04793274 0.6918615 -0.7186987 -0.06928223 0.9301431 -0.3665898 -0.02111607 0.9597889 -0.2783648 -0.03630936 0.7709473 -0.6366944 -0.01613771 0.4116914 -0.9103136 -0.04288756 0.003500759 -0.9999745 0.006228387 8.63147e-4 -0.9999992 9.31944e-4 9.47686e-4 -0.9999994 6.75707e-4 0.004881024 -0.9999668 0.006532549 8.39984e-4 -0.9999986 0.001504898 0.001854479 -0.999998 8.46282e-4 0.001387059 -0.9999988 6.98838e-4 3.842e-4 -0.9999994 0.001121759 0.001388967 -0.9999991 3.57212e-4 -0.001787066 -0.9999907 0.003961205 0.001015782 -0.9999529 0.009660363 0.009271502 -0.999957 -4.41099e-4 0.002806246 -0.9999961 5.53892e-5 -0.006257891 -0.9999227 0.01075184 -0.003637015 -0.9997147 0.02361148 -8.53471e-4 -0.9997275 0.02333152 0.006574571 -0.999977 -0.00169748 0.009650051 -0.9999374 -0.005674123 0.01103532 -0.9999251 -0.005302369 -0.00335139 -0.9999706 0.006908178 -0.005438268 -0.9999512 0.008256137 0.01118898 -0.9999209 -0.005759358 0.007019817 -0.9999592 -0.005679309 -0.003807544 -0.9999839 0.0042212 0.006964981 -0.9999608 -0.005489051 0.002746582 -0.9999893 -0.003740549 -0.005232453 -0.9999803 0.003484666 -0.006755888 -0.9999694 0.003962576 0.002706348 -0.9999082 -0.01327395 -0.005234539 -0.9999843 0.001999735 0.005266249 -0.9998818 -0.01445144 0.005888044 -0.9999301 -0.01025336 4.70695e-4 -0.9999805 -0.006239771 -0.006424844 -0.9999783 0.001486003 -0.001843094 -0.9999983 1.64031e-4 -0.002703428 -0.9998758 -0.01552748 -0.00142771 -0.9999991 -2.45104e-4 -0.003198504 -0.9999096 -0.0130608 -0.001848459 -0.9999224 -0.01231884 -0.009767651 -0.9999343 -0.006014764 -0.01261377 -0.9999043 -0.005702018 -0.01184374 -0.9999215 -0.004100084 -0.002567827 -0.9999868 -0.00446105 -0.005549132 -0.9999726 -0.004915595 -0.006492972 -0.9999562 -0.006743133 0.902799 0.4283905 -0.03789001 0.9443763 0.3214032 -0.06966716 0.1674064 0.9858841 -0.002781212 0.5867996 0.8089733 -0.0350477 0.6374773 0.7690369 -0.04695618 0.9299754 0.350593 -0.1105911 0.359256 0.932488 -0.03743475 0.960954 0.2132058 -0.1763824 0.7394787 0.6607999 -0.1285104 0.8926821 0.3948076 -0.2173607 0.7339296 0.661042 -0.156112 0.5904592 0.7908118 -0.1611666 0.9079861 0.2918111 -0.3006787 0.4612684 0.8783819 -0.1252064 0.8696075 0.3819648 -0.3128671 0.6673156 0.7023772 -0.2477021 0.2929369 0.9501816 -0.1065045 0.5956733 0.7580298 -0.2656395 0.3556062 0.9219532 -0.1534495 0.8286761 0.3718283 -0.4183774 0.8297952 0.3673365 -0.4201239 0.6367914 0.7040244 -0.3143984 0.7678995 0.4040151 -0.4970939 0.773712 0.3766238 -0.5094353 0.6267344 0.661766 -0.4114241 0.5654574 0.7518218 -0.3391493 0.3520867 0.9068686 -0.2315694 0.2600998 0.9516444 -0.1634656 0.740323 0.355086 -0.5708205 0.1125704 0.9902957 -0.08150172 0.4845976 0.7731231 -0.4092016 0.5821993 0.6201469 -0.5257964 0.4851359 0.7785864 -0.3980534 0.6477207 0.3614084 -0.6707026 0.5780779 0.5977848 -0.5554092 0.2934137 0.9125645 -0.2848412 0.4417995 0.7440472 -0.5012055 0.614165 0.2860594 -0.7355076 0.2968005 0.8987118 -0.3228415 0.5631541 0.3789666 -0.7343308 0.5003191 0.537887 -0.6784972 0.4541496 0.6626899 -0.5954748 0.1608639 0.9609189 -0.2252946 0.2688737 0.8561673 -0.4412308 0.4462985 0.3665302 -0.8163782 0.2436439 0.8828438 -0.4015279 0.4199507 0.5326352 -0.734807 0.3522735 0.6691551 -0.6543202 0.4219248 0.2894474 -0.8591855 0.2786709 0.6528635 -0.7043522 0.1484475 0.9218228 -0.358059 0.2840361 0.6481007 -0.7066039 0.1937771 0.8226 -0.5345838 0.2617528 0.4722619 -0.8416972 0.2189407 0.4226417 -0.8794539 0.2256892 0.472957 -0.8516901 0.02659678 0.9954806 -0.09116524 0.1261566 0.8114976 -0.5705754 0.1154487 0.8235118 -0.5554278 0.1347331 0.3484066 -0.9276099 0.06354928 0.9270936 -0.3694037 0.09854692 0.4527297 -0.8861854 0.0757035 0.6578294 -0.7493527 0.003867447 0.3498305 -0.9368051 -0.01087474 0.4234083 -0.9058738 0.0136047 0.7308101 -0.6824454 -0.01097619 0.8355888 -0.5492459 0.01155298 0.9228178 -0.3850635 -0.0927996 0.4643416 -0.880781 -0.07373267 0.7658219 -0.6388116 -0.0380854 0.8323898 -0.5528804 -0.1369562 0.3404148 -0.9302477 -0.0524224 0.9626944 -0.2654648 -0.2032139 0.526926 -0.8252595 -0.1429538 0.7694709 -0.622478 -0.1381601 0.859124 -0.4927655 -0.2770782 0.3882599 -0.8789095 -0.2982428 0.4196058 -0.857311 -0.2455198 0.7486844 -0.6157854 -0.1615028 0.857324 -0.4887868 -0.3728232 0.3305956 -0.8670119 -0.3897686 0.4345006 -0.8119665 -0.2892004 0.7189726 -0.632014 -0.2774679 0.8401083 -0.4660792 -0.4578198 0.3800864 -0.8037012 -0.1105377 0.9659748 -0.2338252 -0.4423475 0.6097221 -0.6576989 -0.27855 0.8394559 -0.4666088 -0.5843438 0.3352116 -0.7390369 -0.4810068 0.5756559 -0.6612509 -0.6301856 0.3289346 -0.7033265 -0.2391543 0.9252158 -0.2945858 -0.5899631 0.5455917 -0.5952085 -0.4658947 0.7095872 -0.5286097 -0.2886396 0.9017335 -0.3218137 -0.2754159 0.9250198 -0.2616952 -0.6251609 0.5444409 -0.5592477 -0.6265892 0.5364462 -0.565342 -0.4254516 0.8318209 -0.3564619 -0.7749539 0.3372965 -0.5344882 -0.6812576 0.5282886 -0.5067538 -0.0983808 0.992399 -0.07392913 -0.5410929 0.7582341 -0.3637301 -0.8245445 0.300714 -0.4792679 -0.5254681 0.7935978 -0.3067345 -0.5170841 0.7996709 -0.3052057 -0.8030193 0.4197815 -0.4230172 -0.303921 0.9366719 -0.1740055 -0.839953 0.3829088 -0.3845255 -0.7822189 0.5440868 -0.3034852 -0.6074492 0.7580201 -0.23751 -0.4952121 0.8530181 -0.1646966 -0.8939062 0.3717081 -0.2505291 -0.3494795 0.9295289 -0.1176445 -0.8880566 0.396341 -0.232958 -0.6626003 0.7364141 -0.1365838 -0.949481 0.2628807 -0.1714048 -0.893539 0.4397816 -0.09044402 -0.132506 0.9908264 -0.02655452 -0.7080343 0.700205 -0.09165376 -0.6508504 0.7523322 -0.1019322 -0.9109449 0.4051952 -0.07743495 -0.3380506 0.9405822 -0.03204697 -0.9572566 0.2865084 0.03965806 -0.898621 0.438422 0.01632404 -0.5888999 0.8079985 0.0183112 -0.4933594 0.8697007 0.01473772 -0.7214001 0.6911668 0.04325157 -0.9315072 0.3335475 0.1450533 -0.7848746 0.6034349 0.1408482 -0.2917847 0.9552425 0.04872065 -0.7447366 0.6485514 0.157317 -0.6349586 0.7579819 0.149302 -0.8662145 0.4174262 0.2746413 -0.1534473 0.9875154 0.03559899 -0.8329466 0.4521113 0.3190539 -0.7834785 0.5313761 0.3221815 -0.5747545 0.7923117 0.2046934 -0.3877265 0.9078514 0.1596063 -0.8013979 0.4284538 0.4173592 -0.7653957 0.5201185 0.3790069 -0.5820482 0.7393537 0.3384907 -0.353101 0.9144269 0.1978464 -0.3476326 0.9175401 0.193059 -0.7816532 0.3497555 0.51642 -0.7261109 0.449111 0.5206363 -0.6286346 0.6327779 0.452118 -0.7446565 0.3073847 0.5924537 -0.3298159 0.9131556 0.2395167 -0.5613644 0.70626 0.4313548 -0.6691709 0.378266 0.6396291 -0.2153469 0.9579536 0.1896066 -0.6002103 0.5191244 0.6084879 -0.5211474 0.7032701 0.4835458 -0.2931705 0.9091542 0.2957871 -0.5698688 0.4355542 0.6968086 -0.5599654 0.5032559 0.6581582 -0.3623473 0.7959297 0.4849748 -0.2710428 0.8984754 0.3453662 -0.4936624 0.3357236 0.802239 -0.1723696 0.9527959 0.2499372 -0.4897803 0.4374579 0.7541525 -0.3672615 0.7148312 0.5950927 -0.3189303 0.7569158 0.5704051 -0.2198318 0.8820482 0.4167312 -0.4112557 0.3957072 0.8211483 -0.3447448 0.5722894 0.7440671 -0.1818791 0.9030952 0.3890234 -0.2944983 0.3662824 0.8826709 -0.3007391 0.6003986 0.7409978 -0.208832 0.7683625 0.6049861 -0.04687434 0.9883751 0.1446292 -0.1988461 0.7734788 0.601823 -0.2324491 0.3952353 0.8886825 -0.2027443 0.4801558 0.8534315 -0.08638113 0.9219014 0.3776721 -0.1061232 0.952599 0.2851197 -0.1333572 0.3871551 0.9123196 -0.149733 0.4992269 0.8534357 -0.08561217 0.7132846 0.695626 -0.05616497 0.7462141 0.6633326 -0.04980283 0.345137 0.9372301 -0.03016054 0.4111539 0.9110668 -0.03799378 0.9188638 0.3927415 -0.03031873 0.7120391 0.701485 0.05303055 0.3198187 0.9459935 -0.002959489 0.9597041 0.2809973 0.03094428 0.7899457 0.6123955 0.04126751 0.8399201 0.5411389 0.08050304 0.3915213 0.9166408 0.1331974 0.3515527 0.9266441 0.06482309 0.8475974 0.5266656 0.176793 0.4720421 0.8636669 0.1473464 0.7047405 0.6939956 0.2347641 0.3593086 0.9032073 0.07003778 0.9510797 0.3009022 0.1898885 0.8031941 0.5646429 0.2878956 0.5272536 0.7994497 0.2043877 0.7897167 0.5784233 0.363655 0.3842628 0.8485854 0.226019 0.806549 0.5462547 0.3906428 0.4344834 0.8115556 0.365653 0.5885597 0.7210378 0.2701754 0.7757886 0.5702258 0.4663307 0.2388542 0.8517538 0.2616376 0.8655036 0.4271407 0.5228911 0.3181698 0.7907926 0.5007913 0.4861655 0.7161364 0.09588825 0.9834531 0.1537061 0.431792 0.6063908 0.6677169 0.2137402 0.9231641 0.3195047 0.5545992 0.5070427 0.6597936 0.5551995 0.4954738 0.6680264 0.02230197 0.9992159 0.03271687 0.354641 0.8427733 0.4049237 0.6370273 0.4409521 0.6322638 0.6366627 0.4707604 0.6107745 0.4559856 0.7961515 0.3977689 0.3459947 0.880474 0.3241194 0.7257525 0.376482 0.5757992 0.27148 0.9308137 0.2447135 0.7030873 0.5139412 0.4914599 0.6022469 0.6788182 0.4201245 0.7844488 0.3717613 0.4964208 0.5139974 0.7983064 0.3138687 0.2403314 0.9570159 0.1623623 0.8294518 0.348854 0.4362463 0.1447351 0.9860264 0.08248543 0.5462797 0.7899658 0.278447 0.7714342 0.531406 0.349996 0.6292052 0.7200412 0.2926458 0.8552141 0.4070908 0.3207584 0.249859 0.9613723 0.1154728 0.8575427 0.4240701 0.291179 0.9180086 0.2971938 0.262557 0.2944207 0.9511662 0.09273272 0.6140886 0.7714709 0.1665174 0.5410547 0.8270893 0.1522606 0.4774122 0.8690726 0.129579 0.8994699 0.402415 0.1703412 0.8504096 0.505935 0.1443378 0.9072443 0.4173409 0.05229216 0.8306017 0.5512086 0.07918351 0.6296693 0.7759978 0.03666353 0.4344797 0.899579 0.044555 -0.00787723 0.9999482 0.006461739 -0.00791639 0.9999473 0.006544172 -0.005330622 0.9999527 0.008147299 -0.007674157 0.9999482 0.006697177 -0.005191802 0.9999542 0.00804156 -0.004879593 0.9999851 0.002462863 -0.004794061 0.9999502 0.008761703 -0.005836308 0.9999815 0.001784384 -3.37306e-4 0.9999994 0.001113533 -0.004402637 0.9999898 0.001131892 -0.00313282 0.9999951 -3.60134e-5 0.002498865 0.9999516 0.009521484 3.14679e-5 0.9999994 0.001105368 -0.00266087 0.9999965 2.38995e-4 0.001012504 0.9999995 2.63285e-4 0.002982258 0.9999476 0.009803533 0.004843473 0.9999038 0.01299881 7.77517e-4 0.9999997 4.27294e-4 0.007425129 0.9998884 0.01296728 -0.001812577 0.9999949 -0.002639591 0.00672394 0.9999015 0.01232099 8.74188e-4 0.9999994 8.46349e-4 -0.002899229 0.9999913 -0.003019392 -0.002915143 0.9999248 -0.01191985 -0.007193207 0.9998998 -0.01219856 0.001111209 0.9999991 8.03416e-4 -0.007192254 0.9999028 -0.01194894 5.73643e-4 0.9999999 2.72814e-4 -0.002918004 0.9999516 -0.009405076 -0.002194344 0.9999327 -0.01140075 -9.2264e-4 0.9999504 -0.009933352 0.006031334 0.99998 -0.001969039 0.00838983 0.9999642 0.001112163 0.01127868 0.9999364 1.98136e-4 0.001390576 0.9999269 -0.01201558 -0.001337766 0.9999881 -0.004713892 0.006679415 0.9999772 -0.00107187 0.003946244 0.9999392 -0.01030385 0.003972172 0.9999275 -0.0113697 0.007653534 0.9999664 -0.002943634 0.006843149 0.9999721 -0.003028571 0.004673659 0.9999369 -0.01021498 0.007211029 0.9999656 -0.004119277 0.002135813 0.9999937 -0.002834022 0.003002822 0.9999927 -0.002368986 0.9583314 -0.2848018 0.0221101 0.6897407 -0.7237545 0.02091425 0.5125316 -0.858668 8.52513e-4 0.9036831 -0.4237722 0.06143373 0.7517685 -0.6569652 0.05692994 0.7102748 -0.6979917 0.09119951 0.9425733 -0.2972008 0.1524057 0.3051745 -0.9514112 0.04105347 0.8645803 -0.4738281 0.1672955 0.4904012 -0.8670057 0.08836215 0.3913418 -0.9177348 0.06793224 0.8428972 -0.4786534 0.2457954 0.8224813 -0.5215178 0.2270327 0.6560385 -0.7325851 0.1814737 0.8391641 -0.4497621 0.3058065 0.4462217 -0.877029 0.1780632 0.3595141 -0.9226717 0.1393799 0.7267053 -0.6056903 0.3240967 0.549021 -0.7969207 0.2519791 0.8106431 -0.3951972 0.4320614 0.4933468 -0.823304 0.280677 0.7651934 -0.4372171 0.472568 0.111344 -0.9922398 0.05534142 0.7248687 -0.5104593 0.4625978 0.4119947 -0.8738753 0.2580747 0.3007513 -0.9330106 0.1975854 0.6161203 -0.6280898 0.4752885 0.6544269 -0.5317262 0.5375804 0.6188784 -0.6318776 0.4666051 0.2492682 -0.947494 0.2003009 0.4164524 -0.8329585 0.3643456 0.6548762 -0.3669949 0.6606452 0.1378708 -0.9822688 0.1270426 0.6187117 -0.5290912 0.5807396 0.4499807 -0.7623189 0.4651747 0.4335681 -0.7732072 0.4627843 0.3108625 -0.8817361 0.3548323 0.6141582 -0.3687774 0.6977198 0.5028262 -0.5983865 0.6237784 0.4438514 -0.6217907 0.6452693 0.4335932 -0.6356702 0.6386864 0.2569334 -0.8959401 0.3623213 0.2060271 -0.9280174 0.3103817 0.4110054 -0.4424265 0.797078 0.3749407 -0.6362866 0.6742098 0.3082388 -0.741723 0.5956811 0.1912153 -0.9216224 0.3377114 0.3565905 -0.3169711 0.8788474 0.2430865 -0.7630817 0.5988449 0.3134621 -0.4221001 0.8506309 0.09525603 -0.971759 0.2158951 0.1639423 -0.8629382 0.4779755 0.2534066 -0.4011937 0.8802436 0.1739502 -0.6157344 0.7685133 0.1390739 -0.8484774 0.5106317 0.07563418 -0.9187587 0.3875074 0.1218997 -0.40933 0.9042065 0.1331939 -0.5859903 0.7992965 0.06744486 -0.7395259 0.6697409 0.05047428 -0.8896714 0.4538031 0.05177164 -0.3894587 0.9195877 0.01751661 -0.5800309 0.8144062 8.50157e-5 -0.9550182 0.2965472 -0.02126163 -0.6107507 0.7915375 -0.03154939 -0.8984373 0.4379672 -0.07273328 -0.4965776 0.8649397 -0.1443097 -0.4135344 0.8989795 -0.1092473 -0.5003057 0.8589292 -0.0931527 -0.8734993 0.4778299 -0.08544671 -0.8636658 0.4967698 -0.217193 -0.4155967 0.8832365 -0.2197734 -0.429905 0.8757176 -0.1842162 -0.7157998 0.673569 -0.07141548 -0.9536951 0.2921737 -0.3150878 -0.4110888 0.8554096 -0.3158407 -0.4447199 0.8381343 -0.2244722 -0.7507292 0.6213033 -0.2021867 -0.8423225 0.4996132 -0.2028671 -0.8443526 0.4958971 -0.4526697 -0.3338761 0.8268113 -0.4166995 -0.4341368 0.7986782 -0.09536433 -0.9776405 0.187416 -0.3231869 -0.7424217 0.5868222 -0.329445 -0.7644022 0.5542161 -0.2701405 -0.8679363 0.4167863 -0.4931787 -0.5129366 0.7026171 -0.5377212 -0.4520183 0.7117131 -0.520664 -0.4862794 0.7017417 -0.3476027 -0.8423398 0.4118689 -0.2787472 -0.8909164 0.358564 -0.6269045 -0.4035943 0.6664102 -0.6235189 -0.4120066 0.6644357 -0.06808745 -0.994888 0.0745784 -0.526875 -0.6748871 0.516653 -0.3894837 -0.8276032 0.4041973 -0.3133133 -0.904411 0.2896127 -0.7318509 -0.2533067 0.6326375 -0.663675 -0.5400163 0.5176079 -0.6153354 -0.6119828 0.4968295 -0.3632364 -0.8850189 0.2912063 -0.7200425 -0.4988158 0.4824125 -0.7078454 -0.5423027 0.4526178 -0.3118709 -0.9292793 0.1979312 -0.400545 -0.8862176 0.2327706 -0.8246328 -0.3943485 0.405549 -0.7450548 -0.52837 0.4070856 -0.4893253 -0.8377735 0.2422736 -0.8302902 -0.4050409 0.382832 -0.7510743 -0.5993875 0.2768069 -0.5018025 -0.8365806 0.2198345 -0.7862462 -0.5640603 0.2522951 -0.7804591 -0.5783702 0.2374273 -0.5393186 -0.8305382 0.1390745 -0.3355609 -0.936098 0.1054493 -0.8841698 -0.4274212 0.1885605 -0.2342377 -0.9698368 0.06744772 -0.85042 -0.4903565 0.1906214 -0.6358472 -0.7649419 0.1027731 -0.9375573 -0.3291319 0.1125105 -0.6216117 -0.7784484 0.08727622 -0.4145322 -0.9093859 0.03435742 -0.8833364 -0.464894 0.05991929 -0.4124346 -0.9103744 0.03341048 -0.8910716 -0.4518425 0.04277682 -0.8086809 -0.5876045 -0.02750045 -0.5340368 -0.8453105 -0.01597428 -0.8715044 -0.4841977 -0.07767188 -0.113012 -0.9935923 -0.001652002 -0.9146032 -0.384787 -0.1242579 -0.8756688 -0.47242 -0.1001181 -0.4182046 -0.9071266 -0.04718518 -0.6139045 -0.7804647 -0.1183057 -0.4431267 -0.8940008 -0.06634283 -0.9250873 -0.3115996 -0.2170696 -0.8801472 -0.4130675 -0.2339154 -0.7195823 -0.6627099 -0.2074054 -0.662587 -0.7269285 -0.1804257 -0.2322599 -0.9704149 -0.06595742 -0.9053314 -0.2513968 -0.3423081 -0.3639282 -0.9228112 -0.1263963 -0.8299055 -0.4416165 -0.340928 -0.7325898 -0.6221164 -0.2761946 -0.5347764 -0.8072081 -0.2498586 -0.407037 -0.8944287 -0.1852521 -0.8155702 -0.3882026 -0.42912 -0.7949108 -0.456902 -0.3991959 -0.619996 -0.7160999 -0.3206335 -0.2550189 -0.9567933 -0.1396854 -0.7762309 -0.3891508 -0.4960113 -0.7295997 -0.4757577 -0.4912627 -0.603333 -0.6997909 -0.3824685 -0.3691903 -0.8888876 -0.2712518 -0.728344 -0.3420341 -0.5937405 -0.7058812 -0.4543008 -0.5434544 -0.3502019 -0.8945729 -0.2776651 -0.4858614 -0.760666 -0.4304951 -0.6805145 -0.3415539 -0.6482601 -0.2089496 -0.9605829 -0.1833596 -0.612347 -0.4832001 -0.6257386 -0.5022764 -0.7123954 -0.4901136 -0.5802922 -0.418014 -0.6989458 -0.3486825 -0.8389274 -0.4178774 -0.2635995 -0.9104141 -0.3188441 -0.5397738 -0.4885423 -0.6855441 -0.4250601 -0.7052855 -0.5673591 -0.1593232 -0.9617292 -0.2229195 -0.4980657 -0.348016 -0.7942389 -0.4601967 -0.4404151 -0.7708786 -0.3683437 -0.7173458 -0.5913864 -0.3038085 -0.7923668 -0.5290135 -0.188057 -0.9329488 -0.3069871 -0.3925225 -0.3852716 -0.8351598 -0.3943838 -0.4237768 -0.8153986 -0.2921456 -0.7547898 -0.5873187 -0.3200019 -0.3800365 -0.8678544 -0.3259593 -0.3661534 -0.8715976 -0.06743991 -0.9826394 -0.1728344 -0.2259289 -0.6945342 -0.6830655 -0.2047234 -0.8236717 -0.5288225 -0.2335577 -0.341026 -0.910578 -0.2261921 -0.3645021 -0.9033135 -0.1003364 -0.9511033 -0.2921217 -0.1830239 -0.670189 -0.7192698 -0.1393697 -0.7362877 -0.6621606 -0.1359238 -0.3474123 -0.927809 -0.07512444 -0.9224677 -0.3786947 -0.1257907 -0.3916072 -0.9114936 -0.1147106 -0.666902 -0.736263 -0.05134338 -0.9430568 -0.3286454 -0.03037828 -0.9067159 -0.4206466 -0.05145466 -0.4516074 -0.8907318 -0.0259487 -0.6926577 -0.7207996 -0.03991991 -0.7541577 -0.6554791 8.2493e-4 -0.2466919 -0.9690936 0.04785209 -0.4362432 -0.8985556 0.03781962 -0.6622202 -0.7483543 0.01406103 -0.9590024 -0.2830489 0.05334585 -0.7157791 -0.6962863 0.05258238 -0.8910877 -0.4507749 0.1365405 -0.2803525 -0.9501364 0.1686794 -0.4388026 -0.8826096 0.1416026 -0.6183115 -0.7730716 0.1392602 -0.7929188 -0.5932003 0.09688067 -0.873324 -0.4774088 0.2392323 -0.3200876 -0.9166853 0.2712966 -0.3854952 -0.881925 0.1935876 -0.7514398 -0.6307631 0.3118962 -0.3144716 -0.8965649 0.2127947 -0.8095857 -0.5470735 0.1214135 -0.9516671 -0.2821144 0.4059859 -0.4323973 -0.8051138 0.05181086 -0.9888508 -0.1396057 0.3603021 -0.5297204 -0.7678403 0.2920718 -0.7175432 -0.6323179 0.2926304 -0.7951279 -0.5311679 0.2480179 -0.8649386 -0.4363123 0.4583749 -0.5050898 -0.7312844 0.4213922 -0.6149795 -0.6665051 0.5408539 -0.3099375 -0.781931 0.2379662 -0.9096153 -0.3405467 0.3982848 -0.7581384 -0.5163289 0.3364276 -0.8409012 -0.4239124 0.5721206 -0.4542216 -0.6829062 0.6226225 -0.3861277 -0.6806222 0.3391044 -0.8675103 -0.3639152 0.6289275 -0.462431 -0.6249862 0.4925727 -0.740719 -0.4568453 0.6977242 -0.341761 -0.6295875 0.1230903 -0.9865686 -0.1073842 0.7131876 -0.4528889 -0.5350282 0.5036405 -0.7558623 -0.418352 0.6871455 -0.5297721 -0.4971646 0.3663166 -0.8928389 -0.2620131 0.2941463 -0.9328272 -0.2081143 0.6966184 -0.5493574 -0.4614428 0.5570521 -0.7561813 -0.3433407 0.7875017 -0.4018116 -0.4673206 0.2291768 -0.9658687 -0.1207296 0.783051 -0.5121154 -0.3529433 0.773278 -0.5262854 -0.353645 0.5566199 -0.7849509 -0.2720785 0.4232148 -0.8864493 -0.1873421 0.8261151 -0.4839341 -0.2886896 0.800114 -0.5413842 -0.2583038 0.5505882 -0.814474 -0.1829885 0.4286938 -0.8861723 -0.1758419 0.8507375 -0.4919438 -0.1850323 0.8420942 -0.5056247 -0.1876729 0.4533263 -0.8868114 -0.08978301 0.2204374 -0.9734973 -0.06091254 0.43532 -0.8954567 -0.09302687 0.8761726 -0.4703856 -0.1051622 0.8623988 -0.4973874 -0.09420335 0.424292 -0.9045202 -0.04265683 0.8676198 -0.4961065 -0.03338271 0.4406855 -0.89673 -0.04088759 0.9931924 -0.002943754 -0.1164482 0.9970035 0.005511224 -0.07715982 0.9744255 0.001124978 -0.2247081 0.9746391 8.84519e-4 -0.2237806 0.9469719 -0.005161702 -0.3212751 0.9334445 0.002698123 -0.358712 0.9003731 -0.002341508 -0.4351125 0.861703 -0.004647254 -0.5073919 0.8888558 8.15541e-4 -0.4581866 0.8353096 0.00271213 -0.5497732 0.8043378 -5.60522e-4 -0.594172 0.7841172 0.003154933 -0.6206048 0.7512651 -0.00223416 -0.6599968 0.7108924 0.003701627 -0.7032911 0.6747337 -0.001302897 -0.7380602 0.6404863 0.005908787 -0.7679469 0.5622445 -1.19467e-4 -0.8269711 0.5624603 -1.83624e-4 -0.8268243 0.4421149 -0.001856029 -0.8969566 0.4300132 0.001406013 -0.9028215 0.3539881 -0.004430115 -0.9352395 0.2427476 -0.001280784 -0.9700887 0.3010941 0.004565358 -0.9535836 0.1415535 -0.003339767 -0.989925 0.203092 0.003354907 -0.9791539 0.0999189 0.003146827 -0.9949907 -2.8764e-4 -0.003160595 -0.9999951 -0.001854538 -0.002739906 -0.9999946 -0.1411939 0.001574397 -0.9899807 -0.1164953 0.003570854 -0.9931849 -0.1378456 9.59378e-4 -0.9904533 -0.2484639 0.001496016 -0.9686401 -0.2424115 1.37491e-4 -0.9701736 -0.3420463 -2.1187e-4 -0.9396831 -0.3452318 4.96711e-4 -0.9385173 -0.4393122 -1.16531e-4 -0.8983345 -0.4356108 -9.88781e-4 -0.9001346 -0.5319917 -2.22794e-4 -0.8467497 -0.523554 -0.00298959 -0.8519874 -0.638616 -0.004497408 -0.7695125 -0.5995733 0.003454923 -0.8003124 -0.7118006 -0.002787232 -0.7023761 -0.6828491 0.001353561 -0.7305582 -0.7840192 -6.14295e-4 -0.6207363 -0.7552071 0.004089713 -0.6554737 -0.8388662 -0.002803206 -0.5443306 -0.8132208 0.004592299 -0.5819373 -0.8912187 0.002909183 -0.4535648 -0.8853006 -3.73521e-4 -0.4650192 -0.9325504 -8.59545e-4 -0.3610389 -0.9292823 -0.003373026 -0.3693552 -0.9645761 0.003391385 -0.263783 -0.9732747 -0.002013504 -0.2296352 -0.9921364 -0.003208398 -0.1251208 -0.9837541 0.003179669 -0.1794934 -0.9995491 -0.002295315 -0.0299406 -0.9976653 0.002041399 -0.06826412 -0.9999392 -0.001905381 0.01087057 -0.9996156 0.001670897 0.02767765 -0.9923486 0.002113103 0.1234501 -0.9916648 0.003274917 0.1288028 -0.9733525 -0.003843545 0.2292819 -0.9626977 0.002601146 0.2705669 -0.9467319 -0.005698263 0.3219729 -0.9340618 -0.004377186 0.3570848 -0.9100296 0.005257487 0.41451 -0.8860868 -0.001380383 0.4635175 -0.8691409 0.002121746 0.49456 -0.8392673 -0.004288911 0.5437022 -0.8093657 0.002862334 0.5872982 -0.7595648 -0.003186166 0.650424 -0.7443251 0.001515626 0.6678158 -0.68066 -0.003983139 0.7325886 -0.6000698 -0.002694666 0.7999432 -0.6366961 0.004646003 0.7711009 -0.5486282 0.003817558 0.8360578 -0.4799467 -0.006228268 0.8772755 -0.4411596 0.002856075 0.8974242 -0.3486987 0.002265155 0.9372323 -0.3641234 -0.001978397 0.9313488 -0.292905 0.004878342 0.9561292 -0.2470761 3.35501e-4 0.9689961 -0.2129769 0.004237174 0.977048 -0.148603 -0.003004193 0.9888924 -0.09956002 0.00144422 0.9950305 -0.05235373 -0.003993988 0.9986206 0.009250104 7.86367e-4 0.9999569 0.03735417 -6.2283e-4 0.9993019 0.04634326 0.001147031 0.9989249 0.1641619 0.00212413 0.9864311 0.154411 1.72792e-5 0.9880067 0.2410748 5.64707e-4 0.9705064 0.2472538 0.002221941 0.9689483 0.383961 -7.91159e-4 0.9233491 0.3390285 0.006170034 0.940756 0.383134 -9.1002e-4 0.9236923 0.4937032 -0.003701806 0.8696227 0.4810839 -8.19557e-4 0.8766743 0.5619071 -0.003412306 0.8271933 0.5675622 -0.001917421 0.8233284 0.6303192 0.003287315 0.7763291 0.6448189 -0.001561343 0.7643339 0.7216775 -0.00339961 0.6922211 0.7460102 0.002225041 0.6659309 0.782786 -0.003612518 0.6222805 0.8075816 3.72525e-4 0.5897559 0.8318386 -0.004420816 0.555 0.8692593 0.003511905 0.4943439 0.8968397 -0.002387583 0.4423493 0.9064664 3.08738e-4 0.4222779 0.9274559 -0.004621326 0.3739043 0.9629412 -0.002961099 0.2696952 0.9485649 0.00186026 0.3165774 0.9857429 -0.004570841 0.1681962 0.9765666 0.003178596 0.2151917 0.9972294 0.006632208 0.07409167 0.9998335 -0.005062222 0.01753407 0.007854163 -0.999913 0.01060235 0.003305792 -0.9999907 0.002786993 0.01172757 -0.9998748 0.01063758 0.003863096 -0.9999797 0.00507909 0.004071593 -0.9999885 0.002556145 0.003029823 -0.9999275 0.01165872 0.00266242 -0.9999831 0.005188226 0.001824676 -0.999998 8.69521e-4 0.003002941 -0.9999279 0.01162964 0.00332117 -0.9999386 0.01058661 0.001665711 -0.9999986 3.89219e-4 4.26388e-4 -0.9999496 0.0100277 0.01029324 -0.999945 -0.002060174 3.49008e-4 -0.9999526 0.009734451 0.01403194 -0.9999015 4.20928e-4 0.01386547 -0.9999037 5.88296e-4 -0.003127396 -0.9999646 0.007811009 0.009485065 -0.9999536 -0.001722037 0.009530901 -0.9999531 -0.001752018 -0.002946734 -0.9999219 0.01215541 0.006665766 -0.9999739 -0.002803981 -0.005518615 -0.9999221 0.01120287 -0.005374491 -0.9999321 0.01035314 0.005472838 -0.9999841 -0.001399993 0.003078281 -0.9999921 -0.002501547 0.008905529 -0.9999023 -0.01077616 -0.00818336 -0.9999184 0.009817183 -0.006242275 -0.9999609 0.006260991 0.008075594 -0.9999023 -0.01141959 0.007530927 -0.9999111 -0.01101344 -0.01066529 -0.9999309 0.004973471 -0.01189148 -0.9999085 0.006456017 0.00602734 -0.9998973 -0.01300841 0.005984008 -0.9999074 -0.01222985 -0.01178717 -0.9999093 0.006530523 -0.002041161 -0.9999979 5.51182e-4 0.001658976 -0.9999761 -0.006713211 1.97023e-4 -0.9999709 -0.007629811 6.72629e-5 -0.9999658 -0.008275449 -0.002243459 -0.9999975 -1.75155e-5 -0.008497536 -0.9999629 -0.001489222 3.4223e-4 -0.9999673 -0.008089482 -0.008243858 -0.9999639 -0.002115249 -0.008233368 -0.9999639 -0.00211656 -9.64107e-4 -0.9999918 -0.003957688 -0.006730556 -0.9999725 -0.003128826 -0.002375304 -0.9999832 -0.005288898 -0.006804883 -0.9999718 -0.003206193 -0.002373397 -0.999985 -0.004933178 -0.003419339 -0.9999833 -0.004676282 -0.004217028 -0.9999841 -0.003751814 -0.004030048 -0.9999786 -0.005175232 -0.005469083 -0.9999755 -0.004383921 0.4569622 0.8891968 -0.02268946 0.9468155 0.3127853 -0.07553678 0.8855922 0.4617009 -0.05058503 0.4718629 0.881571 -0.01334083 0.1910899 0.9813339 -0.02164268 0.7173694 0.6911854 -0.08742862 0.5945011 0.8008372 -0.07230812 0.8628447 0.4734413 -0.1770661 0.4720125 0.8761996 -0.0973581 0.91977 0.3258906 -0.2186745 0.8654525 0.4648896 -0.1867349 0.6902614 0.6998147 -0.183844 0.4700621 0.8774744 -0.09529083 0.8745364 0.3521641 -0.3334166 0.8523167 0.4022791 -0.3342573 0.6911646 0.676218 -0.2549918 0.2611729 0.9602318 -0.09871077 0.4897304 0.8424118 -0.2247371 0.8261991 0.3770225 -0.4186277 0.8065977 0.4151865 -0.4207379 0.5578376 0.7755265 -0.2955943 0.5032818 0.8250231 -0.2569916 0.7685126 0.4196339 -0.4830071 0.6989819 0.538832 -0.4701963 0.2931668 0.9355496 -0.1969778 0.69207 0.4461969 -0.5674041 0.1088846 0.9906913 -0.08170068 0.6550385 0.5763449 -0.4886218 0.4480454 0.8175435 -0.3617707 0.6436551 0.460085 -0.6115799 0.5865395 0.5524907 -0.5922209 0.4151322 0.8126411 -0.4089983 0.3924088 0.8389294 -0.3771114 0.2708262 0.9243823 -0.2686461 0.5622198 0.4966787 -0.6612255 0.4778944 0.6110038 -0.6311033 0.3964896 0.7622781 -0.5115938 0.5299888 0.2639104 -0.8058929 0.4699181 0.571852 -0.6724302 0.2473165 0.9003705 -0.3580051 0.1640214 0.9611608 -0.2219617 0.4111707 0.6350548 -0.653945 0.2772665 0.8347371 -0.4757492 0.418654 0.4384598 -0.7952874 0.02804183 0.9983114 -0.05087345 0.4040862 0.358084 -0.8417186 0.4040427 0.4207606 -0.8122255 0.2593662 0.7707182 -0.5819988 0.2425132 0.8485698 -0.4702308 0.08179199 0.9793479 -0.1848997 0.2864836 0.4623376 -0.8391491 0.222902 0.7715637 -0.5958223 0.1628599 0.8486801 -0.5032085 0.2789493 0.413407 -0.8667653 0.1832354 0.4786382 -0.8586794 0.1723938 0.4260374 -0.8881286 0.114522 0.8456911 -0.5212401 0.1057397 0.8558723 -0.5062627 0.08793067 0.3616782 -0.9281472 0.09606957 0.4349651 -0.8953078 0.01426672 0.9940388 -0.1080901 0.05930072 0.6315504 -0.7730637 0.05025202 0.8431701 -0.5352935 0.03866034 0.8666646 -0.497391 -8.44904e-4 0.2623235 -0.9649797 -0.03689992 0.4107689 -0.9109925 -0.04123169 0.5409169 -0.8400648 -0.01454424 0.8837364 -0.4677591 -0.07319003 0.6829244 -0.7268133 -0.1556097 0.458036 -0.8752079 -0.01947575 0.9904223 -0.1366908 -0.1024139 0.6730579 -0.7324647 -0.125351 0.7636617 -0.6333309 -0.2425943 0.3303647 -0.9121444 -0.06776207 0.954275 -0.2911489 -0.2635807 0.4176266 -0.8695477 -0.2033537 0.7146384 -0.6692827 -0.3269619 0.3181606 -0.8898707 -0.2073916 0.7502624 -0.6277701 -0.1444447 0.9086177 -0.3918543 -0.3583094 0.4272727 -0.8300919 -0.2841157 0.6724188 -0.68347 -0.1431657 0.9238969 -0.3548496 -0.4030454 0.3658474 -0.8388743 -0.2708673 0.8173884 -0.508436 -0.4292877 0.4423753 -0.787411 -0.366011 0.6680516 -0.6478759 -0.2644866 0.8200131 -0.5075681 -0.4865436 0.3234727 -0.811567 -0.2317966 0.9012707 -0.3660346 -0.5828318 0.3048219 -0.7532535 -0.5354629 0.4441733 -0.7183243 -0.4684574 0.6330152 -0.6163113 -0.4553311 0.6701549 -0.5861451 -0.2867069 0.8748039 -0.3905348 -0.6573572 0.2521987 -0.7101249 -0.643818 0.4069495 -0.6479898 -0.2015583 0.9561034 -0.2126985 -0.5280783 0.6437243 -0.5538523 -0.4834761 0.7422206 -0.4640686 -0.2905399 0.9173443 -0.2721509 -0.688915 0.3613328 -0.6283588 -0.6414713 0.5667557 -0.5170131 -0.7639046 0.3643566 -0.5326294 -0.654089 0.5697169 -0.4975845 -0.5534802 0.7446157 -0.3731049 -0.2958323 0.9263705 -0.2330691 -0.5606731 0.7458261 -0.3597071 -0.7744888 0.4654342 -0.4284136 -0.4100281 0.8874254 -0.2106022 -0.8034211 0.4235082 -0.4185158 -0.1749606 0.9777943 -0.1153566 -0.7910016 0.4915425 -0.3642835 -0.737221 0.5906168 -0.3281418 -0.4898177 0.8444473 -0.2167658 -0.4229423 0.8836619 -0.2006526 -0.8954776 0.2797507 -0.3462072 -0.6803596 0.6998326 -0.2175896 -0.5684424 0.8025531 -0.1810575 -0.8962062 0.3563624 -0.2642355 -0.8534151 0.4657883 -0.2339316 -0.1522179 0.9870909 -0.04981362 -0.4616003 0.8792879 -0.11738 -0.3343116 0.9389307 -0.08151763 -0.9432266 0.2953389 -0.1519822 -0.8519433 0.4931119 -0.176163 -0.699367 0.7050785 -0.1172612 -0.9468632 0.3105507 -0.08371609 -0.8783842 0.4758009 -0.04532724 -0.6943415 0.7173283 -0.05770671 -0.2808949 0.9595333 -0.01984935 -0.5113846 0.859238 -0.01400214 -0.9024164 0.4307931 0.007872641 -0.839833 0.5405371 0.05000424 -0.7114503 0.7002845 0.05865263 -0.5531744 0.8326457 0.02644568 -0.9442162 0.3018783 0.1316255 -0.07077342 0.9974887 0.002761006 -0.3740313 0.9261481 0.04847866 -0.8586043 0.4853532 0.1650183 -0.7092159 0.6965021 0.1090759 -0.5026986 0.8574379 0.1099756 -0.5029265 0.8573601 0.1095383 -0.8990804 0.351731 0.2606526 -0.8593844 0.4594603 0.224399 -0.6590895 0.7282249 0.1878549 -0.8548721 0.4148926 0.3115415 -0.2718514 0.9581873 0.08929717 -0.6415367 0.7277362 0.2425505 -0.8697078 0.3231608 0.3730624 -0.5578398 0.793256 0.2440489 -0.3668476 0.9165464 0.1592655 -0.684531 0.6307629 0.3654525 -0.7958338 0.3687394 0.4802913 -0.6859726 0.6348023 0.3556228 -0.5467628 0.7601142 0.3511084 -0.7503123 0.3754351 0.5441324 -0.229981 0.9622336 0.145655 -0.7456818 0.4008424 0.5322444 -0.2038435 0.9712666 0.1228373 -0.569197 0.7159735 0.4042237 -0.511998 0.7566542 0.406611 -0.7108891 0.2732959 0.6480325 -0.28299 0.9285178 0.2403569 -0.690432 0.408647 0.5969183 -0.5754973 0.6353474 0.514914 -0.2487078 0.941526 0.2273178 -0.6298972 0.3722024 0.6816853 -0.5030611 0.6798819 0.5335637 -0.4847174 0.7012858 0.5227307 -0.3916764 0.8113863 0.4338689 -0.6266928 0.2499225 0.7381023 -0.05189013 0.9968861 0.05937671 -0.4989465 0.539504 0.6782241 -0.4695582 0.5630089 0.6801002 -0.2819448 0.875489 0.3924617 -0.2244284 0.9152874 0.3344863 -0.4641121 0.4976859 0.7327405 -0.2138079 0.9104065 0.3541838 -0.3989222 0.5455438 0.7370503 -0.3758333 0.5869855 0.7170757 -0.1426976 0.9464343 0.2896544 -0.3010149 0.5622771 0.7702172 -0.3139343 0.6302766 0.7100681 -0.1821036 0.864389 0.4686897 -0.02227723 0.9979231 0.06044268 -0.2414233 0.5791722 0.7786363 -0.2123425 0.6309174 0.7462265 -0.1608312 0.8645806 0.4760609 -0.1664498 0.35236 0.9209436 -0.07618713 0.9496225 0.3039947 -0.1648586 0.615905 0.7703784 -0.1658499 0.613535 0.7720549 -0.06406486 0.8907268 0.4500016 -0.06007736 0.9148291 0.3993475 -0.09467697 0.2832102 0.9543733 -0.05512303 0.6958265 0.7160915 -0.05164062 0.8314339 0.5532186 -0.05648517 0.3985543 0.9154037 -0.03300261 0.5815008 0.8128762 -0.003718376 0.9891451 0.1468952 0.04114466 0.604023 0.7959042 0.05016136 0.5792918 0.8135754 0.01980561 0.9276226 0.3729936 0.0388801 0.894793 0.4447853 0.1143463 0.5385374 0.8348069 0.1522554 0.6467825 0.7473224 0.08458113 0.8934454 0.4411365 0.08475202 0.9097382 0.4064403 0.2032838 0.5759636 0.7917965 0.2882586 0.5653647 0.7728323 0.2511785 0.6292484 0.7354969 0.1722595 0.8631537 0.4746498 0.1714009 0.8826236 0.4377186 0.4059447 0.3979756 0.8226933 0.3419512 0.5489618 0.7626994 0.2665569 0.8144755 0.5153418 0.4404246 0.3596336 0.8226116 0.455796 0.4275453 0.780676 0.04125463 0.9958775 0.08078545 0.2703135 0.8189216 0.5062591 0.3361093 0.7545557 0.5636279 0.5162667 0.3673644 0.7736358 0.1544677 0.9575513 0.2433831 0.2106972 0.9345674 0.2866892 0.5102323 0.5383265 0.6707217 0.3936262 0.7546945 0.5248759 0.3683192 0.7993684 0.4747117 0.6070206 0.3763923 0.6998963 0.4344543 0.7810997 0.4484783 0.6191722 0.4737786 0.6262266 0.6783341 0.3961414 0.6188172 0.1066275 0.9891012 0.1015359 0.3848935 0.8550169 0.3475677 0.2586541 0.9403098 0.2211686 0.6611721 0.535875 0.5250615 0.6063039 0.6381 0.4745777 0.7645621 0.3468903 0.5432421 0.7903761 0.386167 0.4755846 0.7101356 0.5872393 0.3884036 0.5699227 0.7495015 0.336802 0.3974474 0.8888106 0.2281473 0.3137997 0.9361616 0.1585286 0.8673686 0.3266949 0.3754228 0.7620942 0.5369969 0.3617275 0.8941359 0.3210599 0.3121563 0.8674079 0.4085045 0.2841265 0.6435852 0.7328472 0.2207559 0.6393688 0.7371934 0.2185259 0.4511296 0.8772529 0.164042 0.9056281 0.3715183 0.2044796 0.9027113 0.3796805 0.2023741 0.6804228 0.7156493 0.1577058 0.2525254 0.9661092 0.05351614 0.5977142 0.7948274 0.1048204 0.5433787 0.834907 0.08757984 0.8823006 0.4593012 0.1028993 0.1350425 0.9905474 0.02407366 0.9218111 0.3816412 0.06792807 0.8405222 0.5416579 0.01136958 0.6125603 0.7902845 0.01484364 -0.00313425 0.9999907 0.002957105 -0.003647923 0.9999855 0.003964424 -0.003412663 0.9999903 0.002819061 -0.001933932 0.9999939 0.002903282 -0.001544356 0.9999985 8.88515e-4 -0.001635253 0.9999898 0.004230558 -0.001152217 0.9999935 0.003431141 -0.001791179 0.9999983 5.20036e-4 -0.01288616 0.9999169 3.41819e-4 -0.01244407 0.9999217 0.001369357 -3.15708e-4 0.9999949 0.003186464 -0.009698092 0.9999508 0.002075135 8.84865e-4 0.999971 0.007571756 -0.002236127 0.9999976 -1.64913e-4 0.00349766 0.9999454 0.009848833 9.55368e-4 0.9999719 0.007445096 -0.00214219 0.9999976 -5.26585e-4 0.00330621 0.9999421 0.01023834 -0.006559193 0.9999715 -0.003765225 -0.007981181 0.9999615 -0.003647267 0.00317347 0.9999436 0.01014584 -0.007903933 0.9999635 -0.003253042 0.001023769 0.9999979 0.001802384 -0.002743363 0.9999943 -0.001993954 -0.002398431 0.9999836 -0.005200386 0.001441001 0.9999979 0.001481354 0.006216764 0.9999719 0.004202842 -0.005880773 0.9999577 -0.007075965 0.006249308 0.9999713 0.004294633 -0.004385888 0.9999078 -0.01285356 -0.00622183 0.99989 -0.01346844 0.007641553 0.9999622 0.004167497 0.006384909 0.9999763 0.002583801 -0.006054639 0.9999712 -0.004585504 0.007632136 0.9999696 0.001691877 -0.001174807 0.9999693 -0.007747292 0.01057219 0.9999431 0.001496791 -7.0184e-4 0.9998949 -0.01448118 0.008622169 0.9999629 1.20972e-4 0.001206576 0.9999095 -0.01339793 0.009536147 0.9999545 -5.63531e-4 -2.47939e-4 0.9999392 -0.01102811 0.006578862 0.9999773 -0.0014714 0.001862347 0.9999746 -0.00688076 0.004254996 0.9999562 -0.008335709 0.01038223 0.9999257 -0.006402909 0.01263004 0.9999008 -0.006231784 0.00180149 0.9999857 -0.005042195 0.01257848 0.9999026 -0.00606203 0.001120328 0.9999991 -8.71911e-4 7.5924e-4 0.9999994 -8.52923e-4 -0.1139696 -0.5495232 -0.8276686 -0.02677506 0.8634816 -0.5036693 -0.1238877 -0.5036112 -0.8550015 -0.1163351 -0.7575366 -0.6423431 -0.06017208 -0.8880133 -0.4558638 -0.2687854 -0.4388725 -0.8574063 -0.1905621 -0.7474144 -0.6364415 -0.1531808 -0.9010575 -0.4057475 -0.2905784 -0.6151277 -0.7329271 -0.4508392 -0.3021814 -0.8398991 -0.2135809 -0.892184 -0.3979836 -0.4318285 -0.5891525 -0.6829521 -0.327901 -0.7896277 -0.5186224 -0.6113958 -0.3984924 -0.6836658 -0.5812788 -0.5407626 -0.6080221 -0.6856127 0.1868519 -0.7035777 -0.2656207 -0.9235768 -0.2764989 -0.6771038 -0.3629249 -0.6401687 -0.4274227 -0.8259359 -0.3676138 -0.7241402 -0.5062817 -0.4682946 -0.3554396 -0.9089397 -0.2179252 -0.5956122 -0.6810978 -0.4258543 -0.4394052 -0.87614 -0.1982468 -0.7580502 -0.5448298 -0.3584977 -0.7308129 -0.6028625 -0.3201085 -0.8581632 -0.4458859 -0.2544438 -0.642199 -0.7211946 -0.2597282 -0.432026 -0.8895679 -0.1484007 -0.8908267 -0.4101864 -0.1953841 -0.745113 -0.6573565 -0.1126462 -0.9117103 -0.4096406 -0.03129088 -0.7632251 -0.6361612 -0.113077 -0.4617834 -0.8860928 -0.03994709 -0.9436691 -0.3302981 -0.01979458 -0.4196066 -0.9077041 0.001893699 -0.7898599 -0.6108795 0.05429226 -0.9163467 -0.3591768 0.1769201 -0.8195579 -0.5555558 0.1402948 -0.5347819 -0.8370854 0.11531 -0.8489357 -0.4626794 0.2554135 -0.7147179 -0.6779006 0.1721316 -0.8076806 0.5451061 0.2247478 -0.7610913 -0.5463597 0.3496159 -0.2681298 -0.95649 0.1150361 -0.7110151 -0.6347634 0.3025442 -0.8005815 0.2640953 0.5378877 -0.5334157 -0.7594243 0.3724814 -0.6206385 -0.602378 0.5019449 -0.2804744 -0.9289124 0.241777 -0.5340729 -0.6533975 0.5365052 -0.1442127 -0.9467644 0.2878193 -0.3963375 -0.7451809 0.536304 -0.3764081 -0.6567134 0.6534866 -0.4068735 -0.6163294 0.6742344 -0.1323272 -0.9727365 0.1904557 -0.436882 -0.1154318 0.8920816 -0.2979549 -0.6723533 0.6776164 -0.2699191 -0.4753573 0.8373644 -0.1448081 -0.913248 0.3808001 -0.1658829 -0.6417966 0.7487189 -0.1197319 -0.4764097 0.8710328 -0.0620805 -0.8937495 0.4442499 -0.07931584 -0.5871245 0.8056015 -0.05181908 -0.7491801 0.6603363 0.04960745 -0.4744378 0.8788901 0.0496394 -0.4744739 0.8788689 0.01652407 -0.9180706 0.3960723 0.2272158 -0.3789259 0.8970999 0.1583427 -0.6353183 0.7558428 0.1112477 -0.9084433 0.4029326 0.286144 0.4936887 0.8212145 0.3566686 -0.2253271 0.9066506 0.2895371 -0.7676424 0.5717461 0.4273604 -0.5582678 0.711126 0.1984519 -0.8725106 0.4464773 0.5374478 -0.4114705 0.7360992 0.4266604 -0.637669 0.6413573 0.2703108 -0.8997249 0.3426768 0.5254505 -0.6051632 0.5980631 0.3736181 -0.8800716 0.293059 0.6372061 -0.6081428 0.4734245 0.6616817 -0.5528076 0.5065383 0.448499 -0.8263896 0.3404833 0.3966127 -0.8697257 0.2937271 0.7529458 -0.5418963 0.3733912 0.7600275 -0.5315921 0.3738555 0.3083739 -0.9404589 0.1429779 0.7347236 -0.6268307 0.2593539 0.8787966 -0.4272319 0.2125781 0.4469945 -0.887161 0.1146364 0.5695633 -0.8055918 0.1631554 0.776421 -0.6173089 0.126887 0.4108055 -0.9116536 0.01125717 0.947521 -0.3180943 -0.03193664 0.847674 -0.5305022 0.004044294 0.5573158 -0.8300826 -0.01902651 0.8152344 -0.5677516 -0.1142413 0.8847792 -0.4349632 -0.1672508 0.3608064 -0.9292736 -0.07918065 0.7677599 -0.5687237 -0.2951239 0.9107227 -0.2937287 -0.2903582 0.4489712 -0.8788018 -0.1616546 0.7484496 -0.5482975 -0.3730858 0.5852264 -0.7739621 -0.2418529 0.8064914 -0.2541375 -0.5338407 0.4652303 -0.8517326 -0.2410653 0.5700842 -0.7051386 -0.421644 0.7396401 -0.2541521 -0.6231688 0.3678972 -0.8386279 -0.4016903 0.5492754 -0.6056209 -0.5757777 0.4906272 -0.6168388 -0.6154631 0.4706857 -0.5245997 -0.7094012 0.4254381 -0.7184373 -0.5503184 0.4040376 -0.7660216 -0.4999645 0.3496287 -0.5837867 -0.7327707 0.3389164 -0.6859109 -0.6439425 0.07337039 -0.9855254 -0.1528286 0.1872841 -0.75458 -0.6289147 0.3114416 -0.4771757 -0.821771 0.1810934 -0.7023198 -0.6884419 0.1595848 -0.492994 -0.8552718 0.09818172 -0.9124639 -0.3972027 0.165161 -0.73337 -0.6594621 0.07098764 -0.3071308 -0.949016 0.01534944 -0.7935494 -0.6083123 0.002409517 -0.7608754 -0.6488937 -0.03480231 -4.60474e-4 0.9993942 -0.06483823 7.76866e-5 0.9978958 -0.1692452 -8.66862e-4 0.9855737 -0.2358162 3.48251e-4 0.9717977 -0.3284974 -9.78589e-4 0.9445044 -0.3948688 3.57502e-4 0.9187375 -0.4917122 -6.33389e-4 0.8707576 -0.5005022 -9.01091e-4 0.8657348 -0.5896041 1.16786e-4 0.8076923 -0.6431601 -8.42518e-4 0.7657314 -0.6993987 1.5131e-4 0.7147317 -0.7382982 -7.34224e-4 0.6744741 -0.8082336 3.89131e-5 0.588862 -0.8346015 -3.75605e-4 0.5508542 -0.8404834 -1.3273e-4 0.5418375 -0.8936312 0.001155793 0.4488006 -0.9187933 -4.46839e-4 0.3947387 -0.9606275 1.01863e-4 0.2778395 -0.9616451 -2.4445e-5 0.2742969 -0.9871572 -4.72103e-4 0.1597513 -0.9938538 5.28385e-4 0.1107004 -0.9999436 -9.98824e-4 0.01057374 -0.9963888 3.95653e-4 -0.08490771 -0.9884399 -1.9216e-4 -0.1516129 -0.9792927 5.10713e-4 -0.2024493 -0.9699184 -2.53461e-4 -0.2434304 -0.9243493 4.06284e-4 -0.3815472 -0.9181255 -8.37102e-5 -0.39629 -0.8260645 9.30338e-5 -0.5635757 -0.827669 1.94721e-4 -0.5612167 -0.7192981 -3.61244e-4 -0.6947016 -0.7000833 5.43858e-4 -0.7140611 -0.5760549 0.001123726 -0.8174102 -0.5417956 -5.65498e-4 -0.8405103 -0.4526535 -5.25507e-4 -0.8916864 -0.3471809 4.90908e-4 -0.9377981 -0.3577655 8.26333e-5 -0.9338115 -0.1923367 -4.10041e-4 -0.981329 -0.1340182 0.001024007 -0.9909784 -0.06595003 -3.01111e-4 -0.9978229 0.05390208 1.09763e-4 -0.9985463 0.08586245 -7.40388e-4 -0.9963067 0.2308011 4.25301e-5 -0.973001 0.270055 -7.00254e-4 -0.9628447 0.3088695 2.59464e-5 -0.9511045 0.4588871 -7.10717e-4 -0.8884944 0.4402796 -1.42615e-4 -0.8978608 0.5576685 5.3167e-4 -0.8300636 0.5835394 -1.60329e-4 -0.8120849 0.6993599 7.00145e-4 -0.7147694 0.6904868 3.64944e-4 -0.7233449 0.7422361 8.97507e-5 -0.6701385 0.7918527 -0.001241028 -0.610711 0.8748623 -3.64385e-4 -0.4843718 0.8429836 1.65952e-4 -0.5379395 0.9039534 5.07973e-4 -0.427631 0.9404867 -7.46554e-4 -0.3398299 0.9535647 1.80211e-4 -0.3011881 0.9860353 -1.25867e-4 -0.1665366 0.9880777 -4.9678e-4 -0.1539562 0.999778 5.0756e-4 -0.02106213 0.9992082 -5.77671e-4 0.03978312 0.9893173 8.96821e-4 0.1457758 0.9783632 -5.15136e-4 0.2068948 0.9455525 5.66673e-4 0.3254691 0.922595 -6.21571e-4 0.3857695 0.8926053 3.24805e-4 0.4508391 0.8671909 -4.0953e-4 0.4979757 0.7923895 4.49212e-5 0.6100156 0.7987548 3.62595e-4 0.6016568 0.7150534 -5.36961e-4 0.6990697 0.6074852 -8.06025e-4 0.7943306 0.6804968 2.5161e-4 0.732751 0.5710635 -1.56612e-5 0.8209059 0.474434 -1.11321e-4 0.8802911 0.4616752 -5.08028e-4 0.8870489 0.3978614 1.3487e-4 0.9174456 0.2851508 -9.89843e-4 0.9584822 0.2098999 7.89024e-4 0.9777226 0.1254238 4.03014e-5 0.9921033 0.07968592 8.0354e-4 0.9968197 0.001700222 -0.999998 -0.00108093 -5.8142e-4 -0.9999997 -5.10141e-4 -0.002681732 -0.9999961 7.25449e-4 -0.001068174 -0.9999988 -0.001163899 7.87594e-5 -0.9999982 0.00189495 -0.00110954 -0.9999977 -0.001826941 0.003962695 -0.9999907 -0.001723945 -2.54171e-4 -1 -1.80399e-4 -0.001211047 -0.9999992 5.42704e-4 -0.003203034 -0.9999944 -0.001020371 -0.001347601 -0.9999991 3.2031e-4 -0.002986013 -0.9999951 -0.001059949 -0.001587927 -0.9999986 -6.32644e-4 9.82659e-4 -0.9999984 0.001537382 0.00553286 -0.9999837 0.001380503 2.6566e-4 -0.999998 0.002030372 -0.001651942 -0.9999833 -0.005548238 0.003684461 -0.9999933 6.51427e-5 -0.007530629 -0.9999703 -0.001654684 7.17761e-4 -0.9999991 -0.001204669 -0.002190649 -0.9999966 -0.001510441 -8.09611e-4 -0.9999997 -4.4368e-4 0.001548647 -0.9999985 -8.01769e-4 0.002626955 -0.9999955 0.001470685 -0.001904547 -0.9999914 -0.003674328 -0.002629458 -0.9999961 -0.001052737 3.23695e-4 -0.9999993 -0.001141726 3.61512e-4 -0.9999923 0.003922402 0.003793179 -0.9999928 4.99287e-4 7.23106e-4 -0.9999902 0.004383862 6.93592e-5 -1 -3.21564e-4 6.03308e-4 -0.9999996 6.77049e-4 0.002257168 -0.9999973 6.92435e-4 -0.0013206 -0.9999991 -4.86226e-4 6.65263e-4 -0.9999998 3.70573e-4 -5.94384e-4 -0.9999997 -7.51748e-4 -7.29413e-4 -0.9999995 -7.7332e-4 -4.992e-4 -0.9999867 -0.005135893 -0.001470506 -0.9999985 9.84325e-4 0.00194621 -0.9999981 -2.37885e-4 0.001922249 -0.9999963 -0.001934349 -5.32762e-4 -0.9999984 0.001759529 -0.01438987 0.9463593 0.3227956 -0.02765178 0.1212903 0.992232 -0.06561851 0.7601584 0.6464159 -0.1616824 0.4948166 0.853824 -0.2465443 0.2801762 0.9277486 -0.1983786 0.5998563 0.7751248 -0.2173935 0.6191743 0.7545617 -0.2761343 0.5133162 0.8125618 -0.164767 0.774416 0.6108452 -0.4066848 0.3778083 0.8317862 -0.4176669 0.5564346 0.718286 -0.1896992 0.9070759 0.3758028 -0.5382363 0.3910027 0.7466048 -0.3606736 0.7974207 0.4837716 -0.3483204 0.8158296 0.4616222 -0.5347818 0.5991933 0.5957986 -0.6329645 0.5177662 0.5755643 -0.6680816 0.4561036 0.5879087 -0.2917557 0.9158142 0.2759762 -0.5582312 0.7227905 0.4073719 -0.6477651 0.6124815 0.4530637 -0.0821532 -0.9953506 0.05027979 -0.8905963 0.1514176 0.4288487 -0.4668505 0.8352593 0.2905039 -0.6369163 0.7124513 0.2945347 -0.8375704 0.4626196 0.2906183 -0.5731325 0.8087386 0.1321402 -0.9230809 0.3581001 0.1403074 -0.8147504 0.5549807 0.1678636 -0.5780339 0.8054275 0.1310095 -0.3935857 0.9178449 0.05149066 -0.8840271 0.4670563 0.01882964 -0.8298647 0.5578545 -0.01109325 -0.369 0.9288432 0.03300613 -0.5516547 0.8316302 -0.06378418 -0.9002009 0.4207639 -0.1122331 -0.8873538 0.4462268 -0.1161248 -0.4690696 0.8806277 -0.06684875 -0.8265483 0.5086022 -0.2411259 -0.3365381 0.9346194 -0.1150161 -0.7986729 0.5630238 -0.2124285 -0.7088883 0.6368537 -0.3031415 -0.8131344 0.3860848 -0.4356042 -0.3577829 0.9228982 -0.1423034 -0.5928364 0.7379053 -0.3225535 -0.6919996 0.5677155 -0.4459101 -0.7476723 0.3625868 -0.5563427 -0.392259 0.861204 -0.3232037 -0.6092375 0.5492294 -0.5719938 -0.6242845 0.2559615 -0.7380737 -0.5199027 0.6722266 -0.5270793 -0.4540684 0.7523486 -0.4772774 -0.5183002 0.3567087 -0.7772541 -0.505055 0.4556809 -0.7329901 -0.2658967 0.850363 -0.4540726 -0.3866682 0.5918022 -0.7072892 -0.299663 0.7754002 -0.5558387 -0.3113229 0.4796845 -0.8203541 -0.3176733 0.4665944 -0.8254535 -0.1566937 0.9140127 -0.374203 -0.2123468 0.4059203 -0.8888968 -0.155641 0.5280436 -0.8348329 -0.1053569 0.8968707 -0.4295611 -0.1014447 0.8361643 -0.5390161 -0.06068837 0.4301805 -0.9007007 -0.06052774 0.4308931 -0.9003709 -0.0565496 0.7429201 -0.6669872 0.008685231 0.9471312 -0.3207289 0.06484514 0.5232036 -0.8497371 0.1244058 0.2996101 -0.945916 0.07817304 0.8179864 -0.5699012 0.1092236 0.6821665 -0.7229933 0.09834969 0.7690199 -0.6316139 0.2273022 0.5705871 -0.789154 0.3080856 0.3825582 -0.8710526 0.2106479 0.841138 -0.498111 0.3626617 0.6503468 -0.667477 0.3906483 0.4164625 -0.8209463 0.3375726 0.6725787 -0.6585459 0.4705222 0.6114448 -0.6361951 0.4043493 0.7792659 -0.4787967 0.3904733 0.8674314 -0.3083723 0.6642103 0.2482804 -0.705111 0.6647855 0.5547943 -0.5002636 0.7407153 0.4314707 -0.5149504 0.4112794 0.8696771 -0.2729674 0.4440209 0.8424745 -0.3050938 0.71746 0.5459657 -0.4326347 0.8431311 0.3997471 -0.359628 0.3679161 0.9154799 -0.1628934 0.7981757 0.5256705 -0.2942551 0.5111427 0.8431194 -0.1669821 0.8962925 0.3736199 -0.2388892 0.4197185 0.9011725 -0.1082795 0.8419477 0.5277028 -0.1124901 0.8493768 0.5161346 -0.1102924 0.4296272 0.9017287 -0.04802137 0.5765007 0.8166196 -0.02791649 0.8120808 0.5821483 0.04035085 0.867973 0.4921699 0.06627106 0.3228558 0.9458286 0.0342403 0.7330545 0.6625856 0.1536601 0.7992576 0.558165 0.2227987 0.536673 0.827577 0.1646164 0.8287089 0.4517624 0.3303822 0.9394348 -0.1099869 0.3246 0.6049921 0.7378399 0.2992938 0.4403951 0.8773349 0.1906195 0.7096017 0.5554375 0.4335374 0.7261716 0.4858394 0.4864515 0.3505749 0.9089406 0.2256642 0.6725808 0.5488106 0.4964293 0.4301221 0.8366256 0.3391941 0.684134 0.4482225 0.5753757 0.3127467 0.9083482 0.2776564 0.5533169 0.6041184 0.5734819 0.5131758 0.5345067 0.6715305 0.5540659 0.4581884 0.6950356 0.2522291 0.9180689 0.3058266 0.4387511 0.429363 0.7893953 0.3077402 0.8458408 0.4357174 0.3623732 0.5789628 0.7304025 0.1892853 0.9138261 0.3592952 0.1970859 0.8150216 0.5448826 0.2392565 0.4702766 0.8494682 0.2192713 0.7841875 0.5804913 0.1015003 0.6418002 0.7601252 0.1171078 0.6099174 0.7837644 0.09919381 0.7406501 0.6645284 -0.005980968 0.5457919 0.8378995 0.002449154 0.9999966 0.001031875 -0.001142501 0.9999989 -0.001040041 6.56364e-4 0.9999978 0.001994013 7.84838e-4 0.9999995 -6.83388e-4 1.41466e-4 0.9999988 0.001571953 -2.3486e-4 0.9999998 6.26224e-4 4.04532e-4 0.9999997 -7.22906e-4 -5.11782e-4 0.9999991 -0.001235067 -5.48347e-4 0.9999998 2.27484e-4 -0.004714965 0.9999889 -2.67657e-4 -5.8506e-5 0.9999995 -0.001112759 3.83034e-4 1 3.8249e-4 7.05991e-4 0.9999997 5.45074e-4 -5.86268e-5 1 2.43756e-4 3.62782e-5 1 1.37385e-4 5.4458e-4 0.9999989 -0.001411497 0.004669964 0.9999867 -0.002192556 -3.00358e-4 0.9999999 -5.19318e-4 -0.002124547 0.9999974 -8.55894e-4 -0.001231908 0.9999963 -0.002464234 -0.001205325 0.9999981 0.001571536 1.83853e-4 0.9999994 0.001151144 -6.09223e-5 0.9999943 -0.003412306 0.007309138 0.999966 -0.003838241 -0.002116799 0.999981 0.005810379 5.84464e-4 0.9999977 0.002059519 0.001381099 0.9999946 0.003017961 -3.99329e-4 0.9999998 -3.95332e-4 5.63398e-4 0.999999 0.001359045 -0.005502641 0.9999801 0.003087878 0.001313388 0.9999991 3.85722e-4 4.4527e-4 1 -1.60862e-4 -0.001147925 0.9999817 -0.00594604 -0.002218604 0.9999975 -3.06021e-4 0.00463134 0.9999893 8.89134e-5 0.004591047 0.9999895 6.53917e-5 -0.001842856 0.9999983 9.60869e-5 -0.004439353 0.9999868 -0.002614915 -0.001282513 0.9999992 2.85054e-4 -0.9917746 0.01146852 -0.127482 -0.9711625 -0.01338273 -0.2380425 -0.9111575 0.01601618 -0.4117469 -0.8576881 -0.01739025 -0.5138762 -0.7326191 0.01607441 -0.680449 -0.6496089 -0.0133236 -0.7601518 -0.5207827 0.01200759 -0.8536049 -0.4116874 -0.01524996 -0.9111975 -0.2777519 0.01257914 -0.9605706 -0.07346671 -0.0121023 -0.9972243 0.2230024 0.0032835 -0.9748123 0.262516 -0.01273709 -0.9648436 0.4788501 0.01655489 -0.8777406 0.5965882 -0.01914978 -0.8023191 0.7161549 0.0172457 -0.6977283 0.8064236 -0.01357591 -0.5911827 0.9011505 0.009375512 -0.433405 0.9211484 -0.004728794 -0.3891832 0.9834537 0.007387578 -0.1810091 0.9931048 -0.01147973 -0.1166671 0.9956493 0.01460283 0.09202849 0.984868 -0.01186662 0.1728996 0.9084021 0.002586007 0.4180896 0.8971239 0.01305061 0.4415864 0.7838428 -0.0118224 0.6208468 0.6839493 0.0153228 0.7293686 0.6254224 -0.008805155 0.7802367 0.3990846 0.009545445 0.9168644 0.3551872 -0.007333338 0.9347665 0.1274194 0.006465196 0.991828 0.08815765 -0.007178664 0.9960808 -0.1607469 0.007369637 0.9869682 -0.2390955 -0.01492649 0.9708814 -0.3665097 0.01254189 0.9303297 -0.5449501 -0.01529544 0.838329 -0.6450206 0.02058362 0.7638879 -0.7514345 -0.01556038 0.6596242 -0.8883768 0.01279556 0.4589368 -0.8837378 0.008707523 0.4679017 -0.963479 -0.0128501 0.2674755 -0.9906561 0.01363331 0.1357005 -0.9997482 -0.01047503 0.01984828 0.9722878 0.007322669 0.233673 0.9580667 -0.01040089 0.2863568 0.889319 0.0125578 0.4571151 0.8220208 -0.01184165 0.5693343 0.7546681 0.009337723 0.6560403 0.6622549 -0.01070672 0.7492021 0.5557729 0.01537972 0.8311919 0.4114648 -0.02103382 0.911183 0.2623537 0.02091425 0.9647451 0.0502882 -0.01906985 0.9985527 -0.05871528 0.0172258 0.9981262 -0.2941739 -0.01900291 0.955563 -0.4114796 0.01848447 0.9112315 -0.5833925 -0.01848322 0.81198 -0.6884212 0.02228254 0.7249688 -0.8242539 -0.01898008 0.5659024 -0.9090119 0.01674425 0.4164336 -0.9329414 -0.002303421 0.3600211 -0.9945103 0.002969384 0.1045973 -0.992855 -0.002300798 0.1193052 -0.9907041 -5.02539e-4 -0.1360338 -0.9892815 -0.00420767 -0.1459609 -0.9068947 0.005756497 -0.4213183 -0.8884096 -0.01160782 -0.4589049 -0.7348824 0.01329219 -0.6780644 -0.6736239 -0.01158535 -0.7389835 -0.5472085 0.008957803 -0.8369485 -0.4773163 -0.008726894 -0.8786882 -0.2354604 -0.008149564 -0.9718499 0.09161895 0.006897628 -0.9957703 0.113217 -0.004105985 -0.9935618 0.458746 0.003925263 -0.8885588 0.4681758 -0.001104831 -0.8836346 0.7252906 0.01071482 -0.6883595 0.7006211 -0.001109778 -0.7135326 0.8449462 -0.01357597 -0.5346791 0.911136 0.01724481 -0.4117449 0.9587742 -0.01402431 -0.2838227 0.9946046 0.01598489 -0.1025007 0.9998579 -0.01243889 -0.01138269 0.9039027 0.4276822 -0.006928503 0.7075486 0.7057882 -0.03518551 0.2723536 0.9621567 0.008833885 0.7054823 0.7072494 -0.0457502 0.9471045 0.3020079 -0.1085553 0.9048304 0.4061104 -0.127892 0.5629826 0.8224205 -0.08170241 0.8817552 0.4360225 -0.1799783 0.3782925 0.9230093 -0.07034784 0.3120842 0.9484632 -0.05496478 0.794211 0.5740005 -0.1993803 0.797711 0.5701307 -0.1964899 0.6001362 0.7754855 -0.1961095 0.8751883 0.3830209 -0.2955345 0.08635812 0.9959103 -0.02655309 0.7192406 0.6166453 -0.3200649 0.5780773 0.7851177 -0.2222992 0.3696592 0.9136442 -0.1691346 0.7323513 0.5879217 -0.3435256 0.7354608 0.4801132 -0.4781096 0.6693152 0.6157625 -0.4157571 0.5922458 0.7082996 -0.3841308 0.4022641 0.879383 -0.2546945 0.7577679 0.3426373 -0.5553267 0.6944069 0.3876219 -0.6062577 0.7055577 0.3227198 -0.6309044 0.2582199 0.9454938 -0.1984042 0.5869126 0.6111937 -0.5310142 0.528239 0.7158898 -0.4565801 0.3629866 0.8709141 -0.3312848 0.615572 0.343489 -0.7092859 0.5361589 0.5483658 -0.6417388 0.516555 0.6197625 -0.5908175 0.326918 0.8660805 -0.3781921 0.4984414 0.3874675 -0.7755162 0.2767503 0.8952908 -0.3490899 0.4818741 0.5742046 -0.6618811 0.3199467 0.804201 -0.5008942 0.4409337 0.3314517 -0.8340968 0.4454788 0.4079367 -0.7969544 0.3121821 0.7435572 -0.5913248 0.298326 0.8051427 -0.5125885 0.3801302 0.339581 -0.8603405 0.2937427 0.5894061 -0.7525395 0.2649821 0.7212053 -0.6400371 0.097139 0.9706947 -0.2198083 0.1544225 0.8735909 -0.4615112 0.2283059 0.4497882 -0.8634623 0.1255383 0.8706285 -0.4756535 0.1741144 0.5240027 -0.8337299 0.1499902 0.4993209 -0.8533357 0.06695127 0.9221821 -0.3809172 0.08618074 0.5830514 -0.8078515 0.0411123 0.8162866 -0.5761824 0.03066158 0.3952562 -0.9180591 0.005977869 0.9968425 -0.07918071 0.00624746 0.8402469 -0.5421682 -0.0187909 0.4039153 -0.9146034 -0.01593589 0.9519789 -0.3057484 -0.06549477 0.5886597 -0.8057234 -0.05367457 0.734658 -0.6763111 -0.1477186 0.4536371 -0.8788588 -0.0810821 0.8177632 -0.5698151 -0.1857272 0.4164348 -0.8899931 -0.05958175 0.9110003 -0.4080792 -0.1697551 0.4519838 -0.8757247 -0.1309182 0.7553884 -0.6420662 -0.271771 0.4200978 -0.8658282 -0.2676494 0.3920979 -0.8801267 -0.2041115 0.7565366 -0.6212818 -0.1710456 0.8007646 -0.5740379 -0.07976007 0.952081 -0.2952629 -0.3357372 0.4478862 -0.8286607 -0.05666893 0.9864771 -0.1537905 -0.2569441 0.7412738 -0.6200749 -0.4079442 0.3062368 -0.8601167 -0.2630049 0.8134145 -0.5188305 -0.4431428 0.4138204 -0.7952215 -0.1415241 0.9484204 -0.283672 -0.2950993 0.7829447 -0.547644 -0.4796817 0.3763754 -0.7926203 -0.3649131 0.7459344 -0.5571537 -0.4975656 0.4640115 -0.7328861 -0.5620301 0.3797654 -0.7347792 -0.3346074 0.8492953 -0.4083325 -0.5950371 0.4588893 -0.6598118 -0.5922483 0.4760121 -0.650119 -0.1484764 0.9722095 -0.1810067 -0.465462 0.7351188 -0.4928951 -0.1046603 0.9878537 -0.1148546 -0.7128912 0.3385834 -0.6141234 -0.4749444 0.7736173 -0.419457 -0.7109608 0.4103783 -0.5710731 -0.4092912 0.8527561 -0.3244807 -0.7447743 0.3830265 -0.546445 -0.7399507 0.4609863 -0.489862 -0.5809105 0.7314981 -0.3570066 -0.4335541 0.84834 -0.3038919 -0.8363357 0.2738536 -0.474918 -0.2583433 0.9546613 -0.1479211 -0.5976671 0.7399585 -0.308635 -0.8514025 0.3414717 -0.3981344 -0.8233394 0.4351989 -0.3642998 -0.7204431 0.6136702 -0.3230646 -0.3717939 0.9131531 -0.1670956 -0.8850198 0.35399 -0.3023758 -0.6372288 0.7437018 -0.2021066 -0.4630461 0.8743041 -0.1455361 -0.352604 0.9264962 -0.1314357 -0.7727944 0.599275 -0.2089462 -0.09259796 0.9953977 -0.02468198 -0.817083 0.5539495 -0.159736 -0.3982736 0.9146472 -0.06927365 -0.7961767 0.5920457 -0.1248384 -0.5263909 0.8480891 -0.06047803 -0.9111005 0.4069908 -0.06522703 -0.8799934 0.4693935 -0.07267498 -0.9436422 0.3297041 -0.02889007 -0.6144896 0.7889098 -0.004900574 -0.5409979 0.8405579 -0.0279982 -0.9085609 0.4137754 0.05750662 -0.8814189 0.4673693 0.06831258 -0.6511862 0.7572894 0.04969215 -0.6349254 0.7712358 0.04544222 -0.9141748 0.3686563 0.1684546 -0.3006663 0.9525468 0.04747939 -0.1742926 0.9843766 0.02499747 -0.8770731 0.4395022 0.193858 -0.7352479 0.6576787 0.1639183 -0.9021819 0.3607317 0.2365173 -0.07519245 0.9970681 0.01419186 -0.595631 0.7847875 0.1712667 -0.8588256 0.3697128 0.3545857 -0.8242263 0.4714405 0.3136799 -0.6021504 0.7654766 0.2268492 -0.5503585 0.8025538 0.2302454 -0.8056786 0.4186085 0.4191049 -0.3988065 0.8988261 0.181838 -0.7088257 0.5819968 0.3985547 -0.2822049 0.945403 0.1630138 -0.7011055 0.5884922 0.4026514 -0.7224791 0.4542999 0.5211867 -0.4609211 0.8239989 0.3295111 -0.4050444 0.8673366 0.2892513 -0.6138507 0.5993531 0.5137736 -0.6380071 0.492285 0.592117 -0.6105303 0.5889406 0.5295298 -0.2442242 0.9412002 0.2334454 -0.3300125 0.8717521 0.3621327 -0.5807909 0.4680324 0.6660538 -0.5255624 0.5573968 0.6427232 -0.3317287 0.8661186 0.3738913 -0.5084107 0.3707207 0.777229 -0.2896332 0.8847747 0.3650842 -0.4929119 0.5587016 0.6670011 -0.3311951 0.7769988 0.5353342 -0.08637392 0.9857022 0.1446745 -0.3406725 0.7741371 0.5335299 -0.4328932 0.371806 0.8211966 -0.4329823 0.4130292 0.8012074 -0.3653863 0.6329355 0.6825582 -0.177762 0.9206608 0.3475406 -0.262015 0.7372038 0.6227992 -0.1914091 0.8565156 0.4793158 -0.3020101 0.3803802 0.8741286 -0.3133181 0.4423529 0.8403307 -0.247377 0.4454231 0.8604667 -0.1592663 0.8783504 0.4507049 -0.1393402 0.6408086 0.7549495 -0.1894543 0.6163532 0.7643403 -0.1168915 0.4035134 0.9074763 -0.05047452 0.9707125 0.234882 -0.08698982 0.8154957 0.5721886 -0.05410766 0.8995445 0.4334653 -0.06015837 0.4964036 0.866005 -0.00137788 0.3923324 0.9198225 -0.02622431 0.4880883 0.8724003 -0.01410448 0.8915061 0.4527891 0.0175119 0.7634351 0.6456472 0.08536356 0.3814788 0.9204276 0.1022449 0.4366747 0.8937904 0.0677089 0.7580953 0.6486194 0.02792471 0.9706043 0.239056 0.192049 0.3666923 0.9103044 0.08641284 0.8381628 0.5385315 0.1985198 0.3926805 0.8979933 0.01860231 0.9949723 0.09840828 0.1647703 0.753273 0.6367344 0.3113898 0.3328539 0.8900814 0.2023075 0.7756566 0.5978534 0.3251482 0.5102859 0.7961703 0.3247627 0.5121589 0.7951242 0.1815825 0.8610458 0.4750032 0.4144327 0.301233 0.8587807 0.3458999 0.7087546 0.6148335 0.2266262 0.8623512 0.4527592 0.4722523 0.3615303 0.8039115 0.4569841 0.4981783 0.7368744 0.3607703 0.6942937 0.6227368 0.1447557 0.9632297 0.2263504 0.535288 0.4724215 0.7002033 0.5322316 0.4953767 0.686536 0.3676161 0.7935848 0.4848523 0.3611608 0.8043259 0.4718293 0.06242942 0.994393 0.08535331 0.3742225 0.8241224 0.4251821 0.6556628 0.413062 0.6320492 0.6021418 0.5235001 0.6028043 0.51641 0.6961658 0.4986723 0.2095727 0.9550096 0.2098477 0.5002146 0.7550819 0.423836 0.7350381 0.3304479 0.59205 0.7132995 0.4737935 0.516453 0.2475742 0.9481732 0.1991852 0.6007118 0.6661594 0.4420148 0.7845768 0.3754007 0.4934709 0.2058039 0.9678606 0.1445364 0.7794825 0.4168911 0.4675565 0.6876574 0.6173699 0.3820757 0.5632634 0.7546386 0.336534 0.4307391 0.8697488 0.2408338 0.8762171 0.2600507 0.4057306 0.8466013 0.3834858 0.3690597 0.741644 0.5755899 0.3444716 0.6186516 0.748917 0.2374734 0.468113 0.8618349 0.1952202 0.8598098 0.4248171 0.2832978 0.8716458 0.401979 0.28044 0.6799414 0.6965008 0.2292735 0.8987042 0.3771253 0.2238468 0.267297 0.960452 0.07800292 0.5964342 0.7922161 0.1290736 0.3712873 0.9248546 0.08240103 0.8204185 0.5562976 0.132085 0.7834371 0.6105128 0.1161909 0.9195165 0.3929166 0.01029062 0.7803795 0.6189296 0.0890733 0.6044182 0.7966284 0.007864058 0.2918746 0.9564372 0.006098747 0.9933612 -0.006926238 -0.1148284 0.9934495 -0.007947564 -0.1139959 0.9657913 -0.002818763 -0.2593054 0.9723578 0.0126847 -0.2331511 0.9253093 -0.005494952 -0.3791738 0.9439496 0.02286547 -0.3292968 0.9030833 0.01837021 -0.4290724 0.8727229 1.71599e-4 -0.4882159 0.8676106 0.006319701 -0.4972041 0.8033419 7.32761e-4 -0.5955177 0.8134404 -0.009349703 -0.5815731 0.7631548 -0.01619583 -0.6460129 0.7439593 0.006797194 -0.6681905 0.6747177 -0.01685774 -0.7378833 0.6364472 0.02199685 -0.7710066 0.565869 0.001682341 -0.8244934 0.5710711 -0.002326786 -0.8208973 0.4854729 -0.00852102 -0.8742103 0.4794974 -0.003455877 -0.8775365 0.3897268 -0.003890037 -0.9209223 0.3680641 0.0150426 -0.9296787 0.2894851 0.007397592 -0.957154 0.2878192 0.008532226 -0.9576468 0.1833007 -0.01509726 -0.982941 0.1489565 0.001635372 -0.9888424 0.1105598 -0.01140642 -0.9938041 0.02913844 0.01881742 -0.9993983 0.06373947 -0.01656907 -0.9978291 -0.06410491 0.01620715 -0.9978116 -0.09311485 0.002439022 -0.9956524 -0.09664291 0.003798305 -0.9953119 -0.2168119 9.00584e-5 -0.9762134 -0.197006 -0.01414328 -0.9803003 -0.2807298 -0.01538968 -0.9596635 -0.3023836 0.002601504 -0.9531829 -0.3878641 -0.01021265 -0.92166 -0.4250994 0.0153324 -0.9050169 -0.4790916 -0.01023161 -0.8777054 -0.5260377 0.009633719 -0.8504068 -0.5731459 -0.01289147 -0.819352 -0.6029916 3.19566e-4 -0.7977476 -0.6405662 -0.01776266 -0.7676975 -0.6819499 0.01593595 -0.7312253 -0.7498707 4.30913e-4 -0.6615843 -0.744207 -0.006017446 -0.667922 -0.8177573 -0.009150922 -0.5754905 -0.8138729 -0.01414746 -0.5808706 -0.8567474 -0.0107975 -0.5156233 -0.8629388 -0.001556575 -0.5053063 -0.9108541 -0.006531357 -0.4126769 -0.9138413 -0.00221765 -0.4060657 -0.940757 -0.01340097 -0.3388167 -0.953742 0.01787137 -0.3000949 -0.9769641 0.001341342 -0.2133995 -0.9783781 0.006956517 -0.2067074 -0.9966112 -0.01282298 -0.08125007 -0.9920275 0.01356142 -0.1252908 -0.9997922 0.009525179 -0.01802188 -0.9997103 -0.008915483 0.02236205 -0.9968846 0.009028017 0.07835614 -0.9911733 -0.01211667 0.132018 -0.9861872 0.008741736 0.1654041 -0.9608895 -0.0098567 0.2767566 -0.9654712 0.005416393 0.2604539 -0.9304304 0.006482958 0.3664114 -0.9312039 0.004844188 0.3644665 -0.8861399 -0.01328438 0.4632276 -0.8454039 -7.83396e-4 0.5341269 -0.8674828 0.009918272 0.4973684 -0.7788343 6.19713e-4 0.6272295 -0.8146369 0.02579301 0.5793975 -0.7471789 0.01521438 0.6644489 -0.7122351 -0.0137487 0.7018064 -0.6423226 0.006330668 0.7664084 -0.6454658 0.001538097 0.7637878 -0.5216504 -0.01784247 0.8529728 -0.5680153 0.01759248 0.82283 -0.4680292 0.01696866 0.8835501 -0.3940774 -0.01627045 0.9189332 -0.3478763 0.01093345 0.9374768 -0.289192 -0.01466912 0.9571587 -0.2372319 0.01755309 0.9712945 -0.1577481 0.006141245 0.9874603 -0.1490674 0.01268362 0.9887457 -0.04108262 -0.01491415 0.9990445 -0.009869098 0.008840203 0.9999123 0.100773 -0.009188115 0.994867 0.09895282 -0.01109385 0.9950304 0.248602 -0.01987886 0.9684018 0.2041546 0.01582562 0.9788108 0.3902372 -0.01531231 0.9205871 0.3359677 0.01634418 0.9417317 0.4280799 0.01036244 0.9036816 0.5169171 0.001665532 0.8560339 0.526399 -0.008447527 0.8501957 0.6049907 0.001322746 0.7962315 0.6116409 0.007760286 0.7910975 0.6824945 -0.008876383 0.7308368 0.7032107 0.0119608 0.7108809 0.7798259 -0.00772041 0.625949 0.7830349 -0.003741741 0.6219667 0.8396483 -0.005889356 0.5430988 0.8420956 -0.003596365 0.5393164 0.8639262 -0.01822942 0.5032886 0.9115446 0.006658852 0.4111474 0.9079922 -7.89552e-4 0.4189866 0.9370036 -0.01183515 0.3491194 0.9480257 0.007852673 0.3180972 0.9749116 -0.002462804 0.2225793 0.9760172 -0.006826996 0.2175869 0.9912575 -5.05974e-4 0.1319415 0.9915986 0.001677334 0.1293426 0.9999122 -0.004847168 0.01233899 0.999125 0.01822865 0.03764325 0.9275865 -0.372726 0.02566403 0.8513634 -0.5245646 -0.003531098 0.6733912 -0.7385657 0.03263586 0.6720985 -0.7393807 0.04000055 0.9305546 -0.3505807 0.1056469 0.8540405 -0.5043226 0.1275677 0.5057927 -0.8586527 0.08300244 0.8548746 -0.4727391 0.2137927 0.8156701 -0.547914 0.185668 0.1684101 -0.9854437 0.02321046 0.6296616 -0.762275 0.1498772 0.1145876 -0.9932149 0.01985365 0.8597401 -0.414659 0.2981694 0.4865746 -0.8541089 0.1836932 0.4208111 -0.8916534 0.1669499 0.7628613 -0.5539528 0.3334352 0.7745804 -0.518094 0.3627725 0.3331257 -0.9265783 0.174585 0.7518998 -0.5250043 0.3987696 0.6998643 -0.5878471 0.4057409 0.4077315 -0.8790607 0.2469968 0.6881982 -0.5486599 0.4747163 0.6761156 -0.5598557 0.4789878 0.4190875 -0.8503096 0.3183386 0.6991894 -0.4131045 0.5835058 0.4032016 -0.8589312 0.3156991 0.6315402 -0.4874765 0.6029293 0.2785426 -0.9279837 0.2475082 0.5260234 -0.672327 0.5208415 0.6438569 -0.3727286 0.6682229 0.4444044 -0.7526816 0.4857728 0.1137148 -0.9867184 0.1159995 0.5170447 -0.4994472 0.6951383 0.516772 -0.5047994 0.6914654 0.4203628 -0.7457776 0.5168278 0.2647054 -0.8854517 0.3819768 0.4688915 -0.3834129 0.7956982 0.4655922 -0.4899811 0.7369821 0.2341904 -0.890265 0.390619 0.3275568 -0.7310417 0.5985689 0.2729406 -0.8187435 0.505136 0.379676 -0.4429623 0.8121764 0.3569677 -0.3870211 0.85017 0.07052427 -0.9869583 0.1447058 0.2086821 -0.830703 0.5161245 0.3246103 -0.4405595 0.8369801 0.2380656 -0.6921562 0.6813549 0.2352685 -0.3385925 0.9110455 0.1112197 -0.9292241 0.3523816 0.2090029 -0.4166741 0.8847036 0.1294649 -0.9029206 0.4098456 0.1713157 -0.7289261 0.6628104 0.1365869 -0.800307 0.583826 0.09743589 -0.8155957 0.5703595 0.09778684 -0.3948789 0.9135143 0.08463037 -0.4424101 0.8928108 0.02209419 -0.9885085 0.1495419 0.06589823 -0.6930134 0.7179066 0.02768892 -0.9494088 0.3128198 -0.01957976 -0.4209425 0.906876 -0.01899886 -0.8258402 0.5635841 -0.04249495 -0.3366684 0.9406639 -0.03276425 -0.7792683 0.6258335 -0.01471108 -0.8287525 0.5594221 -0.1486061 -0.3905799 0.9084952 -0.1341522 -0.4319317 0.8918734 -0.09888845 -0.6963629 0.7108445 -0.04358088 -0.9620323 0.2694337 -0.1406941 -0.8140255 0.5635315 -0.1369358 -0.8422779 0.5213604 -0.2586494 -0.3983469 0.8800115 -0.2612053 -0.4228609 0.867733 -0.1062372 -0.9062344 0.4092101 -0.363755 -0.4278737 0.8274095 -0.3384458 -0.4910104 0.8027225 -0.3094962 -0.6266734 0.7151871 -0.2300279 -0.7906528 0.5674113 -0.08650016 -0.9744673 0.2071989 -0.174684 -0.9169461 0.3587412 -0.4921141 -0.3263831 0.8070302 -0.3460276 -0.7536635 0.5587988 -0.3071332 -0.8240287 0.4760736 -0.4909291 -0.4314649 0.7568532 -0.3092094 -0.8498947 0.4266951 -0.5666241 -0.4225157 0.7074021 -0.5490686 -0.5439739 0.6345204 -0.2199922 -0.9424704 0.2517002 -0.650026 -0.4385962 0.6205641 -0.5767152 -0.5522469 0.6020158 -0.4536467 -0.7873095 0.4175504 -0.3208569 -0.8932878 0.314782 -0.7303914 -0.3818322 0.5663327 -0.6889942 -0.4580934 0.5616383 -0.5325344 -0.732182 0.424637 -0.7716531 -0.3659035 0.5202558 -0.7388998 -0.4992091 0.4525675 -0.5559056 -0.7565758 0.3443284 -0.49369 -0.8051599 0.3286147 -0.3618418 -0.9006501 0.2406243 -0.8168538 -0.4112085 0.4045461 -0.8078545 -0.4535584 0.3763719 -0.1731258 -0.9808105 0.08965682 -0.5903678 -0.7623852 0.2650185 -0.58177 -0.7716985 0.2569537 -0.8735927 -0.3489814 0.3391869 -0.2878313 -0.9496546 0.1237307 -0.8602802 -0.4227138 0.2850111 -0.6578953 -0.7192614 0.2232418 -0.8990253 -0.359409 0.2501573 -0.6087726 -0.7767087 0.1616161 -0.8426564 -0.5104621 0.1713442 -0.4319466 -0.8969992 0.09388703 -0.4154521 -0.9050832 0.09068566 -0.842756 -0.5103493 0.1711895 -0.9592632 -0.2531202 0.1254761 -0.8936605 -0.4464293 0.04551845 -0.180913 -0.98325 0.02213788 -0.7381646 -0.6720541 0.05879032 -0.6971123 -0.7150628 0.05215013 -0.9346624 -0.3552529 0.0142039 -0.6389537 -0.7687353 0.02800798 -0.9280901 -0.3644241 -0.07644516 -0.399933 -0.9165225 -0.006333291 -0.8863014 -0.4522805 -0.09956032 -0.7992597 -0.5922986 -0.1018152 -0.7020101 -0.7075244 -0.08118647 -0.4915746 -0.8680799 -0.06922304 -0.3994747 -0.9158648 -0.04014605 -0.9586766 -0.1938506 -0.2082335 -0.879536 -0.4075784 -0.2455535 -0.7658039 -0.6111949 -0.1999631 -0.6737692 -0.7134373 -0.1924641 -0.4919133 -0.8620554 -0.1219914 -0.895982 -0.330262 -0.2968896 -0.3691948 -0.9222713 -0.1145027 -0.7616781 -0.5638003 -0.3193362 -0.6524395 -0.7134829 -0.2554698 -0.5114772 -0.8301345 -0.2219637 -0.7974686 -0.4458608 -0.4065121 -0.05743283 -0.9980467 -0.02458339 -0.4520264 -0.8605996 -0.2346068 -0.7854254 -0.4549807 -0.4196419 -0.65372 -0.6384073 -0.4063081 -0.230355 -0.9633975 -0.1371204 -0.694298 -0.4999049 -0.517731 -0.6486612 -0.6271589 -0.4311734 -0.6887528 -0.3449958 -0.6376501 -0.6528134 -0.5042914 -0.5652654 -0.480988 -0.7516506 -0.4513005 -0.4178516 -0.8351661 -0.3576278 -0.2591382 -0.9416435 -0.2148373 -0.6258079 -0.3302378 -0.706617 -0.1314662 -0.9822422 -0.133854 -0.5043231 -0.5882903 -0.6321176 -0.436061 -0.7600467 -0.4818505 -0.2306783 -0.9278569 -0.2930346 -0.5028755 -0.3904324 -0.7711542 -0.4777688 -0.5874651 -0.653163 -0.3641487 -0.7380346 -0.5680676 -0.2252604 -0.9251264 -0.3056123 -0.4390167 -0.394045 -0.8074607 -0.4397417 -0.3925225 -0.8078078 -0.3335022 -0.7233911 -0.6045508 -0.2778432 -0.7784877 -0.5628145 -0.1395089 -0.9628318 -0.2312842 -0.3657614 -0.3861376 -0.8468273 -0.3240124 -0.474031 -0.8187249 -0.2616565 -0.7703464 -0.5814658 -0.02663022 -0.9972865 -0.06863284 -0.2883587 -0.4473789 -0.8465823 -0.1512156 -0.8770887 -0.455905 -0.1625695 -0.6566578 -0.7364588 -0.1567888 -0.3813768 -0.9110264 -0.06155002 -0.9726881 -0.2238071 -0.1799045 -0.6665643 -0.7234131 -0.08449584 -0.7798459 -0.6202427 -0.08625859 -0.3911097 -0.916293 -0.07619917 -0.4242181 -0.9023485 -0.05773323 -0.909017 -0.4127407 -0.05829459 -0.6982221 -0.7135038 0.005210876 -0.3411144 -0.9400073 0.02748519 -0.7760527 -0.630069 0.0306214 -0.8776057 -0.4784043 0.06982302 -0.4877517 -0.8701857 0.01177668 -0.9546761 -0.2974137 0.07815217 -0.5914872 -0.802518 0.2002099 -0.453882 -0.8682783 0.1585887 -0.6080864 -0.7778694 0.0149694 -0.9928829 -0.1181505 0.1550617 -0.7672695 -0.622297 0.1236761 -0.8574768 -0.4994375 0.2831748 -0.3160319 -0.9055031 0.1128998 -0.8990079 -0.4231292 0.3414129 -0.4506064 -0.8248583 0.1422287 -0.9222648 -0.3594422 0.3410024 -0.4819014 -0.8071485 0.310105 -0.5920408 -0.7438566 0.2459119 -0.8290148 -0.5022568 0.431913 -0.3877238 -0.8143228 0.2771369 -0.830213 -0.4836753 0.5272556 -0.4197773 -0.7387751 0.460051 -0.5547584 -0.6932506 0.4005458 -0.6946688 -0.5974934 0.3968048 -0.7912725 -0.4652248 0.6183627 -0.3985612 -0.6773305 0.6199737 -0.3951827 -0.6778373 0.1437929 -0.9704816 -0.1936212 0.440536 -0.7597644 -0.4782114 0.04429268 -0.9979332 -0.04655671 0.4460644 -0.7771111 -0.4439874 0.6724519 -0.4150495 -0.6128152 0.6030173 -0.6209718 -0.5007635 0.2129092 -0.9616925 -0.1726768 0.6129753 -0.6337426 -0.4718387 0.4483174 -0.8456951 -0.2895021 0.7644688 -0.4107362 -0.4968734 0.7894072 -0.3989344 -0.46657 0.7581358 -0.5071596 -0.4099019 0.4775153 -0.8341116 -0.2761104 0.7692025 -0.5272514 -0.3610174 0.6884458 -0.6632972 -0.2933924 0.4967003 -0.8410157 -0.214433 0.4479302 -0.8684533 -0.2124794 0.8916593 -0.2836426 -0.3528324 0.8689575 -0.4077553 -0.2804434 0.8205453 -0.5067014 -0.2644985 0.9306019 -0.2657396 -0.2517196 0.466077 -0.8731358 -0.1428505 0.6900644 -0.7047746 -0.1646326 0.8894278 -0.4278522 -0.1608131 0.7420153 -0.6571187 -0.1326964 0.9617384 -0.2470487 -0.1184328 0.2597934 -0.9640561 -0.05570822 0.7059292 -0.7017344 -0.09608769 0.5103542 -0.8587552 -0.04558736 0.8521373 -0.5213285 -0.04559272 0.4990478 -0.8665168 -0.009999155 0.001951277 -0.9999973 0.00130254 0.00186932 -0.999997 0.001625716 0.001105785 -0.9999981 0.00165373 2.99301e-4 -0.999997 0.002418756 0.002230942 -0.9999969 0.00113976 0.001760482 -0.9999982 8.54871e-4 0.001294076 -0.9999992 3.14228e-4 2.76028e-4 -0.9999995 0.001014113 -6.18907e-4 -0.9999985 0.001686871 0.00214672 -0.9999977 -4.16512e-4 -1.07591e-4 -0.9999984 0.001827836 0.002065956 -0.9999976 -6.88572e-4 5.48972e-4 -0.9999985 0.001631677 0.002619385 -0.9999965 -2.71611e-4 -0.002299964 -0.9999971 8.20208e-4 0.002200782 -0.9999966 -0.001405477 0.002201735 -0.9999971 -9.90338e-4 -0.001191973 -0.9999959 0.0026443 -9.24329e-4 -0.9999957 0.002789437 -0.001285612 -0.9999983 0.001362562 0.001989901 -0.9999963 -0.001885354 0.001990973 -0.9999943 -0.002714157 0.001460015 -0.9999949 -0.002826154 -0.001173794 -0.9999983 0.001461863 0.003581345 -0.9999935 -6.14125e-4 -9.80742e-4 -0.9999995 4.54072e-4 0.001617908 -0.9999978 -0.001334726 1.92387e-5 -1 -2.09444e-4 -0.00110948 -0.9999994 1.1899e-4 -0.001408874 -0.999999 -2.08166e-4 -0.001409888 -0.999999 -1.84933e-4 -0.002690911 -0.9999884 -0.003993213 -6.05351e-5 -1 -2.111e-4 -5.48405e-4 -0.9999998 -4.19618e-4 -0.003122985 -0.9999944 0.001211345 -1.53922e-4 -1 -7.10312e-5 -4.00402e-4 -0.9999998 -6.09453e-4 1.04199e-4 -0.9999997 -8.89943e-4 -1.19561e-4 -1 -1.19517e-4 0.9478237 -0.3173229 0.03060275 0.657018 -0.7538563 -0.00530821 0.895942 -0.4380002 0.07378387 0.8070814 -0.5870923 0.06278723 0.9372025 -0.3260506 0.123865 0.4472233 -0.8938956 0.03069347 0.3565052 -0.9339889 0.0238527 0.6274716 -0.7723939 0.09842282 0.8951926 -0.3891431 0.2172506 0.8848797 -0.4191226 0.2032842 0.6315244 -0.7643037 0.1304483 0.8794291 -0.399806 0.2583791 0.4965927 -0.85681 0.1388257 0.2453899 -0.9672861 0.06435483 0.1165066 -0.9923505 0.0408256 0.7429741 -0.6026319 0.2912462 0.5671673 -0.7932033 0.2216979 0.8256433 -0.3962324 0.4016383 0.4414815 -0.8715013 0.2134939 0.4549379 -0.8586412 0.2361499 0.7798853 -0.4408167 0.4443643 0.7323487 -0.523487 0.4354618 0.6230379 -0.6352556 0.4563707 0.4130991 -0.8656862 0.2827308 0.6898014 -0.4537988 0.5641283 0.6338787 -0.5977327 0.4908294 0.6965817 -0.3670276 0.6164939 0.2813072 -0.9338634 0.2208293 0.03815722 -0.9987243 0.0330758 0.4373743 -0.7891208 0.4312682 0.6244115 -0.4050728 0.6678521 0.3224134 -0.892018 0.3167862 0.6070843 -0.4380115 0.6630194 0.4898515 -0.6934859 0.5283208 0.233099 -0.9361746 0.2631388 0.5612082 -0.4003267 0.7244198 0.3710042 -0.7816101 0.5014398 0.254186 -0.9050121 0.3410906 0.4981806 -0.4979752 0.7098147 0.4179375 -0.6659664 0.6179134 0.4844373 -0.3359864 0.8077337 0.4181312 -0.4289386 0.8007359 0.1844758 -0.9363953 0.2985507 0.3656409 -0.6926061 0.6217745 0.2619033 -0.8241322 0.5022079 0.4048891 -0.4090527 0.8177658 0.3492613 -0.4753342 0.8075111 0.06240612 -0.9900266 0.1263049 0.268491 -0.6842569 0.6780156 0.3217773 -0.2651938 0.9089179 0.2243403 -0.8162429 0.5323711 0.1330025 -0.9158736 0.3787954 0.2396365 -0.3498643 0.905632 0.1220881 -0.916049 0.3820326 0.1860754 -0.5529583 0.8121658 0.1966701 -0.5341275 0.8222095 0.1270334 -0.7540603 0.6444034 0.1054474 -0.7723039 0.6264404 0.09897243 -0.4255129 0.899524 0.06607657 -0.5231046 0.8497032 0.02903205 -0.981962 0.1868364 0.0310111 -0.9193139 0.3923016 0.009046792 -0.9014058 0.4328811 0.007405698 -0.5634692 0.8261041 0.003911733 -0.5569469 0.8305389 -0.1231142 -0.3477578 0.9294663 -0.0260486 -0.925885 0.3769065 -0.06913715 -0.5732485 0.8164595 -0.09628486 -0.8167773 0.5688621 -0.1788343 -0.2997094 0.9371194 -0.2119092 -0.6126901 0.761384 -0.1109291 -0.8152807 0.5683415 -0.3106606 -0.399538 0.8624729 -0.1105496 -0.9357705 0.3348318 -0.2495253 -0.5895218 0.7682456 -0.255371 -0.6885504 0.6787371 -0.347454 -0.3432163 0.8726272 -0.1700576 -0.8889541 0.4252539 -0.3695106 -0.5880649 0.7194731 -0.450385 -0.407259 0.7945399 -0.3818728 -0.5946763 0.7074838 -0.3652524 -0.6153157 0.6985538 -0.2226595 -0.8755053 0.4288511 -0.5348818 -0.2851903 0.7953414 -0.2038592 -0.921853 0.3295887 -0.4030339 -0.706978 0.5811592 -0.2949636 -0.8660475 0.403681 -0.508116 -0.5453767 0.6666201 -0.3056775 -0.8785806 0.3669571 -0.5625376 -0.524021 0.6394948 -0.5642089 -0.566106 0.6009929 -0.4663628 -0.7444049 0.4778778 -0.6739935 -0.3805774 0.6331617 -0.7219056 -0.36034 0.5907685 -0.1387996 -0.9815172 0.1317523 -0.4433566 -0.8227193 0.3557639 -0.3319272 -0.9072216 0.2584057 -0.6805663 -0.5539743 0.4795228 -0.6174697 -0.6538781 0.4372354 -0.775898 -0.4032658 0.4851382 -0.500339 -0.8326064 0.2375448 -0.8121851 -0.4396439 0.3834953 -0.2854878 -0.9439908 0.1654639 -0.7828155 -0.5159277 0.3478776 -0.4786787 -0.8451413 0.237914 -0.797523 -0.5157417 0.3129979 -0.895793 -0.3294773 0.2983282 -0.6504029 -0.733547 0.1971927 -0.448908 -0.8785538 0.1631719 -0.2493609 -0.965676 0.07272678 -0.9032729 -0.3691985 0.2186108 -0.8632066 -0.4667255 0.192462 -0.7160149 -0.678604 0.1637659 -0.9325003 -0.3459956 0.1035877 -0.6026108 -0.7942782 0.07734566 -0.5377022 -0.8409651 0.0604496 -0.8875662 -0.4570007 0.0581094 -0.4053174 -0.9130525 0.045309 -0.9105885 -0.4128763 0.01902031 -0.2195315 -0.9755935 0.004848778 -0.8498311 -0.5255768 -0.03944903 -0.7030898 -0.709365 -0.04965984 -0.9394787 -0.3224245 -0.1158551 -0.64131 -0.764196 -0.06874668 -0.5014685 -0.8623183 -0.07026004 -0.8873172 -0.4294898 -0.1679485 -0.8941187 -0.3970811 -0.2070708 -0.4978252 -0.8553405 -0.1433981 -0.4394527 -0.8927028 -0.09981602 -0.8649919 -0.444452 -0.2329198 -0.8696389 -0.3983443 -0.2916338 -0.8273029 -0.4614949 -0.3203004 -0.7471806 -0.5831765 -0.3187891 -0.4982686 -0.8487867 -0.1768894 -0.7217056 -0.5970199 -0.3502976 -0.6689768 -0.6558678 -0.349725 -0.8269333 -0.2882384 -0.4828042 -0.3107894 -0.9377062 -0.1552966 -0.7638926 -0.3968154 -0.5089259 -0.4256955 -0.8712646 -0.2442978 -0.6943316 -0.5664518 -0.4438875 -0.05236512 -0.9980847 -0.03294014 -0.7643509 -0.3567039 -0.5371501 -0.4558918 -0.8231865 -0.3384183 -0.4364433 -0.8314415 -0.3438351 -0.676363 -0.4058803 -0.6146497 -0.6646528 -0.4802684 -0.5723452 -0.530478 -0.7128443 -0.4587441 -0.2618339 -0.9369068 -0.2316219 -0.6212567 -0.4017691 -0.6727718 -0.6279006 -0.3879747 -0.6746973 -0.4814 -0.6923535 -0.537495 -0.431842 -0.7434293 -0.5107108 -0.2792373 -0.9042878 -0.3229396 -0.5238965 -0.4534864 -0.7210288 -0.4355493 -0.7059015 -0.5585695 -0.5214142 -0.4033097 -0.7519765 -0.1753506 -0.9528018 -0.2478325 -0.264952 -0.8477622 -0.4594562 -0.3962601 -0.5662735 -0.7227118 -0.267126 -0.8322332 -0.4858308 -0.3873296 -0.3919466 -0.8344781 -0.183317 -0.8766726 -0.4447921 -0.338665 -0.4363117 -0.8336294 -0.2367579 -0.6932293 -0.6807194 -0.2963106 -0.2669839 -0.9170167 -0.1214686 -0.9349572 -0.3333176 -0.2257518 -0.4112409 -0.8831292 -0.1922913 -0.5978761 -0.7781826 -0.1959654 -0.2515723 -0.9477917 -0.1058179 -0.7235934 -0.6820669 -0.1029388 -0.7345773 -0.6706712 -0.09468376 -0.3803808 -0.9199703 -0.07573097 -0.8939795 -0.4416623 -0.08323466 -0.4377342 -0.8952435 -0.02033865 -0.9657213 -0.2587833 -0.009620249 -0.4228271 -0.9061594 0.001143395 -0.8315762 -0.5554094 -0.003546297 -0.9188251 -0.3946492 0.0336942 -0.5341246 -0.8447341 0.0353645 -0.7399118 -0.6717738 0.09609878 -0.3941196 -0.9140213 0.08396393 -0.7822842 -0.617237 0.08007907 -0.9258283 -0.3693632 0.1700352 -0.5373983 -0.8260092 0.230823 -0.3739441 -0.8982687 0.185858 -0.5211091 -0.8330081 0.08007931 -0.9258269 -0.3693671 0.2069712 -0.7198299 -0.6625768 0.1604231 -0.856158 -0.4911803 0.321945 -0.3799874 -0.8671569 0.3259416 -0.4367757 -0.8384445 0.3712615 -0.4776517 -0.7962499 0.3764054 -0.5649367 -0.7342789 0.2244825 -0.8662138 -0.4464094 0.1866039 -0.8937141 -0.4079879 0.4355697 -0.5084956 -0.7427728 0.2483528 -0.8925307 -0.3764438 0.5524535 -0.4391134 -0.7085018 0.4775652 -0.5704037 -0.6682597 0.3321599 -0.8356593 -0.4374282 0.3413457 -0.8461856 -0.4092103 0.5948678 -0.4369591 -0.6746845 0.5581905 -0.6170343 -0.5546999 0.724414 -0.3298524 -0.6053279 0.5788483 -0.61377 -0.5368623 0.2143719 -0.9553495 -0.2033525 0.5320796 -0.7277513 -0.4327462 0.7548233 -0.3777363 -0.5362435 0.3898652 -0.8696519 -0.3028377 0.6519529 -0.6048253 -0.4573225 0.8035084 -0.2637356 -0.5336834 0.3835814 -0.8886876 -0.251197 0.6235497 -0.6918767 -0.3639952 0.8080666 -0.4139726 -0.4191123 0.7746505 -0.5014362 -0.3853291 0.2910345 -0.9416938 -0.1688546 0.6964395 -0.6250084 -0.352614 0.3589391 -0.919909 -0.1578934 0.6380875 -0.7097916 -0.2983964 0.8826186 -0.3259844 -0.3387015 0.3227478 -0.9385901 -0.1219939 0.8615292 -0.4428728 -0.2482559 0.8730876 -0.413769 -0.257902 0.1630707 -0.9853743 -0.04945182 0.6841586 -0.7001374 -0.2042908 0.6401637 -0.7468464 -0.1800304 0.8889774 -0.4243851 -0.1720948 0.8280652 -0.5457978 -0.1281128 0.6458587 -0.753807 -0.1210027 0.4961218 -0.8660777 -0.06142163 0.9139962 -0.4019181 -0.05543392 0.8673022 -0.4932828 -0.06677496 0.3664425 -0.9294086 -0.04381448 0.6575587 -0.7533781 -0.006165921 0.2140871 -0.9768143 -8.7891e-4 0.9965442 -0.009110212 -0.08256483 0.9993188 0.01894736 -0.03167164 0.985961 -0.005281329 -0.166892 0.9896322 0.005890309 -0.1435049 0.9638122 -0.009586751 -0.26641 0.9717614 0.01009601 -0.2357501 0.9294826 0.006471157 -0.3688091 0.9329584 -0.002509236 -0.3599755 0.8911927 -0.004528641 -0.4536026 0.8883146 1.60518e-4 -0.4592356 0.837273 -0.003836512 -0.5467717 0.834495 0.001248955 -0.5510142 0.7441143 0.005464017 -0.66803 0.7478497 3.52169e-4 -0.6638681 0.6914365 8.45124e-4 -0.7224368 0.6933669 -0.001144826 -0.7205839 0.5903359 -0.001175582 -0.8071569 0.6043536 -0.01611381 -0.7965533 0.5164216 -0.006516098 -0.8563097 0.4610767 -0.01257568 -0.8872713 0.5092189 -2.97305e-4 -0.8606371 0.3500426 0.002863466 -0.9367294 0.3826764 0.02102077 -0.9236433 0.2328047 -0.009346544 -0.9724786 0.3070927 0.01898485 -0.9514902 0.2071976 0.00650525 -0.9782775 0.1069929 -0.01397854 -0.9941616 0.08771449 6.14495e-4 -0.9961455 0.004201114 -9.29522e-4 -0.9999908 -0.007813036 0.007987976 -0.9999376 -0.1004115 0.005422711 -0.9949313 -0.09385281 5.77992e-4 -0.9955859 -0.1993347 0.006000995 -0.9799132 -0.2113144 0.01617419 -0.9772843 -0.3059569 -0.00645405 -0.9520236 -0.3411114 0.02077049 -0.9397934 -0.4411315 -0.01787817 -0.8972644 -0.4757169 0.01068377 -0.8795337 -0.5593149 -0.01533305 -0.8288135 -0.5458326 -0.00308901 -0.8378886 -0.6084607 0.0077461 -0.7935463 -0.6733341 -0.01057291 -0.7392628 -0.6876799 0.004345476 -0.7260011 -0.7512876 1.54886e-4 -0.6599749 -0.74747 -0.003722906 -0.6642851 -0.8065273 -0.007141709 -0.5911538 -0.8122313 9.07445e-4 -0.5833349 -0.8766859 0.00197947 -0.4810593 -0.8703873 -0.009661376 -0.492273 -0.9099049 0.009923875 -0.4146982 -0.9108989 0.01198363 -0.4124556 -0.9475266 0.01501655 -0.3193242 -0.9411708 4.25175e-4 -0.3379309 -0.9744521 0.001372516 -0.2245914 -0.9777072 0.01365202 -0.2095286 -0.9935415 0.01610779 -0.1123201 -0.9895523 -0.01348191 -0.1435437 -0.9998137 0.009990513 -0.01651322 -0.9998531 -0.01253539 0.01169919 -0.9917444 0.002850294 0.1281992 -0.9927857 -0.004856467 0.1198042 -0.9764823 -0.006217837 0.2155076 -0.9725385 0.00814265 0.2326 -0.9508661 0.008570849 0.309484 -0.9447245 -0.006121397 0.3278082 -0.9082052 -0.002502977 0.4185177 -0.911158 -0.009574234 0.411946 -0.8665267 0.009312629 0.4990438 -0.8432034 -0.01726585 0.5373173 -0.8103073 0.004484713 0.5859881 -0.7849347 -0.01297563 0.6194426 -0.7486144 0.01054739 0.6629217 -0.7099922 -0.01042604 0.7041324 -0.6504541 -0.01093518 0.7594669 -0.6783062 0.0046615 0.7347646 -0.5730678 -0.008895039 0.8194597 -0.5919349 0.004741311 0.805972 -0.5103789 0.02304482 0.8596408 -0.4427197 -0.01079583 0.8965951 -0.4074241 -0.003318071 0.9132331 -0.4022656 -0.007311284 0.9154939 -0.2844637 0.00138396 0.9586859 -0.2842466 0.001216769 0.9587504 -0.2204901 -0.006538569 0.9753673 -0.1969024 0.01329106 0.980333 -0.1001219 0.01472175 0.9948663 -0.08044105 8.52993e-4 0.9967591 -0.01121211 7.21259e-4 0.9999369 -0.007250189 0.003527343 0.9999676 0.1065242 -0.01556521 0.9941883 0.1350157 0.008166849 0.9908098 0.2302207 -0.008632481 0.9731002 0.2547708 0.01091504 0.9669399 0.3479304 0.01078218 0.9374584 0.3276031 -0.006563007 0.9447926 0.4324623 -8.92438e-5 0.901652 0.4352277 -0.002447605 0.9003171 0.5279396 -0.008865237 0.8492357 0.520527 -0.001840889 0.8538433 0.6001253 -0.005197286 0.7998892 0.6064442 0.001166045 0.7951252 0.6793458 -0.001429855 0.7338169 0.677362 7.8081e-4 0.7356494 0.7509546 -1.09072e-4 0.6603539 0.7517035 -9.57986e-4 0.6595007 0.8215839 0.002878069 0.5700804 0.8085656 -0.009002447 0.5883372 0.8400871 -0.02168822 0.542018 0.8712634 0.01739758 0.4905075 0.9152673 -0.01673072 0.4024996 0.9321597 0.009051918 0.3619342 0.9428526 -0.007649779 0.3331223 0.9748656 0.00658667 0.2226967 0.973652 0.01055693 0.2277951 0.9918813 0.005174279 0.1270626 0.992951 0.01217764 0.1178984 0.9996052 -0.01133602 0.02570921 0.9475706 0.3189378 -0.01971596 0.6642379 0.7474125 -0.01275432 0.4527565 0.8914788 -0.01665312 0.8270646 0.5590137 -0.05888932 0.3595917 0.9322757 -0.03944528 0.8344984 0.537406 -0.1216859 0.8151316 0.5635274 -0.1341555 0.4635185 0.8815721 -0.08933812 0.46464 0.8788492 -0.1083239 0.8700084 0.4339341 -0.2340659 0.8323185 0.5131396 -0.2096042 0.687438 0.6951394 -0.2102621 0.865042 0.3717613 -0.3368915 0.867767 0.361851 -0.3406529 0.6758193 0.6922843 -0.2530037 0.2511814 0.9618722 -0.1082117 0.2875345 0.9504585 -0.1181212 0.585259 0.7710404 -0.2509353 0.8183612 0.3897946 -0.4223092 0.8189905 0.3873801 -0.4233098 0.6589481 0.6652219 -0.3510945 0.7906451 0.3286896 -0.516569 0.579172 0.7298218 -0.363208 0.3662489 0.8991943 -0.2393979 0.7391125 0.4349304 -0.5143426 0.6235926 0.6489132 -0.4359405 0.5222012 0.7311077 -0.4390757 0.7165258 0.3511651 -0.6027222 0.2802835 0.9349111 -0.2176755 0.2599693 0.943632 -0.2048774 0.565296 0.6301882 -0.5322625 0.5946303 0.4306282 -0.6789509 0.5472686 0.6256722 -0.5559061 0.1991788 0.956817 -0.2117288 0.3547556 0.8304239 -0.4295866 0.56202 0.3437711 -0.7522998 0.5605525 0.4047501 -0.7224669 0.07910531 0.9913686 -0.1045501 0.3662556 0.7514533 -0.548794 0.3311589 0.812978 -0.4789578 0.4775199 0.3534268 -0.804403 0.4782883 0.3797519 -0.7918516 0.3810652 0.6783553 -0.6281906 0.1966658 0.9274017 -0.3181959 0.3785738 0.4058425 -0.8318496 0.294081 0.6224936 -0.725271 0.2782095 0.7350185 -0.6183424 0.1715845 0.9059704 -0.3870098 0.1136718 0.9434937 -0.3112851 0.2340131 0.5337668 -0.8126075 0.08392608 0.9670299 -0.2404367 0.2422015 0.6203633 -0.7459812 0.1482543 0.8343695 -0.5308938 0.2318341 0.5324116 -0.8141197 0.1786721 0.2900032 -0.9401991 0.1202674 0.3977828 -0.9095629 0.1321094 0.647633 -0.7504124 0.08718097 0.8077939 -0.5829824 0.105358 0.3832765 -0.9176049 0.06441694 0.8359179 -0.5450614 0.03723877 0.8976233 -0.4391877 0.03419995 0.5160892 -0.8558519 0.02809274 0.9739929 -0.2248302 0.005237758 0.4967675 -0.8678679 -0.01504242 0.8818218 -0.471343 -0.03133249 0.5586877 -0.8287861 -0.03248947 0.9008097 -0.4329972 -0.09512335 0.5171527 -0.8505908 -0.09166103 0.5120487 -0.8540518 -0.1075881 0.7681282 -0.6311924 -0.1956471 0.3284983 -0.924019 -0.2342468 0.5487326 -0.8025093 -0.02772676 0.9903057 -0.1361098 -0.14247 0.774009 -0.616938 -0.1331624 0.900844 -0.4132165 -0.3183379 0.4484795 -0.835181 -0.2963411 0.5107915 -0.8070155 -0.240593 0.7869346 -0.568198 -0.185921 0.8634911 -0.4688459 -0.4314885 0.3629502 -0.8258843 -0.4315035 0.5529698 -0.7127617 -0.3520321 0.7178964 -0.6005816 -0.4726597 0.5009717 -0.7249967 -0.1452245 0.9589608 -0.2435242 -0.3014532 0.8310611 -0.4674008 -0.5829944 0.4283732 -0.6903724 -0.5382829 0.517957 -0.6648098 -0.08150529 0.9898734 -0.1162223 -0.447242 0.7169563 -0.5347413 -0.3686837 0.8065571 -0.4621018 -0.6298579 0.3608009 -0.6878239 -0.2219402 0.9441805 -0.2434455 -0.7023159 0.3794165 -0.602325 -0.6637113 0.4583307 -0.5911179 -0.2751772 0.9277389 -0.2521473 -0.5544202 0.6797443 -0.4801728 -0.4950989 0.7473266 -0.443148 -0.3491787 0.886813 -0.3027163 -0.770294 0.3091648 -0.5577315 -0.7504634 0.459156 -0.4753742 -0.72738 0.5158509 -0.4525662 -0.6015015 0.6864322 -0.4086648 -0.4082978 0.8728752 -0.2671742 -0.06934225 0.9965876 -0.0447759 -0.3366717 0.9230049 -0.1863172 -0.725831 0.5951802 -0.3448622 -0.3444214 0.9198252 -0.1878713 -0.7296102 0.5910311 -0.344022 -0.8831542 0.3781092 -0.2776188 -0.7444352 0.6109697 -0.2693184 -0.6491777 0.7345901 -0.1973469 -0.9019521 0.3644356 -0.2316666 -0.3951743 0.908868 -0.1334031 -0.7383112 0.6599569 -0.139117 -0.7396516 0.6576243 -0.1429892 -0.8906424 0.4459121 -0.08898669 -0.1802534 0.9830298 -0.034078 -0.9392719 0.3430483 -0.009282529 -0.449739 0.8921447 -0.04257708 -0.8891001 0.456584 -0.03212559 -0.6776474 0.7352772 0.01270407 -0.5154143 0.8568533 -0.01227205 -0.9232079 0.3696072 0.1052508 -0.897314 0.4264835 0.1137527 -0.289299 0.9566221 0.03435522 -0.7111845 0.699597 0.06914395 -0.5896998 0.801842 0.09645622 -0.8847022 0.4269862 0.1870425 -0.3839421 0.9204183 0.07361149 -0.7970355 0.5666208 0.2089868 -0.8483461 0.431455 0.3068479 -0.3179612 0.944057 0.08750528 -0.7846251 0.5755915 0.2303431 -0.466973 0.8656473 0.1805303 -0.8191565 0.4343785 0.3745637 -0.8165213 0.4437127 0.36934 -0.468478 0.8593355 0.2051119 -0.7970569 0.3831484 0.4667952 -0.4143522 0.8858458 0.2087806 -0.7857472 0.432623 0.4420844 -0.5180683 0.789406 0.3293076 -0.7543691 0.37371 0.5396926 -0.7233515 0.429456 0.5406758 -0.1091597 0.991327 0.07317841 -0.5115252 0.7886002 0.3412504 -0.6850329 0.4057282 0.6050741 -0.6825199 0.4316309 0.5897977 -0.4177173 0.8177435 0.3959898 -0.3765544 0.8750085 0.3042483 -0.6211305 0.4136166 0.6656712 -0.5950163 0.4588959 0.659826 -0.4037292 0.818652 0.4084259 -0.2986534 0.8866019 0.3531901 -0.5501517 0.4486356 0.7043147 -0.4704213 0.5731566 0.670966 -0.298157 0.8655492 0.4024017 -0.4300572 0.5082736 0.7461293 -0.2100254 0.8934975 0.3969275 -0.2026156 0.9174587 0.342369 -0.3578838 0.5907136 0.7231712 -0.3208813 0.6651904 0.6742085 -0.3731717 0.2690476 0.8878943 -0.01601642 0.9993107 0.03348904 -0.3022999 0.2888822 0.9083843 -0.09286844 0.9574474 0.2732583 -0.2323189 0.5377275 0.8104795 -0.226422 0.704978 0.6721155 -0.1187505 0.8852466 0.4497075 -0.117653 0.887269 0.445995 -0.1731792 0.5273942 0.8317838 -0.1427374 0.5857762 0.7978048 -0.08803629 0.5820125 0.8084003 -0.04176151 0.9264248 0.3741565 -0.05485433 0.6335382 0.7717646 -0.03091293 0.821259 0.5697178 0.02025371 0.4947565 0.8687956 0.0170567 0.491382 0.8707772 0.003617107 0.9914572 0.1303821 0.076204 0.6893981 0.7203634 0.1347957 0.271597 0.9529246 0.03647923 0.8679701 0.4952749 0.1584947 0.4192829 0.8939136 0.0376659 0.9396803 0.3399738 0.1033454 0.6588518 0.7451404 0.207827 0.3958173 0.8945036 0.1497476 0.7889638 0.5959126 0.129562 0.8571324 0.4985356 0.2386003 0.5751191 0.7825012 0.2455332 0.5708277 0.7834982 0.3399472 0.272043 0.9002381 0.1400495 0.9134754 0.3820328 0.2813216 0.6891457 0.6677848 0.4055455 0.3409201 0.8481193 0.405749 0.3507923 0.8439862 0.1167566 0.9526177 0.280869 0.315649 0.6529347 0.6885071 0.4875408 0.3567665 0.7968826 0.4883373 0.3551408 0.797121 0.3420505 0.7584574 0.5547466 0.3363914 0.763801 0.550862 0.1873852 0.9228528 0.3364959 0.5600102 0.3420686 0.7545713 0.5587165 0.4038677 0.7243803 0.4185121 0.7232108 0.549376 0.3912524 0.7516777 0.5309448 0.6366291 0.3728172 0.6750636 0.6225271 0.4007646 0.6721963 0.09385043 0.988945 0.1148042 0.4832101 0.6937804 0.5340194 0.2246804 0.9428281 0.2461583 0.4239833 0.8178468 0.3890563 0.6884592 0.372387 0.6223762 0.6749094 0.4729285 0.566424 0.4022052 0.8299168 0.3866127 0.6873559 0.4736275 0.5506533 0.4179682 0.8411846 0.3430905 0.7764036 0.3030996 0.5525651 0.5483404 0.7524244 0.3649389 0.5454822 0.7501947 0.3737075 0.7992379 0.3843569 0.4620482 0.8095945 0.3443953 0.4753407 0.682976 0.6150705 0.3939952 0.2883336 0.9447754 0.1557667 0.1890857 0.9757404 0.1103512 0.8350651 0.4148306 0.3613614 0.6640321 0.6793968 0.3122203 0.6088079 0.7465394 0.2683876 0.883139 0.3172695 0.3455514 0.4226469 0.8886535 0.1779456 0.8219751 0.513633 0.2460449 0.3855897 0.9123389 0.1376898 0.8505386 0.4853382 0.202561 0.8236487 0.5269904 0.209485 0.5974567 0.7912161 0.1304712 0.1523053 0.987816 0.03198045 0.5574872 0.8244806 0.0971592 0.9035964 0.416803 0.09893834 0.8755753 0.4715745 0.1048112 0.3312984 0.9425881 0.04206132 0.7593742 0.6459494 0.07810336 -0.006232142 0.9999804 -7.15431e-4 -0.003483951 0.9999893 0.0030514 -0.001022934 0.9999893 0.004513025 -0.001236319 0.9999974 0.001900196 -0.001295685 0.9999989 6.86251e-4 -0.001942813 0.9999978 8.48031e-4 -0.001425802 0.9999989 4.01078e-4 -1.32936e-4 0.9999999 5.42174e-4 -8.9909e-4 0.9999992 9.3457e-4 -0.003809154 0.9999853 -0.003853619 -0.001108944 0.9999995 1.99984e-5 0.001371264 0.9999984 0.001176774 1.91933e-4 0.9999977 0.00217092 -0.003234148 0.9999945 -8.06411e-4 -0.002155005 0.9999971 0.001085817 7.62465e-4 0.9999977 0.002007663 -9.23293e-4 0.9999982 0.001706004 -0.001402735 0.9999987 -8.39783e-4 -0.001287102 0.9999991 3.71332e-4 0.002132296 0.9999976 7.1105e-4 6.68911e-4 0.9999995 8.343e-4 -3.50579e-4 0.9999999 -4.10776e-4 0.001719236 0.9999976 0.001369178 9.87748e-5 0.9999989 -0.001505792 -6.30991e-4 0.9999989 -0.001398861 0.002188265 0.9999971 0.001002967 7.98785e-4 0.9999985 0.001519739 -6.4833e-5 0.9999985 -0.001815617 0.001381218 0.999999 5.54408e-4 0.001231551 0.9999992 2.15704e-4 -1.71176e-4 0.9999983 -0.001856327 -0.002604961 0.9999956 -0.001461446 0.001223504 0.9999994 -1.43364e-4 0.001880466 0.999997 -0.001566231 3.66326e-5 1 -1.3877e-4 0.002711832 0.9999963 -5.34571e-4 0.001897692 0.9999971 -0.001464009 0.002484083 0.9999964 -0.001044929 0.0042001 0.9999901 0.001570999 3.40116e-4 1 -2.50465e-4 -1.8498e-4 0.9999977 -0.002120971 2.55142e-4 1 -3.43624e-4 0.9987576 0.04621738 -0.01863437 0.9912878 0.003448486 -0.1316695 0.986719 -0.03712755 -0.1581367 0.9622676 0.0480917 -0.2678215 0.926963 -0.03212505 -0.3737749 0.918119 0.007488191 -0.3962342 0.8594723 0.05629903 -0.5080727 0.8231657 0.03127628 -0.5669393 0.779065 -0.07859182 -0.6219978 0.7394538 0.02670884 -0.6726774 0.6840468 0.07114619 -0.7259603 0.5974518 0.03602051 -0.8010955 0.5255994 -0.09766614 -0.8451074 0.4739233 0.01901662 -0.8803607 0.3787375 0.08321595 -0.9217554 0.2135263 -0.06395274 -0.9748418 0.208705 -0.05128473 -0.9766331 0.1047985 0.04462462 -0.9934918 -0.02233964 0.03736722 -0.9990519 -0.09998828 -0.05256664 -0.9935991 -0.1028085 -0.04767858 -0.9935579 -0.2492287 0.07691621 -0.9653854 -0.3257437 0.05562758 -0.9438202 -0.4036659 -0.05637919 -0.9131677 -0.4374045 -0.00362271 -0.8992577 -0.5255436 0.037588 -0.8499359 -0.6105257 -0.04542654 -0.7906926 -0.6414127 0.02170413 -0.7668891 -0.7486193 0.0509029 -0.6610432 -0.7965112 -0.05270701 -0.6023221 -0.8360989 0.02524614 -0.5479977 -0.9144292 -0.04305356 -0.4024496 -0.8886787 0.02023911 -0.4580836 -0.9308483 0.01568973 -0.3650692 -0.9605072 0.05525243 -0.2727147 -0.9908225 -0.0547102 -0.1236031 -0.9891161 -0.02302581 -0.1453248 -0.996055 -0.003736436 -0.08865994 -0.9966382 0.07406324 0.03502857 -0.9854564 -0.0110681 0.1695678 -0.9781327 -0.06290161 0.1982421 -0.9565179 0.0468418 0.2878879 -0.8853306 -0.02941668 0.4640308 -0.8873812 -0.04354059 0.4589759 -0.8065493 0.08637893 0.5848221 -0.7029412 -0.04656547 0.7097221 -0.6908398 -0.01134943 0.7229188 -0.5969665 0.04117268 0.801209 -0.513076 -0.04040157 0.8573918 -0.4762858 0.02890664 0.8788152 -0.3836618 0.06820809 0.9209513 -0.267651 -0.04106426 0.9626405 -0.2359713 0.01336973 0.9716681 -0.01951313 -0.05573004 0.9982553 -0.05835169 0.01251083 0.9982178 0.1035155 0.07731223 0.9916186 0.1811785 0.0614261 0.9815301 0.2836993 -0.02301073 0.9586372 0.3277785 -0.1170858 0.9374712 0.3902884 0.0526365 0.9191869 0.5332093 -0.02531266 0.8456046 0.5256198 -0.04533487 0.8495109 0.6284987 0.07112544 0.7745519 0.7211341 0.04162585 0.6915439 0.7710426 -0.0709967 0.6328134 0.7985078 -0.008094727 0.6019301 0.8450765 0.04413568 0.5328206 0.893959 0.01781517 0.4477947 0.9137411 -0.07269918 0.3997402 0.9565458 0.08216404 0.2797667 0.9917625 -0.007136344 0.1278921 0.992725 -0.06877517 0.09882897 0.9919617 -0.03835111 -0.120588 0.980973 0.04509407 -0.1888354 0.9603382 -0.05092865 -0.2741476 0.9338755 -0.03687065 -0.3556928 0.8835946 -0.01361453 -0.4680547 0.8998197 0.05502021 -0.4327788 0.7862481 -0.06435286 -0.6145508 0.6894523 -0.01896399 -0.7240828 0.7268446 0.05665582 -0.6844612 0.6153156 -0.03077507 -0.78768 0.5496792 0.04853516 -0.8339648 0.4786785 -0.05779391 -0.8760861 0.309956 -0.004450798 -0.9507406 0.3345994 0.04778885 -0.9411479 0.1924363 -0.04464423 -0.9802935 0.1015121 -0.004363656 -0.9948248 0.1006207 -0.002394676 -0.994922 -0.09729123 -0.01496297 -0.9951435 -0.1317347 0.05518287 -0.9897479 -0.2823315 -0.08322584 -0.9557 -0.4288316 0.05210077 -0.9018808 -0.4178965 0.02153676 -0.9082393 -0.5611684 -0.03569805 -0.8269315 -0.6219536 0.05317664 -0.7812466 -0.6821427 -0.05558288 -0.7291035 -0.7771571 -0.02487075 -0.6288151 -0.8188314 0.07707393 -0.5688365 -0.8430005 0.00683552 -0.5378695 -0.9051426 -0.07275247 -0.4188367 -0.9445551 -0.01517516 -0.3280025 -0.9768921 -0.01839858 -0.2129396 -0.9575061 0.07405084 -0.2787449 -0.9914166 -0.04912155 -0.1211624 -0.9989467 0.03617513 -0.02823042 -0.9993663 -0.02762842 0.02244251 -0.995482 -0.03338479 0.08888781 -0.9830519 0.03897905 0.1791356 -0.9745952 -0.02624899 0.2224304 -0.9323827 -0.02722221 0.3604466 -0.9096258 0.04139655 0.413361 -0.880984 -0.0392062 0.4715189 -0.8406999 -0.04805058 0.5393653 -0.7600557 0.02486002 0.6493824 -0.7713521 0.06522297 0.6330576 -0.6744594 -0.07343721 0.7346506 -0.5555739 -0.002165198 0.8314644 -0.4916714 0.02950114 0.870281 -0.5177257 0.07389622 0.8523495 -0.3908899 -0.0577982 0.9186211 -0.2982116 -0.05314248 0.9530193 -0.219012 0.06512284 0.9735465 -0.1444869 -0.04230535 0.9886019 0.04907751 0.02960723 0.9983561 0.0531013 0.01947236 0.9983993 0.2391889 -0.07120716 0.9683586 0.328588 0.03380852 0.9438681 0.371214 -0.01970058 0.9283384 0.4974924 -0.01319116 0.8673681 0.5240783 0.02576929 0.8512802 0.6092314 -0.05967056 0.7907443 0.7525183 -0.04299592 0.6571664 0.7166512 0.06435 0.6944568 0.862904 -0.02916014 0.5045261 0.907975 -0.02886557 0.4180291 0.8830967 0.02495068 0.4685274 0.9633997 0.01383227 0.2677119 0.9641206 0.008745849 0.2653209 0.9893677 -0.05115628 0.1361415 0.9990829 0.03965014 0.0161671 0.9994701 0.01595014 0.02837395 0.9508531 -0.3088137 0.02264171 0.6994094 -0.7146603 0.009347617 0.909724 -0.4116895 0.0539813 0.6079418 -0.7936438 0.02316015 0.9191029 -0.3771566 0.1140297 0.5331766 -0.8434317 0.06592369 0.865828 -0.4769954 0.1510547 0.4023318 -0.9135291 0.05994939 0.7065166 -0.694386 0.1366111 0.9091297 -0.3246907 0.2608816 0.8787263 -0.3890518 0.2765481 0.2871083 -0.9535062 0.09162396 0.6944078 -0.6797619 0.2360545 0.6392675 -0.7290061 0.2447189 0.8627359 -0.34916 0.3657518 0.4496969 -0.874082 0.183721 0.7558767 -0.5497662 0.3555384 0.7755724 -0.4056532 0.4836661 0.7278627 -0.5394114 0.4233809 0.3930568 -0.8846156 0.2509218 0.5220056 -0.7733984 0.3596739 0.7201553 -0.4135562 0.5570886 0.5598829 -0.6857119 0.4651134 0.7410973 -0.1647045 0.6508819 0.6489006 -0.390035 0.6532999 0.1512677 -0.9806951 0.1239162 0.5111047 -0.7024759 0.4952774 0.4726017 -0.7397616 0.4789577 0.2834482 -0.9083027 0.3076416 0.5920529 -0.3000559 0.7479572 0.4760366 -0.5561338 0.6812521 0.4898437 -0.5436448 0.6815448 0.3588754 -0.7251393 0.5876917 0.4567437 -0.3070156 0.8349411 0.2435505 -0.8814182 0.404704 0.2063634 -0.9290091 0.3071747 0.4211446 -0.3652017 0.8302198 0.3517141 -0.6201004 0.701265 0.37733 -0.2799674 0.882746 0.2519904 -0.5859734 0.7701534 0.2550599 -0.6906351 0.6767331 0.1609473 -0.8951974 0.4155932 0.2130597 -0.3443837 0.9143334 0.2119684 -0.547444 0.809552 0.08225345 -0.9534222 0.2902078 0.1451296 -0.6747362 0.7236495 0.08204251 -0.9187852 0.3861385 0.0766986 -0.6809354 0.7283162 0.04459291 -0.3344003 0.9413756 0.02473455 -0.8312256 0.5553847 0.05043095 -0.3548532 0.9335609 -0.045852 -0.4564506 0.8885666 -0.05575448 -0.7055515 0.7064621 -0.009340822 -0.8550535 0.5184558 -0.02485334 -0.9204707 0.3900206 -0.1340107 -0.2920736 0.9469605 -0.1783982 -0.4805845 0.8586109 -0.1485493 -0.6517578 0.7437372 -0.2685891 -0.361597 0.8928089 -0.154016 -0.8112934 0.5639877 -0.101886 -0.8879023 0.4486076 -0.3079684 -0.546713 0.7786274 -0.200475 -0.7922381 0.5763409 -0.3953405 -0.3906257 0.8313347 -0.3786603 -0.4648978 0.8003041 -0.2031478 -0.8794066 0.430552 -0.4040464 -0.60058 0.6899638 -0.1111514 -0.9740411 0.1972043 -0.5566591 -0.234438 0.7969753 -0.3797736 -0.6895338 0.616697 -0.3949419 -0.7217966 0.5683578 -0.5934787 -0.4147744 0.6897429 -0.297966 -0.8815797 0.366106 -0.5571146 -0.5221921 0.645708 -0.6558166 -0.2658045 0.7065781 -0.3083259 -0.8880513 0.341028 -0.5243167 -0.6694361 0.526258 -0.7264866 -0.2597945 0.6361793 -0.2477446 -0.9410883 0.2301641 -0.6854913 -0.4937965 0.5350391 -0.6058164 -0.6182028 0.5008112 -0.05005961 -0.9980303 0.0378127 -0.7110308 -0.4722166 0.5210055 -0.4099576 -0.8570156 0.3121848 -0.812565 -0.4293764 0.3941754 -0.6882907 -0.629959 0.3597328 -0.6541472 -0.6783137 0.3346371 -0.4717186 -0.8433578 0.2573503 -0.901454 -0.2739436 0.3351652 -0.3437455 -0.9243376 0.1656479 -0.6554528 -0.7246118 0.2128838 -0.8726326 -0.4197024 0.2497246 -0.3873315 -0.9131312 0.1271447 -0.7079679 -0.6740281 0.2108732 -0.9244153 -0.3142775 0.2160695 -0.3041003 -0.9496466 0.07546156 -0.8930249 -0.4342 0.1182246 -0.8578348 -0.5045412 0.09776318 -0.6912734 -0.7149952 0.1045129 -0.9379884 -0.3466656 9.46039e-4 -0.4779657 -0.8773872 0.04171884 -0.4561267 -0.8889402 0.04163777 -0.8562849 -0.5149107 0.04053789 -0.7312785 -0.6820562 -0.005581974 -0.5527567 -0.8332315 0.01361572 -0.9080535 -0.4109494 -0.08099138 -0.7806771 -0.6220449 -0.06002908 -0.9261831 -0.3632754 -0.101074 -0.1352575 -0.9907741 -0.008496582 -0.6644851 -0.7380656 -0.1171274 -0.9081418 -0.3513571 -0.2276549 -0.4365867 -0.8967856 -0.07188642 -0.862755 -0.4685692 -0.1899914 -0.415176 -0.9075557 -0.06302118 -0.7422345 -0.6487239 -0.1680633 -0.9061139 -0.3049195 -0.2932265 -0.6653341 -0.7094961 -0.2322629 -0.8145533 -0.4821465 -0.3225485 -0.8258656 -0.4021349 -0.395264 -0.4823845 -0.853927 -0.1952283 -0.3808614 -0.9130558 -0.145855 -0.1920333 -0.9776971 -0.08503836 -0.7671185 -0.4749667 -0.4312031 -0.5642904 -0.7576935 -0.327837 -0.7806457 -0.3870394 -0.4907064 -0.2356458 -0.9591472 -0.1565499 -0.4682296 -0.8199208 -0.3293799 -0.5476914 -0.7530483 -0.3646267 -0.693925 -0.464729 -0.5499957 -0.6840823 -0.4814326 -0.5479545 -0.666865 -0.4952797 -0.5567668 -0.3943145 -0.8486195 -0.352649 -0.5407702 -0.6514548 -0.5321413 -0.1475009 -0.9806456 -0.1287548 -0.651854 -0.2731012 -0.7074618 -0.623171 -0.3488289 -0.6999831 -0.4243531 -0.8077349 -0.4092541 -0.5511379 -0.5723254 -0.6071991 -0.1100476 -0.9885032 -0.1036875 -0.4382652 -0.6731705 -0.5956216 -0.3268471 -0.8146044 -0.4791563 -0.3012658 -0.8717502 -0.3863812 -0.5247702 -0.3508248 -0.7755891 -0.5249257 -0.3538038 -0.7741291 -0.3096532 -0.8225824 -0.4769415 -0.4009806 -0.3660586 -0.8397712 -0.3978776 -0.4207692 -0.8152586 -0.1920201 -0.910125 -0.3671522 -0.3549223 -0.5528165 -0.7539391 -0.267454 -0.682936 -0.679755 -0.2755967 -0.1873991 -0.9428298 -0.08266282 -0.9773119 -0.1950085 -0.2256415 -0.3746134 -0.8993057 -0.1905935 -0.6388747 -0.7453277 -0.193583 -0.6916018 -0.695854 -0.09949219 -0.8970803 -0.4305208 -0.09968501 -0.2479822 -0.9636222 -0.06592774 -0.4287917 -0.9009946 -0.08694463 -0.6150225 -0.7837015 -0.04620629 -0.9226884 -0.3827676 0.00659728 -0.4507208 -0.8926407 -0.02312898 -0.8671483 -0.4975127 0.07090866 -0.3486529 -0.9345658 0.01392853 -0.8649065 -0.5017398 0.04301738 -0.8063346 -0.5898934 0.1271175 -0.5849683 -0.8010327 0.09546583 -0.7551826 -0.6485258 0.03022366 -0.974303 -0.2232043 0.226346 -0.4302028 -0.8738954 0.1277933 -0.8410776 -0.5256019 0.3092963 -0.2346249 -0.9215677 0.2487999 -0.4351631 -0.8652928 0.24874 -0.6253423 -0.7396455 0.1598651 -0.8266406 -0.5395448 0.1696978 -0.8735991 -0.4561003 0.3993583 -0.3724815 -0.8377175 0.3260722 -0.6020923 -0.7288085 0.08063507 -0.982726 -0.1665761 0.3060447 -0.7378096 -0.6016424 0.4582611 -0.262524 -0.8491632 0.4814733 -0.4684062 -0.7407963 0.3329738 -0.7510342 -0.5701546 0.5486928 -0.4233493 -0.7209104 0.2850661 -0.8670205 -0.4086722 0.557404 -0.468009 -0.6857613 0.2839798 -0.8666474 -0.4102166 0.4879834 -0.675507 -0.5527771 0.6653968 -0.2697034 -0.6960656 0.2174368 -0.9456176 -0.2419273 0.495023 -0.7104436 -0.5002223 0.3449037 -0.8830714 -0.3181607 0.6740708 -0.4745773 -0.5660434 0.70865 -0.4427911 -0.5493189 0.706133 -0.4718656 -0.5279386 0.3560678 -0.8865273 -0.2954406 0.542578 -0.7613539 -0.3548935 0.824914 -0.3427243 -0.4495076 0.534348 -0.7895816 -0.3017172 0.7775316 -0.5050656 -0.3746377 0.1769731 -0.9789058 -0.1020985 0.5737184 -0.7620373 -0.3002439 0.8197796 -0.4615976 -0.338953 0.1210448 -0.9907802 -0.0608496 0.4994645 -0.8507679 -0.1634908 0.9189578 -0.3174483 -0.2339729 0.7820568 -0.578388 -0.2320656 0.7515377 -0.6233638 -0.2158905 0.5331601 -0.8305532 -0.1610026 0.9355491 -0.332729 -0.1184875 0.9159395 -0.3867756 -0.1070501 0.4933164 -0.8655494 -0.08639103 0.8114135 -0.5759631 -0.09937113 0.7725791 -0.6290966 -0.08578372 0.3672337 -0.9293388 -0.03832584 0.1181365 -0.9929931 -0.00289601 0.002426624 -0.9999938 0.002578556 0.004842936 -0.9999848 0.002671718 8.13759e-4 -0.9999812 0.006081044 0.004817426 -0.9999857 0.002368271 0.002615213 -0.9999786 0.006008505 0.002631962 -0.9999909 0.00336349 0.00158149 -0.9999671 0.00796777 9.81135e-4 -0.9999704 0.007635593 0.002130746 -0.9999977 1.99132e-4 0.001420259 -0.9999716 0.007397353 0.005656301 -0.9999809 -0.002540528 0.007005512 -0.9999747 -0.0012995 -8.5589e-4 -0.9999859 0.005264818 -0.009243309 -0.9999381 0.006201326 -0.003770589 -0.9999471 0.009573638 0.005332767 -0.9999853 -9.49101e-4 0.007092356 -0.9999691 -0.003409206 -0.001131415 -0.9999607 0.008798778 -0.002886533 -0.99999 0.003424286 0.002215981 -0.9999941 -0.002668797 0.002925097 -0.9999917 -0.002850592 -0.002296507 -0.9999916 0.003422558 0.00184828 -0.9999926 -0.003388226 -8.92444e-4 -0.9999995 4.61233e-4 5.57058e-4 -0.9999636 -0.00851792 0.001099705 -0.9999879 -0.004816591 0.004254758 -0.9999543 -0.008563756 -0.002074062 -0.9999974 -9.67396e-4 -0.0027377 -0.9999963 3.79188e-4 -3.20222e-4 -0.9999906 -0.004349231 -0.006996691 -0.9999752 -9.00246e-4 -0.004655301 -0.999986 -0.00251168 -1.24037e-4 -0.9999911 -0.004222571 -0.001113653 -0.9999919 -0.003864228 -0.007290005 -0.9999731 8.28067e-4 -9.71903e-4 -0.9999994 -4.4186e-4 -0.003476977 -0.9999821 -0.004887104 -0.003295004 -0.99998 -0.005413353 4.09886e-4 -0.9999943 -0.003335833 -0.005182862 -0.9999749 -0.004827439 0.9555137 0.2946033 -0.01423132 0.9063563 0.4170308 -0.06785082 0.7209661 0.6910716 -0.05126303 0.9254941 0.3589571 -0.1208744 0.9052236 0.4005334 -0.1419271 0.6698523 0.729666 -0.1374249 0.9311002 0.2659931 -0.2496002 0.6790601 0.7215717 -0.134951 0.4629146 0.8804072 -0.1029248 0.7947826 0.5449143 -0.2671874 0.7904613 0.5484745 -0.2726662 0.3544214 0.9288691 -0.107646 0.8591849 0.3332461 -0.3882636 0.5855558 0.7696213 -0.2545732 0.1031619 0.9936096 -0.04579877 0.8209207 0.387549 -0.4193986 0.6709141 0.6263408 -0.3969528 0.5743787 0.7590992 -0.306362 0.3403623 0.9148164 -0.2174043 0.6679407 0.6185266 -0.4138601 0.73609 0.3980205 -0.5474954 0.4384193 0.8123451 -0.3845569 0.6916617 0.4290183 -0.5809884 0.5991352 0.5798331 -0.5521146 0.4459608 0.8193587 -0.3602365 0.3344166 0.8862167 -0.3206021 0.5927857 0.4437878 -0.6720548 0.5656874 0.5651996 -0.6004559 0.2005096 0.9564013 -0.2123501 0.4266809 0.746335 -0.5108107 0.5500672 0.3737753 -0.7468053 0.3936657 0.7576644 -0.5205498 0.4929462 0.4715325 -0.7312054 0.2895369 0.8524125 -0.4353866 0.1905534 0.9413392 -0.2785137 0.4523085 0.4550412 -0.7670427 0.3536941 0.6024092 -0.7155444 0.2770925 0.8204206 -0.5001299 0.08583348 0.9837488 -0.1577052 0.3314618 0.3607861 -0.8717606 0.3443269 0.5952476 -0.7260299 0.145494 0.9255921 -0.3494435 0.2798846 0.4145474 -0.8659186 0.1853862 0.7385149 -0.6482498 0.1920636 0.7743445 -0.6029115 0.1412523 0.9099358 -0.3899548 0.2112022 0.3056395 -0.9284278 0.1520562 0.4641169 -0.8726251 0.1558782 0.7317803 -0.6634754 0.04942446 0.9653584 -0.2562039 0.09898096 0.4546287 -0.8851642 0.08198636 0.3904427 -0.9169693 0.07545155 0.83895 -0.5389527 0.03721314 0.7766439 -0.6288399 0.01374948 0.3616854 -0.9321988 0.01394385 0.7816437 -0.6235693 0.002946019 0.9968317 -0.07948642 -0.05032634 0.6218326 -0.7815316 -0.02809959 0.9549763 -0.2953485 -0.1354108 0.5046474 -0.85264 -0.0892499 0.6138839 -0.7843349 -0.1848462 0.4780415 -0.8586665 -0.09753286 0.8752018 -0.473824 -0.2341816 0.6137201 -0.7539939 -0.1938494 0.7885317 -0.5836439 -0.3410928 0.3953461 -0.8528524 -0.1501163 0.8574407 -0.4921997 -0.3935679 0.3882195 -0.8333006 -0.4130191 0.4950257 -0.7644376 -0.1004289 0.9704327 -0.2194867 -0.3060699 0.7472087 -0.5899156 -0.4869548 0.4126132 -0.7698215 -0.5036256 0.4417941 -0.7424145 -0.2577503 0.8705213 -0.4192343 -0.6044676 0.3250062 -0.727317 -0.3852794 0.7805709 -0.4922085 -0.3049819 0.8560585 -0.4173127 -0.6059904 0.4364567 -0.6650424 -0.4755185 0.7069157 -0.5235958 -0.1827933 0.9648824 -0.1886495 -0.7015017 0.3575772 -0.616469 -0.6989079 0.3637693 -0.615792 -0.60414 0.609753 -0.5130459 -0.4807817 0.7503755 -0.4536362 -0.3405338 0.8943821 -0.2900301 -0.7785989 0.3587263 -0.5148779 -0.7586829 0.4457631 -0.4750743 -0.67462 0.6038606 -0.424547 -0.6279765 0.6581654 -0.4152877 -0.3973065 0.8769205 -0.2704774 -0.8449727 0.3088593 -0.4366086 -0.3495941 0.9144055 -0.2040752 -0.6179017 0.7292002 -0.2940487 -0.2007863 0.9748085 -0.09712493 -0.8408014 0.4254474 -0.3347351 -0.8280552 0.4592859 -0.3215292 -0.6423169 0.7110471 -0.2860788 -0.8990089 0.3657411 -0.2408662 -0.8464922 0.4629311 -0.2629559 -0.6503088 0.742701 -0.1596676 -0.5072124 0.8486424 -0.1501401 -0.3675884 0.9239283 -0.1059979 -0.9104949 0.3686058 -0.1874272 -0.7579237 0.6460267 -0.09056085 -0.7681408 0.6297814 -0.115478 -0.8819432 0.4701923 -0.03309661 -0.2652496 0.9631633 -0.04426407 -0.4577887 0.8888668 -0.01858967 -0.9411345 0.3355172 0.04116177 -0.8762878 0.4817662 0.004598617 -0.4511537 0.8914417 -0.04233384 -0.7440142 0.6670789 0.03806167 -0.7205445 0.6911419 0.05602282 -0.5959674 0.7998582 0.0710619 -0.3689439 0.9293226 0.01549649 -0.9195013 0.3642008 0.147903 -0.8873798 0.4329632 0.1584299 -0.8508291 0.487696 0.1955565 -0.7627909 0.617891 0.1906849 -0.1516461 0.9880625 0.0271278 -0.9252187 0.2542878 0.2816172 -0.5854979 0.8022466 0.1165878 -0.3567439 0.9282214 0.1055409 -0.6827056 0.6820898 0.2620432 -0.5494377 0.8028169 0.231524 -0.8145382 0.4599393 0.3535301 -0.3953306 0.9070665 0.1447209 -0.8219919 0.4016641 0.4037267 -0.5409365 0.7938456 0.2778437 -0.6972486 0.5800417 0.4211843 -0.6956112 0.5791397 0.4251145 -0.7380892 0.3868457 0.5527883 -0.276993 0.9420828 0.18909 -0.1786465 0.9767667 0.1183733 -0.6805016 0.4603131 0.5701136 -0.1050186 0.9915931 0.07559323 -0.436178 0.8307646 0.345802 -0.4729205 0.7749984 0.4191942 -0.6573596 0.3358181 0.6746144 -0.5593746 0.4968988 0.6634695 -0.4136258 0.7859302 0.4595949 -0.5407565 0.4217035 0.7278383 -0.2740899 0.8905411 0.3630583 -0.4720382 0.4912563 0.732016 -0.2796174 0.885842 0.3702678 -0.4502283 0.4546999 0.7684676 -0.3094735 0.8232438 0.475916 -0.3476607 0.5834167 0.7340008 -0.2707631 0.7578175 0.5936329 -0.3319919 0.3917911 0.8580682 -0.05184108 0.9928914 0.1071418 -0.06616228 0.9845215 0.1622965 -0.1894217 0.8402032 0.5081124 -0.1684716 0.7892174 0.5905534 -0.2142927 0.390202 0.8954446 -0.2302734 0.4604629 0.8572912 -0.08969026 0.4781682 0.8736767 -0.06901502 0.8634735 0.4996505 -0.05083012 0.92326 0.3807985 -0.05096048 0.7773472 0.6270043 -0.05406635 0.3371822 0.9398857 -0.001154124 0.9863994 0.1643626 0.02480828 0.7688527 0.6389445 0.05992192 0.4298912 0.9008902 0.07589954 0.5473687 0.8334429 0.216217 0.3259876 0.9203165 0.05884552 0.8913888 0.4494032 0.1397266 0.5881182 0.7966138 0.152798 0.7273412 0.6690497 0.09918588 0.8718659 0.4795956 0.255752 0.3138285 0.9143865 0.1012862 0.9227599 0.371827 0.2669725 0.5987568 0.7551266 0.02657335 0.9972258 0.06953179 0.3635813 0.4717691 0.8032699 0.2916431 0.6099061 0.7368575 0.2584245 0.7862598 0.5612596 0.2025206 0.8765001 0.4367302 0.4530834 0.4796385 0.7514404 0.1759448 0.9281801 0.3279103 0.4438139 0.5659202 0.6948119 0.4463667 0.5774703 0.6835824 0.2923324 0.8665338 0.4045504 0.2381023 0.908421 0.3436258 0.615458 0.3445539 0.7088682 0.5243136 0.5423201 0.6564939 0.4492607 0.7410936 0.4989441 0.6819658 0.292921 0.6701641 0.6707205 0.4735274 0.5708817 0.1233446 0.9846661 0.1233652 0.4622186 0.7663634 0.4461405 0.7094975 0.44399 0.5472535 0.3587681 0.8837537 0.3004416 0.714954 0.4746155 0.5134013 0.446977 0.8400427 0.3074734 0.7415058 0.4560464 0.492129 0.7324919 0.5362483 0.4193966 0.4755356 0.8366404 0.2718432 0.8227823 0.4170525 0.3861304 0.8167777 0.4614973 0.3462578 0.4414703 0.8676772 0.2285615 0.354182 0.9193227 0.1714674 0.6446167 0.7261297 0.239176 0.9127328 0.3086433 0.2676903 0.6360555 0.7428426 0.2088502 0.8904188 0.3885777 0.2369849 0.5386364 0.830338 0.1428629 0.3503386 0.9312655 0.1000377 0.3173168 0.9434098 0.09637457 0.8803758 0.4486244 0.1538662 0.6365408 0.763027 0.1122755 0.9289453 0.3523467 0.1136329 0.9139302 0.3999649 0.06899058 0.6002391 0.7997741 0.008623182 0.5542122 0.832228 0.01566869 0.3362762 0.9417622 0.001540124 0.2807624 0.9597623 0.005369901 -0.001211881 0.9999992 2.44388e-4 -3.75193e-4 0.9999998 5.24331e-4 -0.001714885 0.9999979 0.00117737 -3.40563e-4 0.9999997 8.2908e-4 -0.001736223 0.9999983 6.70879e-4 -2.34026e-4 0.9999997 7.56044e-4 -0.002408981 0.9999972 1.17335e-4 -0.002610564 0.9999966 3.19976e-4 0.00205487 0.9999963 0.001835048 -0.002698838 0.9999957 0.001200854 2.32265e-4 0.9999894 0.004603505 -3.36774e-4 1 -4.22123e-5 -5.64873e-5 0.9999896 0.004568517 4.29102e-4 0.9999995 9.56446e-4 -3.08559e-4 1 -1.54444e-4 -0.003668069 0.99998 -0.005147516 6.94886e-4 0.9999995 8.00635e-4 -0.004241466 0.9999827 -0.004094541 0.007347643 0.9999712 0.001895844 -0.003619432 0.9999856 -0.003966808 0.007164955 0.9999621 0.004966616 0.001819849 0.9999644 0.008242845 -0.002551853 0.9999858 -0.004704892 -0.002766072 0.9999884 -0.003956437 -8.49394e-4 0.9999935 -0.003506243 0.003354787 0.9999919 -0.002262771 0.006156146 0.9999794 0.001843035 0.006316125 0.9999791 0.00141716 0.004320502 0.9999907 -4.35353e-5 -6.72241e-4 0.9999929 -0.003707885 1.62848e-4 0.999999 -0.001427173 0.003902912 0.9999897 -0.002310931 0.008169651 0.9999638 -0.002425193 6.4555e-4 0.9999991 -0.001228988 9.6803e-4 0.9999986 -0.001403212 0.004761934 0.9999842 -0.003023803 0.006079196 0.9999806 -0.001338541 0.001179099 0.9999987 -0.001198709 0.9960348 0.03548794 -0.08158135 0.9841016 -0.0158329 -0.1768992 0.9846114 -0.02275204 -0.1732711 0.9487438 0.05273222 -0.311616 0.9171361 -0.03860527 -0.3967002 0.9067327 0.005126059 -0.4216746 0.8375134 0.02693349 -0.5457528 0.805011 -0.06036418 -0.5901809 0.7462656 0.06557166 -0.6624108 0.6410033 -0.003148615 -0.7675318 0.615309 -0.06059193 -0.7859539 0.5634655 0.02413868 -0.8257869 0.4762342 0.04064178 -0.8783788 0.3792617 -0.06574141 -0.9229511 0.386934 -0.08883118 -0.9178188 0.2946179 0.05265688 -0.9541634 0.190432 0.07446908 -0.9788718 0.07405203 -0.06864976 -0.9948888 0.101122 -0.00629574 -0.9948542 -0.04371851 0.05855149 -0.9973267 -0.1827652 -0.02114552 -0.9829292 -0.1440921 0.03480243 -0.9889521 -0.234624 0.02869087 -0.9716628 -0.3424016 0.01537239 -0.939428 -0.3889176 -0.05022466 -0.9199026 -0.4448405 0.03737998 -0.8948295 -0.560013 0.02049171 -0.8282304 -0.597109 -0.04832637 -0.8007031 -0.6450952 0.03188937 -0.7634366 -0.713419 0.05039978 -0.6989229 -0.7712714 -0.04329001 -0.6350326 -0.7625371 -0.01438903 -0.6467845 -0.8366457 0.03966188 -0.5463066 -0.8872295 -0.03098011 -0.4602872 -0.8938346 -0.006294965 -0.4483528 -0.9249584 0.04961645 -0.3768162 -0.9656129 -0.03383761 -0.2577728 -0.9585829 0.02050065 -0.2840752 -0.9899442 0.05998206 -0.128112 -0.9986497 -0.0436083 -0.02823251 -0.9997499 0.01844066 0.01265561 -0.9923626 0.02165144 0.1214396 -0.9832211 -0.04524755 0.1767175 -0.9725644 0.03231382 0.2303787 -0.9326893 0.02060502 0.360092 -0.9049087 -0.07911354 0.418188 -0.8839893 0.02223485 0.4669783 -0.8408892 0.07980716 0.5352909 -0.7727205 0.02915591 0.6340765 -0.7299376 -0.0869795 0.677957 -0.6723583 0.04647648 0.7387654 -0.5987888 0.05855715 0.7987635 -0.5413514 -0.01656079 0.8406334 -0.5275726 0.001070201 0.8495094 -0.379267 -0.02825164 0.924856 -0.4245943 0.02054983 0.9051505 -0.3347796 0.0324217 0.9417386 -0.2206187 0.02626365 0.9750065 -0.1644056 -0.02691423 0.9860256 -0.1628792 -0.02446848 0.9863426 -0.03083819 0.04735857 0.9984018 0.0673747 -0.02737045 0.9973523 0.02319467 -0.1186466 0.9926656 0.1507205 0.05195665 0.9872102 0.2463474 0.07372248 0.9663737 0.3579544 -0.03833335 0.9329519 0.3520581 -0.02580791 0.9356223 0.3981985 0.004800915 0.9172868 0.5574408 -0.01086527 0.8301457 0.5292273 0.02869826 0.8479946 0.5931649 0.0288468 0.804564 0.7065289 -0.01817065 0.707451 0.6936947 0.01707392 0.7200669 0.8140001 0.02278327 0.5804177 0.8290603 -0.01704078 0.5588995 0.8625088 0.04108971 0.5043712 0.9130988 0.05140227 0.4044852 0.9475643 -0.07665026 0.3102368 0.962967 0.01905769 0.2689449 0.9893415 0.06253832 0.131501 0.9982708 -0.05270665 0.0260266 0.998929 -0.02850073 0.03645092 0.999902 -0.002245724 -0.01382392 0.9899752 -0.06661343 -0.1245465 0.9731869 0.001988172 -0.2300072 0.9637266 0.06474977 -0.2589181 0.9297136 -0.05242788 -0.3645326 0.8896818 -0.005855679 -0.4565436 0.8782711 0.02822065 -0.4773297 0.8390593 -0.05917477 -0.5408124 0.7893359 -0.0674085 -0.61025 0.7135509 0.04570221 -0.6991113 0.7091959 0.05963104 -0.7024852 0.6091408 -0.06554692 -0.7903487 0.5177352 -0.007760822 -0.8555057 0.4378643 -0.006083428 -0.8990204 0.4778917 0.06455248 -0.8760437 0.3330774 -0.04778903 -0.9416877 0.2557056 -0.004925787 -0.9667422 0.2310776 0.03743493 -0.9722149 0.163834 -0.04329991 -0.9855373 0.0545693 -0.05249422 -0.9971292 -0.04873543 0.05604922 -0.9972379 -0.06569963 0.09436935 -0.993367 -0.1548341 -0.04842466 -0.9867531 -0.2842528 -0.06495064 -0.9565469 -0.3658041 0.02635538 -0.9303187 -0.379281 0.06496858 -0.9229979 -0.477814 -0.04382693 -0.8773671 -0.5619199 -0.03184813 -0.8265784 -0.6147616 0.07383239 -0.7852497 -0.6660411 -0.03007042 -0.7453087 -0.7021872 -0.07186347 -0.7083565 -0.7838981 -0.01971983 -0.6205765 -0.8172935 0.09842127 -0.5677542 -0.8652969 -0.05505943 -0.4982268 -0.9265899 -0.062586 -0.3708292 -0.9618469 0.1086797 -0.2510766 -0.9605772 0.06271302 -0.2708477 -0.9823096 -0.03895694 -0.1831673 -0.9958265 -0.05061441 -0.07594686 -0.997258 0.06674522 0.031964 -0.9995561 0.0253517 0.01565599 -0.9856389 -0.03782826 0.1645752 -0.9705563 0.03989839 0.237547 -0.9645174 -0.002203881 0.2640106 -0.928717 -0.04713064 0.3677818 -0.8853095 0.02715647 0.4642087 -0.8913766 0.004247546 0.4532436 -0.8335844 -0.04988694 0.5501348 -0.7902861 0.02337074 0.6122923 -0.7834293 0.007064402 0.6214408 -0.7176396 -0.04237663 0.6951243 -0.6425765 0.02123266 0.7659273 -0.6247545 0.05968159 0.778537 -0.5612293 -0.04529362 0.8264201 -0.4599648 -0.05165863 0.8864333 -0.4002614 0.02299034 0.9161127 -0.3967643 0.03136742 0.9173844 -0.2845925 -0.04342603 0.9576646 -0.1826093 0.04557651 0.9821287 -0.1567044 -0.002991855 0.987641 -0.03588008 -0.04790121 0.9982075 0.1083163 -0.002254366 0.994114 0.07400578 0.08006578 0.9940387 0.2000047 -0.08207613 0.9763512 0.3410931 -0.01709365 0.9398741 0.3839582 0.09144443 0.9188112 0.4743263 -0.04724603 0.8790804 0.5725101 -0.04039746 0.818902 0.6116108 0.009972393 0.7910959 0.6269594 0.05297905 0.7772485 0.7098048 -0.04539322 0.7029343 0.7916352 0.02794396 0.6103547 0.7793705 -0.01074934 0.6264713 0.8596371 -0.02312648 0.5103815 0.8772528 0.02758246 0.4792356 0.9119138 -0.0449112 0.407917 0.9512344 -0.01835691 0.3079226 0.962501 0.05544441 0.2655516 0.9826259 -0.04494267 0.1800736 0.9977813 -0.01334232 0.06522631 0.9985682 0.04992461 0.01921182 0.894901 -0.4386438 0.08212053 0.9281128 -0.3292891 0.1737114 0.8670756 -0.4802833 0.1323177 0.7558243 -0.6392371 0.1417942 0.5937019 -0.7990799 0.09481233 0.8801819 -0.3943591 0.2641229 0.3251928 -0.9423642 0.07873708 0.1582083 -0.9870212 0.02755564 0.7443745 -0.6361724 0.2029567 0.8972643 -0.3330931 0.2897686 0.6033234 -0.7705444 0.205578 0.4481249 -0.8811134 0.1510746 0.8301648 -0.4167996 0.3702765 0.8024268 -0.4667255 0.3718582 0.7192646 -0.6117394 0.3292922 0.8115872 -0.3479481 0.4693171 0.5048432 -0.8118091 0.2934269 0.3112722 -0.933502 0.1779987 0.3059951 -0.9356511 0.175852 0.7001106 -0.5262294 0.4826261 0.623417 -0.6489434 0.4361464 0.7352488 -0.3336465 0.5899909 0.6807417 -0.4086549 0.6079407 0.5707213 -0.6311123 0.5253328 0.5253683 -0.7269582 0.4421763 0.3434414 -0.8905109 0.2983928 0.6879833 -0.2493993 0.681527 0.495178 -0.6745468 0.5475267 0.3247637 -0.8616142 0.3900634 0.5971286 -0.3934197 0.699041 0.2515642 -0.9330348 0.2572187 0.5550702 -0.493289 0.6697486 0.3018012 -0.8602439 0.4109701 0.4743174 -0.4822586 0.7365118 0.4741359 -0.4825434 0.7364421 0.4378792 -0.5620607 0.7016762 0.462405 -0.226378 0.8572834 0.2143314 -0.9133179 0.3462842 0.3278085 -0.6720112 0.6640351 0.2681936 -0.7722536 0.5759312 0.363591 -0.4251701 0.8288741 0.3272972 -0.3149658 0.8908834 0.05165761 -0.9917822 0.1170454 0.1944911 -0.8361216 0.5129075 0.1417656 -0.897507 0.4175929 0.2351357 -0.4984232 0.8344373 0.1981782 -0.4892428 0.8493332 0.1321842 -0.6131481 0.7788304 0.09968346 -0.8540942 0.5104765 0.07165735 -0.3439788 0.9362392 0.09984171 -0.5801408 0.808374 8.40172e-4 -0.3832971 0.9236248 0.02082449 -0.9396792 0.3414227 -0.01742106 -0.6305224 0.7759755 0.001340031 -0.7161451 0.6979503 -0.03858256 -0.1903608 0.9809558 -0.006690561 -0.8653672 0.5010936 -0.09807276 -0.564839 0.8193527 -0.1410678 -0.3216447 0.936293 -0.06403458 -0.8783674 0.4736773 -0.139373 -0.3011635 0.9433323 -0.1328508 -0.7667628 0.6280332 -0.1323789 -0.768444 0.6260749 -0.2164649 -0.4014477 0.8899341 -0.1840232 -0.6653487 0.7234961 -0.2691769 -0.2855423 0.9197878 -0.3148819 -0.4134396 0.8543519 -0.2982668 -0.5795127 0.7584209 -0.1241598 -0.9350455 0.3320758 -0.03558051 -0.9920713 0.1205351 -0.3069809 -0.6349115 0.7089782 -0.2907468 -0.7203631 0.6297168 -0.4559005 -0.3615316 0.8132956 -0.2053242 -0.8725548 0.4432722 -0.4709878 -0.4154529 0.7781834 -0.4029712 -0.6456781 0.6486248 -0.5413831 -0.2963591 0.7868137 -0.2229884 -0.9029603 0.3673404 -0.3980112 -0.7096766 0.5813315 -0.5636261 -0.3938018 0.7261169 -0.4216075 -0.6943799 0.5831671 -0.6059069 -0.340026 0.7192074 -0.6237905 -0.3920568 0.6761485 -0.1280158 -0.979007 0.1586112 -0.4476628 -0.7555395 0.4782867 -0.4191846 -0.7794386 0.4655746 -0.6677799 -0.3387893 0.6627909 -0.2039781 -0.9528791 0.2245312 -0.6744027 -0.4490784 0.5860969 -0.637462 -0.5580856 0.5312088 -0.4895552 -0.7484079 0.447461 -0.3732844 -0.8764678 0.3040773 -0.3708248 -0.8861063 0.2780373 -0.6708576 -0.6032643 0.431303 -0.6622316 -0.622775 0.4166542 -0.6635767 -0.623113 0.4140003 -0.8070264 -0.4336889 0.4007773 -0.2349874 -0.9608878 0.1465463 -0.5267657 -0.814139 0.2443271 -0.8819416 -0.3410878 0.3253279 -0.3888659 -0.9036886 0.1792489 -0.8053479 -0.4922801 0.3302651 -0.6928269 -0.6689357 0.269288 -0.9155734 -0.3026525 0.264815 -0.2400575 -0.9681361 0.07130849 -0.8627648 -0.4652757 0.1978775 -0.168425 -0.9836018 0.06450355 -0.6883762 -0.7067204 0.1633546 -0.6631519 -0.7331802 0.1505866 -0.9384793 -0.3105415 0.1510653 -0.6271057 -0.7741092 0.08656585 -0.4163411 -0.9080772 0.04534316 -0.9011642 -0.4276595 0.07078385 -0.7382448 -0.6723635 0.0540561 -0.9527081 -0.3027278 0.02651542 -0.9223126 -0.3850603 -0.03268569 -0.3134059 -0.9496193 3.75102e-4 -0.7424668 -0.6690849 -0.03268772 -0.7039518 -0.710044 -0.01701402 -0.9565641 -0.281814 -0.07460647 -0.4036229 -0.9147327 -0.01878148 -0.7295716 -0.6760267 -0.1035055 -0.9299217 -0.3400424 -0.1400603 -0.8181362 -0.553206 -0.1568958 -0.4397635 -0.894636 -0.07896053 -0.805609 -0.5636227 -0.1825476 -0.4050586 -0.9099208 -0.08928579 -0.8909529 -0.3707844 -0.2621488 -0.6382789 -0.7463224 -0.1886876 -0.8466237 -0.4129253 -0.3357399 -0.8484752 -0.4092348 -0.3355843 -0.1546307 -0.9865453 -0.05308341 -0.6638245 -0.6982641 -0.2678888 -0.6638523 -0.6982358 -0.2678936 -0.8029667 -0.3768606 -0.4617584 -0.80759 -0.3662672 -0.4622194 -0.3523333 -0.9193382 -0.1751527 -0.6824494 -0.6174315 -0.3912049 -0.5756083 -0.7285993 -0.3712389 -0.3970012 -0.8777113 -0.2683527 -0.707877 -0.4427163 -0.5503749 -0.3599126 -0.8966757 -0.2577512 -0.7078876 -0.4430018 -0.5501315 -0.367236 -0.8714457 -0.3251463 -0.6072489 -0.5435292 -0.579504 -0.5818961 -0.5818789 -0.5681673 -0.5122135 -0.6060476 -0.6085588 -0.5390696 -0.4688673 -0.699691 -0.2200274 -0.9425259 -0.2514613 -0.333422 -0.8286483 -0.4496353 -0.5227227 -0.3943529 -0.7558088 -0.0557034 -0.9954345 -0.07750707 -0.4373347 -0.5044501 -0.7444921 -0.3567513 -0.6966572 -0.6224126 -0.3000335 -0.8182273 -0.4903918 -0.4301763 -0.3711094 -0.8229375 -0.2023088 -0.903838 -0.3770251 -0.3706387 -0.3731338 -0.8505282 -0.2634158 -0.6212875 -0.7379797 -0.2481158 -0.7033677 -0.6661174 -0.1767674 -0.8598285 -0.4790076 -0.2249395 -0.4379782 -0.8703893 -0.1069092 -0.9225782 -0.3707021 -0.2237212 -0.5258402 -0.8206346 -0.1474216 -0.2979671 -0.9431238 -0.1081777 -0.7369518 -0.6672329 -0.08869093 -0.865188 -0.493542 -0.08704692 -0.4415247 -0.8930168 -0.08038568 -0.6619071 -0.7452632 -0.03999316 -0.3239911 -0.9452145 0.004079401 -0.8049748 -0.5932951 0.0382989 -0.37145 -0.9276628 -0.01050132 -0.9316824 -0.3631223 0.05916488 -0.450479 -0.8908245 0.03081816 -0.7600197 -0.6491692 0.009996533 -0.9888216 -0.1487683 0.1145126 -0.4181427 -0.9011346 0.1710043 -0.635375 -0.7530314 0.1083074 -0.8120798 -0.5734073 0.09114342 -0.9009754 -0.424189 0.2094042 -0.5813919 -0.7862147 0.3593015 -0.3914279 -0.8471639 0.2897218 -0.6029117 -0.7433431 0.2758249 -0.7093644 -0.6486315 0.4054926 -0.3054838 -0.8615425 0.1546653 -0.9104626 -0.3835838 0.4949743 -0.362377 -0.7897363 0.4692203 -0.4174508 -0.778182 0.1213631 -0.962016 -0.2445326 0.375503 -0.6746139 -0.6355262 0.3430328 -0.797928 -0.4956203 0.5662674 -0.3500012 -0.7462174 0.2746063 -0.8743805 -0.4000628 0.5620877 -0.4269103 -0.7083821 0.4489029 -0.6924484 -0.5648021 0.6689226 -0.3280893 -0.6670083 0.4832842 -0.7350707 -0.4755076 0.6299575 -0.551115 -0.5471982 0.1745527 -0.9667215 -0.1870319 0.2693874 -0.9313176 -0.2451086 0.6344204 -0.5491805 -0.5439776 0.6204119 -0.6434913 -0.4483392 0.3070551 -0.926092 -0.2192505 0.2851998 -0.9356603 -0.2078486 0.6790638 -0.5956003 -0.429107 0.6745832 -0.6356015 -0.3754308 0.1030157 -0.9927716 -0.06158268 0.4797834 -0.8394382 -0.255248 0.7362868 -0.5653866 -0.3717792 0.899519 -0.2893927 -0.3272882 0.4078074 -0.8959406 -0.1760224 0.7686992 -0.5527533 -0.3218157 0.6492611 -0.730863 -0.210474 0.4615693 -0.8719421 -0.1633126 0.8925279 -0.3870126 -0.2315496 0.6891404 -0.6958543 -0.202169 0.9195303 -0.3294932 -0.2142392 0.9184918 -0.3603314 -0.1628929 0.2830809 -0.9573117 -0.05847734 0.9639257 -0.2338771 -0.1270778 0.741279 -0.6657875 -0.0850439 0.6225845 -0.776308 -0.09866344 0.9389948 -0.3413455 -0.04209554 0.3900725 -0.9189527 -0.05804914 0.806021 -0.5917903 -0.01070666 0.7851029 -0.6191949 -0.0145387 0.5948697 -0.8037835 0.007872343 0.4424666 -0.8967707 -0.005051255 0.005423426 -0.9999715 0.005252778 0.005700826 -0.9999693 0.00539112 0.003654599 -0.9999758 0.005932092 0.007941842 -0.9999596 0.004213631 0.009562015 -0.999944 0.004533708 0.004126012 -0.9999051 0.01314336 0.004859566 -0.9998909 0.01395404 0.01030957 -0.9999429 0.002836465 0.009262859 -0.9999527 0.002973914 0.003371596 -0.9998907 0.01440185 3.64773e-4 -0.9999766 0.006840109 0.004071474 -0.9999917 1.17246e-4 0.007081091 -0.9999721 -0.002412021 0.004366219 -0.9999901 -8.28392e-4 -0.001496851 -0.9999769 0.006638586 -0.002613902 -0.9999604 0.00850737 0.006393253 -0.9999749 -0.003066778 0.005598902 -0.9999819 -0.002218782 -0.003443598 -0.999978 0.005677044 -0.006807148 -0.9999452 0.007970631 0.002513766 -0.9999942 -0.002354681 -0.00605297 -0.9999694 0.004972398 0.004418492 -0.9999531 -0.008616626 0.002110362 -0.9999927 -0.003194451 0.006938278 -0.9999385 -0.008653461 -0.009256303 -0.9999441 0.005127012 -0.008835017 -0.9999529 0.00402522 -0.01021814 -0.999941 0.003712952 7.31379e-4 -0.9999977 -0.002069354 -0.007380306 -0.9999719 0.001358032 2.71175e-4 -0.9999965 -0.002653419 -0.007768452 -0.9999697 6.92943e-4 -6.73195e-4 -0.9999642 -0.008437573 -0.005900621 -0.9999827 -1.66123e-4 -0.001038014 -0.999969 -0.00781393 -0.006020247 -0.9999804 -0.001746416 -0.007287323 -0.9999703 -0.0025478 -0.004392504 -0.9999331 -0.01070767 -0.004616975 -0.9999392 -0.01002311 -0.007668614 -0.9999018 -0.01173162 -0.004783213 -0.9999831 -0.003324508 -0.00591892 -0.9999547 -0.007459521 -0.006397545 -0.9999616 -0.005994796 0.6775035 0.7353304 -0.01668453 0.6189612 0.7854074 -0.004718422 0.9344183 0.3512632 -0.05896329 0.8740003 0.4787011 -0.08347904 0.6943548 0.7188505 -0.03354686 0.315522 0.9488453 -0.01177161 0.9108111 0.373072 -0.1767498 0.8764747 0.4566969 -0.1523816 0.6426543 0.7537543 -0.1372951 0.570904 0.8149441 -0.09967458 0.4300926 0.8998247 -0.07304757 0.6404662 0.7461375 -0.1818844 0.8871911 0.3608419 -0.2875506 0.8777008 0.381725 -0.2897026 0.1901762 0.9797849 -0.06208759 0.8529881 0.3340685 -0.4010108 0.5087008 0.8381569 -0.1967654 0.8227541 0.4422113 -0.3571062 0.398505 0.9028079 -0.1616534 0.683306 0.6598155 -0.3126282 0.7734626 0.3862758 -0.5025403 0.774309 0.3818622 -0.5046057 0.6356239 0.6635238 -0.3946117 0.3449496 0.9082255 -0.236931 0.4314121 0.847743 -0.3085698 0.7165341 0.4152024 -0.5605229 0.7295885 0.2058134 -0.6521822 0.1179435 0.9885575 -0.09404063 0.570299 0.6519813 -0.4996794 0.4988523 0.7454162 -0.4421551 0.6693404 0.342128 -0.6594937 0.4356557 0.786678 -0.4374267 0.6167822 0.3464412 -0.7067944 0.5703456 0.4465004 -0.6894515 0.5151153 0.5802827 -0.6308155 0.2884393 0.8976239 -0.3332782 0.2767055 0.906104 -0.320015 0.3955233 0.7271479 -0.5610858 0.5260739 0.3162303 -0.7894585 0.4700616 0.4153525 -0.7787967 0.3770886 0.7144677 -0.5893559 0.443878 0.3525736 -0.8238109 0.2892305 0.794247 -0.5343382 0.3950691 0.4104645 -0.8218513 0.08506703 0.985565 -0.1463739 0.311035 0.6575134 -0.6862457 0.3734732 0.2893394 -0.881363 0.1443122 0.9433352 -0.2988192 0.2816956 0.3597206 -0.8895215 0.2571967 0.4355804 -0.8626236 0.1246942 0.9279331 -0.3512714 0.2354176 0.6836906 -0.6907575 0.1689226 0.805903 -0.5674378 0.1991384 0.430628 -0.8802861 0.13427 0.5771188 -0.8055467 0.117913 0.7903025 -0.6012642 0.03175854 0.9864609 -0.160892 0.06434881 0.4942497 -0.8669352 0.0461024 0.9046202 -0.423718 0.0310077 0.5400027 -0.841092 -0.005272209 0.5148965 -0.8572363 0.03077369 0.8905584 -0.4538269 -0.01911211 0.9137238 -0.4058861 -0.07439929 0.6383846 -0.7661135 -0.04581493 0.8746213 -0.4826372 -0.1259752 0.5676676 -0.8135625 -0.2573199 0.3510578 -0.9003028 -0.08885991 0.9001132 -0.4264976 -0.1751281 0.6044433 -0.7771607 -0.01059103 0.9986341 -0.05116397 -0.1742706 0.7027243 -0.6897886 -0.08347451 0.9428498 -0.3225934 -0.3276662 0.3184342 -0.8895137 -0.2185315 0.7533208 -0.6202837 -0.1911796 0.8503485 -0.4902631 -0.3490779 0.4047093 -0.8451953 -0.3340582 0.5158879 -0.7888376 -0.4296043 0.2136356 -0.8773825 -0.211052 0.8675447 -0.4503592 -0.3575769 0.6390926 -0.6809548 -0.2942858 0.7944337 -0.5312919 -0.4613012 0.4457856 -0.7671222 -0.5021241 0.4181892 -0.7569605 -0.5032846 0.5010067 -0.7040575 -0.3209925 0.8056371 -0.4979085 -0.2771299 0.8883463 -0.3661149 -0.5575554 0.4782114 -0.6785616 -0.1723698 0.9619868 -0.2118254 -0.5589588 0.5595836 -0.6119079 -0.4794557 0.7160378 -0.507358 -0.654492 0.4201225 -0.6285996 -0.4562759 0.7956851 -0.3983687 -0.721327 0.3970277 -0.5675001 -0.3245311 0.9069005 -0.2687212 -0.6905947 0.462096 -0.5563689 -0.6201123 0.6195898 -0.4812164 -0.811422 0.2475597 -0.5294417 -0.273625 0.9409816 -0.1992058 -0.7979278 0.3905872 -0.4590783 -0.7451599 0.5237888 -0.4127738 -0.6386611 0.6606464 -0.3945357 -0.05265974 0.998153 -0.03029245 -0.4210479 0.873338 -0.244948 -0.7394993 0.5925394 -0.3194339 -0.7223113 0.6229437 -0.300346 -0.4182267 0.8845095 -0.2067111 -0.276046 0.954597 -0.1119961 -0.7288241 0.6320161 -0.2633842 -0.8925775 0.3832812 -0.2374887 -0.5920647 0.788697 -0.1655799 -0.3951605 0.9123111 -0.1074092 -0.8713076 0.4591711 -0.1731619 -0.7647988 0.6298675 -0.1354612 -0.9553741 0.2686653 -0.1227982 -0.9074107 0.4148359 -0.067209 -0.2902412 0.956059 -0.04136943 -0.7169713 0.6937108 -0.06868439 -0.6246592 0.7800452 -0.03647547 -0.3938493 0.9187136 -0.02912133 -0.9449511 0.3269534 0.01300376 -0.9295342 0.3677982 0.02628356 -0.7204239 0.6928999 0.02965044 -0.9281017 0.3528609 0.1188126 -0.909956 0.3939394 0.1295832 -0.6774744 0.7298891 0.09105193 -0.7114672 0.6974248 0.08609956 -0.2551459 0.9663742 0.03196173 -0.9350486 0.2775009 0.2206293 -0.3477741 0.935798 0.0577529 -0.6564962 0.7281863 0.196869 -0.8492037 0.4537754 0.2700762 -0.4200826 0.8994888 0.1202115 -0.7093923 0.666226 0.2300124 -0.8931483 0.2963877 0.3382907 -0.8211512 0.4069749 0.4001029 -0.2533641 0.9610886 0.1100699 -0.7180377 0.58438 0.3780503 -0.6491313 0.6868638 0.3268741 -0.1107274 0.9921823 0.05756592 -0.5131312 0.813333 0.2742006 -0.7712934 0.3583511 0.5260142 -0.7264073 0.5054864 0.465635 -0.4155945 0.8574 0.3035563 -0.7306373 0.3413223 0.5913276 -0.7337441 0.3165671 0.6011696 -0.3328754 0.9080317 0.2543078 -0.5397239 0.731198 0.4171901 -0.5751975 0.6590014 0.4846287 -0.2579398 0.9340407 0.2470527 -0.6450676 0.3814447 0.6621086 -0.5259198 0.6276651 0.5739731 -0.5046864 0.6746593 0.538634 -0.329499 0.8695787 0.3677816 -0.4950546 0.5356838 0.6840789 -0.2542063 0.9007158 0.3522647 -0.4285618 0.6048864 0.6711537 -0.3171485 0.7848271 0.5324129 -0.4454833 0.3800445 0.8106237 -0.307748 0.7896489 0.5307976 -0.4119022 0.3530687 0.8400472 -0.03181046 0.997687 0.06007397 -0.3268395 0.4973033 0.8036575 -0.2928187 0.6231303 0.7252351 -0.3085697 0.3585332 0.8810441 -0.1642404 0.912363 0.374992 -0.2062628 0.7696934 0.6041753 -0.07468396 0.9788538 0.1904409 -0.1797057 0.778728 0.6010729 -0.2225456 0.4084258 0.8852468 -0.1650053 0.5483635 0.8197993 -0.157553 0.6000782 0.7842725 -0.1243963 0.3370826 0.9332208 -0.07180362 0.9393503 0.3353586 -0.07631832 0.9313543 0.3560265 -0.07376432 0.7621669 0.6431645 -0.06157064 0.3345451 0.9403663 -0.03537607 0.7617037 0.6469591 -0.01196932 0.9838789 0.1784358 -0.001941502 0.6280077 0.7782048 0.003632783 0.9250751 0.379767 0.03134924 0.6192652 0.7845558 0.08988493 0.4225831 0.9018561 0.07659846 0.8417332 0.5344325 0.1338343 0.3914112 0.9104316 0.07634669 0.8416695 0.5345689 0.1609807 0.4456298 0.8806244 0.2125669 0.4219099 0.8813667 0.08516246 0.8597187 0.503618 0.07134056 0.9471207 0.3128465 0.2467834 0.5201826 0.8176235 0.2026063 0.7241207 0.6592419 0.2942019 0.4519191 0.8421488 0.2101782 0.8496304 0.4836873 0.1938419 0.8434757 0.5009734 0.404272 0.4486985 0.7970156 0.3619248 0.5363852 0.7624313 0.2958539 0.7245932 0.6224431 0.1435115 0.9470294 0.2872976 0.4576478 0.3965062 0.7958275 0.3007767 0.8229082 0.4820326 0.2030912 0.9209052 0.3326976 0.4568856 0.6414062 0.6163228 0.5775811 0.3917223 0.716208 0.4181615 0.664739 0.6190826 0.6753759 0.2463906 0.6950964 0.6148076 0.3912777 0.6847726 0.139541 0.9759999 0.16719 0.5107114 0.6671758 0.5422641 0.4369481 0.7547343 0.4893391 0.3073756 0.8973184 0.316765 0.6876242 0.4912216 0.5346722 0.6640046 0.4805148 0.5728905 0.4378554 0.8477649 0.2992948 0.7507046 0.3397353 0.5665885 0.446273 0.8327782 0.3275991 0.6895397 0.5922545 0.4168571 0.15593 0.9831337 0.09557157 0.535041 0.7748622 0.3366299 0.8125973 0.4153087 0.4089062 0.8324148 0.4047544 0.3784967 0.450387 0.8675661 0.2109049 0.8198798 0.4511674 0.3524844 0.3709576 0.9132028 0.1686745 0.7029348 0.6600829 0.2649024 0.9272453 0.2656137 0.2639426 0.8731006 0.431541 0.226865 0.7145591 0.6589111 0.2350353 0.2784326 0.9569129 0.08241933 0.5437284 0.8312137 0.1159455 0.8427413 0.5213508 0.1340915 0.5829863 0.8064783 0.09858858 0.8976776 0.4271109 0.108403 0.9425313 0.3337073 0.01655828 0.5225026 0.8506606 0.05803143 0.8974927 0.438902 0.0432676 0.07186287 0.9973714 0.009281218 0.183484 0.9829924 0.007725536 -0.006496131 0.9999116 0.01160562 -0.002945899 0.9999912 0.002980887 -0.007454216 0.9999255 0.009672462 2.55639e-4 1 -3.90994e-4 -0.004378676 0.9999878 0.002305924 -0.006558477 0.9999744 0.002862393 6.64853e-5 1 -2.3571e-4 -0.006006002 0.9999813 0.001222848 -0.005070984 0.9999862 0.001426398 0.002565801 0.9998988 0.01399898 6.32545e-6 1 -3.26781e-4 -0.004566311 0.9999894 5.96519e-4 -3.78775e-4 1 -4.62914e-5 0.004119873 0.9998913 0.01416057 0.004149377 0.9998928 0.01404005 4.44783e-4 0.9999173 0.01285529 -3.56548e-4 1 -1.40677e-4 0.002175211 0.9999918 0.003433406 -0.003227174 0.9999909 -0.002805888 -0.003941476 0.9999878 -0.002976 0.01253318 0.9998811 0.008992791 0.01365834 0.9998054 0.01423513 8.32724e-4 0.9999994 6.76132e-4 -0.003307163 0.9999855 -0.004285335 -0.01099002 0.9996271 -0.02500098 -0.01104152 0.9996268 -0.02499228 5.62725e-4 0.9999999 2.50769e-4 -0.01015317 0.9999443 -0.002894818 -0.004765391 0.999854 -0.01641219 0.002730846 0.9999963 -2.68413e-4 -7.46935e-4 0.9999722 -0.007423222 0.005506157 0.9999847 5.36523e-4 4.6605e-4 0.9999698 -0.007763922 8.32805e-4 0.9999926 -0.003791511 0.00405693 0.9999916 -6.5305e-4 0.007589101 0.9999607 -0.004604339 0.01105213 0.9999291 -0.004447519 0.001670658 0.9999915 -0.003801763 0.001042187 0.9999981 -0.001657724 0.01026034 0.9999139 -0.008178412 0.004050314 0.9999919 0 0.996998 0.01878321 -0.07511436 0.9945275 -0.02723455 -0.1008635 0.9846 0.03020721 -0.1721928 0.9598156 -0.01566427 -0.2801938 0.9595576 -0.01336061 -0.2811951 0.9304252 0.06034672 -0.3614794 0.8681166 -0.06116294 -0.4925777 0.8887537 0.008694529 -0.4583027 0.840584 0.02388411 -0.5411545 0.7821431 0.04939043 -0.6211383 0.7259313 -0.0456143 -0.686253 0.7101638 1.52834e-4 -0.7040365 0.6331844 0.05818045 -0.7718113 0.5754967 -0.02369111 -0.817461 0.5184834 0.04859739 -0.8537057 0.4323815 -0.003005564 -0.9016858 0.4182606 0.02145415 -0.9080737 0.3275367 0.04197901 -0.9439055 0.2453694 -0.05342853 -0.9679563 0.2038387 0.02644169 -0.9786474 0.09288287 0.05258876 -0.9942873 0.02359002 -0.01759028 -0.999567 0.01199722 -0.001035392 -0.9999275 -0.1506413 -0.02720445 -0.9882141 -0.1107704 0.031107 -0.9933591 -0.2419618 0.04950481 -0.9690221 -0.3352151 -0.0293594 -0.9416841 -0.3500564 -6.4207e-4 -0.9367285 -0.4824485 0.03714102 -0.8751367 -0.5218653 -0.04188799 -0.8519989 -0.6051394 0.07084494 -0.7929612 -0.7100617 -0.04000544 -0.7030022 -0.7074579 -0.04804712 -0.7051205 -0.7814008 0.05666327 -0.6214517 -0.8577513 -0.0289309 -0.5132504 -0.8416147 0.0154407 -0.5398577 -0.8686044 -0.001662611 -0.4955035 -0.9136338 0.04601567 -0.4039257 -0.9480031 -0.02360898 -0.3173844 -0.9474733 -0.02656418 -0.3187302 -0.9814586 0.05847346 -0.1825377 -0.9947783 -0.04774957 -0.09020197 -0.9974437 -0.01025402 -0.07071733 -0.9984045 0.04852825 0.02887016 -0.9938744 -0.01550036 0.1094234 -0.9919665 0.008489549 0.1262165 -0.9732547 0.02716481 0.2281175 -0.9570558 -0.03374516 0.2879332 -0.9475569 0.02457517 0.3186411 -0.8901705 0.06054323 0.4515874 -0.8516592 -0.05318099 0.5213907 -0.8319392 0.01560848 0.5546472 -0.8174636 0.03293329 0.575038 -0.7082566 -0.05584198 0.7037431 -0.7456256 0.01779514 0.6661275 -0.6797074 0.01857012 0.7332484 -0.6052096 0.07474333 0.7925496 -0.4879691 -0.09307289 0.8678846 -0.5245539 -0.002272069 0.8513743 -0.4296954 0.0230174 0.9026806 -0.3389148 0.05213046 0.9393717 -0.2493841 -0.04588735 0.9673169 -0.2520821 -0.03917706 0.9669126 -0.1478212 0.03775274 0.9882934 -0.05463635 -0.02740132 0.9981303 -0.04827666 -0.0151109 0.9987197 0.05555629 0.0482769 0.9972878 0.1498962 -0.05118513 0.9873759 0.1881405 0.0230804 0.9818709 0.3019032 0.05775219 0.9515878 0.3833548 -0.0456525 0.9224722 0.3846566 -0.04306864 0.9220545 0.4876813 0.06467151 0.8706231 0.5991878 -0.01321375 0.8004995 0.6038711 -0.03019696 0.7965098 0.7557062 -0.06606066 0.6515706 0.7110543 0.02900415 0.7025387 0.790665 0.03899818 0.6110059 0.8065423 0.05774724 0.5883491 0.8709755 0.04322278 0.4894219 0.9037578 -0.09981036 0.4162449 0.9293335 0.018687 0.3687686 0.9601495 0.07199764 0.2700544 0.986037 -0.01278883 0.1660346 0.9880443 -0.06482821 0.1398781 0.9968014 0.03978812 0.06930983 0.998287 -0.04638415 -0.03566122 0.9968146 -0.05081117 -0.06147378 0.984841 0.01859891 -0.1724599 0.9834944 0.03056985 -0.1783378 0.96163 -0.04330748 -0.2709101 0.9293957 0.006724357 -0.3690235 0.9205605 0.05178445 -0.3871521 0.8660585 -0.0755921 -0.4941951 0.811137 -0.01080435 -0.5847566 0.7435038 -0.03663361 -0.6677275 0.7860922 0.0615065 -0.6150414 0.6446482 -0.002324819 -0.7644759 0.6372684 0.01806163 -0.7704304 0.5378639 -0.04102838 -0.8420327 0.4479943 -0.02675151 -0.8936362 0.4796262 0.01955676 -0.877255 0.3295535 -0.003456473 -0.9441306 0.3197223 0.01183122 -0.9474374 0.255346 -0.05018603 -0.9655464 0.149379 -0.02485591 -0.9884676 0.1004967 0.04967057 -0.9936968 0.04390907 -0.0326004 -0.9985035 -0.09650152 -0.005861997 -0.9953156 -0.1150612 0.02628237 -0.9930107 -0.2007057 -0.06233769 -0.9776663 -0.3358126 0.02007323 -0.941715 -0.332781 0.01299899 -0.9429146 -0.4313846 -0.03229492 -0.9015899 -0.4985457 0.03388345 -0.866201 -0.5185532 -0.006990075 -0.8550168 -0.6052939 -0.05084925 -0.7943763 -0.6946228 0.06035041 -0.7168383 -0.6729109 0.01375448 -0.7395957 -0.7175699 -0.04272294 -0.695175 -0.7958695 0.03389173 -0.604519 -0.8080452 -0.006088197 -0.5890892 -0.8691384 -0.05784356 -0.4911746 -0.9305585 -0.03652483 -0.3643172 -0.9064043 0.04779702 -0.4196985 -0.9623149 -0.00759685 -0.2718316 -0.9682994 0.03034061 -0.2479432 -0.9832966 -0.04826873 -0.1754936 -0.9976291 -0.02126634 -0.06545335 -0.9987812 0.04854005 -0.00895375 -0.9997168 0.02355998 0.003356873 -0.9900003 -0.07150214 0.1216008 -0.9775864 -0.04200679 0.2063015 -0.9630609 0.06492459 0.26134 -0.9480667 -0.02054584 0.3174076 -0.9119715 -0.03316849 0.4089106 -0.8768463 0.06334048 0.4765802 -0.8627155 -0.004890263 0.5056662 -0.7857515 -0.07214289 0.6143208 -0.7099126 0.06956529 0.7008458 -0.7219352 0.03284317 0.6911809 -0.6355547 -0.05522656 0.7700783 -0.5519118 0.04057335 0.8329149 -0.5276508 -0.01406854 0.8493449 -0.4272728 -0.04726535 0.9028865 -0.3596382 0.04844993 0.9318332 -0.3106741 -0.02551573 0.950174 -0.2169706 -0.02503705 0.9758571 -0.1682372 0.05512177 0.9842042 -0.09372061 -0.05944412 0.9938223 0.04141068 -0.0327171 0.9986065 0.0880109 0.03645581 0.9954523 0.1392357 -0.0349977 0.9896407 0.2158455 -0.03658729 0.9757418 0.2897909 0.049241 0.9558225 0.3436847 -0.03978556 0.938242 0.4862979 -0.02919739 0.8733052 0.4649355 0.02063494 0.8851042 0.5708085 -0.02503031 0.8207017 0.6063994 0.039846 0.7941614 0.6748222 -0.05305916 0.7360705 0.7458413 0.006641387 0.6660906 0.762595 0.0619834 0.6438999 0.8121268 -0.05084323 0.5812617 0.8669548 -0.05786484 0.4950165 0.9126049 0.06277829 0.4039941 0.9065365 0.0186088 0.4217171 0.9676316 -0.01411157 0.2519724 0.9427342 -0.03985226 0.3311559 0.9821304 -0.02973622 0.185838 0.9737061 0.01692861 0.2271786 0.9973304 -0.01766926 0.07085233 0.9987748 0.03955107 0.02974253 0.9295454 -0.3601619 0.07892411 0.8804547 -0.4720745 0.04410642 0.08815449 -0.9961062 -0.001105666 0.6369572 -0.7683952 0.06208449 0.5158106 -0.8557165 0.04109615 0.9213787 -0.3628805 0.139209 0.4558087 -0.889048 0.04280239 0.793842 -0.5857412 0.1634697 0.3699809 -0.9240295 0.09635239 0.8271338 -0.5038751 0.2489168 0.7728472 -0.605847 0.1888295 0.425409 -0.8966296 0.1228119 0.825133 -0.4980529 0.266644 0.7854108 -0.5478249 0.2881283 0.4396837 -0.8797572 0.1808472 0.471231 -0.8596922 0.1971566 0.7932404 -0.4864472 0.3662499 0.7331909 -0.5612773 0.3839257 0.676321 -0.6440465 0.3574829 0.785951 -0.4093748 0.4633499 0.2464162 -0.9598981 0.133697 0.7517753 -0.3823105 0.5372827 0.4551997 -0.8315175 0.3183896 0.3764073 -0.8885998 0.2621224 0.6979012 -0.472072 0.5385926 0.5423612 -0.7245727 0.4252514 0.695523 -0.3877898 0.6048693 0.6131509 -0.5037909 0.6084741 0.4734442 -0.7551023 0.4535098 0.3412498 -0.8667524 0.3637154 0.6152294 -0.371518 0.6953181 0.199297 -0.9620739 0.1862649 0.3402291 -0.8502764 0.4015897 0.5427098 -0.4523307 0.7077168 0.4997488 -0.5384764 0.6784501 0.4126018 -0.6143258 0.6725798 0.4331052 -0.5792511 0.6905708 0.2107807 -0.9135579 0.3478268 0.4671809 -0.1825962 0.8651015 0.218133 -0.9088714 0.3554867 0.06958556 -0.9893573 0.1277892 0.3260082 -0.6452472 0.6909231 0.2441318 -0.8170266 0.5223671 0.3596682 -0.388413 0.8483951 0.3299635 -0.5465742 0.7696629 0.3372238 -0.2195362 0.9154692 0.2052196 -0.7056927 0.6781467 0.1591824 -0.8725386 0.4618846 0.2387566 -0.3883771 0.8900329 0.1110966 -0.9320574 0.3448573 0.1860807 -0.5877169 0.7873772 0.2097687 -0.5757371 0.7902682 0.1376128 -0.4168739 0.8984871 0.04126065 -0.9726282 0.2286743 0.08613699 -0.7947554 0.6007865 0.04331237 -0.9450544 0.3240312 0.04775166 -0.6253367 0.7788928 0.004346251 -0.4698566 0.882732 0.01325231 -0.6110106 0.7915115 0.004790723 -0.6396754 0.7686302 -0.01457613 -0.8667522 0.4985259 -0.09467762 -0.2202931 0.9708281 -0.04101353 -0.9008147 0.4322624 -0.1335164 -0.40478 0.904614 -0.1070466 -0.6294482 0.7696338 -0.1144955 -0.7163684 0.6882639 -0.0845493 -0.8543885 0.5127101 -0.1923857 -0.2979848 0.9349828 -0.2252575 -0.5394996 0.8112948 -0.1021704 -0.9098253 0.4022178 -0.3073725 -0.4145079 0.8565661 -0.2599189 -0.5500138 0.7936794 -0.2409802 -0.7186816 0.6522463 -0.1732633 -0.8543519 0.4899621 -0.3952492 -0.3576238 0.8460988 -0.4000727 -0.4629799 0.7909436 -0.3164159 -0.6705326 0.6710194 -0.02570843 -0.9972803 0.06907463 -0.1530439 -0.9355219 0.3183968 -0.2330396 -0.8822735 0.4090062 -0.4725974 -0.413751 0.7781144 -0.476112 -0.5078946 0.7178862 -0.3088028 -0.8414956 0.4433126 -0.2705718 -0.8738161 0.4040254 -0.5845282 -0.3908933 0.7110058 -0.5723697 -0.5380088 0.618821 -0.1092002 -0.985706 0.1282933 -0.4405046 -0.7618173 0.4749634 -0.6606084 -0.4057793 0.6316168 -0.3862079 -0.8454431 0.3688763 -0.3981451 -0.8403304 0.3678662 -0.7671372 -0.2289552 0.5992331 -0.6888297 -0.442033 0.5745613 -0.634496 -0.5922711 0.4966183 -0.6415385 -0.6153969 0.4579467 -0.7570683 -0.4379765 0.4847928 -0.4838153 -0.8200355 0.3057198 -0.3492394 -0.9078347 0.2320953 -0.8029466 -0.372433 0.4653716 -0.2366324 -0.9607056 0.1450861 -0.7913748 -0.4525343 0.4110215 -0.6534022 -0.6837235 0.3249429 -0.8607483 -0.325614 0.3912645 -0.5986015 -0.7654535 0.2361296 -0.8843796 -0.365208 0.2906818 -0.3570276 -0.9236259 0.1394509 -0.8517306 -0.4301851 0.2991588 -0.6727374 -0.7004889 0.2382009 -0.8959351 -0.3879384 0.2163432 -0.2296447 -0.9710742 0.0654087 -0.8229912 -0.5405068 0.1747507 -0.6901409 -0.7042102 0.1667142 -0.4993457 -0.8622137 0.08509653 -0.8264399 -0.5563832 0.08622628 -0.5151478 -0.8537759 0.07543009 -0.8537157 -0.5155234 0.07352113 -0.8643133 -0.5014816 0.03845566 -0.4078031 -0.9130367 0.007800102 -0.7886519 -0.6147166 -0.01232498 -0.6350717 -0.7719324 -0.0283631 -0.9201902 -0.3779391 -0.1020402 -0.1364427 -0.9905807 -0.01154935 -0.9007113 -0.4078943 -0.1494702 -0.8712522 -0.4645204 -0.1585578 -0.6132466 -0.7841255 -0.09526842 -0.5312373 -0.8410723 -0.101904 -0.3023948 -0.9513185 -0.05958759 -0.855155 -0.464369 -0.230372 -0.8454809 -0.4802688 -0.2334611 -0.6301152 -0.7538791 -0.1860678 -0.8613456 -0.3641036 -0.3542774 -0.8321771 -0.4521644 -0.320981 -0.5425205 -0.8101356 -0.222153 -0.5737338 -0.7875766 -0.2248395 -0.2772113 -0.9549338 -0.1060914 -0.8156916 -0.4065707 -0.4115185 -0.5728151 -0.7661706 -0.2913171 -0.8294673 -0.3086088 -0.4655584 -0.170387 -0.9823217 -0.07754009 -0.5019039 -0.8128159 -0.2956737 -0.3361846 -0.9195166 -0.20364 -0.759637 -0.4267005 -0.4907938 -0.5789844 -0.7198294 -0.3829134 -0.7610895 -0.338185 -0.5535105 -0.7142607 -0.4242653 -0.5566243 -0.1918472 -0.9690856 -0.1551379 -0.574731 -0.6885286 -0.4422812 -0.6901049 -0.3352421 -0.6413797 -0.5855709 -0.544375 -0.6006352 -0.4209183 -0.8116713 -0.4049911 -0.3916165 -0.8364881 -0.3833071 -0.5753626 -0.4071438 -0.7093602 -0.5485279 -0.4124134 -0.7273461 -0.5552619 -0.4004076 -0.7289432 -0.4265197 -0.6871158 -0.5881777 -0.3029093 -0.8724253 -0.3835623 -0.2780959 -0.8902245 -0.3607812 -0.5006259 -0.3095637 -0.8084208 -0.4238215 -0.4573845 -0.7817768 -0.03751456 -0.9976018 -0.05816644 -0.3717651 -0.6388492 -0.6735447 -0.3992505 -0.3912693 -0.8291606 -0.2636371 -0.8005179 -0.5382068 -0.2079745 -0.8918733 -0.4016325 -0.1557766 -0.9356074 -0.316816 -0.3411722 -0.4680392 -0.8151938 -0.2607796 -0.7461799 -0.6125437 -0.3063997 -0.3869695 -0.8696976 -0.10736 -0.9441681 -0.3114811 -0.2708249 -0.4482766 -0.8518815 -0.1781514 -0.7974653 -0.5764643 -0.1749481 -0.8017598 -0.5714671 -0.2029066 -0.3880515 -0.8990245 -0.03850764 -0.9867153 -0.1578301 -0.1373626 -0.5760942 -0.8057588 -0.1402814 -0.7987732 -0.5850493 -0.06005334 -0.9113401 -0.4072504 -0.06698417 -0.4394013 -0.89579 -0.0998907 -0.5800645 -0.8084226 -0.03528392 -0.8705841 -0.4907528 0.015374 -0.4719325 -0.8815006 -0.004154562 -0.883441 -0.468524 0.04266768 -0.3907399 -0.9195117 0.02553117 -0.8139009 -0.5804427 0.1390898 -0.4199796 -0.8968117 0.126326 -0.4508929 -0.8835935 0.08577024 -0.7876528 -0.6101201 0.01454108 -0.9888889 -0.1479441 0.1057446 -0.8481112 -0.5191586 0.1985056 -0.4175345 -0.8867133 0.2243764 -0.6247481 -0.7478939 0.1217849 -0.8391229 -0.5301333 0.3339457 -0.3516412 -0.8745449 0.2704498 -0.588433 -0.7619735 0.2872973 -0.7004423 -0.6533307 0.4232707 -0.2720808 -0.8641841 0.1147682 -0.9562564 -0.2690762 0.1849473 -0.9056642 -0.3815324 0.4089891 -0.5098142 -0.7568471 0.4808755 -0.4906551 -0.7266473 0.4624539 -0.530927 -0.7101078 0.4009228 -0.7138015 -0.5742372 0.2914982 -0.8504924 -0.4378257 0.6120588 -0.3093282 -0.727805 0.4652939 -0.689051 -0.555617 0.5887881 -0.5050207 -0.6310964 0.1768708 -0.9633277 -0.2017835 0.5975848 -0.512079 -0.6169826 0.4986708 -0.7354741 -0.4586997 0.3662077 -0.8544461 -0.3685294 0.7033142 -0.3324837 -0.6283342 0.2591014 -0.929356 -0.2629905 0.6984984 -0.4707713 -0.5389568 0.5386573 -0.7165238 -0.4432179 0.7380346 -0.4184988 -0.5293051 0.4133044 -0.8651904 -0.2839456 0.2603666 -0.9456055 -0.1950378 0.7466068 -0.4484556 -0.4913917 0.8395291 -0.2540435 -0.4802632 0.620923 -0.6954419 -0.361684 0.5225178 -0.798561 -0.2987905 0.8197992 -0.3997916 -0.4099952 0.4760206 -0.8508929 -0.2222294 0.8615199 -0.3689429 -0.3488048 0.8419302 -0.4303883 -0.3254526 0.1845393 -0.9803519 -0.06968158 0.6404756 -0.7313883 -0.234227 0.8990496 -0.3650403 -0.2417756 0.6338405 -0.7532904 -0.1754992 0.8759121 -0.4334682 -0.2118567 0.7792115 -0.6000126 -0.1811476 0.9459013 -0.2809038 -0.1623696 0.4311591 -0.8970417 -0.09704685 0.9208695 -0.3711866 -0.1192473 0.7941979 -0.6020539 -0.08234494 0.4020792 -0.9144277 -0.04641503 0.8878228 -0.4600409 0.01154559 0.764298 -0.6416514 -0.06428164 0.5408738 -0.8403388 -0.03586447 0.008482873 -0.9999158 0.009824812 0.007791161 -0.9999231 0.00965017 0.006685256 -0.9999632 0.005380868 0.007779538 -0.9999306 0.00884521 0.007760882 -0.9999595 0.004574775 0.007127761 -0.999967 0.003896594 6.98425e-4 -0.9999984 0.001672387 0.01090002 -0.9999395 0.001534938 0.007155954 -0.9999725 0.001979827 -0.001058101 -0.9999783 0.006524384 7.68874e-4 -0.9999464 0.01032489 0.007711052 -0.9999697 0.001153111 0.01123028 -0.9999369 2.11153e-4 6.18006e-4 -0.9999457 0.01041054 -0.001352608 -0.9999727 0.007270395 0.004448771 -0.9999895 -0.001195371 -0.003014862 -0.999957 0.008779942 -0.002758502 -0.9999759 0.006366312 0.01356428 -0.999866 -0.009176731 0.01630538 -0.9998278 -0.008875608 0.01482635 -0.9998788 -0.004752337 -0.004325389 -0.9999762 0.005390882 -0.01129943 -0.9998851 0.01010996 0.004921674 -0.999976 -0.004879951 0.00667715 -0.9999347 -0.009275794 -0.01133221 -0.9998954 0.008992969 -0.0087592 -0.999922 0.008904695 0.00494194 -0.9999467 -0.009062528 -0.004279971 -0.9999886 0.002170503 0.00534904 -0.9998658 -0.01548755 -0.007010221 -0.9999753 6.90157e-4 0.003343284 -0.9998955 -0.01407289 -0.009586989 -0.9999513 0.00235188 0.003838539 -0.9999146 -0.01250207 -0.009490728 -0.999955 1.43229e-4 -2.78282e-4 -0.9999912 -0.004201233 -0.008395731 -0.9999646 5.25064e-4 -0.001514494 -0.999981 -0.005983769 -0.00287801 -0.9999956 -8.12813e-4 -0.001748085 -0.9999895 -0.004251718 -0.005270361 -0.9999808 -0.003304123 -0.005467474 -0.999962 -0.006783962 -0.005555391 -0.9999595 -0.007088422 -0.004823625 -0.9999828 -0.003359496 -0.006953477 -0.9999523 -0.006857633 0.9203227 0.3869927 -0.05694705 0.3823838 0.9240033 -8.97064e-4 0.9256926 0.3733857 -0.06063467 0.6895839 0.7230603 -0.04071694 0.7121695 0.7000587 -0.05227279 0.1700081 0.985329 -0.01497077 0.9034562 0.3921739 -0.1731089 0.8877922 0.4318876 -0.1590546 0.6344828 0.7655656 -0.1064938 0.6454166 0.7553362 -0.1135988 0.2825423 0.9581315 -0.04641103 0.8926573 0.3868393 -0.2313401 0.8067328 0.5371235 -0.2463341 0.6164135 0.7706483 -0.1616653 0.5121341 0.8441329 -0.1586148 0.8455497 0.4078356 -0.3445515 0.7962365 0.5244488 -0.3015975 0.6348077 0.7257186 -0.265239 0.4739045 0.8624877 -0.1775653 0.3422641 0.9277791 -0.1485979 0.8232702 0.3746187 -0.4264824 0.7682247 0.4721957 -0.4322754 0.6343417 0.685747 -0.3568776 0.5732768 0.7454491 -0.3400875 0.3830025 0.8983412 -0.2151567 0.7794399 0.3695766 -0.5058525 0.7227752 0.4499591 -0.5245311 0.5837897 0.6959441 -0.4181525 0.7333114 0.3439339 -0.5864844 0.1979602 0.9692743 -0.1460111 0.4653874 0.7964128 -0.3861882 0.6687879 0.4066406 -0.6223875 0.2880848 0.9251893 -0.2470467 0.5686006 0.5865642 -0.5767459 0.5904021 0.5726063 -0.5688124 0.5981808 0.3271914 -0.7315228 0.425461 0.7504599 -0.5057598 0.3429363 0.8394646 -0.4215375 0.2235214 0.9407985 -0.2548266 0.5071135 0.5232904 -0.6848381 0.0840829 0.9897046 -0.115823 0.4557289 0.5031064 -0.7342991 0.3925408 0.6065216 -0.6914069 0.3054152 0.7730166 -0.556028 0.2773049 0.8360087 -0.4734887 0.1492912 0.9554522 -0.2546045 0.2565796 0.8005014 -0.5416315 0.3714368 0.4636749 -0.8043882 0.1594939 0.9108938 -0.3805708 0.266408 0.6097255 -0.7464996 0.2610397 0.4596952 -0.8488456 0.2649509 0.6091859 -0.7474581 0.1005366 0.9429168 -0.3174905 0.1406612 0.8320252 -0.5366083 0.1912137 0.4134252 -0.8902342 0.1676603 0.4702714 -0.8664495 0.1259113 0.8052045 -0.5794758 0.02731806 0.9923043 -0.1207723 0.103803 0.470089 -0.8764938 0.06213223 0.5777785 -0.8138254 0.0658012 0.8461982 -0.52879 0.04429554 0.8902538 -0.4533057 -0.02086955 0.4529693 -0.8912819 0.01375257 0.5779116 -0.8159835 -0.02006101 0.875109 -0.48351 -0.01409906 0.8669782 -0.4981467 -0.1012288 0.3533769 -0.929988 -0.08055955 0.4249666 -0.9016172 -0.1018462 0.7614358 -0.6401898 -0.05862432 0.8527824 -0.5189656 -0.1816827 0.4508832 -0.8738969 -0.135417 0.7289359 -0.671055 -0.2305737 0.3402502 -0.911628 -0.1627765 0.7581628 -0.6314215 -0.2737256 0.4484698 -0.8508521 -0.04956024 0.9757692 -0.2131158 -0.1551245 0.8680537 -0.4716135 -0.322292 0.4065737 -0.8548834 -0.3293609 0.434183 -0.8384549 -0.2956552 0.6880347 -0.6627189 -0.1754828 0.863468 -0.4728943 -0.4505069 0.3170394 -0.8345835 -0.1556972 0.9358212 -0.316223 -0.4424139 0.4336865 -0.7849752 -0.3332812 0.6896228 -0.6429185 -0.3066245 0.7879042 -0.5340304 -0.2014434 0.9114443 -0.3587338 -0.4791128 0.5168287 -0.709464 -0.4117044 0.6888408 -0.5966556 -0.5729126 0.3419944 -0.7448565 -0.1836405 0.9456443 -0.2683902 -0.5720669 0.4961106 -0.6531568 -0.4024369 0.7757257 -0.4861012 -0.380953 0.807334 -0.4506515 -0.06296181 0.9949783 -0.07780903 -0.3698479 0.8415047 -0.393805 -0.2983579 0.9048085 -0.303816 -0.6537227 0.4032927 -0.6403138 -0.6529172 0.4746729 -0.5902414 -0.5631956 0.6606734 -0.4963079 -0.7260333 0.352306 -0.5905559 -0.2573449 0.9473876 -0.1903427 -0.7407458 0.451685 -0.4972689 -0.6920426 0.5749345 -0.4364945 -0.5222617 0.7751835 -0.3554341 -0.4161538 0.867811 -0.2715145 -0.7677394 0.4975259 -0.4037873 -0.3974798 0.8949186 -0.2028067 -0.7832077 0.5084295 -0.3578898 -0.7722717 0.5235891 -0.359793 -0.5306716 0.8143987 -0.2348248 -0.871828 0.4087123 -0.2699454 -0.8089517 0.5167808 -0.2802404 -0.57704 0.79384 -0.1919457 -0.1150941 0.9925258 -0.04057091 -0.8859759 0.4228186 -0.1904501 -0.470266 0.8754137 -0.1118073 -0.9378401 0.3003798 -0.1738622 -0.4137548 0.9052463 -0.09662318 -0.6613137 0.7413967 -0.1139968 -0.9369565 0.340871 -0.07693868 -0.8748196 0.4826856 -0.04129701 -0.7421527 0.6695191 -0.03088182 -0.733664 0.6789681 -0.02719211 -0.9508376 0.3089739 0.02105134 -0.2717267 0.9623515 -0.006669878 -0.3763868 0.9264408 0.00635457 -0.8516619 0.517281 0.08421665 -0.7647696 0.6412129 0.06303662 -0.9009419 0.4153226 0.1257416 -0.406028 0.9133665 0.03004884 -0.6504166 0.756389 0.06952601 -0.3140754 0.9478676 0.05388778 -0.8804737 0.4336218 0.1916726 -0.6011893 0.7867863 0.139781 -0.7963889 0.5655921 0.2141742 -0.6505026 0.7394874 0.1732193 -0.8660308 0.3907855 0.3118934 -0.1949666 0.9797656 0.04524964 -0.4842191 0.8557845 0.1821118 -0.855582 0.4062077 0.3208971 -0.6915654 0.647616 0.319892 -0.4844067 0.8551902 0.1843912 -0.8603561 0.2783234 0.4269938 -0.3106122 0.9365651 0.1623763 -0.7668088 0.4903617 0.4141857 -0.6959114 0.6326303 0.3398328 -0.414783 0.8751571 0.249109 -0.7500033 0.4852448 0.4494804 -0.6503325 0.6107379 0.4517377 -0.4654748 0.8200225 0.3330112 -0.6975604 0.434785 0.5695362 -0.6826456 0.430927 0.5901668 -0.665911 0.4580407 0.5888644 -0.4500767 0.7911624 0.4141173 -0.3790776 0.8675973 0.3218309 -0.2483297 0.9419552 0.2259486 -0.6077021 0.4617969 0.6460973 -0.5862112 0.4970471 0.6397661 -0.477488 0.7033219 0.5266342 -0.5497224 0.3979871 0.7344465 -0.36656 0.8023201 0.4710801 -0.2745195 0.8872682 0.3706673 -0.2233403 0.9314696 0.2871994 -0.51321 0.4576897 0.7260412 -0.4554997 0.5943988 0.6627293 -0.493449 0.2643217 0.8286387 -0.4420289 0.3473333 0.8270249 -0.3540363 0.6813722 0.6406171 -0.3311366 0.7161577 0.6143832 -0.2523378 0.8628914 0.4378859 -0.4160499 0.279617 0.8652842 -0.3554841 0.3780832 0.8548007 -0.2771074 0.6874128 0.6713234 -0.2738436 0.7153712 0.6428481 -0.325761 0.2969475 0.8976091 -0.125629 0.9484668 0.2909091 -0.1443713 0.9193456 0.3660066 -0.2711243 0.3831971 0.8829789 -0.2190209 0.6498321 0.727838 -0.2344767 0.2824929 0.9301712 -0.1740784 0.7163634 0.6756628 -0.129135 0.8631949 0.4880768 -0.1822223 0.3662973 0.912481 -0.1563546 0.6694894 0.7261799 -0.1463359 0.2978149 0.9433409 -0.08640748 0.4058856 0.90983 -0.05510973 0.9343624 0.352037 -0.070665 0.7664991 0.638346 -0.06720167 0.7387937 0.6705728 -0.04244506 0.8868454 0.4601126 -0.05204218 0.3511653 0.9348661 0.01073044 0.4574121 0.88919 0.01668709 0.5833621 0.8120409 0.05316102 0.2561751 0.9651675 -5.06471e-5 0.923877 0.3826898 0.06460374 0.7407573 0.6686592 0.05457979 0.8291497 0.5563558 0.1661128 0.3869568 0.9070122 0.1700521 0.5029102 0.8474454 0.187492 0.5220729 0.8320376 0.2802955 0.2959968 0.9131377 0.08707457 0.9282074 0.3617306 0.2063304 0.7057357 0.6777647 0.1354534 0.8782393 0.4586373 0.2883369 0.6029242 0.7438712 0.3024424 0.6009949 0.7398202 0.3795027 0.4559014 0.8050662 0.237009 0.8446401 0.4800102 0.4495099 0.3845906 0.806245 0.1881288 0.8979099 0.3979517 0.4287659 0.433048 0.7928614 0.3351213 0.7638607 0.551553 0.09606146 0.9807282 0.1701304 0.3503854 0.7836924 0.5128901 0.5850301 0.2739604 0.7633383 0.2373582 0.9152134 0.3256464 0.5365886 0.4138531 0.7353899 0.4578763 0.6518284 0.6045404 0.6293218 0.409552 0.6604706 0.529803 0.6352855 0.5618907 0.6856179 0.2782194 0.6726976 0.2320586 0.9397525 0.2510263 0.4979599 0.711344 0.49601 0.3357627 0.8840748 0.3250771 0.7184668 0.3350063 0.6095706 0.6376013 0.5852632 0.5009309 0.6322391 0.6196138 0.4651371 0.516603 0.7816493 0.3494935 0.7888737 0.3483898 0.5062637 0.3491405 0.8985121 0.2660395 0.8287485 0.2975265 0.4739766 0.08817267 0.9946445 0.05392581 0.5272367 0.7911751 0.3099412 0.8008595 0.4339643 0.4126732 0.6826384 0.644973 0.343533 0.8685389 0.3462882 0.3545769 0.3341363 0.9293416 0.1570897 0.8114814 0.503511 0.2966054 0.6830806 0.6719926 0.286054 0.4236858 0.8927358 0.1533401 0.4215041 0.8945706 0.1485864 0.8781997 0.4154196 0.2370482 0.8220018 0.5110504 0.2512782 0.5971519 0.7880258 0.1497499 0.888707 0.427451 0.1657877 0.8578228 0.4938921 0.1421639 0.1698793 0.9845318 0.04287409 0.6047854 0.7879325 0.1157461 0.5481829 0.8320857 0.08443403 0.9336996 0.3544279 0.05085361 0.8667581 0.4936558 0.07095551 0.7266858 0.6856778 0.04211688 0.562831 0.8247273 0.05519187 -0.003841996 0.9999863 0.003559768 -0.00272578 0.9999638 0.008064568 -0.01611888 0.999831 0.008846342 -0.006067752 0.9999372 0.009421169 -0.01529616 0.9998365 0.009653508 -0.01128685 0.9999228 0.00521481 -0.004976987 0.9999138 0.01214724 -0.005353629 0.9998652 0.01552575 -0.01123839 0.9999231 0.005247831 -0.005670785 0.9998641 0.01548218 -0.004097759 0.9999914 7.30323e-4 -0.001363754 0.9999657 0.008183956 -0.00434494 0.9999907 -1.18619e-4 0.002521634 0.9998991 0.01398664 5.77691e-4 0.9999631 0.00858128 -0.006570219 0.9999781 -9.39373e-4 -0.008501648 0.9999589 -0.003153979 -0.006401538 0.9999781 -0.001695573 0.005088806 0.9998521 0.01643246 0.005564928 0.9998792 0.01451361 0.004574418 0.9998937 0.01384347 -0.00617367 0.9999758 -0.00320822 0.003340244 0.999982 0.00499469 -0.006051838 0.99996 -0.006594479 -0.00863713 0.9999374 -0.007118642 0.007672905 0.9999647 0.00345689 0.009545207 0.9999088 0.00955373 -0.008476436 0.9999307 -0.00816667 -0.003606677 0.9999818 -0.004843592 0.011689 0.9999006 0.007887542 0.007479727 0.9999495 0.006707012 -0.002460122 0.9999801 -0.005820333 -0.003316104 0.9998773 -0.01530867 0.004876852 0.9999869 0.001598954 -0.004091799 0.9998919 -0.01412159 -0.002062082 0.9999363 -0.01110029 0.01497417 0.9998877 5.98345e-4 0.01494497 0.9998883 5.49405e-4 9.09218e-4 0.9999251 -0.01220351 -6.28666e-4 0.999972 -0.007463157 0.01740187 0.9998485 -5.75341e-4 0.0106917 0.9999411 -0.001918971 4.68272e-4 0.9999561 -0.009368181 8.50075e-4 0.9999976 -0.002067387 0.01010817 0.9999403 -0.004144906 0.009545922 0.9999459 -0.004131615 0.009470641 0.9999457 -0.004361808 0.002039968 0.9999946 -0.002582371 0.00286597 0.9999938 -0.002097845 0.002252995 0.9999936 -0.002813339 0.9120612 -0.4088193 0.03180044 0.4905146 -0.871117 0.02346748 0.8932244 -0.4468607 0.04965615 0.2195611 -0.9755606 -0.008631646 0.7291963 -0.6802201 0.07465481 0.4688599 -0.8832385 0.007769465 0.7213901 -0.685482 0.09854358 0.9438414 -0.2876497 0.162546 0.3777462 -0.9240879 0.05804717 0.9008278 -0.3984608 0.1724479 0.526412 -0.842844 0.111823 0.5309514 -0.8387063 0.1210879 0.855956 -0.468067 0.2196652 0.7013312 -0.6858179 0.1943925 0.9073444 -0.2933897 0.3010792 0.8361775 -0.4444375 0.321376 0.7114105 -0.6456322 0.2775865 0.306661 -0.9441853 0.1203045 0.336971 -0.9324966 0.1300026 0.5960853 -0.7574245 0.2664404 0.8488801 -0.3117032 0.4269003 0.8278282 -0.3610473 0.4293547 0.6306095 -0.7065054 0.3212195 0.7922578 -0.3659466 0.4882732 0.6673257 -0.5898209 0.4547392 0.5687387 -0.7458509 0.3467603 0.3183994 -0.9229657 0.2162318 0.2265398 -0.9637136 0.1411943 0.7147812 -0.3723619 0.5919752 0.6430239 -0.5811052 0.4988356 0.5936257 -0.6477509 0.477522 0.3338333 -0.9011945 0.2764126 0.3187185 -0.9077672 0.2727219 0.6779501 -0.3102566 0.6664267 0.5130211 -0.6938282 0.5053828 0.4008495 -0.816546 0.4154185 0.6150342 -0.4584236 0.6415457 0.08782875 -0.991792 0.09292304 0.344087 -0.8475682 0.4040203 0.2410939 -0.9210693 0.305786 0.5510156 -0.4598871 0.6963374 0.4867678 -0.577941 0.6550124 0.2263821 -0.9145199 0.3352681 0.4243299 -0.5606722 0.7110491 0.428208 -0.5909838 0.6836491 0.3840335 -0.583343 0.7157019 0.3716143 -0.4969958 0.7841543 0.1664175 -0.916325 0.3642168 0.1332305 -0.9551398 0.2644951 0.2988512 -0.4320274 0.8509056 0.3087505 -0.5279461 0.7911676 0.1743946 -0.84026 0.5133709 0.2234842 -0.4435641 0.8679319 0.2193061 -0.3939087 0.8926035 0.151847 -0.7363567 0.659334 0.134589 -0.8528763 0.5044679 0.0614168 -0.9483031 0.311367 0.09818106 -0.4088544 0.9073029 0.09558147 -0.3944481 0.9139338 0.08672893 -0.6674638 0.7395744 0.02915656 -0.8209304 0.5702836 -0.01076543 -0.3702338 0.9288763 0.008730351 -0.4343175 0.9007177 0.003592431 -0.8236537 0.5670819 -0.01379239 -0.8508079 0.5252959 -0.07994425 -0.3901023 0.9172945 -0.1001901 -0.5003231 0.8600226 -0.06512576 -0.7578279 0.6491962 -0.0183438 -0.9855466 0.1684086 -0.1984758 -0.3569 0.9128143 -0.167212 -0.4641031 0.8698555 -0.1628511 -0.7531943 0.6373209 -0.1308408 -0.815068 0.5643979 -0.08207881 -0.9341025 0.3474416 -0.2671759 -0.4892708 0.8301995 -0.2222228 -0.6868999 0.6919434 -0.318523 -0.3424366 0.8839006 -0.2285026 -0.7157317 0.6599354 -0.1542437 -0.9228603 0.3528992 -0.3866068 -0.4017965 0.8301174 -0.1041564 -0.9608492 0.2567497 -0.3765571 -0.5300866 0.7597453 -0.3082132 -0.6781626 0.6671581 -0.2168147 -0.8774129 0.4279463 -0.2277019 -0.8799738 0.4168909 -0.5073341 -0.316038 0.8017058 -0.4252793 -0.5315935 0.7324929 -0.3943855 -0.6765466 0.6218881 -0.02036833 -0.9992007 0.03439724 -0.1796455 -0.9425678 0.2815914 -0.5421252 -0.4671018 0.6985101 -0.4319171 -0.6906753 0.5800133 -0.3619766 -0.8216665 0.4402693 -0.6069401 -0.3351569 0.7206203 -0.3620511 -0.8130483 0.4559292 -0.6872861 -0.3000442 0.661522 -0.6422353 -0.3991342 0.6543895 -0.5104516 -0.6980964 0.5020962 -0.2312517 -0.9453018 0.230059 -0.4817178 -0.7636787 0.4298173 -0.3814617 -0.8642982 0.3278348 -0.7340688 -0.3339805 0.5912699 -0.6882004 -0.5019333 0.5238735 -0.6894405 -0.5448382 0.4773083 -0.5130233 -0.7985691 0.3147929 -0.3780709 -0.8921596 0.2472119 -0.8239819 -0.3052031 0.4773939 -0.3316956 -0.9191251 0.2125726 -0.8106294 -0.4126598 0.4154418 -0.6439639 -0.6955537 0.3186153 -0.871899 -0.3015889 0.3857932 -0.6294262 -0.7283206 0.2708725 -0.8332611 -0.4464297 0.3261541 -0.5035676 -0.8442263 0.1835798 -0.2500426 -0.9619604 0.1100505 -0.8906484 -0.3791242 0.2510183 -0.9174103 -0.2844638 0.2782784 -0.7465623 -0.6371317 0.1915937 -0.5198795 -0.8365425 0.17298 -0.8806544 -0.4541155 0.1350073 -0.7471243 -0.6463413 0.1550754 -0.543864 -0.8352135 0.08142828 -0.3777853 -0.9230889 0.07200819 -0.9109814 -0.396289 0.1143152 -0.9007334 -0.4182261 0.1173303 -0.1188415 -0.9928569 0.01057738 -0.6202904 -0.7824501 0.05487883 -0.9262943 -0.3748981 0.03781968 -0.6052474 -0.7958004 0.0194295 -0.8082358 -0.5886213 -0.01673322 -0.3837306 -0.9233734 -0.01150566 -0.8963969 -0.435921 -0.08028358 -0.8224619 -0.5661112 -0.05545037 -0.4157941 -0.9090692 -0.02661752 -0.6630894 -0.7439047 -0.08317673 -0.9230135 -0.3467465 -0.1667724 -0.6567772 -0.7454032 -0.1140959 -0.850745 -0.4887554 -0.193265 -0.4641301 -0.8784652 -0.1134988 -0.3349869 -0.9390936 -0.07672739 -0.8550812 -0.4615988 -0.236142 -0.7965891 -0.5451987 -0.2611594 -0.5947259 -0.7764492 -0.2083933 -0.8520455 -0.3998981 -0.3377867 -0.09586864 -0.9948489 -0.03294014 -0.5348631 -0.8164451 -0.2175755 -0.4029679 -0.8967218 -0.1830488 -0.7819601 -0.4776824 -0.4004474 -0.7850241 -0.4724547 -0.4006543 -0.7343709 -0.5239012 -0.4315402 -0.6818186 -0.5951351 -0.4253679 -0.4381719 -0.8509955 -0.2895031 -0.395291 -0.8763006 -0.2753947 -0.7049562 -0.4284087 -0.5652458 -0.1171874 -0.9885411 -0.09515094 -0.6263842 -0.5421116 -0.560141 -0.4689407 -0.7821609 -0.4102669 -0.6299281 -0.4730576 -0.6159604 -0.5795465 -0.5159295 -0.630827 -0.3352262 -0.8755341 -0.347942 -0.575802 -0.42152 -0.7005519 -0.352967 -0.8370703 -0.4180044 -0.5503113 -0.4491566 -0.7038578 -0.3898224 -0.7450857 -0.5411893 -0.3221215 -0.8473953 -0.4220889 -0.5359894 -0.3688228 -0.759398 -0.206232 -0.9301435 -0.3038115 -0.4146706 -0.5903493 -0.6924855 -0.4324868 -0.3712955 -0.8216416 -0.4005975 -0.5869898 -0.7035373 -0.4128726 -0.3004159 -0.8598178 -0.2943416 -0.7413318 -0.6031502 -0.2258154 -0.8591655 -0.4591755 -0.3575911 -0.3923575 -0.8474575 -0.2949853 -0.626843 -0.721146 -0.3307209 -0.200524 -0.9221789 -0.1178382 -0.9424386 -0.3129277 -0.2227886 -0.6904056 -0.6882626 -0.143395 -0.8569369 -0.495073 -0.2345813 -0.4218068 -0.8758143 -0.2198542 -0.496141 -0.8399454 -0.1564795 -0.5683548 -0.8077668 -0.1196107 -0.347119 -0.9301622 -0.09253692 -0.8573335 -0.5063756 -0.09179228 -0.8045093 -0.5868042 -0.02541649 -0.9723851 -0.2319942 -0.02868801 -0.5090171 -0.8602783 -0.04567199 -0.783775 -0.6193633 -0.01209735 -0.883065 -0.4690948 -0.005964338 -0.4577008 -0.8890863 0.02465951 -0.4844344 -0.87448 0.1099776 -0.2622252 -0.9587194 0.07468533 -0.728264 -0.6812149 0.07441323 -0.7693098 -0.6345275 0.03002297 -0.891541 -0.4519439 0.1406321 -0.4171223 -0.897904 0.02751529 -0.9855581 -0.1670874 0.1226117 -0.785991 -0.6059576 0.2117795 -0.4399958 -0.8726701 0.2147486 -0.4864329 -0.8469156 0.1148978 -0.8930383 -0.4350645 0.2675137 -0.5196073 -0.8114461 0.2760323 -0.5978671 -0.7525697 0.1687987 -0.862711 -0.4766937 0.3474278 -0.5492049 -0.7600447 0.3501181 -0.5542886 -0.7551037 0.2796899 -0.7921066 -0.5425319 0.17141 -0.9118607 -0.3729997 0.1159536 -0.9672031 -0.2259932 0.4417133 -0.4214849 -0.7919847 0.4600875 -0.478397 -0.7479677 0.3704501 -0.7192522 -0.5877439 0.5385742 -0.3354153 -0.7729389 0.3501985 -0.8070803 -0.4753761 0.3300677 -0.836359 -0.4376746 0.2311094 -0.9214526 -0.3122717 0.5479469 -0.5037702 -0.6678097 0.6133877 -0.4302674 -0.6622882 0.5888859 -0.4779223 -0.6517697 0.4272148 -0.7843182 -0.4498139 0.4152078 -0.8100995 -0.4139342 0.3026124 -0.9126529 -0.2747556 0.6737795 -0.422959 -0.60591 0.113476 -0.9862174 -0.12041 0.6479994 -0.5341213 -0.5429654 0.6588343 -0.5535502 -0.5094306 0.7160577 -0.4875419 -0.4995642 0.3523498 -0.8933444 -0.2789007 0.7152503 -0.5128931 -0.4747186 0.5343631 -0.7919197 -0.2954983 0.8521621 -0.2755053 -0.4448782 0.3159079 -0.9295738 -0.1899864 0.2294182 -0.9647065 -0.1292619 0.8144312 -0.4498671 -0.3664991 0.6420191 -0.708785 -0.2922934 0.8777462 -0.3398579 -0.3377251 0.8588414 -0.4370148 -0.2672257 0.5813241 -0.7843003 -0.216646 0.4581342 -0.8761087 -0.1501553 0.38488 -0.9140483 -0.1279965 0.8804115 -0.4045807 -0.2473666 0.1842001 -0.9816173 -0.04997944 0.8652471 -0.4566529 -0.2069192 0.6242846 -0.7710869 -0.1252751 0.9148097 -0.3682497 -0.1658778 0.8699177 -0.4812167 -0.1080458 0.6738965 -0.7349464 -0.0756129 0.6014408 -0.7940726 -0.08785086 0.303017 -0.9522094 -0.03844547 0.9291715 -0.3644633 -0.06169956 0.8839337 -0.4675329 -0.008620262 0.6868017 -0.7260597 -0.03377425 0.9972427 6.82886e-4 -0.07420599 0.9973871 2.89265e-4 -0.07224309 0.9859582 -0.001653909 -0.1669844 0.9824908 0.002312302 -0.186297 0.963333 -0.003006637 -0.2682919 0.9319657 -0.002057731 -0.3625407 0.9496721 0.003740251 -0.3132236 0.8854745 -0.004876315 -0.4646626 0.9131065 0.002835571 -0.4077113 0.8627425 0.002943336 -0.5056351 0.8135082 -0.00101453 -0.5815528 0.8107628 -3.33421e-5 -0.585375 0.7527397 -0.003800272 -0.6583074 0.72758 0.002755999 -0.6860174 0.6746277 -0.001844525 -0.738156 0.6490926 0.004564881 -0.7606957 0.5742058 -0.002256453 -0.8187078 0.5791929 -9.36106e-4 -0.81519 0.474062 -0.004396796 -0.8804804 0.5201617 0.001366913 -0.8540668 0.3883351 -0.00429362 -0.9215083 0.4327558 6.40239e-4 -0.901511 0.3468381 -0.001966595 -0.937923 0.3389332 -1.84927e-4 -0.9408105 0.2465187 0.003282189 -0.9691325 0.2728201 -0.00455141 -0.9620544 0.1116126 -0.004568397 -0.9937413 0.1627454 0.004630088 -0.9866573 -0.002847313 -0.004164814 -0.9999873 0.04060292 0.002580046 -0.9991721 -0.146724 -0.005706846 -0.9891611 -0.08983546 0.004541218 -0.9959464 -0.2076076 6.5922e-5 -0.9782123 -0.2050584 -6.46155e-4 -0.9787496 -0.3365823 0.001061677 -0.9416535 -0.3304079 -7.49435e-4 -0.943838 -0.433419 -8.04997e-5 -0.9011927 -0.4480012 0.003357648 -0.8940266 -0.5280824 -0.004816472 -0.8491795 -0.4893895 0.003140628 -0.8720597 -0.5517459 -0.006395757 -0.8339878 -0.6461079 -0.00374484 -0.763237 -0.5992019 0.002727031 -0.8005933 -0.7132101 -0.002886056 -0.7009444 -0.686077 0.001504361 -0.7275274 -0.7890042 -0.006035327 -0.6143583 -0.7468689 0.001638889 -0.6649694 -0.8419985 -0.001747786 -0.5394773 -0.8171984 0.001020729 -0.5763557 -0.8669415 0.00345689 -0.4983982 -0.890641 -0.004021525 -0.4546894 -0.9319716 0.002152025 -0.3625252 -0.9317175 0.001960158 -0.3631786 -0.9614257 -0.003770112 -0.2750389 -0.9843537 -9.51889e-4 -0.1762021 -0.9754411 0.004244685 -0.2202195 -0.9976015 -0.004651486 -0.06906181 -0.990598 0.002922892 -0.1367747 -0.9996769 -4.08886e-5 -0.02541959 -0.999925 -0.003827929 0.01162999 -0.9959887 0.004346847 0.08937388 -0.9912938 -0.003001034 0.1316348 -0.9773813 0.004674255 0.2114336 -0.9628497 -0.00536412 0.269985 -0.947029 0.003067791 0.3211337 -0.9164645 -0.001924991 0.4001117 -0.9112249 6.79322e-4 0.4119087 -0.8591278 6.55438e-4 0.5117608 -0.8584691 0.001009643 0.5128644 -0.8102815 0.001973628 0.5860376 -0.7921903 -0.002926707 0.6102672 -0.7399904 0.004466056 0.6726027 -0.71715 -0.001304566 0.6969177 -0.6371043 0.003452062 0.7707699 -0.6440674 7.24768e-4 0.7649685 -0.5274939 -0.001618504 0.8495573 -0.5229399 -2.19462e-4 0.8523695 -0.4387337 -2.42678e-4 0.8986172 -0.4322287 0.001302778 0.9017631 -0.334117 -0.00390172 0.9425236 -0.2911421 0.005283832 0.9566653 -0.2086688 -0.005569338 0.9779706 -0.1558502 0.002208769 0.9877783 -0.108361 -0.003363132 0.9941059 -0.0444523 0.002933859 0.9990072 5.14318e-4 -0.002165794 0.9999976 0.05764955 0.003241062 0.9983316 0.1058225 -0.00220561 0.9943827 0.1398868 0.003399729 0.9901617 0.238479 -0.001008689 0.9711472 0.2526569 0.002112746 0.9675537 0.3436812 5.45947e-4 0.9390863 0.3393033 -3.59355e-4 0.9406771 0.4335284 -0.001045167 0.9011394 0.4336027 -0.001030802 0.9011036 0.525045 -0.001002669 0.8510739 0.5302627 3.49368e-4 0.8478334 0.6057226 -5.02392e-4 0.7956758 0.6016069 4.22045e-4 0.7987924 0.6530598 0.00391376 0.7572963 0.706343 -0.005065083 0.7078516 0.746093 0.00334239 0.6658334 0.7897163 -0.003564834 0.6134619 0.8149132 0.001439154 0.5795814 0.8337733 -0.003314375 0.5520972 0.8849171 0.00300157 0.4657388 0.895188 -0.001866757 0.4456849 0.9305867 0.003317594 0.3660566 0.9491464 -0.005314528 0.3147904 0.9648889 0.003501296 0.2626349 0.9852701 -0.005879342 0.1709049 0.9912955 0.003038346 0.1316216 0.9995353 0.001123428 0.03046059 0.9997567 -0.001041173 0.02203369 0.004681587 -0.9999838 0.003264844 0.005135118 -0.9999775 0.004325568 0.001108467 -0.9999983 0.001450419 0.004990696 -0.9999783 0.004333913 9.06329e-4 -0.9999982 0.001723349 0.003551363 -0.9999924 0.001658082 0.002428054 -0.9999336 0.01127004 0.01240819 -0.9999226 9.45172e-4 0.003547668 -0.9999253 0.0116949 0.01252794 -0.9999144 0.003806889 0.01382052 -0.9998993 0.00323683 0.002213239 -0.9998636 0.016366 0.001342713 -0.9998839 0.01518517 0.0120278 -0.9999238 0.002784788 -8.00408e-5 -1 0 0.00156182 -0.9998885 0.01485908 -6.14545e-5 -1 7.38457e-6 -9.16717e-5 -1 5.44935e-4 -1.92264e-4 -0.9999999 5.05813e-4 0.009545087 -0.9999405 -0.005296885 -9.88566e-5 -1 2.09464e-5 0.009188771 -0.9999459 -0.00487715 -0.007976889 -0.9999242 0.009381055 -0.008790671 -0.9998736 0.01325273 0.005917072 -0.9999719 -0.004616916 -0.01035982 -0.9998669 0.01261049 0.005967319 -0.9999709 -0.004768729 -0.007830917 -0.9999414 0.007486641 0.002103388 -0.9999946 -0.002558112 -0.008918881 -0.9999358 0.006997644 0.001623749 -0.9999942 -0.002994 0.002132236 -0.9999765 -0.006521701 -0.007193148 -0.9999666 0.003901422 -0.01040375 -0.9999393 0.003638923 0.002220511 -0.999976 -0.006565988 -0.009823858 -0.9999483 0.002672314 7.22e-4 -0.9999335 -0.01151084 0.001282155 -0.999919 -0.01266872 -0.01106667 -0.999936 0.002397894 -0.002119779 -0.9999978 -2.15367e-5 -0.001437246 -0.9999222 -0.01239365 -0.001287221 -0.9999126 -0.01316648 -0.002156794 -0.9999976 -5.4636e-4 -0.004096686 -0.9999243 -0.01160115 -0.01023936 -0.9999318 -0.005621314 -0.003584384 -0.9999328 -0.0110256 -0.01212304 -0.9999108 -0.005615592 -0.004961073 -0.9999507 -0.008617103 -0.01163667 -0.9998932 -0.008841514 -0.0111649 -0.9999043 -0.008180677 -0.006534516 -0.999953 -0.007177829 -0.006430447 -0.9999338 -0.009547054 0.847674 0.5293663 -0.03493279 0.4408441 0.8975718 -0.004640817 0.9277904 0.3644422 -0.07991826 0.8484272 0.5278084 -0.03987079 0.6611413 0.7463102 -0.07689857 0.1713305 0.9850432 -0.01832115 0.9440413 0.2781242 -0.1772935 0.9064201 0.3941437 -0.1518332 0.7548871 0.6397631 -0.1443917 0.6574023 0.7472521 -0.09714251 0.3662193 0.9271031 -0.07976984 0.8507508 0.4580013 -0.2577947 0.7402555 0.6403418 -0.2049006 0.651277 0.7330996 -0.1959679 0.3752889 0.9208626 -0.10569 0.877245 0.3847199 -0.2871096 0.2911896 0.9513016 -0.1011623 0.8557244 0.3354203 -0.3939911 0.8231112 0.4414028 -0.3572835 0.6442868 0.7039918 -0.2988147 0.5899225 0.7659938 -0.2554311 0.3405476 0.929765 -0.139873 0.8160954 0.3478324 -0.4615203 0.7447666 0.4921213 -0.4507099 0.6266981 0.7036975 -0.3347527 0.4039714 0.8783839 -0.2554386 0.232197 0.9631505 -0.1357415 0.715317 0.4961026 -0.492142 0.7491024 0.3667802 -0.5516502 0.4923159 0.7805823 -0.3851186 0.4893053 0.7821194 -0.3858362 0.6722951 0.4237502 -0.6070051 0.6282625 0.5117185 -0.5860294 0.06586509 0.9965841 -0.04981952 0.2926934 0.9157176 -0.2753033 0.5738564 0.5603851 -0.5972081 0.3830131 0.8175357 -0.4300423 0.3463287 0.8588445 -0.3774158 0.586629 0.4219905 -0.691224 0.5081316 0.5182973 -0.6878738 0.3781751 0.7777863 -0.5020281 0.5050424 0.4938186 -0.7078669 0.3159482 0.8290856 -0.461296 0.1421325 0.9598495 -0.2418416 0.4230635 0.541563 -0.7264481 0.44711 0.3858012 -0.8070006 0.163087 0.950244 -0.2654036 0.4263846 0.5546086 -0.7145667 0.4191063 0.3017363 -0.8563324 0.2832351 0.7406885 -0.6092278 0.1822502 0.9073157 -0.3788971 0.3478497 0.4213028 -0.8375588 0.2872215 0.5983967 -0.7479473 0.1185507 0.9404402 -0.3186193 0.2204867 0.4957903 -0.8399868 0.2392411 0.6399523 -0.7302224 0.1563894 0.8226356 -0.546638 0.1657571 0.511525 -0.8431292 0.1136902 0.835104 -0.5382156 0.1507068 0.1979528 -0.9685568 0.115471 0.6541967 -0.7474578 0.07962894 0.6498082 -0.7559158 0.04557955 0.4024448 -0.9143089 0.02460408 0.960866 -0.2759192 0.0369938 0.4741688 -0.8796564 0.01649779 0.929691 -0.367971 0.02786898 0.4855459 -0.873767 -0.03867071 0.7688677 -0.6382376 -0.08491128 0.3462324 -0.9342983 -0.02065426 0.8818814 -0.4710187 -0.1040918 0.444607 -0.889657 -0.07938295 0.6909422 -0.7185383 -0.1958833 0.3536036 -0.9146553 -0.1266341 0.7895537 -0.6004738 -0.0526899 0.9504502 -0.3063796 -0.2130708 0.4422323 -0.8712242 -0.1686798 0.7322999 -0.6597605 -0.1923067 0.761955 -0.6184197 -0.1462417 0.904081 -0.4015606 -0.3208473 0.3302165 -0.8877016 -0.3209547 0.3298175 -0.887811 -0.03974986 0.9860701 -0.1615108 -0.2786905 0.6269425 -0.7275128 -0.4105405 0.2471691 -0.8777039 -0.3079739 0.7009681 -0.6432697 -0.2104967 0.8720976 -0.4417432 -0.3828399 0.5902172 -0.7106878 -0.48892 0.3939095 -0.7783268 -0.4031137 0.5813243 -0.7067967 -0.1798166 0.9322718 -0.3139032 -0.347126 0.7991783 -0.4907318 -0.5703228 0.3095414 -0.7608654 -0.5584366 0.340648 -0.7563779 -0.3796985 0.7819293 -0.4943842 -0.4182823 0.7614012 -0.4952859 -0.3816756 0.7911249 -0.4779593 -0.6322769 0.3422791 -0.6950331 -0.6209886 0.4213539 -0.6609342 -0.2095035 0.9526466 -0.2203926 -0.7085397 0.3601965 -0.6068196 -0.6494921 0.4756123 -0.5932564 -0.4638955 0.7859972 -0.4086681 -0.4709573 0.779626 -0.4127743 -0.2605414 0.9359445 -0.2369096 -0.7510874 0.3524825 -0.5582327 -0.7199291 0.4851108 -0.4963563 -0.5206092 0.7665282 -0.3760327 -0.1695755 0.9779794 -0.1216571 -0.4729657 0.8246201 -0.3103307 -0.3299744 0.9212355 -0.2060149 -0.8256598 0.3254135 -0.4608601 -0.7480041 0.4902346 -0.4473926 -0.6562272 0.6574538 -0.3702976 -0.8351313 0.3984984 -0.3791503 -0.7487609 0.5770481 -0.3261483 -0.6537687 0.6899071 -0.3108293 -0.3978051 0.9022461 -0.1664428 -0.9229058 0.1336302 -0.3610927 -0.3991608 0.9014262 -0.1676352 -0.2647632 0.9593991 -0.09723174 -0.840717 0.4653457 -0.2768543 -0.7766512 0.5691778 -0.2699065 -0.6527003 0.729058 -0.2060507 -0.8868124 0.4064228 -0.2199647 -0.7997602 0.5782247 -0.1613684 -0.6356071 0.756971 -0.1516532 -0.4948807 0.8625804 -0.105111 -0.9267857 0.3628933 -0.09683436 -0.8293172 0.5481332 -0.1085503 -0.428537 0.9016422 -0.05828708 -0.6742349 0.7369445 -0.04816913 -0.5247973 0.8501999 -0.04180914 -0.9562264 0.2914131 -0.02663916 -0.9066048 0.4218046 0.01220321 -0.8104481 0.585689 0.01193034 -0.9600102 0.2695805 0.07554399 -0.3422043 0.9392867 0.02523356 -0.3428255 0.9390554 0.02541214 -0.797304 0.5899446 0.1275609 -0.7028583 0.7081746 0.0669251 -0.7982441 0.5904383 0.1191183 -0.8989561 0.385702 0.2076343 -0.5087876 0.848842 0.1435359 -0.8521336 0.458519 0.252247 -0.5281732 0.8395022 0.1275514 -0.8619633 0.416767 0.2886602 -0.4022589 0.9061528 0.1306711 -0.8215923 0.4751654 0.3149666 -0.600758 0.7575581 0.2553344 -0.4201065 0.895288 0.1482223 -0.8388379 0.3936079 0.3760636 -0.7823732 0.4768589 0.4006217 -0.6118615 0.7275507 0.3103151 -0.8062328 0.3683443 0.4629376 -0.4546915 0.8467505 0.2761693 -0.2884865 0.9447419 0.1556864 -0.6466054 0.5985636 0.4728882 -0.4770318 0.8151311 0.3286364 -0.6822484 0.4909815 0.5417328 -0.6675645 0.4541124 0.5900336 -0.2960296 0.9192752 0.2594221 -0.6455087 0.4876621 0.587796 -0.3754952 0.8411633 0.389163 -0.5967147 0.346462 0.7238065 -0.5813111 0.4483047 0.6790436 -0.4333578 0.7308685 0.5272877 -0.3700838 0.8380634 0.4008589 -0.4964815 0.4470405 0.744084 -0.1802335 0.9533551 0.2421364 -0.382282 0.7379155 0.5561845 -0.3246948 0.8011216 0.5027698 -0.2531329 0.8825052 0.396369 -0.4952802 0.3802753 0.7810814 -0.3900298 0.3482635 0.8524021 -0.3882215 0.4978787 0.7755006 -0.3405469 0.640677 0.6881576 -0.1236854 0.9531128 0.2761849 -0.3095588 0.413472 0.8562794 -0.2512237 0.6315262 0.7335267 -0.217679 0.7927244 0.5693892 -0.187323 0.8446333 0.5015025 -0.289206 0.1797536 0.9402386 -0.1702522 0.4911417 0.8542799 -0.1594155 0.5981912 0.785337 -0.1610823 0.5919811 0.7896904 -0.1032328 0.8667886 0.4878736 -0.1432076 0.2931868 0.9452689 -0.08242619 0.8935494 0.441334 -0.06568163 0.7014133 0.7097221 -0.03808492 0.863398 0.5030842 -0.05290204 0.3779966 0.9242943 -0.04044383 0.4413463 0.8964251 -0.03185653 0.8714768 0.4894011 0.001523137 0.9794171 0.2018409 0.0284897 0.476727 0.8785896 0.04749798 0.5554878 0.8301671 0.02368479 0.8204119 0.5712823 0.04627561 0.8818271 0.4692968 0.1446192 0.4410845 0.8857368 0.1209573 0.5477509 0.8278517 0.1225879 0.731859 0.6703391 0.07893818 0.8662737 0.4932938 0.2295582 0.3069507 0.9236257 0.07424145 0.948926 0.3066394 0.260859 0.6220383 0.7382554 0.3250128 0.4236912 0.8454894 0.2438774 0.6037507 0.7589526 0.2220918 0.7709445 0.5969255 0.1559433 0.8899865 0.4284925 0.3898225 0.4341284 0.8121398 0.3901263 0.4448875 0.8061494 0.2932951 0.7269968 0.6208491 0.1243044 0.9620396 0.2429574 0.2741056 0.8273634 0.4902408 0.2058839 0.9101317 0.3595445 0.4571232 0.4326968 0.7770534 0.4390904 0.5948696 0.6732977 0.4933826 0.5788565 0.6492294 0.4936971 0.6192355 0.6105822 0.385115 0.8106992 0.4409686 0.278194 0.9007261 0.3336175 0.6181854 0.4161963 0.6668039 0.6730346 0.4258457 0.6047148 0.6730105 0.425862 0.6047301 0.09231352 0.9919751 0.08639252 0.4645718 0.781788 0.4159097 0.4225288 0.8368955 0.3479593 0.7481541 0.3894585 0.5372035 0.2478963 0.9488363 0.1955943 0.7432184 0.4123264 0.5268903 0.5779669 0.7174534 0.3888639 0.5638445 0.7500169 0.3457658 0.353579 0.9152718 0.1930273 0.8219936 0.3734818 0.4299278 0.8075512 0.4212033 0.4128547 0.7238693 0.5851497 0.3655313 0.3249971 0.9317988 0.161642 0.6543343 0.6993274 0.287729 0.4136857 0.8920373 0.1820266 0.8973366 0.27272 0.3470028 0.861648 0.4145783 0.2927244 0.7462078 0.6127766 0.2601518 0.9241237 0.2907609 0.2478983 0.6563207 0.7297255 0.1916871 0.4648184 0.8749384 0.1357446 0.886347 0.4214908 0.1916629 0.7596905 0.6287246 0.1660598 0.3733813 0.9236465 0.08639192 0.6420532 0.760447 0.0974068 0.9483025 0.2880392 0.1332507 0.1986894 0.97938 0.03657317 0.9354252 0.3520039 0.03275668 0.8962155 0.4368091 0.07743161 0.6812281 0.7293473 0.06309533 0.6223724 0.7821435 0.03007131 0.4599523 0.8879338 0.004187583 -0.009727954 0.9999061 0.009657263 -0.01115792 0.9998674 0.01186001 -0.0111618 0.999862 0.01231521 -0.009544372 0.9999375 0.005830287 -0.005512952 0.9999368 0.009802043 -0.007120013 0.9999595 0.005491971 -0.005780935 0.9998722 0.01490861 -0.0080024 0.9999652 0.002402305 -0.004185318 0.9999259 0.01143038 -0.003524541 0.9999023 0.01353132 -0.009425759 0.9999528 0.002361595 -0.009849607 0.9999509 0.001079499 -5.65628e-4 0.9999468 0.01030331 1.29947e-4 0.9999279 0.0120114 -0.0171808 0.999852 -9.55226e-4 -0.01665556 0.9998602 -0.001509547 0.001513421 0.9999493 0.009966611 -0.01391148 0.9999033 2.72296e-4 0.00334084 0.9999206 0.01216369 -0.01227939 0.9999162 -0.004121184 -0.01082611 0.999937 -0.002972722 0.002498924 0.9999598 0.008619129 0.004293322 0.9999377 0.01031219 -0.007936239 0.9999573 -0.004748165 -0.005714178 0.9999824 -0.001667916 0.002863824 0.9999886 0.003816723 -0.001231431 0.9999986 -0.001232683 0.004853904 0.9999795 0.004190385 0.005237936 0.9999752 0.004725873 -0.00649482 0.9998415 -0.01658004 -0.009509861 0.9998346 -0.01550501 -0.009115397 0.9998707 -0.01325744 0.00619769 0.9999806 6.06711e-4 0.01097398 0.9999271 0.005054652 -0.00482887 0.9998961 -0.01358604 -0.005031406 0.9999258 -0.01109433 0.01297152 0.9999092 0.003668487 -4.76017e-4 0.9999951 -0.003113508 0.007210016 0.9999735 0.001021504 7.2423e-5 0.9999954 -0.003065228 0.007654666 0.9999707 -7.17611e-5 0.005689501 0.9998477 -0.01650077 0.004849433 0.9999882 -4.87697e-4 0.004740774 0.9998139 -0.01870357 0.004071235 0.9999911 -0.001193284 -0.001432955 0.9999016 -0.01395756 0.003028631 0.9999954 -1.88694e-4 0.002499997 0.9999833 -0.00522685 0.00197345 0.9999975 -0.001117169 0.005063652 0.9999654 -0.006602704 0.00522983 0.9999587 -0.007437229 0.006617069 0.9999583 -0.006304919 0.006669878 0.9999579 -0.006305634 -0.1204852 -0.5287685 -0.8401709 -0.1439133 -0.4641787 -0.8739721 -0.1048126 -0.8000763 -0.5906711 -0.06375348 -0.8935758 -0.4443624 -0.2045308 -0.6064773 -0.7683441 -0.3098599 -0.5504276 -0.7752525 -0.3067788 -0.5078516 -0.8049682 -0.1337843 -0.9267534 -0.3510413 -0.4161857 -0.5606945 -0.715829 -0.2647737 -0.8085908 -0.5254293 -0.4233185 -0.4849287 -0.765275 -0.2176674 -0.9005226 -0.3764043 -0.4804423 -0.5979228 -0.6416102 -0.6326263 -0.399277 -0.6635976 -0.5307867 -0.5928199 -0.605665 -0.3025538 -0.9055718 -0.2973232 -0.6232748 -0.324215 -0.7116271 -0.5628744 -0.5756326 -0.5931437 -0.7469799 -0.3105213 -0.5878756 -0.5442501 -0.7599565 -0.355328 -0.7409309 -0.5062141 -0.4413262 -0.6110868 -0.7015329 -0.3666396 -0.899982 -0.1811599 -0.3965017 -0.5737656 -0.7543094 -0.3190772 -0.1951175 0.9760113 -0.09659868 -0.7936573 -0.5526008 -0.2544417 -0.4603105 -0.8711377 -0.1709779 -0.7683182 -0.5959249 -0.2335823 -0.8496304 -0.5202692 -0.08630234 -0.7985308 -0.5942236 -0.09616065 -0.3317354 -0.9433422 -0.007576465 -0.8970623 -0.4415112 -0.01863008 -0.4781843 -0.8739383 0.08701556 -0.8731702 -0.4664146 0.1415317 -0.8833835 -0.4445173 0.1484524 -0.7278161 -0.6779763 0.1031113 -0.4780033 -0.8730103 0.09677696 -0.9068924 -0.2881311 0.3074522 -0.6017984 -0.7809189 0.1673455 -0.3303789 0.9389566 0.09597134 -0.6688427 -0.7026703 0.2427012 -0.8596282 0.2324525 0.4549782 -0.5240911 -0.8063768 0.2740162 -0.6204615 -0.6320061 0.464323 -0.4279968 -0.8584575 0.282612 -0.6174986 -0.6351935 0.4639233 -0.6554458 -0.4449803 0.6102323 -0.2904057 -0.9185109 0.2683325 -0.3408107 -0.8548166 0.3913266 -0.530006 -0.5618155 0.6351827 -0.5404674 -0.4637421 0.7020244 -0.2436469 -0.9165779 0.3170505 -0.4596658 -0.5798246 0.6726893 -0.3820052 -0.5246261 0.760815 -0.2237029 -0.8561731 0.4657517 -0.3800435 -0.4257454 0.8211625 -0.18805 -0.8924614 0.4100611 -0.2460016 -0.5982652 0.7626022 -0.2002029 -0.422388 0.884029 -0.1813896 -0.4931321 0.8508341 -0.1583652 -0.73076 0.6640108 -0.05886363 -0.9396159 0.3371306 -0.0189799 -0.4182343 0.9081409 -0.04610061 0.5514522 0.8329317 -0.0241366 -0.4601426 0.8875169 0.004423916 -0.8138262 0.5810916 -0.001437067 -0.8540382 0.5202082 0.0877906 -0.621878 0.7781777 0.1816125 -0.4227761 0.8878499 0.07517093 -0.936648 0.3421111 0.2551736 -0.5860499 0.7690463 0.1909813 -0.8249575 0.5319507 0.3283077 -0.4824414 0.8120742 0.3299273 -0.5091418 0.7949356 0.1687263 -0.8974916 0.4074804 0.4751219 -0.4756855 0.7402585 0.4739785 -0.4903333 0.7313807 0.333429 -0.8236773 0.458673 0.5677388 -0.5071383 0.648447 0.5423443 -0.1369345 0.828922 0.6408668 -0.3685999 0.6733676 0.290743 -0.9083167 0.3007145 0.6426516 -0.5495152 0.533884 0.8154093 -0.2411528 0.5262632 0.5178418 -0.7707477 0.3711981 0.4287842 -0.8560338 0.2887049 0.7737447 -0.5187737 0.3635835 0.8422111 -0.3913549 0.3708394 0.1608476 0.9830092 0.08843678 0.6029536 -0.7612158 0.2387419 0.4480813 -0.8723567 0.195492 0.7752798 -0.577735 0.2552715 0.8644938 -0.4803154 0.1481474 0.9426735 -0.307388 0.1299214 0.3735419 -0.9259097 0.05619347 0.8458953 -0.528788 0.06960171 0.686749 -0.7261203 0.03354334 0.9112573 -0.3990614 -0.1017849 0.8193513 -0.5702359 -0.0591163 0.3771432 -0.9253828 -0.03781455 0.8840384 -0.420965 -0.203137 0.3685335 -0.926958 -0.0702269 0.7972443 -0.5498005 -0.2492411 0.8564129 -0.3962925 -0.3309218 0.6138689 -0.7529931 -0.2369947 0.4667835 -0.8693402 -0.1623603 0.7194145 -0.5981973 -0.3529912 0.7327477 -0.4867711 -0.4755363 0.7522309 -0.4531385 -0.4783453 0.3466048 -0.9092227 -0.2306064 0.5150793 -0.7485705 -0.4175353 0.6168015 -0.551138 -0.5619634 0.5620351 -0.698565 -0.4428585 0.4106929 -0.7761261 -0.4784974 0.4184412 -0.6599242 -0.6240249 0.5210356 -0.501071 -0.6909774 0.3781777 -0.5773916 -0.7236025 0.5334146 -0.02395075 -0.8455148 0.1998578 -0.8964074 -0.395614 0.3583761 -0.4602333 -0.8122511 0.2442547 -0.6017243 -0.760439 0.08951771 -0.910471 -0.4037689 0.2278097 -0.499485 -0.8358334 0.1114282 -0.6393494 -0.7607998 0.1046685 -0.6573927 -0.7462435 0.02722048 -0.431228 -0.9018324 0.007938504 -0.5118338 -0.8590478 0.02641725 -0.9161784 -0.3998994 -0.04216474 3.27118e-4 0.9991106 -0.07656019 -4.12887e-4 0.9970649 -0.2006733 7.75525e-5 0.9796583 -0.197271 1.56943e-4 0.980349 -0.366487 -1.62013e-4 0.9304233 -0.3333475 5.23138e-4 0.942804 -0.4486856 2.88611e-4 0.8936897 -0.4782072 -3.01341e-4 0.8782471 -0.5403189 6.43734e-4 0.8414602 -0.6290878 -2.17048e-4 0.7773342 -0.6563381 3.26578e-4 0.7544668 -0.7114701 -6.79747e-4 0.7027161 -0.7673053 5.29728e-4 0.6412818 -0.8137792 4.35823e-4 0.581174 -0.8681326 -0.002748489 0.4963248 -0.8833267 -2.23172e-4 0.4687581 -0.8918411 1.64126e-4 0.4523489 -0.9566532 -6.91242e-4 0.2912288 -0.9454084 3.56306e-4 0.3258882 -0.9814474 -1.64052e-4 0.1917317 -0.9878258 8.18288e-4 0.1555624 -0.9998942 -1.3443e-4 0.01454603 -0.9996704 1.81319e-4 0.02567321 -0.9917006 5.02869e-4 -0.1285681 -0.9854152 -4.10295e-4 -0.1701672 -0.9601229 5.55786e-4 -0.2795781 -0.9435473 -5.96115e-4 -0.3312375 -0.9111554 4.59735e-4 -0.412063 -0.8689584 -2.64877e-4 -0.494885 -0.8582298 2.24238e-4 -0.5132657 -0.791736 2.36412e-4 -0.6108633 -0.7710464 -6.18339e-4 -0.6367789 -0.688763 1.66176e-4 -0.7249866 -0.6604676 -5.23739e-4 -0.7508545 -0.5866032 3.0525e-4 -0.8098745 -0.5557571 -2.10689e-4 -0.8313449 -0.4958934 4.21235e-4 -0.8683833 -0.4464902 -3.53861e-4 -0.8947885 -0.37151 3.51765e-4 -0.928429 -0.3040161 -6.83446e-4 -0.9526666 -0.2627903 1.1531e-4 -0.9648529 -0.1294425 -1.80841e-5 -0.991587 -0.1174115 -3.93025e-4 -0.9930833 0.008913516 -5.08889e-5 -0.9999603 0.01902538 -2.80247e-4 -0.999819 0.1414877 4.10034e-4 -0.9899399 0.1669877 -1.56087e-4 -0.9859589 0.2951939 -1.99548e-4 -0.9554374 0.3186962 4.90241e-4 -0.9478568 0.4645233 -4.57371e-4 -0.8855608 0.4674559 -5.61388e-4 -0.8840162 0.5444474 2.74897e-4 -0.838795 0.6709154 -0.001377522 -0.7415328 0.650901 -4.10415e-4 -0.7591625 0.7732523 -4.87909e-4 -0.6340984 0.7335175 8.75791e-4 -0.6796701 0.8411509 -1.84596e-4 -0.5408006 0.8264576 4.86388e-4 -0.5629987 0.8999175 1.40334e-4 -0.4360603 0.9022996 -2.4831e-6 -0.4311096 0.9406574 -1.48458e-4 -0.3393577 0.9592219 9.59466e-4 -0.2826529 0.9836593 -3.99932e-4 -0.1800395 0.9942895 6.09362e-4 -0.1067151 0.9991546 -5.92665e-4 -0.04110729 0.9994129 4.43523e-4 0.03426182 0.9901823 -9.93074e-4 0.1397781 0.9788183 4.92374e-4 0.2047308 0.9473383 -7.09584e-5 0.3202347 0.9550634 4.67464e-4 0.2964013 0.8873668 5.84025e-4 0.4610639 0.892871 9.48644e-4 0.4503117 0.8367456 -4.94135e-4 0.5475916 0.7790437 8.88547e-4 0.6269692 0.7460739 -2.52386e-4 0.6658632 0.6429959 -8.1287e-5 0.7658696 0.662114 4.64777e-4 0.7494031 0.5337803 -1.19096e-4 0.8456233 0.5593183 8.06104e-4 0.8289527 0.4356303 -3.80422e-4 0.9001256 0.4088138 2.40835e-4 0.9126178 0.2850815 -1.27345e-4 0.9585034 0.2692023 -5.55133e-4 0.9630836 0.1375849 7.5806e-4 0.9904897 0.06921952 -7.74019e-4 0.9976012 0.006223678 -0.9999703 -0.004553616 0.002794444 -0.9999912 -0.003122866 -0.00217694 -0.9999933 0.00295335 -0.00452882 -0.9999817 0.00401169 4.29734e-4 -0.9999997 7.18605e-4 4.78387e-4 -0.9999998 6.41248e-4 0.001397311 -0.9999991 5.46353e-5 8.88769e-4 -0.9999997 -1.79754e-5 -0.001903295 -0.9999982 -2.96896e-4 -0.004842281 -0.9999783 -0.004494071 -0.002950668 -0.9999927 -0.002441823 0.003416955 -0.9999939 -7.96225e-4 -0.002425372 -0.999997 5.86298e-4 -0.002176821 -0.9999976 -3.16271e-4 -1.89917e-4 -0.9999997 -8.22655e-4 -0.002480506 -0.9999917 -0.0032503 -0.001383781 -0.9999986 9.77307e-4 -0.002393186 -0.999992 -0.003217637 0.003098785 -0.9999921 0.002476811 8.53292e-5 -0.9999999 5.48285e-4 -2.19213e-4 -0.9999991 -0.001424193 0.002485394 -0.9999813 0.005586981 -3.39894e-5 -1 4.06999e-4 1.69857e-4 -0.9999954 0.00306636 -0.001423001 -0.9999951 -0.002803266 -5.13318e-4 -0.9999999 -4.4653e-4 0.002557992 -0.9999967 3.26257e-5 1.23112e-4 -1 4.58848e-4 -8.60835e-5 -1 3.4613e-4 2.74845e-4 -0.9999998 -7.07772e-4 -0.001825034 -0.9999983 -4.40435e-4 6.63537e-4 -0.9999998 3.87307e-4 5.02209e-4 -0.9999995 -8.5979e-4 8.10385e-4 -0.9999997 -2.55377e-4 -0.003201723 -0.9999882 0.003654778 -1.51492e-4 -0.9999917 -0.004076063 0.001160442 -0.9999991 7.70636e-4 0.001545965 -0.9999986 -6.79996e-4 -0.002226293 -0.9999876 0.004490256 -0.02392232 0.242026 0.9699749 -0.02940064 0.8170296 0.5758458 -0.07058644 0.4656013 0.8821752 -0.07580035 0.721885 0.6878492 -0.2194235 0.3957074 0.8917787 -0.0436148 -0.9700558 0.2389345 -0.1110616 0.7809961 0.6145817 -0.2889088 0.5865162 0.7566575 -0.115828 0.9139209 0.3890147 -0.2863398 0.4395157 0.8513727 -0.1757231 0.9339962 0.3110832 -0.4629852 0.4244248 0.7781442 -0.3200279 0.7049027 0.6330043 -0.3737635 0.7776678 0.5055035 -0.5827404 0.2980111 0.7560444 -0.4416614 0.6490213 0.6194407 -0.4106147 0.7823172 0.4683753 -0.5999806 0.5352644 0.5945716 -0.1212552 -0.9832154 0.1363256 -0.4908412 0.7344413 0.4686905 -0.7041348 0.3442968 0.6210104 -0.3889455 0.8735328 0.2926806 -0.6607116 0.6025215 0.4476919 -0.7716951 0.4918698 0.4031763 -0.6522169 0.6573122 0.377563 -0.5526324 0.775815 0.3044808 -0.7361259 0.6261186 0.2570878 -0.6868157 0.6933658 0.2180095 -0.5604752 0.8281589 -0.004534125 -0.7628805 0.6305489 0.1429042 -0.8334064 0.5442415 0.09610003 -0.5216275 0.8524541 0.03502798 -0.6082752 0.7936391 -0.01176679 -0.5697438 0.8066545 -0.1571643 -0.7153812 0.6927998 -0.09087544 -0.8515593 0.460861 -0.2499082 -0.6412906 0.7515813 -0.1545062 -0.5389734 0.8309681 -0.1378393 -0.7483581 0.6056408 -0.27048 -0.8007403 0.5091871 -0.3155056 -0.4103316 0.8873803 -0.2102012 -0.8428579 0.2666927 -0.4674029 -0.5427057 0.7602919 -0.3569689 -0.5239633 0.7975631 -0.2989238 -0.7482434 0.2988324 -0.59231 -0.6445395 0.5454362 -0.5357875 -0.2849403 0.9371345 -0.2014646 -0.6445519 0.5451834 -0.5360298 -0.3885527 0.8386458 -0.3817065 -0.5722036 0.5027471 -0.6479417 -0.5751568 0.497777 -0.6491633 -0.2326489 0.9335008 -0.2728569 -0.4569747 0.5213829 -0.7206484 -0.4566749 0.5289721 -0.7152879 -0.1835433 0.9379919 -0.2940803 -0.352239 0.6378142 -0.684924 -0.3032501 0.6933326 -0.6537043 -0.288269 0.5072722 -0.8121429 -0.2692318 0.5380671 -0.7987479 -0.2653006 0.7601499 -0.593117 -0.2611367 0.3764789 -0.8888595 -0.1146895 0.8455299 -0.521465 -0.1148043 0.5208232 -0.8459097 -0.101126 0.7375308 -0.667699 -0.04175901 0.8807608 -0.4717168 -0.07893717 0.3892059 -0.9177624 0.04221284 0.5025315 -0.8635278 0.04483115 0.4941524 -0.8682187 0.04217755 0.9260084 -0.3751397 0.1276108 0.6396338 -0.7580132 0.2574461 0.4155248 -0.872388 0.1659339 0.7181625 -0.6758021 0.254725 0.5222052 -0.81389 0.148834 0.812646 -0.5634315 0.3953071 0.5231424 -0.7550196 0.3071844 0.7791995 -0.5463388 0.4026994 0.5056421 -0.7629938 0.2658421 0.8260284 -0.4969961 0.5520043 0.3515179 -0.7561261 0.2454941 0.9109932 -0.3313974 0.539641 0.5559954 -0.6321842 0.3883991 0.838677 -0.3817946 0.7301704 0.2742216 -0.6258225 0.4226824 0.7946833 -0.4356813 0.6528874 0.5893225 -0.4758542 0.5736019 0.7396349 -0.3520243 0.7605813 0.5168578 -0.3929049 0.6760409 0.6195988 -0.3988311 0.4626536 0.8504002 -0.2505423 0.7224349 0.6024535 -0.3393193 0.7544358 0.6131644 -0.2342137 0.7593248 0.6073197 -0.2336424 0.3393492 0.9374723 -0.07738101 0.8777264 0.4364269 -0.1978085 0.5935695 0.8007619 -0.08034813 0.8873052 0.4595924 -0.03826618 0.8955275 0.4429804 -0.04241651 0.9664815 -0.2028217 -0.1574069 0.6553215 0.7551075 -0.01914501 0.4079742 0.912063 -0.04121041 0.5483397 0.8335993 0.06660121 0.8793082 0.45326 0.1461932 0.6444797 0.7625435 0.0563333 0.7422428 0.6256222 0.240151 0.5034382 -0.8594434 0.0889219 0.4981736 0.8584124 0.1222757 0.7075473 0.6605358 0.2511365 0.7724217 0.5424148 0.3303802 0.320582 0.9320321 0.168948 0.7121718 0.61801 0.332979 0.6056153 0.7088739 0.3615634 0.7699826 0.4145595 0.4850435 0.5827081 0.6847078 0.4377515 0.4097303 0.8741441 0.2607547 0.6362274 0.4981925 0.5890832 0.6269201 0.5338062 0.5674699 0.2873452 0.9091452 0.301476 0.6372825 0.2393043 0.732533 0.5741381 0.4394921 0.6908054 0.384653 0.7351855 0.5581617 0.443079 0.5366086 0.718145 0.3093129 0.858622 0.408771 0.3821807 0.5010403 0.7764641 0.4006207 0.4613284 0.7916308 0.1914489 0.911201 0.3647741 0.2069198 0.8120442 0.5456817 0.2811521 0.4251027 0.8603727 0.2184934 0.799028 0.5601918 0.2059459 0.5873562 0.782687 0.2036564 0.5431349 0.8145726 0.107151 0.7972904 0.5940091 0.1105704 0.7175754 0.6876481 0.04854011 0.6658102 0.7445406 0.08617782 0.4872192 0.8690172 0.08966696 0.7740294 0.6267681 0.002658724 0.9999782 0.006047725 -0.001385867 0.9999849 -0.005343496 -0.00412929 0.9999901 -0.001691579 0.003635525 0.9999917 0.001892089 -0.002114832 0.9999964 -0.001706421 0.005995333 0.9999799 0.002117037 -8.05433e-5 0.9999978 0.002107262 -4.68587e-4 0.9999951 -0.00311619 -0.006150186 0.9999809 -5.58275e-4 -1.72545e-4 0.9999998 6.47961e-4 5.72676e-4 0.9999997 -6.81469e-4 1.91196e-4 0.9999992 0.001247763 0.005274653 0.999985 -0.001464128 0.004453957 0.9999887 -0.001733958 -0.001469433 0.9999854 -0.005212366 -0.004843711 0.9999871 0.001535773 -0.002339363 0.9999954 0.001945018 -0.004036307 0.9999907 0.00156933 -1.68251e-4 1 -2.44374e-4 6.19515e-4 0.9999998 6.23636e-5 3.50151e-4 0.9999999 3.88025e-4 -9.53672e-5 1 -4.23367e-4 2.91792e-4 0.9999998 -6.82231e-4 -5.46025e-4 0.9999995 9.23399e-4 8.4062e-4 0.9999958 -0.002752482 0.003545701 0.9999754 -0.006069958 -0.001251995 0.9999992 -1.10888e-4 8.46286e-4 0.9999992 9.90859e-4 -5.61872e-4 0.9999985 0.001664996 -0.001246035 0.9999992 -3.31251e-4 -7.44346e-4 0.9999981 0.001822113 5.64662e-4 0.9999895 -0.004546165 6.95806e-4 0.9999951 -0.003065049 -0.001017332 0.9999917 0.003965795 0.007477104 0.9999695 0.002304494 -0.005829989 0.9999697 -0.00516498 -0.005857884 0.9999707 -0.004936337 -0.002375662 0.9999955 -0.001837372 -0.002728402 0.9999663 0.007743537 -0.002467632 0.9999967 7.87424e-4 -0.002671003 0.9999946 -0.001908183 8.8994e-4 0.9999924 0.003830969 -2.72181e-4 1 2.75058e-4 -0.9962213 0.01031267 -0.08623689 -0.9580277 -0.0135374 -0.286356 -0.9365481 0.008955836 -0.3504248 -0.816286 -0.003380596 -0.5776381 -0.817178 -0.002770423 -0.5763788 -0.6293829 0.002943158 -0.7770898 -0.6238851 -7.63877e-5 -0.7815162 -0.310299 0.0107305 -0.9505785 -0.3425422 -0.004150629 -0.9394933 -0.03366988 -0.01238352 -0.9993563 0.02543258 0.009353995 -0.9996328 0.2875853 -0.003375947 -0.9577491 0.3102909 -0.01273512 -0.9505563 0.5149636 0.01552909 -0.8570714 0.6293166 -0.01532751 -0.776998 0.7277957 0.01532846 -0.6856228 0.8161853 -0.0155307 -0.5775815 0.9215299 0.01169562 -0.3881314 0.9414572 -0.007978975 -0.3370382 0.996513 0.01290345 -0.08243495 0.9995058 -0.02221119 0.02224785 0.9781906 0.01845961 0.206888 0.9194698 -0.01334518 0.3929342 0.8856704 0.01008886 0.4642049 0.7838327 -0.01181906 0.6208596 0.6839498 0.01532346 0.7293682 0.6338837 -0.005417883 0.7734094 0.3955495 0.001264035 0.9184439 0.4148021 -0.007971763 0.9098768 0.2097569 0.01027166 0.9776996 0.1154361 -0.01391798 0.9932175 -0.07783699 0.01085329 0.9969071 -0.1357944 -0.005259275 0.9907231 -0.3272799 0.003598928 0.9449206 -0.3624939 -0.006393074 0.9319643 -0.5292896 0.01036119 0.8483781 -0.6231392 -0.01899886 0.7818803 -0.7499854 0.02125155 0.6611129 -0.8558071 -0.01821756 0.5169742 -0.9225224 0.01397454 0.3856906 -0.9618475 -0.01071047 0.2733765 -0.9914675 0.009553074 0.1300042 -0.9998748 -0.01099967 0.01138222 0.9962256 0.009909272 0.08623439 0.9731624 -0.01218634 0.2297967 0.9365131 0.01228463 0.3504176 0.8783807 -0.01385867 0.477761 0.8114143 0.0149573 0.58428 0.6742807 -0.01629704 0.7382953 0.6032971 0.01445388 0.7973856 0.3732913 -0.01641017 0.927569 0.3101574 0.01064515 0.9506257 -0.008899986 -0.004720926 0.9999493 0.008899986 0.004720926 0.9999493 -0.2940209 -0.009856283 0.9557483 -0.3579112 0.01264023 0.9336702 -0.5469384 -0.01233249 0.8370821 -0.617487 0.01560789 0.7864263 -0.800312 -0.01781803 0.5993191 -0.8503226 0.01386117 0.5260793 -0.944068 -0.008748948 0.3296349 -0.9610454 0.005323648 0.2763397 -0.9975998 0.005265474 0.06904298 -0.9940499 -0.004805028 0.1088206 -0.9892632 -0.007389843 -0.1459587 -0.9854032 0.001104772 -0.1702333 -0.91614 0.007077038 -0.4007961 -0.8995898 -0.007957458 -0.4366632 -0.740626 8.89452e-4 -0.671917 -0.7437685 -0.001166939 -0.6684364 -0.5472193 0.006939411 -0.8369605 -0.4901432 -0.01455926 -0.8715204 -0.297277 0.0145359 -0.9546807 -0.2118883 -0.009913086 -0.9772437 0.002674043 0.00110656 -0.9999958 0.01405775 0.005826294 -0.9998843 0.2740499 0.001111388 -0.9617149 0.3157699 -0.0135414 -0.9487392 0.4885104 0.01659697 -0.8724002 0.6403074 -0.01970523 -0.767866 0.7252337 0.01652723 -0.6883044 0.8548034 -0.01541262 -0.5187231 0.9111623 0.01548081 -0.4117569 0.9611607 -0.01265215 -0.2756993 0.9906815 0.01055848 -0.1357897 0.9997574 -0.009540438 -0.01985502 0.9126971 0.4083675 -0.01483744 0.8905725 0.4539204 -0.02893245 0.574877 0.8181425 -0.01262706 0.5911053 0.8064181 -0.01686578 0.9221658 0.3650321 -0.1279131 0.881632 0.4607564 -0.1021209 0.7200173 0.6862041 -0.1034363 0.8918203 0.4013378 -0.2087695 0.2053573 0.9780604 -0.03501886 0.6486459 0.7452822 -0.1543145 0.6394021 0.7530933 -0.1549695 0.9385123 0.2219675 -0.2644338 0.2450774 0.9681717 -0.05080217 0.6398483 0.7379521 -0.2145249 0.8336399 0.4410417 -0.3324558 0.8419901 0.3902323 -0.3725207 0.4437269 0.8720698 -0.2063995 0.8148396 0.4287024 -0.3901932 0.2455759 0.9630684 -0.1104173 0.8198692 0.3095245 -0.4816732 0.523886 0.8039789 -0.2813567 0.750163 0.4374973 -0.4958343 0.09265232 0.9942663 -0.05338674 0.5243757 0.7796258 -0.3423651 0.4805032 0.8083879 -0.3400378 0.7292407 0.3851712 -0.565554 0.6615275 0.4994227 -0.5594267 0.3290976 0.9077002 -0.2603368 0.6390045 0.4963786 -0.5876067 0.3060525 0.9047158 -0.2963465 0.5189431 0.6435066 -0.5626699 0.5608752 0.4320819 -0.7062042 0.519613 0.6459864 -0.5591993 0.1668388 0.9656746 -0.1990918 0.5119104 0.4651994 -0.7221755 0.378544 0.7160408 -0.5865067 0.3503621 0.7900068 -0.503126 0.5061197 0.2712525 -0.8186972 0.2035511 0.9362367 -0.2864048 0.4038217 0.4366679 -0.8038964 0.356232 0.7090107 -0.6086071 0.4055394 0.4403716 -0.801006 0.1871755 0.8910029 -0.4136173 0.1316066 0.9582193 -0.2539598 0.284488 0.4628515 -0.8395447 0.2880843 0.5509507 -0.7832374 0.1809773 0.8309472 -0.5260932 0.1583356 0.847716 -0.506268 0.2319927 0.3954657 -0.8886992 0.1216438 0.8227784 -0.5551924 0.1450045 0.5319141 -0.8342909 0.1341704 0.5148654 -0.8467066 0.05568683 0.5826561 -0.8108088 0.05382913 0.8940829 -0.4446554 0.03646254 0.9242946 -0.3799342 0.04055649 0.5638667 -0.8248695 -0.005251049 0.5924977 -0.8055551 -0.05114233 0.4617291 -0.8855454 -0.03135257 0.8121417 -0.5826174 -0.01543724 0.9225811 -0.3854944 -0.02130454 0.9105998 -0.4127399 -0.1094223 0.4177652 -0.9019419 -0.1575514 0.5237681 -0.8371647 -0.1240606 0.7148291 -0.6882066 -0.2215242 0.4133623 -0.8832094 -0.01025342 0.9983607 -0.05631119 -0.2635591 0.456188 -0.8499584 -0.1105133 0.9017534 -0.4178849 -0.1061811 0.9072639 -0.4069372 -0.3338727 0.3209406 -0.8862993 -0.208611 0.8037083 -0.5572562 -0.1724292 0.859454 -0.4812556 -0.3839769 0.4250302 -0.8197019 -0.3376106 0.6431789 -0.68727 -0.4461544 0.2954149 -0.8447937 -0.1465998 0.9401566 -0.3075941 -0.4608967 0.5154537 -0.7224139 -0.07680368 0.9889434 -0.1268548 -0.3690687 0.6952223 -0.6168097 -0.337818 0.7679778 -0.5441408 -0.5255771 0.4155534 -0.7423503 -0.3122692 0.8504419 -0.4233635 -0.5714177 0.4352872 -0.6957061 -0.2763966 0.8914288 -0.3591096 -0.5643593 0.5007824 -0.6562892 -0.5990078 0.5300748 -0.6001754 -0.5866038 0.5892301 -0.5556113 -0.3553681 0.87044 -0.3406578 -0.6645807 0.5195723 -0.5370077 -0.2797719 0.9329854 -0.2264195 -0.6543851 0.6070777 -0.450818 -0.5414075 0.7690938 -0.3396659 -0.8111077 0.3293772 -0.4833374 -0.4191022 0.8670884 -0.2692791 -0.8379651 0.3249047 -0.4384649 -0.8282659 0.3713288 -0.4196317 -0.7044149 0.6239897 -0.3382847 -0.9023593 0.2557961 -0.3468663 -0.2593371 0.9590442 -0.113924 -0.6770104 0.6851158 -0.2688368 -0.8539001 0.4410233 -0.2763204 -0.4659399 0.870138 -0.160499 -0.8781946 0.409634 -0.24693 -0.8573765 0.4792199 -0.1877604 -0.7655271 0.6248592 -0.1533601 -0.9320562 0.3248782 -0.1603918 -0.4975522 0.8586329 -0.1232541 -0.3877515 0.9196643 -0.06218123 -0.9424659 0.3260141 -0.07397884 -0.6685135 0.7426792 -0.03895062 -0.4348132 0.8992822 -0.0472154 -0.8464568 0.5320811 -0.02002054 -0.6707631 0.7406893 -0.03816181 -0.8937587 0.4473169 0.03321367 -0.8810662 0.4684079 0.06569993 -0.1977285 0.9801762 0.01257836 -0.9302098 0.3476055 0.1178144 -0.6926717 0.7166661 0.08121335 -0.5396646 0.840422 0.04952883 -0.4079301 0.9115184 0.0522232 -0.892691 0.4086121 0.1901026 -0.8287956 0.5222206 0.2009564 -0.7155765 0.6815825 0.1529562 -0.4603905 0.8809931 0.1090499 -0.8737272 0.385977 0.2960112 -0.3976725 0.9090746 0.1242586 -0.8260447 0.5040332 0.252192 -0.6345866 0.7294187 0.2554374 -0.8697691 0.2909998 0.3985233 -0.8576372 0.3422231 0.3838514 -0.4331085 0.8884308 0.1520124 -0.6791637 0.6612807 0.3185035 -0.6583144 0.6781558 0.3266909 -0.4556807 0.8485833 0.2688151 -0.7999395 0.3390725 0.4951029 -0.2816916 0.945171 0.1652321 -0.7374705 0.4781946 0.4769353 -0.2523258 0.9555788 0.1523188 -0.7017422 0.5247322 0.481886 -0.5701517 0.7123972 0.4091667 -0.7237018 0.3446286 0.5979019 -0.6902152 0.3832688 0.6137654 -0.5246925 0.6938442 0.4932323 -0.4691768 0.7907268 0.3932228 -0.6792694 0.3017008 0.6690065 -0.2945731 0.9196105 0.2598912 -0.2761891 0.9305593 0.2403726 -0.5679917 0.5029244 0.6515002 -0.4937534 0.6951159 0.5225147 -0.3381225 0.8604366 0.3812114 -0.5504572 0.4406017 0.7091313 -0.2489849 0.9047374 0.3456251 -0.4785318 0.5261434 0.7029798 -0.2715656 0.8686245 0.4144198 -0.4619112 0.4120917 0.785378 -0.4059982 0.4630815 0.7878586 -0.2539978 0.7871725 0.5620005 -0.3808029 0.3540641 0.8541826 -0.2268447 0.8678069 0.4421002 -0.2604521 0.5625325 0.7846796 -0.2397547 0.7725359 0.5879678 -0.2529837 0.5535778 0.7934425 -0.1918193 0.6110697 0.7679839 -0.1214987 0.823023 0.5548617 -0.1180908 0.8932643 0.4337435 -0.1581947 0.4308143 0.8884669 -0.03560292 0.9926206 0.1159179 -0.0201832 0.9968519 0.07667511 -0.06431072 0.8513098 0.520707 -0.06290513 0.4887646 0.8701449 -0.02199059 0.9604458 0.2775975 -0.03558713 0.5812816 0.812924 -0.0337184 0.7340653 0.6782413 0.03553575 0.4948594 0.8682463 0.02861261 0.8828192 0.4688405 0.02160918 0.9287218 0.3701474 0.08657568 0.5604682 0.8236383 0.1433078 0.4177244 0.8972008 0.08536165 0.7663445 0.6367336 0.2342104 0.3911322 0.8900343 0.205729 0.4577318 0.8649608 0.03131109 0.9800936 0.1960519 0.1394951 0.7831632 0.6059674 0.1436039 0.8418446 0.5202651 0.2970673 0.3664146 0.8817548 0.3125682 0.5051848 0.8044188 0.1759973 0.8349504 0.5214238 0.1829217 0.8669687 0.4635784 0.1645591 0.9157859 0.3664102 0.3910533 0.4870982 0.7809051 0.3724177 0.5103517 0.7751427 0.4087837 0.4972487 0.765271 0.494663 0.3271611 0.8051548 0.3751823 0.7036522 0.6034168 0.2040169 0.9094353 0.36236 0.5477278 0.3764947 0.7471587 0.1740969 0.9531792 0.2472642 0.5195099 0.5413354 0.6611093 0.4195918 0.6922339 0.5871584 0.2573247 0.9112095 0.321685 0.5908885 0.5103057 0.6248511 0.5592253 0.5507454 0.6196344 0.3129754 0.8882754 0.3361745 0.6253894 0.5190775 0.5826206 0.6067333 0.5987358 0.5228673 0.325966 0.9016328 0.2842615 0.3096275 0.910512 0.2740413 0.7339161 0.4600536 0.4997179 0.1489285 0.9816907 0.1187595 0.6573845 0.585756 0.4740629 0.5199808 0.7789423 0.3505268 0.8077171 0.3657198 0.4624309 0.4952484 0.8164638 0.2968433 0.8631196 0.3357415 0.3772299 0.7965391 0.4653308 0.3859961 0.3528451 0.9161105 0.190373 0.6764354 0.665369 0.3157836 0.3254641 0.9333387 0.1514998 0.6212297 0.7408813 0.2552818 0.8624867 0.4258702 0.2734073 0.2268155 0.9699057 0.08853018 0.6551532 0.721413 0.2243608 0.8941807 0.3641877 0.2604002 0.5621874 0.8127864 0.1527212 0.3648087 0.9256669 0.1002779 0.6446262 0.7526429 0.1341111 0.8883131 0.4234517 0.1777316 0.8491808 0.5053632 0.153297 0.9080661 0.4161009 0.04770886 0.8281044 0.5548869 0.07964688 0.5805408 0.813202 0.04092621 0.5627 0.8259128 0.03516906 0.276876 0.9601191 0.03887122 0.9970413 -0.006607472 -0.07658451 0.999542 0.011532 -0.02797943 0.986468 -0.0117712 -0.1635316 0.9917861 0.009742498 -0.127537 0.9609312 0.0152505 -0.2763671 0.9628108 0.00836879 -0.2700473 0.9301966 -0.01297014 -0.3668325 0.8862785 -0.01085197 -0.4630256 0.9143957 0.01148766 -0.4046586 0.8611815 0.008209824 -0.5082312 0.8435002 -0.01326972 -0.5369651 0.7833495 0.007062017 -0.6215415 0.7847516 0.004779696 -0.6197921 0.7044996 0.008378326 -0.7096551 0.7077863 0.004792213 -0.7064104 0.6502623 0.007668018 -0.7596711 0.6473908 0.01055979 -0.7620852 0.5528219 -0.009414553 -0.8332462 0.4646931 -0.0128203 -0.885379 0.5296372 0.01014775 -0.8481636 0.4198725 0.01693463 -0.9074252 0.3428114 -1.50598e-4 -0.9394043 0.3470176 -0.003164291 -0.9378533 0.2410209 -0.004693865 -0.9705086 0.2411573 -0.004833877 -0.9704741 0.1409953 0.01430034 -0.989907 0.1019586 -0.00816363 -0.9947552 0.04759186 0.006653606 -0.9988448 0.01258677 -0.007168412 -0.9998951 -0.03321921 0.01110666 -0.9993864 -0.1001015 -9.40594e-4 -0.9949769 -0.1143094 0.007155179 -0.9934194 -0.2054769 -0.01071631 -0.9786033 -0.2362505 0.01322418 -0.9716023 -0.3388993 -0.009878218 -0.9407708 -0.3491674 -0.001718699 -0.9370589 -0.4239485 -0.01823204 -0.9055027 -0.4794093 0.01624423 -0.8774412 -0.5314925 -0.01156389 -0.8469842 -0.5598704 0.01399022 -0.8284621 -0.6459602 0.01699399 -0.7631821 -0.6718912 -0.0109561 -0.7405688 -0.719362 0.01434242 -0.6944873 -0.7555834 -0.003837585 -0.6550413 -0.7859801 0.02086776 -0.6178996 -0.8254331 0.001208543 -0.5644986 -0.8315321 0.006275653 -0.5554413 -0.8832655 -0.01519042 -0.4686272 -0.8933005 0.001372277 -0.4494578 -0.9295606 -0.005027055 -0.3686351 -0.9320675 -0.001315116 -0.3622825 -0.9563751 -0.01627868 -0.2916879 -0.9635939 0.002196848 -0.2673617 -0.9860441 -0.001600086 -0.1664769 -0.9851039 -0.006921648 -0.1718211 -0.9978837 0.01048046 -0.06417304 -0.9994109 -0.008658409 -0.03320944 -0.9996595 0.0114876 0.02343416 -0.9973519 -0.006845533 0.07240384 -0.9923249 0.01338225 0.1229317 -0.9826657 -0.01291638 0.1849358 -0.9729432 0.01513469 0.2305483 -0.9574503 0.005934894 0.288537 -0.9482431 -0.01866036 0.3169966 -0.9119231 -0.007052421 0.4103007 -0.9097849 -0.002693772 0.4150714 -0.8715708 -0.0256012 0.4896008 -0.8150192 -0.00955528 0.5793552 -0.8393576 0.007468342 0.5435282 -0.7477548 -0.01305705 0.6638467 -0.7854818 0.0101428 0.6188017 -0.7059788 0.01988697 0.7079538 -0.6512984 -0.01422619 0.7586884 -0.5649821 -0.02088248 0.8248389 -0.608833 0.007298886 0.7932648 -0.5175799 0.0140472 0.8555195 -0.4406179 -0.01444917 0.8975785 -0.3895885 0.02104264 0.9207487 -0.3426713 0.001027703 0.9394548 -0.2906488 0.02150541 0.9565882 -0.2458075 0.004579126 0.9693079 -0.1962962 0.02280849 0.9802793 -0.1327939 -0.01841074 0.9909727 -0.05097299 -0.00485748 0.9986883 -0.05231857 -0.006348431 0.9986103 0.08924996 -0.007690966 0.9959797 0.04587328 0.01418447 0.9988466 0.1413683 0.01280301 0.9898744 0.1917935 0.0101782 0.9813826 0.2153714 -0.01506954 0.9764159 0.2992097 -0.02161794 0.9539425 0.3798263 -0.01625996 0.924915 0.3465581 -3.02115e-4 0.9380285 0.428064 0.015329 0.9036185 0.5167376 -1.76289e-4 0.8561438 0.5180789 -0.001733601 0.8553311 0.6061721 3.00779e-4 0.7953335 0.6121794 0.006370782 0.7906933 0.6778188 0.0065369 0.7351999 0.6791309 0.005177199 0.733999 0.7568656 0.006233572 0.653541 0.7566824 0.006438255 0.653751 0.821241 0.01207435 0.5704538 0.8021601 -0.009508311 0.5970335 0.8513323 -0.01464462 0.5244225 0.8941197 -0.01519715 0.4475702 0.8665897 -2.55353e-4 0.4990214 0.915414 0.01606261 0.402193 0.9457992 -0.01347023 0.3244726 0.9601768 0.01426094 0.2790288 0.9772611 -0.01238995 0.2116776 0.9906596 -0.002579331 0.136334 0.9866719 0.007076919 0.1625688 0.9960448 0.01677894 0.08725464 0.9997935 -0.008434891 0.01849007 0.9547228 -0.2962747 0.02694278 0.1804161 -0.9835903 3.24056e-4 0.6498811 -0.7587592 0.04403764 0.9321312 -0.3488173 0.09725165 0.8269608 -0.5497619 0.1178888 0.4536937 -0.8896509 0.05180156 0.8969174 -0.3805362 0.2252364 0.8176975 -0.5541872 0.1557153 0.3952896 -0.912739 0.1032173 0.5769457 -0.8013324 0.1581143 0.8727229 -0.3892479 0.2946878 0.3993884 -0.9107258 0.1052017 0.8876563 -0.3573128 0.2905061 0.7017754 -0.6682969 0.2467603 0.8275107 -0.4161347 0.3769058 0.7333403 -0.5773195 0.3590464 0.6599017 -0.6948016 0.285973 0.3879038 -0.9059095 0.169878 0.6845208 -0.6106715 0.3981354 0.698429 -0.578998 0.420664 0.2824299 -0.9466997 0.154897 0.4577659 -0.8388333 0.2946338 0.6846212 -0.5081417 0.5225762 0.1398304 -0.9865074 0.08515238 0.6716772 -0.5227965 0.524913 0.5501654 -0.6963276 0.4609186 0.4735156 -0.7967952 0.3753673 0.7129351 -0.2917354 0.6376629 0.2443839 -0.9456296 0.2146185 0.5279366 -0.6845409 0.5026795 0.6417568 -0.3607779 0.6767477 0.6128808 -0.4283016 0.6640293 0.5601802 -0.4818097 0.673838 0.4795408 -0.6408521 0.5994575 0.3927458 -0.8029434 0.4483667 0.5651866 -0.3287146 0.7566446 0.230836 -0.9302634 0.2851748 0.1738258 -0.9642054 0.2002316 0.4829167 -0.3795456 0.7891366 0.4855914 -0.3222562 0.8126205 0.2477273 -0.8942872 0.3726684 0.4027675 -0.6139001 0.6788998 0.3879823 -0.6990079 0.6007144 0.3145748 -0.6828927 0.659318 0.3868935 -0.2951056 0.8736281 0.2070227 -0.8542459 0.4768709 0.1692792 -0.9274495 0.3334397 0.3368879 -0.5051279 0.794577 0.1430743 -0.8653548 0.4803029 0.2106003 -0.5338227 0.818951 0.2229909 -0.5125208 0.829215 0.1027359 -0.9051833 0.412418 0.1781426 -0.4743825 0.8621059 0.11966 -0.5466022 0.8287988 0.08054792 -0.8893049 0.4501653 0.0791893 -0.5048158 0.8595872 0.04383605 -0.5563652 0.8297808 0.01256239 -0.8993213 0.4371079 0.02316194 -0.9252747 0.3785897 -0.01960772 -0.5132798 0.8579974 -0.02696812 -0.8758248 0.4818753 -0.07985842 -0.6592523 0.7476691 -0.00332719 -0.9985177 0.05432724 -0.1633198 -0.3301356 0.9296973 -0.0707941 -0.6667364 0.7419238 -0.2094445 -0.3527951 0.9119588 -0.04466032 -0.9677777 0.2478141 -0.2413524 -0.2685413 0.932542 -0.1619853 -0.744199 0.648019 -0.1734659 -0.722946 0.668774 -0.100809 -0.9214919 0.375087 -0.3192589 -0.3248217 0.890261 -0.3206105 -0.3425388 0.883106 -0.2517149 -0.6424955 0.7237674 -0.1230545 -0.9383552 0.3230285 -0.2780804 -0.7273618 0.6273884 -0.4051476 -0.3433337 0.8473356 -0.4057686 -0.4345091 0.8040857 -0.2496603 -0.8089855 0.532177 -0.4169962 -0.4387621 0.7959912 -0.06146121 -0.9915661 0.1141023 -0.5371035 -0.2657999 0.8005439 -0.2724324 -0.8469578 0.4565559 -0.5076997 -0.4773954 0.7171713 -0.4304425 -0.6317573 0.6446721 -0.1547272 -0.9581774 0.24074 -0.3742973 -0.7425717 0.5554178 -0.6208738 -0.4090448 0.6687289 -0.5894048 -0.4723064 0.6553844 -0.3904519 -0.8122577 0.4333418 -0.373159 -0.8358706 0.4025825 -0.255303 -0.9254246 0.2800171 -0.6828817 -0.3769573 0.6257603 -0.6738007 -0.4577294 0.580066 -0.1338793 -0.9831147 0.124747 -0.4897663 -0.7639601 0.420112 -0.7377097 -0.4018387 0.5425037 -0.4589329 -0.8211417 0.3392742 -0.3181688 -0.9220258 0.2205383 -0.6982474 -0.56813 0.4355214 -0.7179444 -0.551442 0.424815 -0.2867145 -0.9423785 0.1723881 -0.7840201 -0.5204888 0.3382366 -0.7028003 -0.6210947 0.346862 -0.5438944 -0.8021629 0.2464015 -0.1305653 -0.9896875 0.05891919 -0.49369 -0.8510075 0.1790438 -0.8806701 -0.3845161 0.2767084 -0.7972882 -0.5319562 0.2852265 -0.617054 -0.7628709 0.193061 -0.2738939 -0.9570669 0.09489566 -0.8827167 -0.4253594 0.1997013 -0.7262347 -0.6723307 0.1433688 -0.6677669 -0.7298818 0.1461502 -0.9503862 -0.2607914 0.1695695 -0.9242159 -0.3658978 0.109288 -0.7779985 -0.6214152 0.09252846 -0.9584953 -0.2745885 0.07673442 -0.3316571 -0.9425259 0.04060131 -0.2801741 -0.9591646 0.03880465 -0.725251 -0.6862617 0.05528223 -0.9143798 -0.4040408 -0.02570343 -0.4268649 -0.9040371 0.02243226 -0.9540772 -0.2993282 -0.0118016 -0.8153551 -0.578839 -0.01190519 -0.731638 -0.679835 -0.05030339 -0.4954502 -0.8676124 -0.04216688 -0.8939204 -0.4281181 -0.1327456 -0.4113842 -0.9112353 -0.02032971 -0.8298441 -0.5447748 -0.1207448 -0.935885 -0.3128711 -0.1619602 -0.5073349 -0.8560957 -0.09854727 -0.6358699 -0.7563095 -0.1538361 -0.9121527 -0.3218397 -0.2537654 -0.05370604 -0.9984781 -0.01253914 -0.641919 -0.7489672 -0.1642806 -0.7835873 -0.5678719 -0.2520171 -0.150951 -0.9875306 -0.04468947 -0.819417 -0.4462849 -0.3597022 -0.7616569 -0.5608605 -0.3245218 -0.7021468 -0.6360151 -0.3201167 -0.8618791 -0.2239568 -0.4549812 -0.4620938 -0.8614071 -0.210825 -0.4148421 -0.8940836 -0.1688809 -0.7603444 -0.461383 -0.4571675 -0.6904057 -0.5987684 -0.405976 -0.3954882 -0.8898227 -0.2276062 -0.5485757 -0.7501016 -0.3693403 -0.7810347 -0.3257193 -0.532815 -0.1361058 -0.985729 -0.09906345 -0.5481262 -0.7498284 -0.3705605 -0.6580229 -0.5162627 -0.5481594 -0.6863569 -0.3973681 -0.6091083 -0.6576154 -0.5151907 -0.549655 -0.482061 -0.7418498 -0.4661288 -0.3784158 -0.8687286 -0.3195499 -0.2296136 -0.9527299 -0.1989559 -0.6326593 -0.2963603 -0.7154808 -0.6271262 -0.3800388 -0.6799142 -0.4639875 -0.733084 -0.4972961 -0.4111505 -0.7794525 -0.4726619 -0.1969739 -0.9510218 -0.2382416 -0.5273497 -0.3840812 -0.7578812 -0.4111757 -0.6849569 -0.6014721 -0.5217131 -0.2647764 -0.8109925 -0.1526187 -0.9674071 -0.2020671 -0.3195453 -0.7759853 -0.5438176 -0.1914105 -0.9308518 -0.3112509 -0.4069849 -0.4174765 -0.8124511 -0.3608417 -0.5370368 -0.762486 -0.3147826 -0.7319106 -0.6043334 -0.2987059 -0.3772141 -0.8766324 -0.3079771 -0.5352059 -0.7865779 -0.2038669 -0.7604131 -0.6166118 -0.1859187 -0.8541974 -0.4855729 -0.08387672 -0.9723371 -0.2180032 -0.05667406 -0.9846824 -0.1648898 -0.2041273 -0.4586414 -0.8648585 -0.1678147 -0.7305726 -0.6618927 -0.1873333 -0.3856792 -0.9034147 -0.08758747 -0.8388538 -0.5372642 -0.09125208 -0.4354481 -0.895577 -0.08915042 -0.4412791 -0.8929306 -0.06090837 -0.7463285 -0.662785 -0.07213473 -0.8322452 -0.5496951 -0.01267784 -0.3801736 -0.9248283 0.05909574 -0.6081978 -0.7915828 0.03501272 -0.7354665 -0.6766559 0.03276956 -0.895354 -0.444148 0.1117056 -0.4259423 -0.8978281 -0.002133607 -0.9523832 -0.3048965 0.07285034 -0.5857945 -0.8071788 0.2134097 -0.3980227 -0.8922075 0.06852388 -0.9231809 -0.3782086 0.220501 -0.4972572 -0.8391155 0.04780548 -0.9816356 -0.1846786 0.1728654 -0.7060889 -0.6866995 0.1703143 -0.7292892 -0.662669 0.3292677 -0.3961718 -0.857106 0.2131361 -0.7739865 -0.5962532 0.3357061 -0.4317688 -0.8371841 0.2960984 -0.6455926 -0.7039433 0.4267612 -0.3466985 -0.8352695 0.1530864 -0.9249895 -0.3477916 0.1534164 -0.9246503 -0.3485473 0.4284468 -0.4904314 -0.7588877 0.3323997 -0.686952 -0.6462255 0.2640036 -0.8445212 -0.465925 0.2769864 -0.8514554 -0.4453117 0.5324181 -0.3513007 -0.7701421 0.4825586 -0.4665017 -0.7412917 0.4038558 -0.7205258 -0.5636872 0.5868788 -0.3514503 -0.7294217 0.5598274 -0.5437554 -0.6252387 0.4512702 -0.7063966 -0.5453065 0.1648233 -0.9656713 -0.2007794 0.6886472 -0.3265969 -0.647379 0.285784 -0.9101285 -0.2999894 0.6072613 -0.5141446 -0.6057137 0.5337544 -0.7133554 -0.4541261 0.7479581 -0.2621955 -0.6097641 0.3608697 -0.875975 -0.3200641 0.7304424 -0.4269329 -0.5330876 0.6183593 -0.6355301 -0.4623131 0.7844412 -0.3455771 -0.5150035 0.2778147 -0.940508 -0.1956112 0.7458943 -0.530994 -0.4021036 0.5760167 -0.7386931 -0.3500532 0.5021873 -0.811567 -0.2986088 0.8397601 -0.3510119 -0.4142386 0.7457585 -0.53114 -0.4021624 0.09689038 -0.9937594 -0.05526906 0.8850629 -0.3025948 -0.353695 0.8592869 -0.4024809 -0.3156508 0.6735558 -0.690098 -0.2647404 0.627497 -0.7412303 -0.2383806 0.4571682 -0.8702093 -0.1836654 0.4242735 -0.8899597 -0.1672236 0.9137551 -0.3200507 -0.2502384 0.8968874 -0.3858413 -0.2161472 0.733044 -0.6593989 -0.1668519 0.942419 -0.285233 -0.1746097 0.3483564 -0.9340264 -0.07901012 0.6714965 -0.7304745 -0.1244975 0.4498169 -0.8900559 -0.07392758 0.8655543 -0.4952983 -0.07413154 0.4182906 -0.9072026 -0.04490596 0.8703371 -0.4910317 -0.03743267 0.8779301 -0.4760149 -0.05146592 0.6751069 -0.7376171 0.01232594 3.66463e-4 -0.9999989 0.001441299 0.001002907 -0.9999987 0.001328289 0.001172125 -0.9999992 5.45463e-4 9.3387e-4 -0.9999994 6.65408e-4 -0.001070857 -0.9999948 0.00307101 0.001187205 -0.9999992 4.46434e-4 9.05591e-4 -0.9999958 0.002772152 0.003351509 -0.9999909 -0.002657771 0.003156602 -0.9999946 9.62677e-4 0.002089619 -0.9999932 0.003058791 0.003309547 -0.9999945 2.84147e-4 -1.34102e-5 -0.9999989 0.001509964 8.92427e-4 -0.9999994 7.89655e-4 9.79184e-4 -0.9999996 -1.43264e-4 0.001101136 -0.999998 -0.001732707 -9.71108e-5 -1 2.55781e-4 0.001554787 -0.9999985 -7.04605e-4 0.001553237 -0.9999986 -6.85113e-4 -0.00180453 -0.9999983 3.10511e-4 5.52198e-4 -0.9999979 0.001991212 -0.001046657 -0.9999986 0.001333236 0.001078069 -0.9999989 -0.001024901 6.64581e-6 -0.9999939 -0.003502309 0.01034706 -0.9999465 -3.50742e-5 3.71046e-5 -1 -6.92258e-5 -2.01486e-4 -1 1.30557e-4 -1.92084e-4 -1 1.4e-4 2.08732e-5 -1 -6.8221e-5 -1.90431e-4 -1 5.27728e-5 -0.002356112 -0.9999942 -0.002457439 -2.05594e-4 -1 6.13805e-6 6.43764e-6 -0.9999972 -0.002409934 -0.001512765 -0.9999976 -0.001595854 -5.56955e-4 -0.9999962 -0.002722203 -0.001321852 -0.9999992 -2.28299e-4 -0.001937329 -0.9999971 -0.001460075 -8.34657e-4 -0.9999961 -0.002677559 7.30666e-4 -0.9999974 -0.002167642 -0.002337098 -0.9999967 -0.001027464 3.98035e-4 -0.9999982 -0.001927495 -0.002898037 -0.9999953 0.001066923 -1.47304e-4 -1 -2.36913e-4 -1.88477e-4 -1 -1.6589e-4 0.9315345 -0.3601459 0.05038243 0.9286619 -0.3666539 0.05614423 0.7186917 -0.6915699 0.07220369 0.6281697 -0.7769175 0.04245203 0.9514314 -0.2870027 0.1113898 0.08278048 -0.9965215 0.009612441 0.8704057 -0.4621285 0.1697978 0.7574974 -0.6405053 0.1262968 0.8793428 -0.4378935 0.1870981 0.5243021 -0.841553 0.1299842 0.393289 -0.9156757 0.08283549 0.2183891 -0.974634 0.0489366 0.8712074 -0.3700292 0.3226082 0.8070634 -0.5343152 0.2513089 0.6038097 -0.7724879 0.1966633 0.8469249 -0.3896737 0.3617633 0.614343 -0.7264586 0.3079624 0.8667576 -0.2653892 0.422256 0.5197548 -0.8251556 0.2212994 0.2409244 -0.9646593 0.1067143 0.7510595 -0.4883529 0.4443209 0.6192802 -0.7033169 0.3490523 0.7816657 -0.3339615 0.5267529 0.150577 -0.9852212 0.0816453 0.7464368 -0.3668706 0.5551919 0.4697351 -0.8187473 0.3301541 0.7462722 -0.3092415 0.5894469 0.4836762 -0.7897431 0.3773106 0.455389 -0.7990316 0.3926442 0.6728261 -0.3163649 0.6687439 0.6621362 -0.4049013 0.6305796 0.5723866 -0.5998669 0.5590468 0.2977973 -0.9064768 0.2993605 0.5668307 -0.425418 0.7054946 0.5088863 -0.6113895 0.6060013 0.5669178 -0.3573552 0.7422274 0.3389646 -0.8240115 0.4539916 0.4922126 -0.2422114 0.8360984 0.3241182 -0.8308808 0.4523103 0.4954102 -0.411652 0.7649258 0.3926993 -0.6538103 0.6467762 0.3802115 -0.3795924 0.843415 0.1765248 -0.9392606 0.2943274 0.3395456 -0.65236 0.6775953 0.3747459 -0.3587976 0.8548859 0.1782218 -0.8882457 0.423387 0.1998732 -0.8494058 0.4884266 0.2267858 -0.5718201 0.7884097 0.1931735 -0.7732017 0.6040226 0.2161749 -0.5242965 0.8236393 0.0459932 -0.9852529 0.1648076 0.1708791 -0.4403795 0.8814002 0.1794537 -0.4970715 0.8489502 0.0704649 -0.9214206 0.3821242 0.09155029 -0.358716 0.9289465 0.05813932 -0.7985416 0.5991254 0.05467474 -0.8703311 0.4894227 0.06465971 -0.4358747 0.8976817 0.03952276 -0.7422239 0.6689856 -0.006878018 -0.3942673 0.9189702 -0.05333042 -0.5477862 0.834917 -0.01666092 -0.7359306 0.6768521 -0.09813475 -0.4982833 0.8614426 -0.05282366 -0.8822351 0.4678366 -0.04899722 -0.9005195 0.4320461 -0.01371556 -0.963737 0.2665012 -0.1267329 -0.5363758 0.83441 -0.1048494 -0.7732784 0.6253377 -0.1670591 -0.4699374 0.8667469 -0.2807182 -0.4368909 0.8545898 -0.2403887 -0.5378507 0.8080409 -0.1997271 -0.7277253 0.656144 -0.3197395 -0.4170126 0.8508039 -0.1925602 -0.8204565 0.5383046 -0.08614242 -0.9573768 0.2756973 -0.3532906 -0.5823191 0.7321819 -0.053083 -0.9895231 0.1342616 -0.334697 -0.6530423 0.6793481 -0.2494453 -0.7912204 0.5583434 -0.466822 -0.2658234 0.8434543 -0.1795998 -0.929924 0.3209133 -0.3955941 -0.6839523 0.6129556 -0.5122337 -0.4223811 0.7478041 -0.4782615 -0.5608705 0.6757887 -0.2219875 -0.9164757 0.3328573 -0.2163742 -0.9261705 0.3088535 -0.5064491 -0.6024453 0.6169028 -0.6531625 -0.3074995 0.6919703 -0.4749473 -0.704496 0.5273619 -0.3843164 -0.8263897 0.4115594 -0.3449803 -0.8597108 0.3766778 -0.6620802 -0.4312052 0.6129534 -0.6766276 -0.4216856 0.6036195 -0.6694427 -0.489002 0.559217 -0.5954907 -0.6586428 0.4599788 -0.4268116 -0.8405858 0.3335376 -0.4486522 -0.8257842 0.3417479 -0.1918757 -0.9663884 0.1711059 -0.7912439 -0.2996802 0.5330336 -0.7175405 -0.5286199 0.4535382 -0.4186033 -0.8684707 0.2655752 -0.7810889 -0.4924487 0.3839197 -0.7054398 -0.5973209 0.3815266 -0.5937663 -0.740353 0.3151495 -0.2282593 -0.9665113 0.1172754 -0.8296347 -0.4678471 0.304673 -0.8120887 -0.4931024 0.312029 -0.5495564 -0.7988716 0.2445241 -0.4111958 -0.8976441 0.158598 -0.828574 -0.4816674 0.285415 -0.6005471 -0.7846937 0.1536196 -0.9109821 -0.3462314 0.2241323 -0.4078123 -0.9031572 0.1341501 -0.1886687 -0.9813026 0.03807109 -0.8067338 -0.5759166 0.13229 -0.6550529 -0.7470401 0.1133002 -0.3007732 -0.9528377 0.04044634 -0.5819416 -0.8091208 0.08165615 -0.9086428 -0.4085406 0.08638894 -0.9081245 -0.4184827 0.01350623 -0.8938969 -0.4482563 0.003850042 -0.7662015 -0.6422447 -0.02138096 -0.6512396 -0.7588681 -0.002542316 -0.3686853 -0.9293817 -0.01791244 -0.9638351 -0.2401506 -0.1155412 -0.8982585 -0.418977 -0.1326271 -0.7758716 -0.6218674 -0.1063213 -0.8126268 -0.5742466 -0.09939157 -0.2980383 -0.9539533 -0.03385728 -0.4845583 -0.8697301 -0.09366399 -0.3715773 -0.9262341 -0.06340891 -0.932032 -0.2523732 -0.2600467 -0.6922943 -0.6913691 -0.2067306 -0.6238945 -0.7587125 -0.1873793 -0.8106355 -0.5208467 -0.2675609 -0.8220756 -0.4431743 -0.3574751 -0.2015761 -0.976584 -0.07517284 -0.435615 -0.8804221 -0.1873413 -0.7875728 -0.4825947 -0.3831861 -0.8036476 -0.4274658 -0.4140334 -0.5166287 -0.8129168 -0.2688143 -0.7639476 -0.4159939 -0.4932882 -0.7330598 -0.4700762 -0.4915808 -0.4828427 -0.8243612 -0.2954516 -0.3862966 -0.8816543 -0.2710366 -0.6808351 -0.4881936 -0.5460134 -0.6830827 -0.4848474 -0.5461878 -0.4677976 -0.7894803 -0.3973492 -0.3964565 -0.8629019 -0.313405 -0.6252853 -0.4841542 -0.6120563 -0.6056998 -0.5136108 -0.6077267 -0.4905233 -0.7188597 -0.4925726 -0.5772362 -0.4282814 -0.6952507 -0.2091427 -0.9527296 -0.2203763 -0.3904276 -0.8053449 -0.4460784 -0.5388664 -0.4821214 -0.6907837 -0.3997399 -0.7453125 -0.5335891 -0.5188453 -0.3751248 -0.7681674 -0.09957748 -0.9875692 -0.12162 -0.360222 -0.7731006 -0.5220688 -0.2050864 -0.9210136 -0.3311701 -0.4533641 -0.4642875 -0.7608535 -0.388537 -0.655626 -0.6474516 -0.4430773 -0.3885065 -0.8079266 -0.356669 -0.3269562 -0.8751497 -0.1711103 -0.9214165 -0.3488741 -0.36502 -0.4445584 -0.8180027 -0.2535775 -0.764185 -0.5930598 -0.2542859 -0.7543768 -0.6051896 -0.2989455 -0.3460019 -0.8893336 -0.2069514 -0.60834 -0.7662204 -0.05158007 -0.9884392 -0.1425747 -0.2110831 -0.7458187 -0.6318216 -0.2097457 -0.6093944 -0.7646211 -0.1747341 -0.2952596 -0.9393028 -0.09539383 -0.9203909 -0.3791844 -0.118483 -0.7248774 -0.6786122 -0.1209045 -0.3483227 -0.9295448 -0.07544183 -0.8820912 -0.4649987 -0.07041531 -0.5950267 -0.8006154 -0.02863281 -0.9196836 -0.391615 -0.04877722 -0.6156767 -0.7864878 -0.02065694 -0.7058106 -0.7080994 0.01237231 -0.2980948 -0.9544561 -0.006170451 -0.9640057 -0.2658103 0.08921653 -0.4018383 -0.9113542 0.09576791 -0.473941 -0.8753334 0.05156707 -0.687807 -0.7240597 0.07583999 -0.8515466 -0.5187646 0.05184268 -0.9213265 -0.3853178 0.1700381 -0.5278183 -0.8321629 0.1339656 -0.7740627 -0.6187731 0.2301194 -0.3845411 -0.8939649 0.04522961 -0.9845354 -0.1692463 0.3435015 -0.2545716 -0.9039912 0.2897295 -0.4215461 -0.8592763 0.2758367 -0.6487391 -0.7092614 0.1834169 -0.8316837 -0.5240807 0.1665303 -0.8750174 -0.4545462 0.4065663 -0.3669015 -0.8367122 0.351564 -0.5710117 -0.7418548 0.4557307 -0.2612814 -0.8509064 0.4904264 -0.3802961 -0.7841283 0.3680284 -0.7158418 -0.5934018 0.3492203 -0.7363383 -0.5795267 0.5273807 -0.3157164 -0.788792 0.2258589 -0.8891271 -0.3980463 0.1363383 -0.9680486 -0.2104606 0.6003965 -0.379702 -0.7038115 0.5767136 -0.438786 -0.6891069 0.512295 -0.6154781 -0.5989496 0.4501361 -0.7057378 -0.5470938 0.7042456 -0.234677 -0.6700485 0.3169112 -0.8822367 -0.3481748 0.682249 -0.4161184 -0.6011504 0.5971503 -0.5907511 -0.5426091 0.3002426 -0.9099883 -0.2859649 0.5036525 -0.7640143 -0.4032571 0.4789756 -0.7888715 -0.3850509 0.7406911 -0.3757398 -0.5569528 0.6573445 -0.605257 -0.448957 0.1174069 -0.9887023 -0.09318578 0.8102324 -0.392464 -0.435311 0.2991256 -0.9355092 -0.1880068 0.6856504 -0.6065642 -0.4024468 0.5509105 -0.7894471 -0.270686 0.346387 -0.918661 -0.1899425 0.564656 -0.781971 -0.2639791 0.8673908 -0.3471371 -0.3565517 0.8222899 -0.4789882 -0.3072617 0.8242853 -0.4977191 -0.2698695 0.1258634 -0.9911831 -0.04140996 0.48983 -0.8569918 -0.1600993 0.8803831 -0.4064626 -0.2443646 0.5795351 -0.7989996 -0.1604331 0.1615028 -0.9856767 -0.04856449 0.5936809 -0.7938377 -0.1317752 0.8638807 -0.4823296 -0.1451492 0.8831431 -0.4415447 -0.1584196 0.5204062 -0.8489086 -0.09236818 0.367909 -0.9282518 -0.05469715 0.861592 -0.50165 -0.07750135 0.7742267 -0.6322357 -0.02917122 0.7913203 -0.6091861 -0.05200737 0.600548 -0.79952 0.01048409 0.3292044 -0.9441429 -0.01478654 0.9991952 -0.01320981 -0.03787702 0.985793 -0.01231348 -0.1675133 0.9931087 0.01686608 -0.1159772 0.9627219 -0.007068514 -0.2704008 0.9731725 0.009712874 -0.2298718 0.9279708 -0.017596 -0.3722373 0.9464091 0.0125879 -0.3227251 0.863269 -0.01969742 -0.5043597 0.8887331 0.02302783 -0.4578464 0.8179575 -0.01132982 -0.5751671 0.813607 -0.003039479 -0.5814073 0.7489594 0.008588671 -0.6625602 0.7250871 -0.01517522 -0.6884899 0.6759989 0.009661257 -0.7368393 0.6422638 -0.009152054 -0.766429 0.5684756 -0.006222963 -0.8226767 0.6013096 0.01035219 -0.7989491 0.4724637 -0.006441831 -0.8813267 0.5121824 0.01846641 -0.8586783 0.3501858 -0.01094019 -0.9366164 0.4016526 0.0260775 -0.9154208 0.2350339 -0.01872152 -0.9718069 0.2952091 0.008637905 -0.9553936 0.1838414 0.01201719 -0.9828825 0.1154845 -0.01144599 -0.9932434 -0.01454865 -0.009628415 -0.9998478 0.07248747 0.01276111 -0.9972877 -0.08064901 -0.008786201 -0.9967039 -0.04789096 0.008821666 -0.9988137 -0.2137682 0.009345471 -0.9768397 -0.2019851 -0.001918911 -0.9793867 -0.2802463 -0.01358753 -0.959832 -0.3914495 -0.01459342 -0.9200839 -0.3408367 0.02229267 -0.9398583 -0.4757786 0.001361191 -0.8795641 -0.4793401 0.005198776 -0.877614 -0.5641753 0.00164777 -0.8256534 -0.5590888 -0.002890288 -0.8291028 -0.647719 -0.003869175 -0.7618696 -0.6443323 -0.007361233 -0.7647103 -0.719075 -0.006787717 -0.6948994 -0.7653035 -0.01090723 -0.6435772 -0.7172059 -0.008696436 -0.6968072 -0.7886052 0.01224666 -0.614778 -0.8361983 0.002351105 -0.5484222 -0.836915 0.003392994 -0.5473225 -0.8886774 -0.0150026 -0.4582877 -0.9096212 0.01295524 -0.4152366 -0.9270135 -0.006777584 -0.3749668 -0.9503632 0.005296945 -0.3110978 -0.9613682 -0.01371848 -0.2749239 -0.9712902 0.009880304 -0.2376925 -0.9926158 -0.01093077 -0.1208077 -0.9935523 -0.002868235 -0.1133387 -0.9996071 0.01489675 -0.02374625 -0.9998068 -0.008151888 0.01788485 -0.9973794 0.00981158 0.07168143 -0.9919055 -0.01373034 0.1262347 -0.984054 0.001742541 0.1778616 -0.9752522 -0.01659297 0.220472 -0.9659296 0.007873833 0.2586852 -0.9315287 -0.01058238 0.363514 -0.924019 0.005637705 0.3823049 -0.907366 0.006670176 0.4202888 -0.8854657 -0.02274382 0.4641479 -0.8381772 -0.005104422 0.5453742 -0.8428808 -0.01569634 0.5378714 -0.7776305 0.01383018 0.6285694 -0.7568448 -0.01103758 0.6535015 -0.6649551 0.00662893 0.746854 -0.6838009 -0.01952743 0.7294074 -0.5993815 -0.008655488 0.8004168 -0.6064687 -0.003408551 0.7951 -0.4690763 -0.0104283 0.8830962 -0.5072903 0.01820516 0.8615831 -0.4369992 0.002690672 0.899458 -0.3899682 -0.009973585 0.9207744 -0.3245033 0.0151509 0.9457633 -0.2850725 -0.006564557 0.9584835 -0.2576588 -9.60977e-5 0.966236 -0.2023106 -0.02012932 0.9791145 -0.1439949 0.004143357 0.9895699 -0.03627437 0.01824671 0.9991754 -0.09496945 -0.007378816 0.9954529 -0.0644288 -0.01215183 0.9978483 0.0646556 0.01320052 0.9978204 0.09209835 -0.001177608 0.9957493 0.1387895 0.01698356 0.9901763 0.1998137 -0.006804108 0.9798103 0.2595723 0.01302355 0.965636 0.2870489 0.002083659 0.9579137 0.3763805 -0.01771867 0.9262958 0.326507 0.01062989 0.9451351 0.4353775 0.01896947 0.9000481 0.5129435 3.0687e-4 0.8584223 0.5146052 -0.00170964 0.8574255 0.608487 6.34035e-4 0.7935637 0.6103451 0.00293076 0.7921303 0.6830224 0.0171203 0.7301968 0.7076966 -0.009816408 0.7064483 0.7777084 0.0092839 0.6285567 0.7751407 0.005185544 0.6317675 0.8460378 -6.04726e-4 0.5331227 0.8491222 0.003793179 0.5281829 0.8908931 0.004713177 0.4541888 0.8831658 -0.01143819 0.4689216 0.9360675 0.02081274 0.3512042 0.9487594 9.29535e-4 0.3159981 0.9567126 0.009122669 0.2908915 0.9722991 -0.01629823 0.2331714 0.9915081 -0.01034319 0.1296333 0.9861617 0.01000511 0.1654843 0.9999899 -0.00437051 0.001114904 0.9996144 0.01682066 0.02209734 0.6011238 0.7979411 -0.04404842 0.8893943 0.4421258 -0.1162006 0.863716 0.4952871 -0.09319555 0.4643279 0.8833537 -0.06392121 0.1179979 0.9928945 -0.01539903 0.1062952 0.9942572 -0.01241528 0.8629017 0.4701212 -0.1854366 0.8496322 0.491864 -0.19025 0.5913915 0.7930113 -0.1462509 0.8734644 0.3770046 -0.3081032 0.8290424 0.4922548 -0.265281 0.6490505 0.7239338 -0.2337809 0.5545316 0.814837 -0.1689247 0.3658707 0.9224516 -0.1233761 0.810846 0.4403483 -0.3855156 0.6774263 0.6597073 -0.3253919 0.6221774 0.73075 -0.2808909 0.8528969 0.2780898 -0.4418519 0.3693013 0.910936 -0.1838808 0.309353 0.935294 -0.1718316 0.752842 0.3792264 -0.5379744 0.7436603 0.4267324 -0.5146541 0.6115475 0.6772024 -0.4091536 0.5167904 0.773964 -0.3659337 0.1216069 0.9893002 -0.08060389 0.697514 0.3454864 -0.6277846 0.6913102 0.4056903 -0.5979177 0.4663373 0.775237 -0.4260719 0.4399036 0.8111298 -0.3854263 0.2698423 0.9327529 -0.2390757 0.6401878 0.3596539 -0.6788289 0.5991036 0.4432583 -0.6667811 0.4722572 0.7366665 -0.484041 0.5432558 0.4431307 -0.7130978 0.5306166 0.4645655 -0.7089605 0.1253852 0.9799849 -0.1546221 0.3618404 0.8069971 -0.4667197 0.2755489 0.8761333 -0.3955541 0.4620175 0.4756475 -0.7485315 0.4168972 0.5548415 -0.7199637 0.2742398 0.8602784 -0.4297834 0.3743993 0.5529325 -0.7443728 0.3783992 0.2610388 -0.8880726 0.1866775 0.9047456 -0.3828667 0.2892931 0.6757166 -0.6780241 0.2968519 0.4236536 -0.8558018 0.1248903 0.9477799 -0.2934548 0.2586999 0.636064 -0.726978 0.2725301 0.298056 -0.9148169 0.2004325 0.7207698 -0.6635645 0.1363336 0.8516179 -0.5061225 0.1929426 0.3509638 -0.9162956 0.1698054 0.449822 -0.8768275 0.09436845 0.8788262 -0.467717 0.06555438 0.4934883 -0.8672785 0.09864044 0.5579039 -0.8240228 0.06761699 0.8266839 -0.558589 0.004792094 0.9967613 -0.08027404 0.02560591 0.8675773 -0.4966428 0.05905538 0.7364864 -0.6738696 -0.003177583 0.5457929 -0.8379142 -0.05209267 0.1713848 -0.983826 -0.01612931 0.7708256 -0.636842 -0.00228095 0.981052 -0.1937314 -0.09273707 0.3949963 -0.91399 -0.06578868 0.8288186 -0.5556363 -0.06686627 0.8877906 -0.4553644 -0.1747368 0.4445424 -0.8785495 -0.1632593 0.4628607 -0.8712672 -0.1007127 0.9047887 -0.4137807 -0.2257043 0.5255256 -0.820293 -0.2058907 0.743435 -0.6363282 -0.3337366 0.2882982 -0.8974988 -0.08168411 0.9639344 -0.2532948 -0.369988 0.4317662 -0.8226099 -0.2426836 0.7585262 -0.6047667 -0.2200658 0.8581297 -0.4638797 -0.4257746 0.3839333 -0.8193358 -0.2309464 0.86131 -0.4525583 -0.439135 0.5109779 -0.7389603 -0.3709316 0.7082117 -0.6007046 -0.5353338 0.3660128 -0.7612178 -0.1527734 0.9595181 -0.236612 -0.5530896 0.4185503 -0.7203525 -0.3997758 0.7365474 -0.5455981 -0.6035098 0.3565883 -0.7131766 -0.3643405 0.814433 -0.4516139 -0.6194712 0.426563 -0.6590141 -0.2485961 0.9182876 -0.3081359 -0.4994226 0.7014997 -0.5084046 -0.6805937 0.318145 -0.6599819 -0.1976769 0.959349 -0.2014283 -0.4905571 0.7578964 -0.4300546 -0.3902521 0.8611043 -0.3258878 -0.7110379 0.3765599 -0.5938247 -0.6654773 0.5349041 -0.5205936 -0.8146203 0.2893651 -0.5026548 -0.7215594 0.5141866 -0.4636423 -0.3654769 0.8995704 -0.2391648 -0.6694675 0.6296276 -0.3941857 -0.2897665 0.9417281 -0.1708328 -0.8774252 0.2466883 -0.4114241 -0.8238974 0.4376167 -0.3601177 -0.7020132 0.622828 -0.3453446 -0.05903118 0.9977996 -0.03018867 -0.5019537 0.8402961 -0.2048049 -0.8434767 0.4437839 -0.3026596 -0.788447 0.5671442 -0.2381153 -0.4956633 0.852857 -0.1641731 -0.4146771 0.8932466 -0.1736476 -0.7850599 0.5665841 -0.2503271 -0.9235746 0.3314682 -0.1927146 -0.6639178 0.7339833 -0.1431138 -0.9164959 0.3632925 -0.167493 -0.4499131 0.8869392 -0.104486 -0.7420216 0.6592323 -0.1217247 -0.9486906 0.2885574 -0.1293098 -0.3541769 0.9333156 -0.05899715 -0.8697943 0.491132 -0.0474056 -0.7242745 0.6858058 -0.07139348 -0.5162218 0.8560386 -0.02670437 -0.8939465 0.4478865 -0.01604831 -0.8672737 0.4970797 0.02735173 -0.4840856 0.8747589 0.02140635 -0.5096052 0.8602934 0.01406431 -0.910597 0.4062332 0.0760774 -0.5071573 0.8610645 0.0368697 -0.8833466 0.4466197 0.1422316 -0.8335784 0.5288483 0.1595825 -0.6601951 0.7418543 0.117451 -0.9188987 0.2847371 0.2730386 -0.4113458 0.9039712 0.1167513 -0.8496652 0.4806094 0.2169877 -0.2926909 0.9537158 0.06898033 -0.9026939 0.2756028 0.3304343 -0.7337075 0.6006407 0.317654 -0.6633687 0.7036033 0.2547243 -0.4857283 0.8564097 0.1750155 -0.8016777 0.4223974 0.4229577 -0.735473 0.580654 0.3491709 -0.7868608 0.372682 0.4918926 -0.7453639 0.4487389 0.4930173 -0.2837498 0.9451242 0.1619461 -0.5528956 0.7596671 0.3423633 -0.4336919 0.8537887 0.2880215 -0.7470822 0.2603971 0.6116058 -0.715745 0.4315001 0.5491053 -0.5836487 0.6397539 0.5000692 -0.4305832 0.8368241 0.3381179 -0.6511847 0.3972035 0.6466746 -0.5861734 0.5662164 0.5794824 -0.6618302 0.2743937 0.697631 -0.2779896 0.9203961 0.2749413 -0.4791627 0.6898952 0.5426304 -0.4116401 0.7753012 0.4790205 -0.5644042 0.3679041 0.7389821 -0.5386031 0.4322395 0.7232398 -0.5091063 0.4621754 0.7260886 -0.08287078 0.9915772 0.09953546 -0.3265646 0.8078466 0.4906522 -0.4891008 0.3865201 0.7819098 -0.2977816 0.8313756 0.4691918 -0.2483176 0.8794535 0.4060787 -0.3657923 0.5824391 0.7259206 -0.1913858 0.9009454 0.3894473 -0.3502539 0.4560014 0.8181595 -0.3421913 0.567469 0.7489221 -0.2482757 0.7449521 0.6191975 -0.3194224 0.3862323 0.8653289 -0.1085937 0.958356 0.2641236 -0.2250027 0.5663247 0.7928746 -0.1950342 0.7645233 0.6143824 -0.141248 0.8503555 0.506897 -0.1821851 0.3762925 0.9084122 -0.1740157 0.4608672 0.8702415 -0.1047322 0.8702114 0.4814181 -0.1166191 0.5819439 0.8048238 -0.05946195 0.9251806 0.37484 -0.09214609 0.585744 0.8052411 -0.04197239 0.3667296 0.9293802 -0.0234192 0.7756301 0.6307531 -0.01968646 0.8618017 0.5068632 0.02261805 0.4270827 0.9039297 0.04724568 0.586355 0.8086754 0.02202528 0.9375418 0.3471748 0.1539402 0.4330548 0.8881251 0.02126425 0.9849205 0.1716958 0.08858883 0.6213911 0.7784762 0.09795987 0.7528337 0.6508805 0.2013516 0.4395537 0.8753572 0.2181821 0.6291176 0.7460615 0.1519461 0.7748827 0.6135709 0.1161507 0.9041838 0.4110483 0.3309872 0.4015946 0.8539141 0.2577676 0.5980274 0.7588933 0.3908979 0.3890508 0.8341693 0.3936401 0.5063586 0.7672344 0.2851433 0.7275328 0.6240108 0.2321012 0.8480519 0.4763792 0.1500619 0.9290913 0.3380399 0.4607557 0.4767332 0.7486186 0.4724535 0.4539051 0.7554854 0.07481229 0.9877732 0.1367741 0.3085148 0.8275756 0.4689747 0.2982805 0.8587694 0.4165861 0.5413116 0.4060221 0.7362933 0.540714 0.5569136 0.6304566 0.4283022 0.7541417 0.4978229 0.3336455 0.8434016 0.421135 0.6298322 0.4144793 0.6569006 0.4395992 0.7990858 0.4101397 0.1960971 0.9632443 0.183593 0.7350156 0.3391984 0.5871086 0.6718847 0.4743822 0.5687991 0.2838878 0.9279727 0.2414011 0.6136748 0.6065914 0.5054209 0.3662889 0.8938668 0.2585242 0.7745375 0.3576286 0.5217217 0.6798666 0.6094309 0.4078913 0.579428 0.7157452 0.3898361 0.8197897 0.4107201 0.3990665 0.6973608 0.6045466 0.3849824 0.5791422 0.7743517 0.2548995 0.8473403 0.3919752 0.3582877 0.2620609 0.9546701 0.14117 0.7150455 0.6558044 0.2421376 0.5922769 0.7696503 0.238425 0.1134351 0.9925171 0.04519331 0.8911901 0.3971578 0.2191941 0.2353726 0.969244 0.07187485 0.7244112 0.6494204 0.231261 0.914158 0.3722161 0.1605315 0.9070307 0.392418 0.1526549 0.5514665 0.8274842 0.1056152 0.4295869 0.8992801 0.08216172 0.7219518 0.6864787 0.08679139 0.951727 0.3056571 0.02809941 0.8904596 0.4549629 0.009524524 0.7329782 0.6794252 0.03353273 0.6090697 0.7931153 -0.001513123 0.3064659 0.9517541 0.0155847 -0.001559913 0.9999977 0.001478075 -0.001390457 0.9999976 0.001746177 -0.001345098 0.9999969 0.002100467 -0.001497089 0.9999985 9.0921e-4 -5.20397e-4 0.9999967 0.002525508 -9.99115e-4 0.9999962 0.00257045 -0.001650214 0.9999986 4.66376e-4 -0.002985298 0.9999951 -0.001009941 -3.78977e-4 0.9999961 0.002762854 5.39468e-4 0.9999939 0.003471791 -0.002959668 0.9999953 7.94404e-4 -0.0026564 0.9999966 3.47289e-5 -0.002484917 0.9999921 0.003138899 6.67758e-5 0.9999999 5.75203e-4 -0.002690255 0.9999964 -3.5788e-4 -0.002474308 0.9999967 -7.34893e-4 2.19045e-4 0.9999999 5.05249e-4 -0.002497076 0.9999955 -0.001689255 -0.002442955 0.9999956 -0.00172466 0.003433585 0.9999939 7.29061e-4 -0.004197895 0.9999903 0.001394391 0.001986682 0.9999951 0.002423882 -1.9593e-4 0.9999939 0.003508269 -3.37313e-4 1 -4.24621e-4 7.93727e-4 0.9999995 6.392e-4 8.67527e-4 0.9999975 -0.002079546 9.70699e-4 0.9999995 4.10491e-4 -3.82534e-5 1 -1.06309e-4 -0.002589166 0.9999963 -9.06878e-4 3.614e-4 0.9999998 7.00922e-4 -3.72025e-6 1 -1.08983e-4 3.7136e-4 1 7.38436e-6 3.46262e-4 1 4.32626e-5 0.002381563 0.9999955 -0.001893341 8.73707e-4 0.9999961 -0.002672493 2.33704e-4 1 -8.8921e-5 4.18705e-4 0.9999965 -0.002623319 -8.50089e-5 0.9999988 -0.001612246 0.001385569 0.9999986 -9.76636e-4 0.00105822 0.9999986 -0.00131154 7.10235e-4 0.9999969 -0.002425372 0.9980175 0.06093364 -0.01575338 0.9840995 -0.03423726 -0.1742874 0.9846621 -0.04822915 -0.1676742 0.9590234 0.05194312 -0.2785247 0.9283768 0.04357832 -0.3690767 0.8994413 -0.05097913 -0.4340584 0.8692805 0.02652239 -0.4936073 0.8058169 0.01670801 -0.5919291 0.7750064 -0.05108737 -0.6298852 0.7085149 0.06229674 -0.7029409 0.6393798 0.05037575 -0.7672391 0.5688443 -0.05433112 -0.8206488 0.5321816 0.01683092 -0.846463 0.4488366 0.06489759 -0.8912541 0.3302647 -0.01334577 -0.943794 0.2931396 -0.08562159 -0.9522281 0.2034882 0.04379397 -0.9780975 0.08443427 0.06598466 -0.9942419 -0.02535551 -0.08003455 -0.9964696 -0.08691114 0.02544629 -0.9958911 -0.2119008 0.03947502 -0.9764937 -0.2950999 -0.05013889 -0.95415 -0.3414866 0.02729755 -0.9394901 -0.478215 0.04256212 -0.877211 -0.5626164 -0.06438922 -0.8242068 -0.5666945 -0.05493026 -0.8220949 -0.68513 0.08651584 -0.7232648 -0.8048768 -0.07766133 -0.5883386 -0.8060513 -0.07338076 -0.587279 -0.8660448 0.04963248 -0.4974968 -0.9139074 0.0628485 -0.4010281 -0.9546098 -0.04824572 -0.293926 -0.9639153 0.007179081 -0.2661125 -0.992582 0.03859889 -0.1152876 -0.9971511 -0.07146704 -0.02413141 -0.9995441 0.01587206 0.02568703 -0.9895856 0.05911296 0.1312473 -0.9682203 -0.0368129 0.2473749 -0.962765 0.0028705 0.2703245 -0.8805412 -0.05170804 0.4711406 -0.9134369 0.02491414 0.4062171 -0.860386 0.01992791 0.5092532 -0.8164123 0.07177859 0.5729913 -0.7388161 0.03364396 0.6730669 -0.6901896 -0.07145005 0.7200925 -0.6526238 0.00729227 0.7576471 -0.5616874 0.05480748 0.8255323 -0.445743 -0.03725415 0.8943855 -0.4601002 -0.01486462 0.8877425 -0.4009321 0.0190562 0.9159095 -0.2938855 0.04742121 0.9546636 -0.1933606 -0.03511071 0.9804994 -0.1930401 -0.03575032 0.9805394 -0.05287176 0.04871815 0.9974123 0.04009056 2.709e-4 0.9991961 0.03458595 0.01077538 0.9993436 0.2188072 -0.02618139 0.9754168 0.1652988 0.01198208 0.9861708 0.2776479 0.04397982 0.9596757 0.4163159 -0.02527803 0.9088686 0.3969762 0.005741834 0.917811 0.5237795 0.04195719 0.8508201 0.5872116 -0.05147331 0.8077951 0.6712238 0.073816 0.7375702 0.7797912 -0.0123893 0.625917 0.787679 -0.04685419 0.6143016 0.8825553 0.03107321 0.4691811 0.9154205 -0.04026132 0.4004803 0.9195178 -0.02457374 0.3922795 0.961834 0.07249242 0.2638566 0.984167 0.04883939 0.1703821 0.9918774 -0.08018165 0.09874325 0.9968795 -0.0343762 -0.07106065 0.9795305 -0.07215631 -0.1879188 0.9300586 -0.02338415 -0.3666664 0.9443448 0.08898812 -0.3166922 0.879226 -0.06199246 -0.4723542 0.8102194 0.07278901 -0.5815896 0.7798846 -0.03236961 -0.6250857 0.6454173 -0.002079844 -0.7638275 0.6501468 -0.01608669 -0.7596384 0.4939447 0.01824909 -0.8693019 0.4936889 0.01760637 -0.8694604 0.3804342 -0.07706367 -0.9215916 0.2395151 0.05168288 -0.9695161 0.2557169 0.01508212 -0.966634 0.1003341 -0.03267806 -0.994417 0.01724225 0.06341278 -0.9978384 -0.05169975 -0.04938453 -0.9974409 -0.2104704 -0.05316293 -0.9761537 -0.2928013 0.09790569 -0.9511477 -0.3830447 -0.04911351 -0.9224234 -0.4713652 -0.05477505 -0.8802356 -0.5303343 -0.00412184 -0.8477786 -0.5740392 0.09445464 -0.8133618 -0.646905 -0.04973292 -0.7609472 -0.7493379 -0.06510967 -0.6589792 -0.7994624 0.07226926 -0.5963531 -0.8572325 -0.04084569 -0.513307 -0.9128537 0.01148074 -0.4081256 -0.9230953 0.05340433 -0.3808453 -0.9487276 -0.04036897 -0.3135067 -0.981406 -0.05665326 -0.1833924 -0.9942951 0.08374232 -0.06606519 -0.9956 0.03693264 -0.08612012 -0.9973146 -0.04370236 0.0587691 -0.9826942 0.04749464 0.1790431 -0.981241 0.02010166 0.1917343 -0.9671925 -0.0431413 0.2503548 -0.9254157 -0.04877012 0.3758022 -0.8972715 0.02860003 0.4405518 -0.8848262 0.07733362 0.4594588 -0.835835 -0.04170185 0.5473946 -0.7890739 -0.05809521 0.611545 -0.7058393 0.05768847 0.7060192 -0.7223095 0.004103541 0.6915578 -0.5782637 -0.01584309 0.8156961 -0.5521729 0.02597427 0.833325 -0.4635522 -0.0558747 0.8843061 -0.3385422 0.05308014 0.9394529 -0.2939181 -0.03416848 0.9552197 -0.1112973 -0.02160948 0.9935522 -0.06566178 0.06082856 0.9959862 0.03704982 -0.04347831 0.9983672 0.1530047 -0.009059309 0.988184 0.1928296 0.05936706 0.9794347 0.2921588 -0.0485984 0.9551343 0.3887221 -0.02171391 0.9210992 0.4376713 0.06009489 0.8971245 0.5101233 -0.03635036 0.8593328 0.591291 -0.03851145 0.8055384 0.6350424 0.02767956 0.7719814 0.6852506 -0.0264185 0.7278281 0.764979 0.02383911 0.6436139 0.7857967 -0.03035426 0.6177398 0.8622521 -0.03248131 0.5054368 0.9110755 -0.02235376 0.4116331 0.8880031 0.02842265 0.4589582 0.9522002 -0.02742928 0.3042408 0.9723241 -0.01594936 0.2330911 0.9640367 0.01589757 0.2652936 0.9925783 -0.0461114 0.1125262 0.999347 0.01165878 0.03419983 0.9979724 0.06358146 0.002927482 0.8814097 -0.4723294 0.004680097 0.8122696 -0.5825542 0.02913343 0.3598643 -0.9329358 0.01133048 0.8110359 -0.5826658 0.05216908 0.8999955 -0.4147364 0.1341708 0.8960696 -0.4166098 0.153283 0.5295344 -0.8428496 0.09590554 0.3972367 -0.9154657 0.06423205 0.2972064 -0.9527878 0.06215924 0.7762124 -0.5950799 0.2082648 0.6702648 -0.7188649 0.1843323 0.8536653 -0.4274799 0.2975175 0.5715296 -0.791431 0.216774 0.797048 -0.4880401 0.3557127 0.8059772 -0.4624015 0.369575 0.3695671 -0.9185174 0.1405199 0.6429455 -0.7096873 0.2880367 0.5624526 -0.7614809 0.3221707 0.7874077 -0.4144214 0.4563378 0.705603 -0.5349922 0.4646588 0.5799339 -0.7310924 0.3594171 0.1950967 -0.9746788 0.1092638 0.7047632 -0.5280773 0.4737544 0.1954669 -0.9745756 0.1095224 0.762247 -0.2173151 0.6097162 0.6796001 -0.3946567 0.6183769 0.405475 -0.8570635 0.3178561 0.5986689 -0.5885298 0.5433493 0.5866764 -0.6224396 0.518054 0.2506638 -0.9494485 0.1889851 0.4560274 -0.7951833 0.3996533 0.6720426 -0.2076408 0.7108053 0.3382977 -0.8592788 0.3836596 0.4904447 -0.6531209 0.5769724 0.1628435 -0.9749315 0.1516264 0.5609952 -0.4005101 0.7244833 0.3489662 -0.8354609 0.4245324 0.5382812 -0.4608566 0.7055952 0.3172475 -0.8508606 0.4187965 0.4483238 -0.533438 0.7172515 0.3419384 -0.7289618 0.593037 0.4525505 -0.3473255 0.821318 0.3217853 -0.7716898 0.5485883 0.08398562 -0.983952 0.1574323 0.382068 -0.3526176 0.854216 0.3382115 -0.457438 0.8224132 0.1450348 -0.9368547 0.3182268 0.2989531 -0.597634 0.7439494 0.274024 -0.2175891 0.9367849 0.2237444 -0.7089971 0.6687763 0.1618276 -0.8388566 0.5197416 0.195723 -0.3676737 0.9091252 0.1831074 -0.5520321 0.8134694 0.1562573 -0.281435 0.9467725 0.09079521 -0.7276491 0.679914 0.0821557 -0.3982058 0.9136096 0.08672559 -0.8932879 0.4410389 0.08147603 -0.8799191 0.4680856 0.06493884 -0.6697208 0.7397682 0.0336911 -0.280363 0.9593026 4.55284e-4 -0.7154569 0.6986568 -0.04957306 -0.4074887 0.9118638 -0.04234623 -0.6233195 0.7808198 -0.1086681 -0.2624394 0.9588101 -0.02027523 -0.9031178 0.428914 -0.01372897 -0.9231337 0.3842342 -0.1038175 -0.7162889 0.6900379 -0.01457613 -0.9935523 0.1124335 -0.08151662 -0.82753 0.555472 -0.1774492 -0.4417614 0.8794081 -0.1570028 -0.6056368 0.7800989 -0.2792172 -0.2567986 0.9252525 -0.2985563 -0.3974871 0.8676798 -0.1089833 -0.9267706 0.3594705 -0.2407453 -0.6879656 0.6846496 -0.127663 -0.891874 0.4338929 -0.2394412 -0.7286228 0.6416984 -0.3942699 -0.3927923 0.8308222 -0.3210234 -0.6898618 0.6488719 -0.4495324 -0.2400381 0.8604083 -0.331532 -0.710841 0.6203158 -0.2733069 -0.8466838 0.4565414 -0.4837692 -0.4468597 0.7525184 -0.4480843 -0.5508022 0.7041572 -0.1198969 -0.963631 0.2388308 -0.5624239 -0.2801367 0.7779479 -0.03413569 -0.9983343 0.04651302 -0.3125621 -0.8520665 0.4198664 -0.4375063 -0.7294597 0.5258107 -0.6100003 -0.4311535 0.6648357 -0.478051 -0.695867 0.5359445 -0.6638858 -0.3317027 0.6702455 -0.1537595 -0.974318 0.1645064 -0.4612106 -0.7716231 0.4380443 -0.7042148 -0.4072912 0.5815458 -0.3246984 -0.9043897 0.2768582 -0.6735143 -0.5193293 0.5259997 -0.3522492 -0.9032344 0.2451292 -0.6833118 -0.5649476 0.4625141 -0.8218055 -0.3146753 0.4749897 -0.4471679 -0.8513993 0.2741534 -0.7728798 -0.4517961 0.4455751 -0.747648 -0.553097 0.3675678 -0.4714698 -0.8430883 0.2586862 -0.8670245 -0.3754205 0.3276096 -0.7837763 -0.5254975 0.3309791 -0.6363889 -0.7421725 0.2102125 -0.8980391 -0.3511083 0.265045 -0.3913552 -0.9079897 0.1496524 -0.3354967 -0.934621 0.1180068 -0.7130888 -0.6821074 0.161969 -0.7832785 -0.5999875 0.162757 -0.4575862 -0.8846706 0.08929133 -0.9218602 -0.3712353 0.1111676 -0.8463643 -0.5194543 0.117622 -0.9636382 -0.2588874 0.06617337 -0.7565475 -0.6525005 0.04334926 -0.02330517 -0.9997231 0.003256261 -0.374117 -0.9269813 0.02724081 -0.6031216 -0.7976082 0.008088171 -0.9188261 -0.3945906 -0.007558763 -0.1993368 -0.9799213 0.004393517 -0.9299097 -0.3612293 -0.069148 -0.8895787 -0.4448577 -0.1036882 -0.6896395 -0.7191138 -0.08528083 -0.9332299 -0.3125502 -0.1771845 -0.5550525 -0.8230917 -0.1201537 -0.8769302 -0.4086319 -0.2530091 -0.5533958 -0.8237437 -0.1232861 -0.8829784 -0.3764691 -0.2803928 -0.5846239 -0.798018 -0.1462268 -0.1959287 -0.9779897 -0.07175052 -0.8411501 -0.4377853 -0.3175068 -0.612055 -0.7494658 -0.2523681 -0.8496981 -0.3593731 -0.385829 -0.8095882 -0.4157178 -0.4144219 -0.5511175 -0.790293 -0.2677807 -0.6112663 -0.7206261 -0.3271875 -0.8220616 -0.2793023 -0.4961907 -0.3854215 -0.9020812 -0.1941642 -0.7442123 -0.419292 -0.5199446 -0.608706 -0.661307 -0.4383493 -0.5650968 -0.7015783 -0.4341124 -0.7382044 -0.2182668 -0.6382898 -0.4214647 -0.8370556 -0.3488632 -0.228847 -0.9572566 -0.1768869 -0.6042748 -0.5333941 -0.5918976 -0.1454337 -0.981535 -0.1242504 -0.574979 -0.5572694 -0.5990409 -0.4183217 -0.7768482 -0.4706526 -0.5921575 -0.3424607 -0.7294315 -0.3687263 -0.8153688 -0.4463348 -0.2270197 -0.9349504 -0.272635 -0.5212962 -0.4022618 -0.7526193 -0.469558 -0.5025805 -0.7258983 -0.3704632 -0.7564055 -0.5390806 -0.4313087 -0.4645242 -0.7734276 -0.2288783 -0.8656795 -0.4452121 -0.09007132 -0.9820177 -0.1659168 -0.3385232 -0.3498547 -0.873501 -0.3486788 -0.545738 -0.7619667 -0.1174668 -0.9637411 -0.2395927 -0.2699089 -0.7216847 -0.6374327 -0.2805316 -0.4095759 -0.8680723 -0.1800009 -0.7283849 -0.6611016 -0.2069833 -0.2294294 -0.9510626 -0.187477 -0.7207722 -0.667338 -0.1574668 -0.4066609 -0.8999062 -0.08305597 -0.9431756 -0.3217476 -0.1386371 -0.6621649 -0.7364221 -0.05229872 -0.9615657 -0.2695484 -0.04815793 -0.2723214 -0.9610005 -0.07459628 -0.7490009 -0.6583564 -0.03676921 -0.8796412 -0.4742144 -0.01078581 -0.4048563 -0.9143168 -7.64473e-4 -0.5837128 -0.8119599 -0.002765357 -0.8897138 -0.4565106 0.04815852 -0.6835718 -0.7282928 0.0983414 -0.2383357 -0.9661911 0.1426343 -0.4526277 -0.880218 0.07449775 -0.6676215 -0.7407642 0.02547699 -0.9644417 -0.2630649 0.1957365 -0.4303444 -0.8811873 0.1215976 -0.8420983 -0.5254376 0.2183616 -0.5030217 -0.8362341 0.2106529 -0.6708448 -0.7110504 0.1302831 -0.8373789 -0.5308702 0.3669114 -0.2542872 -0.8948263 0.1244084 -0.9456411 -0.3004755 0.3668878 -0.5293744 -0.7649549 0.3086898 -0.6528277 -0.6917562 0.2442353 -0.8515251 -0.463955 0.4727409 -0.4286906 -0.7698964 0.4522926 -0.4836903 -0.7493165 0.4165866 -0.6552103 -0.6302025 0.2790399 -0.8381954 -0.4685779 0.6303565 -0.2023792 -0.7494621 0.4961097 -0.6397522 -0.5870199 0.6104807 -0.4225354 -0.6699084 0.2078744 -0.946085 -0.248418 0.3847861 -0.8413786 -0.3795021 0.6682906 -0.4539844 -0.5893098 0.3269989 -0.8859887 -0.3287796 0.5411164 -0.7133554 -0.4453282 0.7682833 -0.2070888 -0.6056856 0.558247 -0.7254429 -0.4026078 0.7988021 -0.3627089 -0.4799559 0.7562681 -0.4852173 -0.438888 0.7298111 -0.5802568 -0.3614938 0.1594727 -0.982828 -0.09283113 0.429181 -0.8670658 -0.2529834 0.2818277 -0.9482662 -0.1461664 0.7412391 -0.578096 -0.3411301 0.8977347 -0.2906014 -0.3310942 0.880345 -0.401362 -0.2527872 0.5935202 -0.7800547 -0.1981122 0.4713703 -0.8671985 -0.1605516 0.6888247 -0.7000611 -0.1882423 0.9337502 -0.3054296 -0.1866103 0.8868241 -0.442017 -0.1347748 0.7148611 -0.6908687 -0.1080467 0.6908963 -0.7136627 -0.1155335 0.3667266 -0.926923 -0.07953238 0.9314031 -0.35653 -0.07331323 0.6550002 -0.7554617 -0.01588988 0.1751624 -0.9844177 -0.01549309 6.3503e-4 -0.9999997 6.7306e-4 0.003148734 -0.9999088 0.01313728 0.006171584 -0.9999535 0.007411301 0.002256214 -0.9999969 -0.001081168 0.003908932 -0.9999903 0.002046465 0.00243479 -0.9999828 0.005344271 0.00379467 -0.9999899 0.00243175 0.001181721 -0.9999842 0.005514442 0.002450585 -0.9999969 5.30283e-4 4.04019e-4 -0.9999786 0.006550371 0.002749621 -0.9999961 -5.39165e-4 0.00336498 -0.9999944 -2.88152e-4 -5.1914e-4 -0.9999778 0.006646215 0.00139755 -0.9999894 0.00439316 -7.08842e-4 -0.9999977 0.002058863 0.002762973 -0.9999955 -0.001168727 0.002488195 -0.9999968 -6.17294e-4 -0.001381039 -0.999997 0.002039194 -0.001458525 -0.9999963 0.002327561 0.001061618 -0.9999989 -9.99705e-4 -0.001396656 -0.9999983 0.001233935 0.004227399 -0.9999664 -0.007029175 -5.78564e-5 -0.9999726 -0.007414638 -0.003859102 -0.9999926 -2.68321e-4 -0.003423571 -0.9999932 0.001433432 0.002910494 -0.9999489 -0.009688317 0.002534925 -0.9999511 -0.009566605 -0.005364537 -0.9999855 7.05808e-4 0.002791523 -0.9999485 -0.009765744 -0.006051301 -0.9999816 5.84257e-4 1.92105e-4 -0.9999714 -0.007560133 0.00372219 -0.9999722 -0.006468176 -0.004925251 -0.9999879 -4.16075e-4 -2.99989e-4 -0.9999996 -9.15729e-4 -0.004841804 -0.9999867 -0.001811206 -0.003536343 -0.9999938 5.28299e-5 -0.001334547 -0.9999983 -0.00128138 -0.00242263 -0.9999957 -0.001716494 -0.002356767 -0.9999964 -0.00138837 -0.001254737 -0.999998 -0.00154525 0.9443661 0.3286482 -0.01277631 0.921361 0.3880258 -0.02302265 0.8718593 0.4764998 -0.1131785 0.5797612 0.811075 -0.07768118 0.9042701 0.3972337 -0.1565278 0.06341058 0.9978965 -0.01348227 0.5172796 0.849525 -0.1035822 0.8679382 0.440985 -0.2285075 0.8192848 0.519061 -0.243615 0.5904858 0.7902984 -0.1635699 0.1700389 0.9843095 -0.04713571 0.8440855 0.4048796 -0.351557 0.8114601 0.4899676 -0.3185346 0.5277944 0.8091446 -0.2582991 0.4812214 0.8518872 -0.2066744 0.8185085 0.3343253 -0.4671943 0.5209583 0.8099238 -0.2694925 0.7403258 0.4727117 -0.4779764 0.6733999 0.5943937 -0.4395779 0.7702262 0.2868386 -0.5696273 0.3068414 0.9284614 -0.2093033 0.5567495 0.7015085 -0.4448775 0.3416167 0.8988074 -0.2746698 0.679633 0.3854292 -0.6241341 0.5888529 0.5747569 -0.5682489 0.5047408 0.6503811 -0.5676628 0.2729648 0.923277 -0.2702772 0.4935095 0.6076117 -0.6222993 0.143253 0.9749112 -0.1703728 0.4862842 0.6112006 -0.624469 0.4563735 0.5573373 -0.6936126 0.2309389 0.8980796 -0.3743265 0.3876207 0.6155366 -0.6861959 0.38336 0.3718149 -0.8454518 0.2273064 0.8773637 -0.4225695 0.3582434 0.5439647 -0.7587912 0.2891473 0.650003 -0.7027732 0.3238688 0.2111092 -0.9222483 0.1547049 0.9084671 -0.3882706 0.1856331 0.8849197 -0.4271504 0.226437 0.4385951 -0.86969 0.2108709 0.5839397 -0.783931 0.1686714 0.6873279 -0.7064916 0.1244764 0.8516547 -0.5091071 0.1939066 0.3191118 -0.927668 0.08341878 0.8951717 -0.4378459 0.0769937 0.4037594 -0.9116197 0.0925033 0.3369504 -0.9369673 0.08072096 0.5969532 -0.7982049 0.03320538 0.7353782 -0.676843 0.03535377 0.8394421 -0.5422981 -0.03256523 0.415035 -0.9092224 -0.03170585 0.6687204 -0.7428377 -0.07705515 0.2775657 -0.9576116 -0.06448894 0.7243178 -0.6864438 -0.07155036 0.861944 -0.5019297 -0.1642616 0.4524745 -0.8765187 -0.02694487 0.937301 -0.3474777 -0.1853421 0.4378258 -0.8797482 -0.2269034 0.5345378 -0.8141157 -0.1233064 0.8431927 -0.5232797 -0.236157 0.5309317 -0.8138436 -0.3375692 0.285121 -0.8970803 -0.2484483 0.7702153 -0.5874028 -0.1481299 0.8815016 -0.4483444 -0.4086694 0.4206404 -0.8099698 -0.2680372 0.7595907 -0.5926029 -0.04846239 0.9935473 -0.1025436 -0.4255721 0.3967179 -0.8133286 -0.2814733 0.8291969 -0.4829132 -0.5362995 0.3675399 -0.759801 -0.4810378 0.4682649 -0.7411684 -0.2202435 0.9130898 -0.343162 -0.415732 0.670804 -0.6141571 -0.5829989 0.4245295 -0.6927388 -0.472615 0.6912091 -0.5466855 -0.4725329 0.6913829 -0.5465368 -0.6697683 0.2433898 -0.7015497 -0.2877848 0.8992816 -0.3293519 -0.677775 0.4110418 -0.609644 -0.577873 0.6262016 -0.5233874 -0.2558656 0.9309061 -0.2606655 -0.5385072 0.7189923 -0.4393861 -0.7594439 0.3095448 -0.5722124 -0.4222764 0.8455286 -0.3267478 -0.7377393 0.4524086 -0.5010661 -0.7905532 0.4158406 -0.449558 -0.533191 0.7882589 -0.3071734 -0.7559736 0.4675557 -0.4581437 -0.4052391 0.8738444 -0.2686585 -0.2823109 0.9449363 -0.1655173 -0.8220205 0.4277426 -0.3759236 -0.7911403 0.5168734 -0.3270154 -0.5923663 0.7732222 -0.2263402 -0.5940648 0.7718822 -0.2264618 -0.3253353 0.9343121 -0.1456645 -0.9114534 0.3252956 -0.2518643 -0.6012234 0.7753631 -0.1932429 -0.8620498 0.4646533 -0.2024042 -0.7663384 0.6193367 -0.1707272 -0.1010017 0.9946466 -0.0218389 -0.4137663 0.906705 -0.08175241 -0.7077862 0.7021803 -0.07734006 -0.2057543 0.9781346 -0.03029721 -0.9255478 0.3708339 -0.07644218 -0.938823 0.3369173 -0.07140123 -0.7127915 0.6975476 -0.07318198 -0.9517102 0.3069896 0.00230807 -0.6326797 0.7743576 -0.009326934 -0.8709928 0.485966 0.07217168 -0.3721018 0.9281705 0.006313085 -0.7581702 0.6487984 0.06510466 -0.9344936 0.3323656 0.1274946 -0.3120045 0.9490144 0.04500204 -0.6294513 0.7691484 0.1104616 -0.2668986 0.9627288 0.04379898 -0.882404 0.3974595 0.251772 -0.9012357 0.3554056 0.2479137 -0.7354272 0.6449763 0.2077317 -0.6499531 0.7174087 0.2507705 -0.4307168 0.8810672 0.1954581 -0.8529589 0.3652169 0.3729316 -0.8000838 0.4663771 0.377304 -0.7834827 0.4627939 0.4147008 -0.3555403 0.9153831 0.1888519 -0.7184882 0.5466959 0.4299982 -0.4391067 0.8515958 0.2863041 -0.705143 0.4733703 0.5279147 -0.4364711 0.8392047 0.3243893 -0.6859397 0.4954636 0.5329189 -0.6730517 0.4362455 0.5972365 -0.3508536 0.8822317 0.3139567 -0.3619909 0.8602765 0.3590083 -0.5435376 0.5879732 0.5990447 -0.573282 0.4173635 0.7050926 -0.539796 0.5600993 0.6284179 -0.5373674 0.3011488 0.7877472 -0.3925026 0.7174558 0.5754989 -0.1997736 0.9355708 0.2912005 -0.4607609 0.4083921 0.7879818 -0.2278205 0.9051242 0.3589541 -0.4014828 0.5569254 0.7270803 -0.2245073 0.895884 0.3833907 -0.3522797 0.6055955 0.7135496 -0.2779549 0.760518 0.5868163 -0.3196016 0.4736682 0.8206664 -0.3023681 0.480621 0.8231508 -0.2671739 0.3673037 0.8909019 -0.1751829 0.784126 0.5953632 -0.1713562 0.82456 0.5392012 -0.08838266 0.9574948 0.2745769 -0.1667795 0.3510345 0.9213899 -0.1930586 0.4219355 0.8858323 -0.1489846 0.7435672 0.6518523 -0.04328995 0.9837875 0.1740351 -0.09937018 0.3991646 0.9114786 -0.04431599 0.6002391 0.798592 -0.08402371 0.7887474 0.6089481 -0.0413056 0.9071543 0.4187661 -0.01155149 0.611462 0.7911896 0.06791651 0.4363955 0.897188 0.1160838 0.4708898 0.8745213 0.03272503 0.8922165 0.4504207 0.1409821 0.543502 0.827484 0.03050607 0.889913 0.4551091 0.0997129 0.7930556 0.6009329 0.2207336 0.4848993 0.8462561 0.2753403 0.2962307 0.9145684 0.03073632 0.9888049 0.1460143 0.1594122 0.870702 0.4652589 0.236119 0.7256466 0.6462855 0.3723163 0.3278336 0.8682776 0.1588727 0.8712489 0.4644188 0.3799526 0.4795116 0.791015 0.3585411 0.5537056 0.7515707 0.5072117 0.2609164 0.8213763 0.3262722 0.7873032 0.5231636 0.21908 0.8986935 0.3799395 0.1280004 0.9730564 0.1917736 0.5293065 0.4536312 0.7169752 0.4274995 0.7001164 0.5719103 0.6526496 0.2432868 0.7175375 0.4328998 0.758563 0.4870112 0.6480451 0.4334776 0.6262066 0.3610308 0.8588094 0.3634603 0.2887009 0.9124948 0.2898365 0.741003 0.34034 0.5788637 0.6962857 0.429989 0.5747137 0.5282581 0.7474297 0.4028552 0.1914868 0.9684684 0.1593799 0.5131985 0.7851474 0.3466569 0.7761523 0.438823 0.4527937 0.3468225 0.9119362 0.2192867 0.7149418 0.5826006 0.386568 0.7151535 0.5841814 0.3837808 0.3043536 0.9414024 0.1453629 0.8528228 0.4152213 0.3166775 0.5434002 0.8083308 0.2265339 0.8459852 0.4517362 0.283273 0.8099609 0.5292363 0.2527298 0.402613 0.9006232 0.1636478 0.3946025 0.9131479 0.1022242 0.778005 0.6040667 0.1726605 0.9140506 0.383344 0.13251 0.7900633 0.5963194 0.1421376 0.3345187 0.9405524 0.05880796 0.3404142 0.938293 0.0610283 0.7331944 0.6708542 0.1112692 0.6973193 0.7163305 0.02482885 0.520953 0.8535174 -0.01077783 0.3997815 0.9165952 0.005317747 -0.004309415 0.9999906 6.14585e-4 -0.004250347 0.9999859 0.00318396 -0.001969397 0.9999936 0.003014087 -0.001967608 0.9999945 0.002680599 -0.007429361 0.9999707 0.00191164 -0.007535934 0.9999682 0.002641916 -0.001008749 0.9999942 0.003273129 -0.005037188 0.9999737 0.00523591 -9.89775e-4 0.999994 0.003352165 -0.001474559 0.999999 1.59111e-4 2.533e-5 0.9999961 0.002840697 -0.001537859 0.9999988 -2.35598e-4 -0.002803266 0.9999952 -0.00130707 0.004000663 0.9999725 0.006263315 0.003194391 0.9999635 0.007934212 -5.00565e-4 0.999971 0.007605731 -0.002762198 0.9999953 -0.001332044 -0.003342807 0.9999655 -0.007613778 -0.006144285 0.9999659 -0.005531191 0.001006007 0.999999 0.001103281 -0.005997836 0.9999812 -0.001321077 0.00308752 0.999995 8.22873e-4 -0.002115666 0.9999907 -0.003756046 0.00295639 0.9999944 0.001613914 -0.001764595 0.999973 -0.007140696 0.005659461 0.9999839 5.91043e-4 0.005553066 0.9999837 0.001309633 -0.001536905 0.9999737 -0.007097721 0.00318253 0.9999907 0.002930045 1.18759e-4 0.9999643 -0.008450806 9.50075e-4 0.9999495 -0.01001954 0.002779841 0.9999961 -6.11037e-5 0.004817962 0.9999858 -0.002323091 6.25945e-4 0.9999502 -0.009957492 0.002652227 0.9999647 -0.007978618 0.006395995 0.999978 -0.001839995 -0.001965165 0.9999797 -0.00606662 0.005264103 0.9999812 -0.00318551 0.004907131 0.9999866 -0.001706659 0.002743422 0.9999909 -0.003293573 0.003425419 0.9999879 -0.003532707 0.9988399 -0.01907229 -0.04421752 0.9937471 -0.08268564 -0.07503193 0.9849443 0.05273789 -0.1646313 0.9577 0.07400518 -0.2780901 0.9442058 0.03215384 -0.3277829 0.9119632 -0.114848 -0.3938694 0.8900099 0.01587659 -0.4556649 0.834147 0.06647366 -0.5475217 0.7646442 -0.04789686 -0.6426703 0.7492045 0.001588165 -0.6623369 0.6811864 0.04335552 -0.7308252 0.6281919 0.004267752 -0.7780469 0.5951963 -0.0631296 -0.8010969 0.5181879 0.06056946 -0.8531193 0.4366026 0.05678915 -0.8978604 0.3565987 -0.04665809 -0.9330918 0.3344992 -0.003636598 -0.9423891 0.2545326 0.05287617 -0.9656176 0.09036469 -0.07015359 -0.9934349 0.134935 0.008566677 -0.9908175 2.83897e-4 0.06647211 -0.9977883 -0.1447991 0.05158805 -0.9881153 -0.2224947 -0.06827151 -0.9725406 -0.261864 0.004627227 -0.9650937 -0.3214597 0.03325229 -0.9463393 -0.4280803 0.01877713 -0.9035457 -0.4571284 -0.03391498 -0.888754 -0.5301128 0.03293007 -0.8472874 -0.5815696 0.01243185 -0.8134016 -0.6191161 -0.05277907 -0.7835239 -0.6806963 0.06127196 -0.729999 -0.7503234 0.05976146 -0.6583642 -0.8074946 -0.05225521 -0.5875557 -0.7996066 -0.01829117 -0.6002456 -0.8631244 0.04032498 -0.5033789 -0.9295999 -0.07204824 -0.3614599 -0.9160819 0.00383836 -0.4009732 -0.9617833 0.06973993 -0.2647815 -0.9809835 0.05812752 -0.1851831 -0.9934092 -0.04208403 -0.1066164 -0.996937 -0.002410888 -0.07817178 -0.9992861 0.02180272 0.03085297 -0.9941552 -0.03865855 0.1008019 -0.9911518 0.02000546 0.1312177 -0.9595176 0.07824534 0.2705618 -0.935259 0.002292037 0.3539569 -0.9137998 -0.09597533 0.3946627 -0.8903031 0.01071286 0.4552425 -0.8356387 0.0602461 0.5459657 -0.7456872 -0.0994206 0.658837 -0.7840035 -2.11712e-5 0.6207566 -0.7030005 0.03270405 0.710437 -0.5618473 0.05991101 0.8250688 -0.4805092 -0.1379695 0.866069 -0.404381 0.04808777 0.9133256 -0.2931716 0.07069134 0.9534429 -0.2032127 -0.01451325 0.9790271 -0.1807848 -0.06515139 0.9813625 -0.08174991 0.04185765 0.9957735 0.0427587 -0.03641092 0.9984218 -0.004526913 0.03916692 0.9992225 0.1479113 0.04587596 0.9879361 0.2500417 -0.02386003 0.9679411 0.240444 -0.04243069 0.9697353 0.3452301 0.05094325 0.9371345 0.4281916 0.02402949 0.9033685 0.4864578 -0.0769928 0.8703051 0.5246855 0.002956748 0.8512911 0.6066219 0.06107801 0.7926407 0.7168017 -0.05872952 0.6947994 0.7048587 -0.09840559 0.7024889 0.7850611 0.06005024 0.6165008 0.8435209 0.07494294 0.5318423 0.8823923 0.0121017 0.470359 0.8962132 -0.05616039 0.4400547 0.9293899 0.02901238 0.3679577 0.9648391 0.01504719 0.2624107 0.9759798 -0.04458206 0.2132508 0.9845705 0.01934891 0.1739154 0.9947195 0.06537961 0.07911151 0.9969882 -0.03259664 -0.07037103 0.9817005 -0.03205001 -0.187715 0.9887431 0.03383684 -0.1457465 0.9617004 -0.06056141 -0.2673288 0.9114983 -0.007656574 -0.4112327 0.9228873 0.06621664 -0.3793342 0.86613 -0.07246506 -0.494538 0.7835276 0.03447103 -0.6204002 0.7816275 0.04129552 -0.622377 0.6848753 -0.05509263 -0.7265747 0.601995 0.03091394 -0.7979012 0.611532 0.009969294 -0.791157 0.5298684 -0.0323891 -0.8474612 0.4312555 0.00695008 -0.9022031 0.4492996 0.04759889 -0.8921123 0.3345763 -0.07995325 -0.9389708 0.2435477 -0.01992797 -0.9696843 0.2069141 0.05345368 -0.9768978 0.09231328 -0.05671554 -0.9941136 -0.0148341 0.01632344 -0.9997568 -0.01563251 0.01773691 -0.9997205 -0.1016523 -0.04138714 -0.9939588 -0.2102006 -0.01678782 -0.9775142 -0.2536026 0.05610466 -0.9656801 -0.3413719 -0.05734974 -0.9381771 -0.4734473 0.02027904 -0.8805887 -0.4981454 0.07501518 -0.8638425 -0.5579435 -0.03443014 -0.8291645 -0.6485028 -0.07882678 -0.75712 -0.7454209 0.06381666 -0.6635324 -0.7513127 0.09832626 -0.6525804 -0.832679 -0.07160705 -0.5491068 -0.8907768 -0.05401265 -0.45122 -0.9462407 -0.02843624 -0.3222112 -0.9219766 0.07106494 -0.3806689 -0.9850092 -0.009273648 -0.1722524 -0.9872568 0.01719802 -0.1582031 -0.9977051 -0.05560684 -0.03863382 -0.9964045 0.03711551 0.0761612 -0.9936844 0.06639188 0.0904628 -0.9833365 -0.0439409 0.1764047 -0.9625486 -0.0545507 0.2655646 -0.9228084 0.07384288 0.3781166 -0.9339588 0.0235328 0.3566052 -0.9041292 -0.02659541 0.4264308 -0.8343248 0.01181358 0.5511468 -0.8312436 0.0215497 0.5554906 -0.7510109 -0.06420117 0.6571613 -0.6500539 0.01033711 0.7598178 -0.6688052 0.06566643 0.740532 -0.5610546 -0.05905395 0.8256697 -0.4607993 0.01389127 0.8873957 -0.3948222 -0.007604002 0.9187261 -0.4354938 0.06037318 0.8981651 -0.2942088 -0.06644809 0.9534285 -0.1892999 -0.002416968 0.9819164 -0.1518452 0.07418251 0.9856166 -0.04913079 -0.05557769 0.997245 0.1035101 0.02475374 0.9943204 0.1045705 0.02721649 0.994145 0.2442725 -0.04948461 0.9684432 0.3126428 0.08881926 0.9457092 0.3449496 0.01831406 0.9384427 0.4336269 -0.05647665 0.899321 0.5211465 -0.04312223 0.8523771 0.619533 -0.01440095 0.7848387 0.5852158 0.05869561 0.8087505 0.6798292 -0.05483978 0.7313173 0.7636809 0.03194391 0.6448032 0.7533367 0.061351 0.6547671 0.8155495 -0.05728268 0.5758453 0.8870745 -0.02069371 0.4611622 0.9031344 0.04301619 0.4271979 0.9312492 -0.02432674 0.3635702 0.9661329 0.001700103 0.2580395 0.9680976 0.01007223 0.2503712 0.9816659 -0.05674391 0.1819676 0.9995821 -0.001772999 0.02885395 0.9986834 0.02608603 0.04417198 0.9471163 -0.3181953 0.04150152 0.869297 -0.4942448 0.006690979 0.7341324 -0.6786626 0.02160704 0.9335566 -0.3268955 0.1470084 0.7859834 -0.6000773 0.148787 0.7144573 -0.690471 0.1131393 0.4157912 -0.9055143 0.08462661 0.8612057 -0.4180009 0.2891367 0.3601921 -0.9284232 0.09106063 0.7743554 -0.5896344 0.2295764 0.5668393 -0.7959857 0.2123678 0.8737245 -0.3431096 0.344792 0.8255972 -0.4158107 0.3814324 0.562149 -0.7935497 0.2329539 0.8249983 -0.3684935 0.4284745 0.4836763 -0.8412123 0.2417003 0.800971 -0.4068815 0.4391958 0.65302 -0.642643 0.400718 0.5420664 -0.7737655 0.3277975 0.1422668 -0.9862631 0.08393728 0.7918796 -0.2667988 0.5493134 0.716048 -0.4451292 0.5377132 0.4007336 -0.8629721 0.3077201 0.6781328 -0.4783053 0.5579963 0.3063881 -0.9194099 0.2466005 0.5983891 -0.5926297 0.539185 0.2324856 -0.946984 0.221747 0.5621569 -0.5835478 0.5860477 0.5200123 -0.6294569 0.5773831 0.527424 -0.4147015 0.7415165 0.2739793 -0.9119619 0.3053868 0.5009417 -0.5945795 0.6289139 0.4918004 -0.384563 0.7811811 0.4572638 -0.4361954 0.7750118 0.1988475 -0.9341599 0.296319 0.2675644 -0.8524574 0.4491388 0.2786294 -0.7926343 0.5423068 0.4083936 -0.3215358 0.8543006 0.2911493 -0.7942139 0.5333447 0.338502 -0.448192 0.8273695 0.3227201 -0.4482411 0.8336256 0.2512909 -0.5908082 0.7666803 0.1750993 -0.8619989 0.475708 0.1572672 -0.8813015 0.4456172 0.172324 -0.4946079 0.8518612 0.1717153 -0.5100076 0.842856 0.09656202 -0.725986 0.6808966 0.09912091 -0.1871143 0.9773246 0.09082376 -0.8675122 0.489054 0.04539215 -0.7030581 0.7096824 0.01298159 -0.4260171 0.904622 0.01134747 -0.9816774 0.1902129 -0.04254192 -0.3489727 0.9361668 -0.02777117 -0.8557266 0.5166825 -0.0662288 -0.4102583 0.9095615 -0.09110248 -0.6454625 0.7583394 -0.04079174 -0.8440752 0.5346711 -0.2056315 -0.3001697 0.931458 -0.17857 -0.3959655 0.9007353 -0.1539942 -0.5970517 0.7872834 -0.08033221 -0.8872746 0.4541922 -0.1636468 -0.7251529 0.6688596 -0.2718377 -0.3417743 0.8996081 -0.06616234 -0.9705502 0.2316353 -0.3073126 -0.483592 0.8195717 -0.3037803 -0.5331622 0.789592 -0.2319705 -0.7112541 0.6635566 -0.1719809 -0.8933656 0.4151151 -0.001475214 -0.9999914 0.003888249 -0.1893868 -0.8984078 0.3962274 -0.4489164 -0.4095842 0.7941756 -0.400892 -0.5413368 0.7390806 -0.3642652 -0.7117469 0.6006057 -0.3445176 -0.748682 0.5663771 -0.543314 -0.2837583 0.790121 -0.1190071 -0.9705649 0.2093829 -0.5556547 -0.4078263 0.7245175 -0.5342398 -0.4869745 0.6909731 -0.3012901 -0.8542367 0.4236791 -0.6345392 -0.2097977 0.7438716 -0.5109295 -0.6543572 0.5574654 -0.347994 -0.846958 0.4019483 -0.6597673 -0.4181349 0.624396 -0.2796543 -0.9171401 0.2839853 -0.5785394 -0.5865569 0.5667832 -0.705492 -0.3210561 0.6318259 -0.4741373 -0.8010706 0.3653489 -0.3803958 -0.8746287 0.3005396 -0.8081568 -0.299031 0.5074083 -0.7356118 -0.4637466 0.4937758 -0.6138093 -0.6787034 0.4032368 -0.8310845 -0.3454087 0.4358799 -0.7895179 -0.480112 0.3823012 -0.2108719 -0.9678878 0.1368439 -0.621338 -0.7135708 0.3236601 -0.8676962 -0.3801486 0.3202977 -0.4983908 -0.8374554 0.2242214 -0.3817213 -0.9079607 0.1729061 -0.8615276 -0.4126527 0.295784 -0.237421 -0.9676246 0.08563983 -0.6368777 -0.74335 0.2044939 -0.898496 -0.3543911 0.2590596 -0.872618 -0.4481555 0.1941508 -0.6149755 -0.774301 0.1492088 -0.7027543 -0.6955153 0.1496495 -0.4656019 -0.8794849 0.09859728 -0.932783 -0.3245266 0.1568388 -0.7272738 -0.6836279 0.06103926 -0.9262248 -0.3648849 0.09469252 -0.9557579 -0.2858074 0.06957942 -0.4039913 -0.9132912 0.051867 -0.7203307 -0.6912538 0.05737572 -0.5172579 -0.8553075 0.02989089 -0.9358586 -0.352106 -0.01379066 -0.8672538 -0.4967998 -0.03257369 -0.8221721 -0.5656386 -0.06392484 -0.4826372 -0.8753893 -0.02747821 -0.4446591 -0.8949817 -0.03586578 -0.8278859 -0.5526987 -0.0955463 -0.9565199 -0.2348528 -0.1729569 -0.7234295 -0.6780061 -0.1302207 -0.1873405 -0.9819117 -0.02744239 -0.6373386 -0.7607778 -0.1225426 -0.8556112 -0.4600358 -0.2372696 -0.8900489 -0.3375048 -0.3064368 -0.8478768 -0.4607266 -0.2623661 -0.661198 -0.7129226 -0.2335777 -0.5557097 -0.8146109 -0.1661204 -0.3325371 -0.9368533 -0.1082825 -0.809464 -0.4428287 -0.3855786 -0.6485388 -0.7097166 -0.2751362 -0.4910045 -0.8353278 -0.2472696 -0.819547 -0.394983 -0.4151281 -0.2347054 -0.9659688 -0.1087101 -0.7648328 -0.4506554 -0.4603702 -0.1424033 -0.9869127 -0.07566201 -0.794749 -0.2993358 -0.527989 -0.5791833 -0.71932 -0.3835694 -0.5146178 -0.7629708 -0.3912087 -0.6942291 -0.3889527 -0.6056086 -0.3928069 -0.8601979 -0.3252115 -0.6826588 -0.4157351 -0.6009503 -0.3587726 -0.8759964 -0.3223551 -0.5908324 -0.4988978 -0.634049 -0.2405635 -0.9394814 -0.2439342 -0.4727985 -0.7092526 -0.5228981 -0.5973342 -0.3680448 -0.7125552 -0.5407971 -0.401245 -0.7392841 -0.2228087 -0.934961 -0.2760512 -0.5310906 -0.3670395 -0.7636916 -0.3365079 -0.8142213 -0.4730815 -0.3291084 -0.8414548 -0.4285344 -0.4286464 -0.3792411 -0.8200235 -0.4272387 -0.4689497 -0.7730157 -0.3266258 -0.7112176 -0.6224831 -0.05182325 -0.9950016 -0.08536028 -0.2776806 -0.8246228 -0.4928396 -0.1642346 -0.9265052 -0.3385484 -0.3260709 -0.3488784 -0.8786135 -0.3041474 -0.4169571 -0.8565286 -0.2543258 -0.6706099 -0.6968507 -0.1395981 -0.9139838 -0.3809807 -0.1877058 -0.7801731 -0.5967382 -0.03503304 -0.9858828 -0.1637308 -0.181193 -0.3811181 -0.906597 -0.1899597 -0.4240547 -0.8854902 -0.1469153 -0.7515236 -0.6431393 -0.1026618 -0.8014143 -0.5892332 -0.1321495 -0.3913984 -0.9106833 -0.06300425 -0.5587149 -0.8269632 -0.03856348 -0.9723604 -0.2302786 -0.07285761 -0.7751506 -0.6275616 -0.02601432 -0.5268313 -0.8495717 -0.002438426 -0.8946837 -0.4466938 -0.004131317 -0.8754408 -0.4833078 0.02902936 -0.5962144 -0.8023003 0.04224598 -0.7101038 -0.7028285 0.1043787 -0.3349546 -0.9364351 0.1096782 -0.7370854 -0.6668403 0.1723724 -0.4628252 -0.869529 0.03465491 -0.9674778 -0.2505708 0.1735483 -0.5629376 -0.8080732 0.08680379 -0.905708 -0.4149196 0.2371931 -0.603032 -0.7616377 0.3198277 -0.4420713 -0.8380234 0.1739559 -0.8541234 -0.4901148 0.3768087 -0.4857588 -0.7887037 0.4411996 -0.3187261 -0.838902 0.1854509 -0.8879134 -0.4209725 0.06153285 -0.9915283 -0.1143915 0.3186623 -0.7492029 -0.5806457 0.4923267 -0.2707841 -0.8272184 0.2830305 -0.8014791 -0.5268067 0.4935451 -0.5507079 -0.6731525 0.5603684 -0.406284 -0.7217484 0.4747371 -0.5527814 -0.6848777 0.2049887 -0.9350466 -0.2892537 0.4303641 -0.7451373 -0.5094676 0.6268916 -0.4067044 -0.6645288 0.6311352 -0.3980354 -0.6657599 0.2678177 -0.9075113 -0.3235691 0.4915893 -0.6923022 -0.528259 0.7564171 -0.2683761 -0.596496 0.4595307 -0.7879444 -0.4098479 0.7114387 -0.3865637 -0.586876 0.2181839 -0.9570707 -0.1908183 0.248676 -0.9411711 -0.2288174 0.6053305 -0.647216 -0.4633426 0.7658632 -0.4408479 -0.4680883 0.6173226 -0.6566928 -0.4332061 0.4487071 -0.8537592 -0.2641159 0.7658817 -0.440849 -0.4680569 0.2856637 -0.9385049 -0.1939198 0.7266639 -0.5896767 -0.3524785 0.4906405 -0.8327366 -0.2565572 0.8636661 -0.3541228 -0.3587173 0.7511124 -0.5632098 -0.3444199 0.4103178 -0.8972739 -0.1629078 0.6810355 -0.6970719 -0.2242353 0.4506909 -0.8785135 -0.1584041 0.8915089 -0.3587303 -0.2766304 0.7791787 -0.5897686 -0.2122586 0.8904113 -0.4371097 -0.1268974 0.3847818 -0.91864 -0.08968693 0.7706587 -0.6201699 -0.1465423 0.6453375 -0.7565375 -0.1057857 0.9254698 -0.3714049 -0.07459342 0.5836468 -0.8119463 -0.009984731 0.3111077 -0.9503731 0.001750528 0.1416366 -0.989834 -0.01295232 5.9375e-4 -0.9999964 0.002624154 0.005954504 -0.9999697 0.005019783 0.004115819 -0.999979 0.005013883 0.003608882 -0.9999011 0.01359969 0.0038805 -0.9999905 0.001999974 0.02306646 -0.9997122 0.006600141 0.007390677 -0.9998579 0.01515465 0.02007859 -0.9997224 0.01233381 0.00734353 -0.9998559 0.0153079 0.005206167 -0.9999855 0.001417398 0.002557754 -0.9999125 0.01298552 0.001419067 -0.9998729 0.01587933 0.005163669 -0.9999868 1.30336e-5 -7.56644e-4 -0.999934 0.01147013 0.008159577 -0.9999663 -9.65816e-4 -0.005939126 -0.9998711 0.01492029 0.005441308 -0.9999836 -0.00182116 -0.006897151 -0.9997943 0.01907575 0.01568531 -0.9997685 -0.01473057 0.02114826 -0.9997734 -0.002429485 -0.006157398 -0.999938 0.009280204 0.002322077 -0.999996 -0.001677632 -0.008664786 -0.9999282 0.008277595 0.002448379 -0.9999946 -0.002173125 -0.008238077 -0.9999333 0.008102297 0.001759111 -0.9999964 -0.002042651 -0.009082198 -0.9999272 0.007946193 0.001569032 -0.9999951 -0.002759695 -0.006261646 -0.9999752 0.003249645 0.004190087 -0.9999035 -0.0132448 -0.01044827 -0.9999426 0.002395868 0.003430008 -0.9999098 -0.01298439 -0.01365357 -0.9999037 0.002491772 -0.008819878 -0.9999612 -4.16435e-5 0.004473328 -0.9999428 -0.009721279 4.75135e-5 -0.9999962 -0.002768695 -0.01276671 -0.9999179 -0.001107394 -0.00658226 -0.9999765 0.00194174 -0.001233518 -0.9999914 -0.003979921 -0.002849519 -0.9999692 -0.007320463 -0.003084897 -0.9999945 -0.001276493 -0.003831028 -0.9999634 -0.007649004 -0.006227791 -0.9999705 -0.004498481 -0.006014049 -0.9999718 -0.004492938 -0.002919733 -0.9999873 -0.00414586 -0.005948781 -0.999975 -0.003822624 0.9468141 0.3206953 -0.026416 0.6714478 0.7410506 0.001413524 0.4166375 0.9088451 -0.02034157 0.8025888 0.5875004 -0.1034154 0.8084756 0.581766 -0.08897083 0.4462504 0.89204 -0.07159107 0.8696144 0.4672151 -0.1596269 0.8517127 0.4887456 -0.1889796 0.8718601 0.4364306 -0.2222349 0.4038273 0.9107506 -0.08635425 0.5463746 0.8220345 -0.1604192 0.8534127 0.3808087 -0.3559096 0.8061389 0.5061855 -0.3064579 0.09240674 0.9951312 -0.03427731 0.5713294 0.7907804 -0.2196568 0.4974663 0.8378742 -0.2247088 0.8468259 0.3324305 -0.4151819 0.7793467 0.4520673 -0.4338823 0.1790307 0.9801011 -0.08573174 0.5491169 0.7811891 -0.2970088 0.7663646 0.3896533 -0.5107405 0.7305788 0.4460698 -0.5169877 0.4767168 0.8165006 -0.3256806 0.6987481 0.4063413 -0.5887597 0.3719273 0.8827665 -0.2870426 0.3223117 0.9130051 -0.2500742 0.6442071 0.4962682 -0.5819923 0.4773023 0.7568599 -0.4464817 0.604726 0.4421275 -0.6624424 0.1922787 0.9666379 -0.1692342 0.5589113 0.5040353 -0.6584578 0.4790756 0.6569611 -0.5821415 0.4175406 0.7636389 -0.4924587 0.5742248 0.3276235 -0.7502858 0.3461747 0.8355711 -0.4265959 0.2342676 0.9301037 -0.2828882 0.5128191 0.3307414 -0.792229 0.4153236 0.5722114 -0.7071636 0.08810031 0.9857869 -0.143048 0.400285 0.5915639 -0.6998743 0.2775511 0.8357187 -0.4738562 0.1962321 0.9056892 -0.3757926 0.3636137 0.5293315 -0.7665464 0.3185791 0.5721015 -0.7557826 0.1954904 0.846926 -0.4944694 0.2993836 0.5208662 -0.7994173 0.1516346 0.8681143 -0.4726358 0.1911992 0.4869058 -0.8522709 0.1989383 0.5928665 -0.7803415 0.1666476 0.7184239 -0.6753486 0.06229019 0.9640368 -0.2583661 0.1332885 0.3979542 -0.907671 0.0392397 0.9350783 -0.3522625 0.05339092 0.8329561 -0.5507573 0.05448871 0.5508203 -0.8328434 0.04018849 0.7783638 -0.6265259 -0.009334444 0.4107545 -0.9116982 -0.047558 0.481812 -0.8749831 -0.04587942 0.7698073 -0.6366253 -0.01019257 0.991185 -0.132092 -0.05491042 0.7910945 -0.6092246 -0.126704 0.3824853 -0.9152329 -0.1762644 0.5432389 -0.8208669 -0.03074139 0.9730986 -0.2283291 -0.1381176 0.709334 -0.6912082 -0.2145176 0.4788374 -0.8512914 -0.1377295 0.8696253 -0.4741125 -0.3579812 0.4202216 -0.8338245 -0.310155 0.5610012 -0.7675164 -0.2835934 0.6954935 -0.6601998 -0.410948 0.2957091 -0.8623677 -0.1794696 0.8657262 -0.4672352 -0.1271299 0.9585808 -0.2548746 -0.4863933 0.3910204 -0.7813607 -0.4399748 0.4713885 -0.7643398 -0.379137 0.6584517 -0.6501511 -0.3114375 0.8391982 -0.4458172 -0.5601695 0.3865901 -0.7326378 -0.5402842 0.4291943 -0.7237991 -0.4231367 0.7528677 -0.5041288 -0.3481951 0.83318 -0.4296176 -0.3129786 0.8773835 -0.3636519 -0.6226845 0.352203 -0.6987253 -0.5885772 0.542045 -0.5998035 -0.3080117 0.901369 -0.3044059 -0.6241953 0.5414746 -0.5631924 -0.6106196 0.6097737 -0.5052918 -0.4481015 0.8176389 -0.3614853 -0.7336149 0.4623113 -0.4980738 -0.7359403 0.4655726 -0.4915629 -0.07049524 0.9963107 -0.0489431 -0.8430058 0.2419683 -0.4804087 -0.3973519 0.8792786 -0.2626419 -0.1641854 0.9813535 -0.09994304 -0.6469781 0.6663292 -0.3707085 -0.5089819 0.8088041 -0.2945735 -0.8578215 0.3435738 -0.3822297 -0.8672722 0.3054898 -0.3930838 -0.763857 0.5422465 -0.3499875 -0.6770735 0.6873076 -0.2630204 -0.466848 0.8641226 -0.1880027 -0.4421547 0.8798882 -0.1740582 -0.8967977 0.3444373 -0.2776991 -0.8014125 0.5523663 -0.2294115 -0.3672221 0.9242733 -0.1042444 -0.7479181 0.6455894 -0.1543794 -0.8906494 0.4383602 -0.1207649 -0.4072422 0.9074705 -0.1032041 -0.7382609 0.6547812 -0.1619644 -0.9335139 0.3534511 -0.06020033 -0.9055173 0.4177851 -0.07412135 -0.461955 0.8868917 0.004557311 -0.6610826 0.7502693 -0.008119821 -0.9489994 0.3152101 0.006538987 -0.4842633 0.874485 -0.02766031 -0.3823897 0.9239405 -0.01059687 -0.8826804 0.4668303 0.05426543 -0.7601805 0.6473465 0.05539101 -0.9588004 0.250302 0.1343537 -0.7233442 0.6855248 0.08263772 -0.872605 0.4533273 0.1818102 -0.3830821 0.9202232 0.08023291 -0.4335696 0.8983342 0.07080477 -0.8661288 0.4509252 0.2156097 -0.7608327 0.6015068 0.2435638 -0.453327 0.8855034 0.1018745 -0.8381465 0.4175686 0.3509231 -0.7594954 0.5979769 0.2561065 -0.8434208 0.3012467 0.4448506 -0.5292184 0.8103993 0.2513585 -0.8176345 0.4202612 0.3935154 -0.308583 0.9404332 0.1426952 -0.2635082 0.9581354 0.1119832 -0.6114734 0.7174522 0.3337106 -0.8023468 0.3185584 0.5047379 -0.7270966 0.4691401 0.5012366 -0.5915983 0.7108792 0.3803451 -0.4804369 0.810032 0.3361975 -0.7171541 0.3862029 0.5801184 -0.2858246 0.9380961 0.1956529 -0.6731503 0.4369529 0.5966078 -0.1693142 0.9758545 0.1379884 -0.6852578 0.2062995 0.6984714 -0.504 0.7088394 0.4934884 -0.4601969 0.7701871 0.441623 -0.3198409 0.8901392 0.3245828 -0.5956217 0.3848271 0.7050836 -0.5148998 0.611464 0.6008245 -0.5456158 0.2513214 0.799463 -0.5250391 0.3143334 0.7909036 -0.4080387 0.7072861 0.5772789 -0.3670514 0.7582837 0.5387755 -0.2595989 0.9003369 0.3492878 -0.4474926 0.4040193 0.7978212 -0.3283068 0.6974887 0.6369649 -0.3159068 0.7494971 0.5817707 -0.09675115 0.9810951 0.1676058 -0.3958992 0.2317785 0.8885621 -0.3441246 0.3784514 0.8592746 -0.1477603 0.9380677 0.3133624 -0.303761 0.6620839 0.6851089 -0.2832933 0.3759595 0.8822695 -0.2433617 0.4614991 0.8531082 -0.1935651 0.6961593 0.6912994 -0.1940573 0.7801587 0.5947219 -0.1420259 0.8898155 0.4336556 -0.1808204 0.3013538 0.9362105 -0.06337666 0.9487666 0.309557 -0.05303496 0.9587162 0.2793753 -0.1059449 0.7609769 0.6400702 -0.1245648 0.3763844 0.9180514 -0.0632897 0.6463915 0.7603766 -0.06813663 0.6427828 0.7630124 0.02124053 0.313574 0.9493263 -0.005020022 0.90255 0.4305559 -0.0032444 0.5761874 0.8173113 0.04972928 0.6811757 0.7304292 0.04389035 0.8549853 0.5167918 0.01131713 0.9101473 0.4141304 0.1255019 0.3422343 0.9311954 0.134942 0.4730753 0.8706265 0.2424751 0.3914875 0.8876619 0.1820425 0.5212068 0.8337891 0.1563355 0.7933282 0.5883789 0.0995047 0.8762056 0.4715533 0.3081855 0.403598 0.8614699 0.3189354 0.4768283 0.819094 0.05348992 0.984599 0.1664447 0.1852318 0.7921088 0.581595 0.1724174 0.9022048 0.3953466 0.4217322 0.3320444 0.843735 0.3703153 0.4729073 0.7995157 0.1874019 0.894571 0.4057379 0.3439095 0.689748 0.6371608 0.4966442 0.2611478 0.8277356 0.5094276 0.4560525 0.7297258 0.3948133 0.6819732 0.6156584 0.3289024 0.8250766 0.4594254 0.5577089 0.3978474 0.7284767 0.1963152 0.9356162 0.2933986 0.5665531 0.429477 0.7032547 0.1166133 0.9821026 0.1479048 0.4539609 0.7474793 0.4849683 0.6798064 0.2885058 0.6742609 0.6744897 0.3791309 0.6335009 0.4237418 0.7940248 0.4358527 0.4574244 0.7716081 0.4420227 0.7130156 0.393981 0.5799895 0.6967184 0.4725942 0.5396651 0.4656366 0.7876018 0.4035668 0.4322557 0.8393681 0.3295702 0.7231461 0.484645 0.4921169 0.6740339 0.6153945 0.4086171 0.1565608 0.9825344 0.1005739 0.530429 0.7819032 0.3275247 0.7972456 0.468793 0.380306 0.4067107 0.8903592 0.2045656 0.8651425 0.3783223 0.3292427 0.8005457 0.4871014 0.3490831 0.4295085 0.884099 0.1840968 0.53557 0.8203665 0.2004088 0.1993298 0.9777284 0.06568688 0.8758854 0.4058264 0.2610166 0.8372401 0.50055 0.2201792 0.5669477 0.8047478 0.1759305 0.4852726 0.8673704 0.110359 0.8540351 0.4975678 0.1518234 0.8527225 0.5002529 0.1503714 0.5279492 0.846117 0.0731827 0.5415803 0.8364367 0.08405053 0.8976786 0.4387376 0.04102098 0.9085354 0.4140673 0.05578273 0.6791682 0.7339499 0.006943523 0.2587346 0.9658974 0.009937942 -0.006219327 0.9999597 0.006489217 -0.007018387 0.9999525 0.0067752 -0.006108403 0.999948 0.008179068 -0.005694985 0.9999806 0.002543449 -0.007575631 0.9999632 0.004045128 -0.002131342 0.9999887 0.004271149 -0.006099939 0.9999803 0.001545608 -9.57853e-4 0.9999879 0.004846274 -4.61348e-4 0.9999626 0.008638203 -0.009409844 0.9999557 1.96337e-4 -0.009244501 0.9999573 -2.22314e-4 3.4019e-4 0.9999641 0.008482277 -0.01252496 0.9999201 -0.001743912 0.003258645 0.999907 0.01324659 0.002981483 0.9999073 0.01329672 -0.01238203 0.9999161 -0.003808736 -0.005291938 0.9999855 0.001031756 0.001217365 0.9999358 0.0112726 0.002077281 0.9999877 0.004513442 -0.006660044 0.9999664 -0.004788339 0.003207981 0.9999852 0.00439161 -0.006444752 0.9999682 -0.004710555 0.01555353 0.9997906 0.01329922 0.01555335 0.999801 0.01249378 0.01050943 0.9998723 0.01204097 -0.004203677 0.9999724 -0.006151318 -0.006358265 0.9998949 -0.01303005 0.006783604 0.9999727 0.002963006 0.01082009 0.9999386 0.002430617 -0.006155371 0.9999454 -0.008444607 -0.001667797 0.999984 -0.0054093 0.01098763 0.9999357 0.002828299 -0.001676678 0.9999843 -0.005345821 3.20288e-6 1 9.12098e-5 0.003410875 0.9999942 3.32835e-4 0.002737283 0.9999962 -4.81318e-4 -3.6386e-5 1 1.38083e-4 0.002441883 0.999997 -2.7526e-4 0.0108273 0.999795 -0.01711565 -3.49417e-4 1 1.71417e-4 0.007228732 0.9998453 -0.01603871 0.004802346 0.9999645 -0.006923198 0.003669083 0.999966 -0.007394373 -2.75703e-4 1 2.32539e-4 0.9979808 0.05437558 -0.03283053 0.9865419 -0.03093695 -0.1605559 0.9862963 -0.02534055 -0.163026 0.9614688 0.04380559 -0.2714019 0.9362419 0.005111098 -0.3513191 0.9375582 -0.001021206 -0.347827 0.8606309 -0.03293925 -0.5081629 0.8823943 0.0264014 -0.4697695 0.8142302 0.06366539 -0.5770407 0.7510565 0.01293253 -0.6601113 0.7257939 -0.04984754 -0.6861038 0.6801083 0.03189504 -0.7324175 0.6078611 0.02556586 -0.7936317 0.5614706 -0.05873721 -0.8254094 0.5205723 0.02217131 -0.8535298 0.4308509 0.04607075 -0.9012464 0.3562617 -0.04702061 -0.9332025 0.3330894 3.42749e-4 -0.9428952 0.2044273 0.0362969 -0.9782086 0.1559648 -0.02863115 -0.9873477 0.1071219 0.03002667 -0.9937924 -0.05088973 -0.02336061 -0.998431 -0.01765125 0.01894867 -0.9996647 -0.09807974 0.04109269 -0.9943299 -0.2365642 0.02829372 -0.9712038 -0.2719041 -0.04075062 -0.9614612 -0.3464662 0.0299378 -0.9375847 -0.4425824 -0.01918953 -0.8965225 -0.4327 -0.04272663 -0.900525 -0.5243634 0.0546379 -0.8497399 -0.6113912 0.009952187 -0.791266 -0.6301786 -0.04188328 -0.7753198 -0.7115491 0.05038821 -0.7008273 -0.7721656 -0.02349561 -0.6349868 -0.7839891 0.004363656 -0.6207593 -0.8664708 -0.03017526 -0.4983153 -0.8443529 0.03279989 -0.5347827 -0.9077695 0.04625511 -0.4169114 -0.9507549 -0.04255354 -0.3070088 -0.9467388 -0.06649768 -0.3150615 -0.9745966 0.07881009 -0.2096434 -0.9920775 0.05147993 -0.1145953 -0.9971792 -0.07069796 -0.0252096 -0.996642 -0.07881975 -0.0221886 -0.9940251 0.06380224 0.08856278 -0.9845128 0.06030595 0.1646145 -0.9689615 -0.05078554 0.2419394 -0.9583423 0.02027773 0.2849014 -0.9108117 0.002942919 0.4128118 -0.9142911 -0.01575511 0.4047513 -0.8650715 0.04102456 0.4999684 -0.8203162 -0.02689194 0.5712776 -0.8074263 0.009580373 0.5898906 -0.7143942 -0.03041386 0.6990823 -0.7414875 0.02824401 0.6703721 -0.6460995 0.04714959 0.7617955 -0.5755122 -0.02269327 0.8174783 -0.5573437 0.01211476 0.8301935 -0.4168465 -0.06114429 0.9069181 -0.4740306 0.03354102 0.8798694 -0.342518 0.06687855 0.9371279 -0.2536031 0.05525588 0.9657289 -0.1724294 -0.06928598 0.9825821 -0.1451501 -0.01270937 0.989328 -0.04409593 0.04757761 0.9978938 0.05321991 -0.05488914 0.9970731 0.09133267 0.02260994 0.9955638 0.2068229 0.06003683 0.9765347 0.2908402 -0.06429427 0.9546089 0.3371465 0.01933008 0.9412539 0.4321789 0.02986842 0.9012932 0.4961245 -0.06275051 0.8659809 0.5266908 0.008389294 0.8500156 0.5910763 0.07526475 0.8030967 0.6955474 -0.04615217 0.7169964 0.6785326 0.001586556 0.7345687 0.7529235 0.0398252 0.6569021 0.8239741 -0.03256201 0.565691 0.8377708 0.01932102 0.5456804 0.9087097 0.04811608 0.4146465 0.9334713 -0.08155322 0.3492572 0.9589983 0.04867303 0.2792012 0.9862928 0.05745691 0.1546785 0.9955397 -0.02680462 0.09045606 0.995204 -0.05935478 0.07775545 0.9993758 -0.0307964 -0.01730966 0.9915652 -0.03707504 -0.1241933 0.9741612 -0.03559428 -0.2230313 0.9835892 0.02721345 -0.1783587 0.9293865 -0.001579046 -0.3691048 0.9282664 0.003417193 -0.3719002 0.8886829 -0.05950689 -0.4546446 0.8252451 0.05935817 -0.5616468 0.8107622 -0.007411599 -0.5853288 0.7131124 -0.07126396 -0.6974182 0.6103363 -0.01733314 -0.7919528 0.6481953 0.07184195 -0.7580776 0.5198847 -0.03457063 -0.8535366 0.4261631 -0.03224718 -0.9040715 0.4641172 0.03940087 -0.884897 0.3396724 -0.06741315 -0.9381249 0.2606507 0.004743397 -0.9654216 0.2476407 0.03370797 -0.9682654 0.144521 -0.04836523 -0.9883191 0.02571982 0.04405391 -0.9986981 0.02181017 0.03442114 -0.9991694 -0.09921574 -0.07056283 -0.9925609 -0.2098533 -0.003808498 -0.9777256 -0.2373065 0.06147414 -0.9694878 -0.3449132 -0.05664294 -0.936924 -0.43383 -0.001693427 -0.9009933 -0.4323978 -0.005385577 -0.9016669 -0.5583497 -0.009380042 -0.8295527 -0.5754691 0.02582472 -0.8174158 -0.6442369 -0.04022824 -0.7637674 -0.7218649 0.01894748 -0.6917746 -0.7147173 -3.63297e-4 -0.6994134 -0.7790651 -0.0338329 -0.6260295 -0.8203294 0.0262472 -0.5712887 -0.8440474 -0.03606957 -0.5350544 -0.8864939 -0.04777163 -0.4602678 -0.9307813 -0.03702241 -0.3636974 -0.9107193 0.01458144 -0.4127685 -0.9740919 -0.02224659 -0.2250558 -0.9683631 0.02809983 -0.2479587 -0.9955185 -0.03999894 -0.0856924 -0.9973723 0.07189279 -0.008939325 -0.9996849 -4.98011e-4 0.02510076 -0.9891141 -0.07439643 0.1269596 -0.96531 0.03749257 0.2584007 -0.964125 0.04487305 0.2616285 -0.9307532 -0.05806136 0.3610088 -0.8830558 0.04004281 0.4675566 -0.8741552 -5.13179e-4 0.4856466 -0.8128257 -0.06255495 0.5791385 -0.788203 -0.03427428 0.6144602 -0.7134823 -0.03515762 0.6997907 -0.7619259 0.0348109 0.646728 -0.6345241 0.003186464 0.7728965 -0.6278184 0.01519936 0.7782114 -0.575667 -0.0483244 0.8162551 -0.4684326 -0.009629249 0.8834468 -0.4453437 0.04277437 0.8943374 -0.3474303 -0.04637324 0.9365585 -0.2350382 0.0482704 0.9707869 -0.2394111 0.06094574 0.9690036 -0.09794294 -0.09440404 0.9907044 0.001210749 -0.008589327 0.9999624 0.09618121 -0.0186693 0.9951888 0.03573644 0.06043642 0.9975322 0.2036247 -0.02370584 0.978762 0.2496143 0.05346769 0.9668681 0.338809 -0.06723016 0.9384502 0.4197779 -0.03654831 0.9068907 0.5228167 -0.03345835 0.8517883 0.4638873 0.05041283 0.8844587 0.6004617 -0.023494 0.7993085 0.6870164 -0.04157441 0.7254516 0.6383066 0.04878646 0.7682347 0.7834337 0.01186072 0.6213623 0.7794069 -0.003948152 0.6265056 0.8657413 -0.01037591 0.5003844 0.877286 0.02613669 0.4792558 0.9093052 -0.04972118 0.4131487 0.9489244 -0.01935744 0.3149095 0.9624499 0.05634737 0.2655471 0.9734147 -0.007898747 0.2289137 0.9920632 -0.05251634 0.1142491 0.9979313 0.05337148 0.03584152 0.5971981 -0.8018885 0.01815074 0.3817979 -0.9242392 0.003501653 0.8786032 -0.47527 0.04663705 0.6905971 -0.7201879 0.06637001 0.9590813 -0.2588673 0.1146779 0.2396491 -0.970651 0.02012652 0.6761481 -0.731514 0.0878126 0.8887953 -0.424312 0.1732114 0.7329892 -0.6678268 0.1293614 0.9089577 -0.3632614 0.204541 0.3590003 -0.9311156 0.06436353 0.5873166 -0.7890475 0.1801755 0.8645178 -0.4028071 0.300592 0.3532618 -0.9307714 0.09418499 0.8451285 -0.4552868 0.2801285 0.6229838 -0.7548016 0.2053436 0.1572789 -0.9859029 0.05708682 0.85983 -0.3483918 0.37325 0.7631372 -0.5144718 0.3910759 0.5664592 -0.7778673 0.2721146 0.779052 -0.4136055 0.4711779 0.4674868 -0.8489599 0.2464209 0.7680831 -0.4291945 0.4752269 0.4171433 -0.8589314 0.2970328 0.4561627 -0.8370822 0.3020088 0.7395966 -0.3332587 0.5847526 0.7539566 -0.2985891 0.5851444 0.2667167 -0.9420501 0.2034792 0.5752411 -0.6588324 0.4848067 0.6555055 -0.3910653 0.6460499 0.5325748 -0.6804132 0.5033906 0.5684311 -0.5945178 0.5687133 0.3679422 -0.851364 0.3738957 0.6706295 -0.208913 0.7117664 0.5000679 -0.6228603 0.6016453 0.3157637 -0.8734901 0.3705516 0.574603 -0.3542808 0.7377781 0.5274925 -0.4781018 0.702261 0.2337847 -0.9217608 0.3093569 0.4766311 -0.5127341 0.7140915 0.4657207 -0.4307216 0.773035 0.4633865 -0.4785559 0.7458266 0.2427219 -0.9040391 0.3518515 0.4167253 -0.391907 0.8202128 0.2613888 -0.7926326 0.5508264 0.2032463 -0.8993129 0.3872045 0.2711298 -0.6703041 0.690783 0.2948863 -0.3580175 0.8859264 0.2943342 -0.6821897 0.6693167 0.05316561 -0.9881975 0.1436634 0.2046368 -0.7657995 0.6096515 0.2131354 -0.4542167 0.8650206 0.1786422 -0.6551198 0.7341015 0.190627 -0.3251671 0.9262439 0.09090542 -0.9357767 0.3406729 0.12242 -0.7455958 0.6550574 0.0748043 -0.8760906 0.4763085 0.09540039 -0.4007466 0.9112086 0.08311372 -0.4450401 0.8916454 0.04162615 -0.9008348 0.4321619 0.04077148 -0.4887071 0.8714948 0.008444011 -0.5898588 0.8074623 0.01221698 -0.8530467 0.5216916 -0.03824359 -0.5696379 0.8210055 -0.1040621 -0.2178552 0.9704176 -0.08896338 -0.6754271 0.7320408 -0.0431661 -0.8978489 0.4381828 -0.1484187 -0.396314 0.9060393 -0.09714031 -0.6600735 0.7448937 -0.04803264 -0.9525114 0.3006907 -0.2166035 -0.4205213 0.8810476 -0.2488642 -0.3236067 0.9128776 -0.185301 -0.6639409 0.7244628 -0.1672809 -0.8359414 0.5227036 -0.320119 -0.347996 0.8811485 -0.3338813 -0.4325251 0.8375234 -0.3084889 -0.6338967 0.7092317 -0.1884498 -0.8385139 0.5112546 -0.4534286 -0.2751321 0.8477647 -0.4537265 -0.365801 0.8126019 -0.1653715 -0.9125143 0.3741257 -0.3689742 -0.62777 0.6853926 -0.3529068 -0.7048994 0.6152834 -0.2421907 -0.875212 0.4187454 -0.2311274 -0.8990756 0.3718107 -0.5245627 -0.3203067 0.7888205 -0.4823069 -0.5918654 0.6458138 -0.5886271 -0.4596588 0.6650053 -0.4897195 -0.6289142 0.6038559 -0.4763967 -0.6581996 0.5829405 -0.3029383 -0.8742825 0.379287 -0.2648363 -0.9155349 0.3027501 -0.661682 -0.3852184 0.6432602 -0.464485 -0.7854565 0.4090378 -0.6599758 -0.4559924 0.5970786 -0.06466794 -0.9961424 0.05931782 -0.58925 -0.6371684 0.4967907 -0.4583599 -0.7887803 0.4095508 -0.2907731 -0.9326335 0.2136493 -0.2660721 -0.9414544 0.2070488 -0.7001413 -0.5457586 0.4603801 -0.6953293 -0.5766429 0.4289526 -0.5387515 -0.7810465 0.3157742 -0.7816094 -0.464401 0.4164356 -0.7840492 -0.4961883 0.372913 -0.6367626 -0.7232197 0.26737 -0.4827426 -0.8445371 0.231769 -0.8813074 -0.3192379 0.3484027 -0.3624958 -0.9162657 0.1704525 -0.8025688 -0.5420824 0.2490585 -0.6610357 -0.7107558 0.2405371 -0.2039058 -0.9764106 0.07102745 -0.8162427 -0.529855 0.2302208 -0.4749622 -0.870858 0.1265597 -0.9155843 -0.3370745 0.2192855 -0.3275763 -0.9407452 0.08770602 -0.6728127 -0.7264547 0.1399527 -0.6993121 -0.7053724 0.1158123 -0.9282054 -0.3470333 0.1341735 -0.8810386 -0.4604744 0.1083248 -0.5486917 -0.8352542 0.03588694 -0.9258927 -0.3774212 0.01661747 -0.2943223 -0.9553864 0.02472501 -0.8731427 -0.4853218 0.04565942 -0.6581256 -0.7528331 0.01063847 -0.1401391 -0.9901306 -0.001601278 -0.9162912 -0.3919619 -0.0823186 -0.8954688 -0.4398058 -0.06860584 -0.6805875 -0.7310553 -0.04856854 -0.5739568 -0.8153406 -0.07611399 -0.4177698 -0.9065006 -0.06103527 -0.9162794 -0.3399408 -0.2118311 -0.8870001 -0.4218232 -0.187873 -0.735291 -0.658036 -0.162283 -0.8381388 -0.4567824 -0.2981162 -0.6705985 -0.7088694 -0.2186365 -0.8455036 -0.4350886 -0.309551 -0.5107049 -0.8379046 -0.1926047 -0.3350121 -0.9351265 -0.1153495 -0.7621079 -0.522686 -0.3820875 -0.7128494 -0.5931122 -0.374251 -0.5390365 -0.8029963 -0.2542373 -0.1060999 -0.9930654 -0.0506373 -0.343156 -0.9161791 -0.2070266 -0.73833 -0.4437708 -0.5078744 -0.6794029 -0.6025843 -0.4186933 -0.4434279 -0.8419144 -0.3074932 -0.7139304 -0.427829 -0.5543158 -0.644971 -0.5297761 -0.550772 -0.43759 -0.8205202 -0.3677793 -0.6424309 -0.4187276 -0.6418331 -0.342974 -0.878842 -0.3316709 -0.6145199 -0.4496994 -0.6481789 -0.4057628 -0.7856537 -0.4670172 -0.3296411 -0.8785879 -0.3455722 -0.5975579 -0.3491358 -0.7218233 -0.565152 -0.3895794 -0.7272078 -0.4207686 -0.6969466 -0.5807059 -0.5405902 -0.2672753 -0.7977006 -0.4826409 -0.3925915 -0.7828984 -0.09509414 -0.985915 -0.1375818 -0.3963477 -0.6271307 -0.6705338 -0.3755594 -0.7214182 -0.5818169 -0.1876661 -0.9253128 -0.3295114 -0.4372838 -0.255177 -0.8623616 -0.336297 -0.6061908 -0.7207199 -0.3299828 -0.6135942 -0.7173657 -0.2010808 -0.8553109 -0.4775039 -0.2825143 -0.450736 -0.846772 -0.2636739 -0.4745731 -0.8397955 -0.136242 -0.8949108 -0.4249387 -0.1221513 -0.9128967 -0.3894854 -0.1620877 -0.7624408 -0.6264278 -0.1973302 -0.3111259 -0.9296566 -0.1511161 -0.4116623 -0.8987203 -0.1047807 -0.7009178 -0.7055035 -0.09087485 -0.2564018 -0.9622889 -0.03948402 -0.9673421 -0.2503802 -0.09257102 -0.7184057 -0.6894374 -0.05183815 -0.8394798 -0.5409129 -0.03563046 -0.3643898 -0.9305647 -0.0293743 -0.5423929 -0.8396113 0.008131563 -0.2329721 -0.9724495 -0.01063424 -0.9924928 -0.1218402 0.02031832 -0.6772268 -0.7354938 0.005135297 -0.8478913 -0.5301453 0.01941877 -0.9055213 -0.4238563 0.01930809 -0.9089422 -0.416475 0.08999705 -0.5193572 -0.8498051 0.1335362 -0.4578164 -0.8789609 0.1158159 -0.5085816 -0.8531891 0.1073758 -0.7983605 -0.5925293 0.199038 -0.4322404 -0.8795182 0.1316556 -0.858709 -0.4952632 0.05436736 -0.9735534 -0.2218967 0.2349019 -0.6027678 -0.7625563 0.1649034 -0.8160395 -0.5539733 0.2868189 -0.5249815 -0.8013298 0.03361123 -0.9938535 -0.1054778 0.3813131 -0.5440784 -0.7473815 0.344915 -0.6022495 -0.7199509 0.2351417 -0.8214421 -0.5195587 0.4931315 -0.3771978 -0.7839281 0.1906656 -0.9073882 -0.3745576 0.4320719 -0.5266032 -0.7321223 0.3949683 -0.7126356 -0.5797849 0.58252 -0.3121072 -0.7505063 0.2371405 -0.897888 -0.3708931 0.5766537 -0.4153038 -0.7035577 0.462996 -0.6731081 -0.5766804 0.4292412 -0.762292 -0.4844204 0.1934871 -0.9471343 -0.2559288 0.09196901 -0.9907009 -0.1002674 0.6756712 -0.326523 -0.6609472 0.6756041 -0.3271894 -0.6606863 0.5342597 -0.6761726 -0.5073038 0.4520234 -0.7564064 -0.4727835 0.248537 -0.9435429 -0.2189888 0.7176171 -0.416885 -0.5578823 0.550334 -0.6875514 -0.4737147 0.4278371 -0.8483458 -0.3118731 0.7571036 -0.3562014 -0.5476447 0.7502462 -0.4269399 -0.5048297 0.67951 -0.6004488 -0.4215772 0.4368095 -0.8460371 -0.3056447 0.848294 -0.2722145 -0.4541991 0.7076169 -0.6086106 -0.3589869 0.6871298 -0.6465653 -0.33137 0.3591162 -0.9116228 -0.1999487 0.2540842 -0.9591206 -0.1246153 0.8623045 -0.3991321 -0.3116484 0.7086306 -0.6374083 -0.3025779 0.6159206 -0.7581139 -0.214255 0.4764843 -0.8663703 -0.1495509 0.8519493 -0.4702738 -0.2302716 0.8683849 -0.446907 -0.2148995 0.4623512 -0.8769651 -0.1310101 0.8098613 -0.568093 -0.1462705 0.6970347 -0.707638 -0.1157202 0.9055827 -0.4119931 -0.1009042 0.2741999 -0.9605266 -0.04693847 0.6287184 -0.7739832 -0.07525426 0.3765957 -0.925488 -0.04059171 0.9006446 -0.4343974 -0.01175975 0.874767 -0.4837262 -0.02814185 0.7244857 -0.6886949 -0.02863323 0.007445514 -0.9999526 0.006291031 0.005117118 -0.9999716 0.005544781 0.006311655 -0.9999421 0.008723497 0.009241461 -0.9999337 0.006878972 0.00330317 -0.9999572 0.008645474 0.009278774 -0.9999474 0.004388689 0.003020584 -0.9999617 0.008217215 0.004465818 -0.9999859 0.002904117 0.01629966 -0.9998584 0.00420767 -0.001828789 -0.9999796 0.006123363 0.00686568 -0.9999764 3.68814e-4 0.001291632 -0.9999239 0.01227349 0.006725013 -0.9999774 2.98124e-4 -0.002461493 -0.9999132 0.01294422 0.005640566 -0.9999841 -3.82111e-4 0.006716728 -0.9999771 -9.8867e-4 -0.002267897 -0.9998897 0.01468735 -0.003834962 -0.9998968 0.01385408 0.004180908 -0.9999899 -0.00171411 -0.003723859 -0.9999635 0.007698595 -0.00806421 -0.9999253 0.009190261 0.006042003 -0.9999758 -0.003488421 0.004718899 -0.9999818 -0.003752827 -0.008164048 -0.9999259 0.009043574 -0.007662475 -0.9999321 0.008778274 0.002356171 -0.9999926 -0.003069937 0.005342423 -0.9999731 -0.005050003 -0.003852128 -0.9999893 0.00256741 0.001592338 -0.9999938 -0.003171563 -0.004789471 -0.999987 0.001826882 -0.004813015 -0.9999868 0.001830935 0.001687765 -0.9999842 -0.005375504 8.19668e-4 -0.9999923 -0.003849208 -0.004132211 -0.9999915 1.82192e-4 -0.006300151 -0.99998 5.81322e-4 -6.14952e-5 -0.9999923 -0.003917872 3.23108e-4 -0.9999957 -0.002938866 -0.002838671 -0.999996 -4.60756e-4 -2.99657e-4 -0.9999994 -0.001131772 -0.003038287 -0.9999947 -0.001253962 -0.00853461 -0.9999341 -0.007680296 -0.009682357 -0.9999349 -0.006042003 -0.005827784 -0.9999319 -0.01011407 -0.003722071 -0.9999595 -0.008205711 -0.01283496 -0.9998993 -0.006063938 -0.002888917 -0.9999927 -0.002487361 0.9372181 0.3474804 -0.02966225 0.594936 0.803771 0.00187987 0.8906521 0.4505504 -0.06118291 0.7974646 0.6001807 -0.06191539 0.9463824 0.281602 -0.1583065 0.3801151 0.9241424 -0.03838503 0.6834502 0.7196471 -0.1224911 0.4851208 0.8701547 -0.0865367 0.8737711 0.4439259 -0.19863 0.8092494 0.5541476 -0.195028 0.7486882 0.6188166 -0.2377647 0.5086561 0.8394187 -0.1914297 0.858703 0.3750247 -0.3492646 0.3739395 0.9200915 -0.1166232 0.5059044 0.8323696 -0.2263222 0.8034545 0.4335082 -0.4080829 0.7891136 0.4602637 -0.4067645 0.3988758 0.8896194 -0.2224311 0.7061825 0.5522053 -0.443143 0.607196 0.6913952 -0.3915172 0.7505645 0.387129 -0.5355222 0.2302507 0.9612892 -0.1513533 0.4696981 0.7896347 -0.3947922 0.3379127 0.9011305 -0.2716226 0.6635821 0.4470311 -0.5998517 0.6540601 0.4914711 -0.5750319 0.4930862 0.7557973 -0.4308556 0.6300369 0.3910448 -0.6709228 0.5769131 0.4731501 -0.6658079 0.4554378 0.698763 -0.5516399 0.3888261 0.8119027 -0.4354634 0.5666899 0.3100998 -0.7633485 0.2415313 0.9269415 -0.2871273 0.5280461 0.3668534 -0.765889 0.1879522 0.9522165 -0.2407439 0.4029915 0.6936936 -0.5969816 0.3975546 0.699604 -0.5937209 0.5014002 0.2771468 -0.8196265 0.209737 0.9282212 -0.3072715 0.4406819 0.3835383 -0.8116021 0.37247 0.6610178 -0.6513997 0.4131886 0.3246337 -0.8508163 0.2842983 0.7570119 -0.5883089 0.2034451 0.8667384 -0.4553843 0.3364144 0.4468526 -0.828944 0.1542088 0.9405054 -0.3027696 0.3086358 0.421332 -0.8527739 0.2858257 0.4606224 -0.8403158 0.2386553 0.5874177 -0.7732944 0.03096801 0.9962998 -0.08017355 0.1412408 0.8728513 -0.4670994 0.1399723 0.8879549 -0.4381138 0.2022377 0.3036171 -0.9310836 0.1543933 0.5068321 -0.8481062 0.1630287 0.6235276 -0.7646143 0.1033357 0.8429527 -0.5279703 0.09864336 0.8466088 -0.5229943 0.07679331 0.4145612 -0.9067755 0.09773963 0.5015677 -0.8595795 0.05836451 0.7917672 -0.6080282 0.01519912 0.9784253 -0.2060412 0.02622163 0.4100425 -0.9116894 -0.02990174 0.6262709 -0.7790318 0.01178008 0.837239 -0.5467104 5.25302e-4 0.8962267 -0.4435963 -0.1153065 0.4386793 -0.8912155 -0.05949246 0.6135852 -0.7873842 -0.09129303 0.7947657 -0.6000109 -0.06234836 0.9041308 -0.4226823 -0.1648598 0.4822234 -0.8603963 -0.1646842 0.6413966 -0.7493261 -0.2370141 0.250401 -0.9386819 -0.06363427 0.9439172 -0.3239926 -0.2900686 0.3976145 -0.8704959 -0.2050281 0.6694002 -0.7140496 -0.1821676 0.8228099 -0.5383296 -0.3184114 0.3546425 -0.8791149 -0.3676224 0.4211894 -0.829128 -0.4166924 0.3192837 -0.8511319 -0.2642193 0.7975841 -0.5422618 -0.2170699 0.8420102 -0.493862 -0.4756768 0.3593564 -0.8028665 -0.4708428 0.4550189 -0.7558208 -0.3024359 0.7975914 -0.5219008 -0.3129519 0.7880225 -0.5301714 -0.5658299 0.3882598 -0.7273864 -0.5322948 0.4564194 -0.7129821 -0.10616 0.9844416 -0.1400176 -0.4073526 0.7455782 -0.5274249 -0.37642 0.7821698 -0.4965063 -0.2479853 0.9266351 -0.2825785 -0.6090994 0.467894 -0.6403696 -0.5586706 0.5856197 -0.5873133 -0.6700018 0.348564 -0.6554394 -0.4734313 0.7752451 -0.4181602 -0.3178769 0.9038513 -0.2863691 -0.7057595 0.4249847 -0.5668259 -0.6893882 0.4904689 -0.5330894 -0.6310295 0.6074338 -0.4825205 -0.2740417 0.9343873 -0.2276434 -0.8204483 0.2444806 -0.5168112 -0.575478 0.725268 -0.3779042 -0.4086059 0.8758272 -0.2568424 -0.3725305 0.9049402 -0.2056802 -0.7718027 0.4986912 -0.3944969 -0.737765 0.5572973 -0.3809496 -0.8416647 0.3793787 -0.3842815 -0.1216213 0.9909663 -0.0565173 -0.5308846 0.8127613 -0.2399601 -0.8580502 0.4191889 -0.2966992 -0.8464511 0.4507921 -0.283385 -0.7288196 0.6454485 -0.2285133 -0.5359887 0.8222492 -0.1913698 -0.4779713 0.86351 -0.1609156 -0.9335136 0.2901349 -0.2106518 -0.8032021 0.5801972 -0.135047 -0.7326157 0.667134 -0.1349321 -0.567171 0.8182891 -0.09338235 -0.4493155 0.8891556 -0.08670705 -0.8820211 0.4654706 -0.07332152 -0.1939882 0.9807987 -0.02006578 -0.9273453 0.3739105 -0.01488995 -0.8739882 0.4837453 -0.04620981 -0.652114 0.7580763 -0.008232295 -0.5797916 0.8146461 -0.01390546 -0.4001061 0.916468 0.001251876 -0.9175608 0.3943085 0.05102097 -0.7956466 0.6004955 0.07969731 -0.9075168 0.3748664 0.1894425 -0.354887 0.9339755 0.04177385 -0.7792665 0.6192351 0.09639358 -0.5393913 0.8355689 0.1043162 -0.8971837 0.3853057 0.2158728 -0.9301051 0.2514237 0.2677512 -0.6690006 0.7144617 0.2048969 -0.5416356 0.8288156 0.1403411 -0.7976099 0.5090696 0.3235223 -0.7342743 0.6111084 0.2956144 -0.861698 0.3279788 0.3871775 -0.238699 0.9664101 0.09525972 -0.5788221 0.7626431 0.2886875 -0.815041 0.3253552 0.4794291 -0.3963398 0.893795 0.2098702 -0.3541532 0.9102372 0.2145781 -0.7574718 0.4403804 0.4819769 -0.6996095 0.564646 0.4378602 -0.7615271 0.3587978 0.5397599 -0.5168861 0.7722419 0.3694201 -0.1431359 0.9833661 0.1118185 -0.6936771 0.343571 0.6330648 -0.6769863 0.4615091 0.5733227 -0.5146487 0.7300509 0.4496247 -0.4342216 0.7967477 0.4202913 -0.3069037 0.9008167 0.3071472 -0.5914693 0.4581111 0.6635497 -0.5005692 0.6705128 0.5475794 -0.5969994 0.3841682 0.7042774 -0.2080311 0.9377063 0.2782623 -0.5242348 0.4040767 0.7495998 -0.3324087 0.8026942 0.4951633 -0.2878352 0.8539299 0.4335375 -0.4362563 0.5638761 0.7012305 -0.434256 0.324259 0.8404034 -0.4167512 0.518975 0.7463132 -0.02997893 0.9980721 0.0543465 -0.2695474 0.729412 0.6287309 -0.1735035 0.8989318 0.4022663 -0.3406839 0.3213235 0.8835642 -0.1580798 0.9125636 0.3771451 -0.2765289 0.5363238 0.7974263 -0.21307 0.334035 0.9181622 -0.2199751 0.5601158 0.7986747 -0.1576834 0.7127137 0.6835021 -0.1119549 0.9011197 0.4188668 -0.1518587 0.2846679 0.9465216 -0.04673618 0.9636794 0.2629407 -0.09703785 0.4461372 0.8896884 -0.09061229 0.6656998 0.7406979 -0.04096227 0.3439145 0.9381071 -0.02249735 0.8064347 0.5908952 -0.02031785 0.9076756 0.4191805 -0.00617063 0.4329184 0.901412 -0.001244604 0.7557817 0.6548226 0.08246254 0.3448826 0.9350166 0.112189 0.4822469 0.868822 0.06523329 0.7309266 0.6793313 0.01821172 0.985504 0.1686724 0.2039697 0.2919614 0.9344276 0.1624183 0.4396092 0.8833822 0.08794933 0.8897584 0.4478783 0.2819157 0.4081922 0.8682758 0.1963234 0.6814505 0.7050407 0.1609382 0.8223029 0.5458176 0.3115509 0.3616003 0.8787385 0.1646625 0.8278505 0.5362368 0.1467392 0.9202423 0.3627971 0.3419342 0.4347934 0.8330882 0.3053433 0.6428289 0.7025215 0.4144859 0.312052 0.8548831 0.3165799 0.705435 0.634144 0.2043965 0.8886874 0.4104351 0.4428936 0.3927224 0.8059868 0.4161575 0.5681388 0.7099516 0.2031713 0.9200565 0.3349886 0.4365981 0.6170603 0.6546899 0.3557047 0.7880495 0.5024461 0.552523 0.4247615 0.7171445 0.08600193 0.9898409 0.11322 0.5920435 0.4603511 0.6614842 0.6292237 0.3843241 0.6755536 0.5029429 0.6829975 0.529682 0.3734791 0.823188 0.427639 0.2797828 0.9130257 0.2968263 0.7040205 0.3568714 0.6140018 0.6961856 0.4012827 0.5952293 0.545561 0.6920329 0.4727089 0.5327199 0.7139515 0.454404 0.3304849 0.8937444 0.3033162 0.2355284 0.9568456 0.1702143 0.549676 0.7328265 0.4010258 0.7758503 0.3687787 0.5119166 0.7384188 0.4916016 0.4615903 0.4082656 0.876259 0.2559089 0.7379293 0.4976287 0.4558795 0.6682893 0.6508215 0.3603067 0.4522457 0.8553606 0.2526504 0.8838393 0.2396013 0.4017704 0.8429202 0.3988962 0.361064 0.7344762 0.5854328 0.3432393 0.3497743 0.9260978 0.1414246 0.8339753 0.4673429 0.2933868 0.639057 0.7378985 0.2170534 0.5909305 0.7838859 0.1905887 0.9121087 0.316218 0.2608907 0.4110374 0.8995768 0.1476821 0.8803555 0.4344951 0.1902318 0.6630871 0.7319272 0.156838 0.9031325 0.3926459 0.1737267 0.5295188 0.8462079 0.05951631 0.9157987 0.4008638 0.02492028 0.2471983 0.9681517 0.03969228 0.8025064 0.5940092 0.05600452 0.6126733 0.7894021 0.03841638 -6.74672e-4 0.9999996 5.97284e-4 -0.006032884 0.9999774 0.002971768 -5.73445e-4 0.9999994 0.001008689 -0.002749025 0.9999719 0.006984472 -0.005995035 0.9999788 0.00258249 -0.0128315 0.9999125 0.003243088 -0.0126869 0.9999055 0.005302667 -0.001270651 0.9999755 0.006906151 -0.001561999 0.9999871 0.004826962 -0.004162251 0.9999912 4.20823e-4 2.14169e-4 0.9999876 0.004993617 -0.004818081 0.9999884 -5.17387e-4 -0.01065373 0.9999396 -0.002733767 0.003091394 0.999929 0.01151961 0.003024339 0.9999268 0.01172202 -0.009776353 0.9999451 -0.003808796 0.002450406 0.9999324 0.01137149 -0.01287472 0.9998953 -0.006614863 0.003789544 0.99997 0.006773829 0.00659424 0.9999409 0.008639931 -0.01006454 0.9999226 -0.007323324 -0.007321715 0.9999709 -0.002176463 0.005424797 0.9999714 0.005274355 0.008491218 0.9999483 0.005606293 -0.003933012 0.9999799 -0.004985988 -0.007733285 0.9998416 -0.01603657 -0.008287608 0.9998359 -0.0161131 0.007913351 0.9999613 0.003878891 0.004430413 0.9999824 0.003964781 -0.008378028 0.9998443 -0.01553827 -0.003601133 0.9998693 -0.01576399 0.003663659 0.999993 7.99941e-4 -0.004220843 0.999949 -0.009188473 0.01936292 0.99981 -0.00226736 0.0198521 0.9998019 -0.001497566 0.002146244 0.9999539 -0.009372472 0.001239061 0.9999063 -0.01364201 0.01142966 0.9999321 0.002289474 0.00205183 0.9999836 -0.005359649 0.003229379 0.9999015 -0.01365536 0.01350319 0.9998936 -0.005514264 0.01290845 0.9999012 -0.005572557 0.01384043 0.9998793 -0.007068216 0.00370264 0.9999887 -0.00300014 0.005689322 0.9999545 -0.007656514 0.006087839 0.9999685 -0.00511676 0.4759722 -0.8794342 0.006781339 0.9103131 -0.4068329 0.0762701 0.8778472 -0.4750496 0.06092864 0.1668089 -0.9859731 0.005647182 0.1273656 -0.9918553 0.001067459 0.6656523 -0.7428365 0.0714212 0.930944 -0.3246595 0.1671508 0.6064027 -0.7872717 0.1117099 0.4301859 -0.8989136 0.08303332 0.8803812 -0.4319557 0.1958141 0.645761 -0.7521351 0.1314743 0.897356 -0.3609892 0.2538484 0.8320927 -0.4794923 0.2787634 0.633147 -0.7435703 0.2150071 0.8665355 -0.3195666 0.3833975 0.5088331 -0.8372135 0.2004062 0.3292871 -0.9362252 0.1226879 0.8306679 -0.3941564 0.3932324 0.5465279 -0.7981958 0.2533589 0.1457552 -0.9871188 0.0659694 0.7765238 -0.447081 0.4439924 0.7830128 -0.4263384 0.452909 0.5755586 -0.7419596 0.3438435 0.5126431 -0.8078025 0.2909506 0.3218597 -0.926683 0.1940751 0.7520111 -0.3562182 0.5546062 0.7166207 -0.4288716 0.5500218 0.5720816 -0.6856667 0.450093 0.2489639 -0.9464018 0.2057684 0.5228664 -0.7334987 0.4342699 0.3241385 -0.9027799 0.2827064 0.666507 -0.3739154 0.6449463 0.6723693 -0.3345927 0.6602782 0.5672161 -0.6161992 0.5464105 0.3921675 -0.7862644 0.477486 0.6005659 -0.3635511 0.7121456 0.5759132 -0.4153056 0.7041628 0.4074495 -0.786388 0.4643049 0.3279411 -0.8464794 0.4194368 0.5351706 -0.4013729 0.7432983 0.1977756 -0.9405487 0.2761397 0.403961 -0.6436848 0.649989 0.4123582 -0.4459605 0.7944053 0.3822852 -0.6493266 0.6574443 0.3182051 -0.741128 0.5911639 0.1958246 -0.9104495 0.3643274 0.3449409 -0.3864523 0.8553774 0.3493949 -0.4484873 0.822668 0.2856798 -0.7015587 0.6528419 0.1140581 -0.9570772 0.2664471 0.1764245 -0.837598 0.5170146 0.2578361 -0.461883 0.8486371 0.171058 -0.8132682 0.556178 0.2403204 -0.4072163 0.8811475 0.1502093 -0.5722414 0.8062115 0.133303 -0.8182497 0.5591938 0.0740168 -0.8979041 0.4339238 0.1217376 -0.3564022 0.9263679 0.1396044 -0.5583394 0.8177823 0.05245709 -0.723292 0.6885471 0.04725497 -0.8852974 0.462618 0.03723627 -0.2461996 0.9685036 0.05451703 -0.3512619 0.9346888 0.02889662 -0.6449232 0.763701 -0.05404937 -0.4012938 0.9143534 4.24237e-4 -0.9626331 0.2708087 -0.02195513 -0.6422103 0.766214 -0.0791521 -0.3438568 0.9356803 -0.05977177 -0.7886486 0.611932 -0.03795969 -0.9085187 0.4161165 -0.1372656 -0.510017 0.8491414 -0.1104289 -0.7059885 0.6995612 -0.1912798 -0.3808732 0.9046257 -0.1460868 -0.7895525 0.5960417 -0.2743127 -0.4092898 0.8701922 -0.0644418 -0.9532033 0.2953827 -0.2537689 -0.4574555 0.8522534 -0.04947471 -0.9843739 0.168998 -0.189986 -0.7372956 0.648306 -0.2124412 -0.8000127 0.5611137 -0.3459074 -0.4212231 0.8384028 -0.3487403 -0.488353 0.7999323 -0.2762624 -0.7270363 0.6285677 -0.1234793 -0.9416066 0.3132571 -0.445618 -0.3873502 0.807084 -0.2832147 -0.7955717 0.5355885 -0.2311461 -0.8901056 0.3927897 -0.452881 -0.4862184 0.7473223 -0.2330183 -0.884011 0.4052493 -0.4812567 -0.4824993 0.7318378 -0.5181121 -0.4056064 0.7530229 -0.3730849 -0.7726766 0.5135939 -0.1136461 -0.9795101 0.1662666 -0.5962872 -0.3647275 0.7151332 -0.5919691 -0.4319936 0.6804074 -0.3846588 -0.7957663 0.467754 -0.3587651 -0.83694 0.4133026 -0.6418243 -0.4240888 0.6389133 -0.6248844 -0.5144947 0.5872092 -0.3766319 -0.8395472 0.391547 -0.3392775 -0.8852078 0.3182734 -0.7455751 -0.3358983 0.5755781 -0.6539984 -0.5208411 0.5486443 -0.5260602 -0.7540057 0.3933653 -0.7906184 -0.3397153 0.5094275 -0.7617964 -0.4496789 0.4663209 -0.1009165 -0.9917679 0.0788182 -0.5294833 -0.7655537 0.3654794 -0.4146193 -0.8745186 0.2516108 -0.7617573 -0.4496796 0.4663842 -0.4388978 -0.8709619 0.2208942 -0.8690295 -0.2869908 0.4030185 -0.8434117 -0.3894121 0.3701552 -0.6925766 -0.6460818 0.3208055 -0.6079689 -0.7463987 0.2706711 -0.8915967 -0.3473296 0.2905469 -0.878325 -0.3785637 0.2919504 -0.6622225 -0.7189949 0.2109688 -0.1563591 -0.9862715 0.05310922 -0.6120079 -0.772102 0.1711864 -0.3818508 -0.919444 0.09387564 -0.9185903 -0.3594013 0.1643853 -0.8985627 -0.4109548 0.1539523 -0.8136585 -0.5640668 0.1406723 -0.6661972 -0.743897 0.05290174 -0.4526954 -0.8911223 0.03111565 -0.9136539 -0.4048067 0.03698879 -0.8433851 -0.5370709 0.01602017 -0.4051083 -0.9140969 0.01772642 -0.9103061 -0.4057959 -0.08168584 -0.8149631 -0.5776028 -0.0470131 -0.6718575 -0.7382156 -0.06037575 -0.4983583 -0.8664255 -0.03075796 -0.04326522 -0.9990546 -0.004255235 -0.9254764 -0.3396394 -0.1677456 -0.2276474 -0.9726753 -0.04560023 -0.8348879 -0.5131747 -0.1990329 -0.640269 -0.7567118 -0.1320719 -0.6573594 -0.7398955 -0.142945 -0.8615188 -0.447829 -0.2392379 -0.1553183 -0.9876545 -0.02037209 -0.4671849 -0.8670074 -0.1733106 -0.8014352 -0.5182947 -0.2984499 -0.7170047 -0.6315745 -0.2949879 -0.4658204 -0.8681443 -0.1712808 -0.7795269 -0.4629247 -0.4219462 -0.711737 -0.6014339 -0.3629155 -0.3231613 -0.9333346 -0.1563758 -0.1817376 -0.9784304 -0.0982111 -0.5264227 -0.7941365 -0.3036879 -0.7839624 -0.3430406 -0.5174226 -0.7500752 -0.3995153 -0.5270435 -0.5361307 -0.7475285 -0.3921289 -0.4875508 -0.8016327 -0.345947 -0.744476 -0.2969649 -0.5979695 -0.3501294 -0.8988664 -0.2635313 -0.6119071 -0.5387877 -0.5790317 -0.2816252 -0.9294379 -0.2383959 -0.6270986 -0.5297504 -0.571062 -0.6565414 -0.2942486 -0.6945296 -0.4462941 -0.7579148 -0.4758014 -0.3882856 -0.8217118 -0.4171617 -0.07460558 -0.9940394 -0.07949703 -0.5135045 -0.5857545 -0.6270606 -0.2761693 -0.9006491 -0.3355025 -0.5224946 -0.3964942 -0.7548456 -0.4819851 -0.5557981 -0.6773322 -0.4232673 -0.6523055 -0.6287626 -0.3101223 -0.8255513 -0.4714755 -0.5031924 -0.2475705 -0.8279531 -0.4470812 -0.3565195 -0.8203733 -0.3981812 -0.5118947 -0.7611936 -0.2317357 -0.8793218 -0.4160432 -0.1932927 -0.9109508 -0.3644263 -0.3469032 -0.5901031 -0.7289969 -0.1719012 -0.9150408 -0.3648979 -0.3421576 -0.3423534 -0.8750556 -0.3332849 -0.5848066 -0.739542 -0.2164004 -0.7542763 -0.6198696 -0.2921314 -0.3448022 -0.8920598 -0.2241244 -0.5675677 -0.7922344 -0.2154357 -0.7542369 -0.6202533 -0.05820208 -0.9820562 -0.1793832 -0.1164172 -0.8881686 -0.4445264 -0.1680395 -0.4187456 -0.8924208 -0.1709347 -0.5699115 -0.8037303 -0.1273862 -0.6983389 -0.7043406 -0.09429407 -0.8680189 -0.4874955 -0.01414561 -0.9981545 -0.05905604 -0.0544427 -0.9208787 -0.3860291 -0.08099782 -0.3387119 -0.9373973 -0.05502533 -0.4427026 -0.8949787 -0.05257326 -0.6139999 -0.7875533 0.01572775 -0.3702269 -0.9288083 -0.001976013 -0.7802803 -0.6254269 -0.0147891 -0.8904709 -0.4547999 0.04101091 -0.2475191 -0.9680147 0.03402078 -0.7372393 -0.6747748 0.03981804 -0.7389809 -0.6725488 0.05781567 -0.9149863 -0.3993214 0.1358098 -0.4182862 -0.8981049 0.1342947 -0.3844226 -0.9133369 0.01457309 -0.9790217 -0.203234 0.1065001 -0.6149596 -0.7813338 0.1326128 -0.7332102 -0.6669458 0.09451878 -0.8878879 -0.4502459 0.2416492 -0.5033058 -0.8296319 0.2466697 -0.4984941 -0.8310583 0.2528743 -0.5206679 -0.8154505 0.1421735 -0.8974487 -0.4175794 0.1063888 -0.9224627 -0.3711388 0.3080986 -0.5244828 -0.793721 0.3186599 -0.5959401 -0.7370965 0.2047645 -0.8625323 -0.4627196 0.172959 -0.8938751 -0.4136091 0.4070025 -0.4872534 -0.7726145 0.4903736 -0.392056 -0.7783483 0.4307958 -0.5058511 -0.7473484 0.06923812 -0.9893864 -0.1277522 0.2952999 -0.8285686 -0.4756808 0.2849642 -0.8574901 -0.4283761 0.5329912 -0.4859327 -0.6926687 0.3245865 -0.8398708 -0.4350413 0.5844767 -0.4082812 -0.7012085 0.315721 -0.8736913 -0.3701132 0.596017 -0.4763 -0.6464534 0.4604581 -0.744845 -0.4828917 0.2071794 -0.9531404 -0.2204542 0.6658217 -0.3829106 -0.6403601 0.6544083 -0.4829947 -0.5817784 0.5364393 -0.6943704 -0.4796693 0.7287239 -0.4402789 -0.524515 0.7262303 -0.4451343 -0.523875 0.4454708 -0.8383401 -0.3142324 0.5152388 -0.7667417 -0.3829309 0.3414009 -0.9055168 -0.2519619 0.2598344 -0.9497784 -0.1743762 0.7994198 -0.3849369 -0.4612501 0.7741098 -0.4829462 -0.4092886 0.6127313 -0.7210589 -0.3234724 0.5141309 -0.8229189 -0.2418139 0.8473104 -0.374774 -0.3763106 0.5109263 -0.8284211 -0.2295058 0.8393758 -0.4230591 -0.3412762 0.7310567 -0.6225984 -0.2791549 0.379449 -0.9142518 -0.1419944 0.9069129 -0.2879489 -0.3075621 0.4547545 -0.8799323 -0.1375408 0.8638683 -0.4478286 -0.2306103 0.7695567 -0.60094 -0.215995 0.9101973 -0.3594405 -0.2057754 0.6043806 -0.78378 -0.1428749 0.895893 -0.4208312 -0.1423977 0.5809329 -0.8078851 -0.09919053 0.9389755 -0.323027 -0.118232 0.450156 -0.889737 -0.0756821 0.6448192 -0.7589794 -0.09032446 0.9187613 -0.393607 -0.03084486 0.8745129 -0.4848435 -0.01241803 0.6623507 -0.748286 -0.03687393 0.9997643 -4.42291e-5 -0.02171206 0.9997931 -3.29068e-4 -0.02034169 0.9921877 1.75449e-4 -0.124754 0.9909003 0.002348959 -0.1345783 0.9747221 -0.002534925 -0.2234064 0.9480499 -0.00279653 -0.3181095 0.9621435 0.005411505 -0.2724897 0.9100499 0.002140462 -0.4144935 0.9136714 -9.72226e-5 -0.4064538 0.8670673 -7.57208e-4 -0.4981904 0.8658331 -2.50179e-4 -0.5003331 0.8073144 -6.7745e-5 -0.5901217 0.8137894 -0.002996861 -0.5811522 0.7509311 0.002438187 -0.6603761 0.7248852 -0.003665506 -0.6888599 0.685043 0.002489209 -0.7284985 0.6384364 -0.003914594 -0.7696647 0.6079943 0.002245426 -0.7939382 0.5300622 -0.003421962 -0.8479519 0.5207188 -0.00105375 -0.8537276 0.4303178 0.003091931 -0.9026722 0.3914623 -0.004269897 -0.9201843 0.4463155 -3.52923e-4 -0.8948757 0.2891756 -0.005437612 -0.9572607 0.3306994 0.001976072 -0.9437342 0.1632517 -0.003540396 -0.9865781 0.2034594 0.003102064 -0.9790785 0.04049634 -0.004612863 -0.9991691 0.08816754 0.003873646 -0.9960982 -0.09428328 -0.003595113 -0.995539 -0.04397797 0.004347264 -0.9990231 -0.2013226 -0.004555284 -0.9795145 -0.1513834 0.001602709 -0.9884738 -0.2537575 7.61212e-4 -0.9672676 -0.280823 -0.00350666 -0.9597532 -0.39859 0.00381267 -0.9171214 -0.4246071 -0.00157243 -0.9053764 -0.3834366 -2.01907e-4 -0.9235672 -0.5215769 -0.002745449 -0.8531999 -0.4712578 0.003650009 -0.8819881 -0.6109704 -0.003148198 -0.7916472 -0.5650829 0.003003537 -0.8250287 -0.6755949 -0.005790293 -0.7372503 -0.6434853 -2.28561e-4 -0.7654585 -0.7209222 0.00475198 -0.6929997 -0.7739608 -0.003697454 -0.6332229 -0.8428881 -0.00310862 -0.53808 -0.8050762 0.004379689 -0.5931553 -0.8665881 0.001854598 -0.4990208 -0.896445 -0.004592239 -0.4431312 -0.9180665 9.73772e-4 -0.3964253 -0.9262566 -0.001460731 -0.3768908 -0.9494241 0.003763318 -0.313974 -0.9602293 -0.002820909 -0.2791984 -0.9839953 7.80082e-4 -0.1781926 -0.9838711 6.07989e-4 -0.1788781 -0.9974296 -0.001194953 -0.07164478 -0.9978964 1.74059e-4 -0.06482899 -0.9996432 -0.005791246 0.02607786 -0.9966922 0.00541836 0.0810886 -0.9853957 -0.00525552 0.1701999 -0.9764307 0.003979742 0.215795 -0.9505023 -0.001880168 0.3107119 -0.9444776 0.002151489 0.328569 -0.9068468 -0.002796292 0.4214512 -0.8944927 0.003541529 0.4470685 -0.8449057 -0.001538693 0.5349131 -0.8392182 6.52946e-4 0.5437946 -0.7770121 8.32436e-4 0.6294851 -0.7785551 3.0972e-4 0.6275762 -0.7193235 -0.001024246 0.6946746 -0.7150838 2.02589e-4 0.6990388 -0.6414726 1.83028e-4 0.7671459 -0.6346241 0.002126038 0.7728181 -0.5615463 -0.002630174 0.8274412 -0.4773862 -0.003563642 0.8786864 -0.5214559 0.004333019 0.8532673 -0.3936768 0.002443969 0.9192457 -0.3935037 0.002494513 0.9193196 -0.2975089 -0.003092229 0.9547141 -0.2548282 0.003825306 0.9669788 -0.1983286 -0.0034855 0.9801294 -0.1477015 0.001225769 0.9890312 -0.09988403 -0.004063904 0.9949909 -0.04976791 0.003678262 0.998754 0.03946334 -0.001498222 0.99922 0.06249272 0.003481209 0.9980394 0.15726 -0.002603769 0.9875538 0.1916155 0.002319455 0.9814674 0.2446711 -0.00339812 0.9696002 0.2898271 0.004038453 0.9570705 0.381078 -0.002778351 0.9245387 0.3939263 5.78149e-5 0.9191421 0.4900624 -0.002352297 0.8716842 0.4839994 -5.48634e-4 0.8750683 0.5494583 -0.005678653 0.8355019 0.5939596 0.003573954 0.8044869 0.6432564 -3.50283e-4 0.7656508 0.6311262 0.002835333 0.775675 0.7230551 4.01948e-4 0.6907902 0.7212706 -3.21617e-4 0.6926534 0.8087005 6.73824e-4 0.5882203 0.8083688 8.21455e-4 0.588676 0.8720607 -5.22138e-4 0.4893975 0.862388 0.004272997 0.5062302 0.9152598 -2.28539e-4 0.402864 0.9187652 0.001891791 0.3947999 0.9599953 -0.002902388 0.2800011 0.9508339 0.0034433 0.3096822 0.9846403 0.002692878 0.1745752 0.9836761 0.001256406 0.179944 0.9974744 4.09515e-4 0.07102543 0.9977337 -4.29248e-4 0.06728649 0.01142126 -0.9997896 0.01703947 0.01227658 -0.9998837 0.009055912 0.01380807 -0.9997664 0.01663166 0.002890765 -0.9999932 0.002331733 0.003245413 -0.9999933 0.00176841 0.004183709 -0.9998584 0.01629972 0.003950357 -0.9999639 0.007526695 0.005501806 -0.9999827 0.00214672 0.004617393 -0.9999886 0.001266002 0.004216313 -0.9998578 0.01633226 0.006061851 -0.9999113 0.01186358 0.001366078 -0.9999374 0.01111972 0.006742 -0.9999772 2.17644e-4 2.54275e-4 -0.9999749 0.007089316 0.006969392 -0.9999757 2.52943e-4 -0.001598834 -0.999979 0.006296992 0.003691911 -0.999993 -6.72169e-4 -0.001642465 -0.9999756 0.006789088 0.0111469 -0.9999122 -0.007176399 0.003929853 -0.9999911 -0.001578271 -0.00215274 -0.9999884 0.004294037 -0.005805313 -0.9999634 0.006300806 0.0110675 -0.9999104 -0.00753659 0.006237685 -0.9999788 -0.001919507 -0.006142616 -0.9999521 0.007613718 -0.008028805 -0.9999446 0.006813049 0.004841864 -0.9999723 -0.005674958 0.008324444 -0.9998881 -0.01242995 -0.008659958 -0.9999374 0.007085204 0.007491052 -0.9998697 -0.01431167 0.005566716 -0.9999651 -0.006227731 -0.007470011 -0.9999644 0.003942728 -0.009514927 -0.9999477 0.00376439 0.001805961 -0.9999734 -0.007071435 -0.006168484 -0.9999797 0.001679062 0.001385271 -0.9999147 -0.01298713 0.001781761 -0.9999189 -0.01261645 2.25654e-4 -0.9999615 -0.008781254 -0.006710946 -0.9999775 -6.32142e-5 -0.008841931 -0.9999607 -5.85927e-4 -0.001164495 -0.9999541 -0.00950849 -7.04488e-4 -0.9999957 -0.002893447 -0.003833532 -0.9999922 -9.88725e-4 -9.85198e-4 -0.9999974 -0.002072095 -0.00352627 -0.9999926 -0.001594483 -0.003557443 -0.9999924 -0.001636087 -0.00993216 -0.9998512 -0.0141102 -0.01214981 -0.9998986 -0.007434785 -0.002289891 -0.9999961 -0.001605033 -0.009100079 -0.9998633 -0.01381069 -0.002313852 -0.9999948 -0.002275288 0.9288387 0.3689388 -0.03380799 0.8695598 0.4937513 -0.008694827 0.6783912 0.7343278 -0.02341115 0.5853133 0.8108016 -0.003024637 0.9322251 0.3415453 -0.1195971 0.9227461 0.3654985 -0.1222724 0.7054449 0.7033429 -0.08750021 0.6426905 0.7582207 -0.1097741 0.8623318 0.4609498 -0.209545 0.1753255 0.9840469 -0.03020864 0.730156 0.6600443 -0.1766744 0.9225251 0.2810879 -0.264456 0.3014053 0.9510508 -0.06824344 0.6158648 0.7614314 -0.2023187 0.4002486 0.9072405 -0.1292892 0.826052 0.4626903 -0.3218011 0.6716548 0.6970971 -0.2508698 0.8531963 0.3564168 -0.3808192 0.5696542 0.7757771 -0.2714111 0.3072289 0.9416568 -0.1374515 0.7962841 0.4455184 -0.4092004 0.4306881 0.8730866 -0.2285336 0.7922291 0.406837 -0.454815 0.4316895 0.8731077 -0.2265551 0.7554058 0.4606499 -0.4660086 0.6356421 0.6511136 -0.4147414 0.7714945 0.31863 -0.5507007 0.5581108 0.7113642 -0.427169 0.2827618 0.9397962 -0.1919088 0.7127585 0.4187632 -0.5626836 0.5624837 0.7011272 -0.4382155 0.7132223 0.3233873 -0.6218799 0.1546909 0.980354 -0.12238 0.6462693 0.4367789 -0.6257478 0.4945986 0.7169117 -0.4913349 0.4726644 0.7535767 -0.4568485 0.6469261 0.3071027 -0.697979 0.2638683 0.9276536 -0.264258 0.5948727 0.3995121 -0.6975075 0.4970947 0.6320499 -0.594483 0.5858276 0.2363445 -0.7752081 0.439745 0.6862095 -0.5794317 0.518533 0.3663231 -0.7726132 0.185105 0.9527975 -0.2406514 0.467169 0.5142315 -0.719249 0.2476385 0.9010169 -0.3561514 0.3957812 0.5896503 -0.7040382 0.3337743 0.7030546 -0.6279402 0.2379623 0.8759021 -0.4197255 0.4160117 0.2770673 -0.8661224 0.1362975 0.9459826 -0.2941767 0.3079516 0.3616409 -0.8799896 0.3162878 0.4109591 -0.8550291 0.2666089 0.6992421 -0.6633101 0.1712332 0.8466405 -0.5038642 0.2191739 0.443892 -0.868863 0.1368731 0.813697 -0.5649451 0.1334998 0.8572509 -0.4972914 0.1921797 0.3580745 -0.9137011 0.1268473 0.4581007 -0.8798032 0.09196627 0.7257162 -0.6818199 0.08553975 0.3092768 -0.9471172 0.03245878 0.9803528 -0.1945637 0.03223752 0.8154889 -0.5778742 0.001011192 0.4648325 -0.8853981 0.005722045 0.7908223 -0.6120191 -0.04402965 0.3487055 -0.9361976 -0.01718902 0.8179368 -0.5750514 -0.03243029 0.9335507 -0.3569754 -0.09933567 0.4529808 -0.8859689 -0.08280241 0.6833198 -0.7254087 -0.1411725 0.3523263 -0.9251685 -0.08497166 0.8958559 -0.4361445 -0.1269183 0.7941206 -0.5943604 -0.2287712 0.4296476 -0.8735369 -0.2252066 0.3845605 -0.8952068 -0.1855612 0.7021197 -0.6874554 -0.2061045 0.7313429 -0.6501219 -0.06008243 0.9814694 -0.1819559 -0.351202 0.3358001 -0.8740112 -0.345985 0.4712213 -0.8113229 -0.1858496 0.8741422 -0.4487041 -0.1694689 0.9019519 -0.3971941 -0.3635271 0.5489321 -0.7526763 -0.4567861 0.3738651 -0.8071997 -0.3981723 0.5267094 -0.7510233 -0.1893277 0.9153416 -0.355394 -0.3520002 0.756204 -0.55159 -0.5342925 0.29987 -0.7903224 -0.379094 0.7439525 -0.5502932 -0.5332595 0.4687143 -0.704231 -0.06956106 0.9931911 -0.09344899 -0.4942237 0.5778823 -0.6494575 -0.6084892 0.3071874 -0.7316945 -0.2335425 0.9365855 -0.2612768 -0.6589002 0.3994008 -0.6374399 -0.6591573 0.3979144 -0.6381033 -0.5062162 0.6937169 -0.5123496 -0.4544531 0.7722822 -0.4439061 -0.3085981 0.8985495 -0.3120512 -0.6971055 0.4710493 -0.5405151 -0.5457153 0.7245826 -0.4209216 -0.7659248 0.3295978 -0.5520187 -0.5070373 0.7798162 -0.3671512 -0.2778873 0.9360016 -0.2160548 -0.7891308 0.4091114 -0.4581491 -0.7960603 0.3826418 -0.4689065 -0.5707089 0.750256 -0.3337775 -0.5523595 0.7732974 -0.311304 -0.1461215 0.9848883 -0.09297072 -0.8355068 0.3839911 -0.3930384 -0.7642636 0.5539281 -0.3302499 -0.10682 0.9922483 -0.06350404 -0.5789285 0.7638115 -0.2853665 -0.4553863 0.8723105 -0.1780384 -0.8708267 0.4138702 -0.2652782 -0.7699003 0.5782247 -0.270018 -0.5034008 0.8498907 -0.1557999 -0.5096092 0.8450956 -0.1615924 -0.9058753 0.3909475 -0.1629423 -0.8720293 0.4586763 -0.1708249 -0.6636601 0.7388905 -0.1166031 -0.605739 0.787484 -0.1137954 -0.3283493 0.9436293 -0.04184073 -0.1692332 0.9850363 -0.03261464 -0.950717 0.3046514 -0.05766063 -0.9080483 0.4129936 -0.06988912 -0.7690895 0.637533 -0.04531037 -0.7279148 0.6852854 -0.02289193 -0.3947986 0.9187119 -0.01013523 -0.9513626 0.2994744 0.07228016 -0.9319145 0.357598 0.0604906 -0.7801608 0.6240773 0.04332005 -0.7045456 0.7065357 0.06650507 -0.3309369 0.9432156 0.02872347 -0.3040181 0.9524263 0.02138119 -0.8643683 0.4752251 0.1644033 -0.7520501 0.6445243 0.1378741 -0.9170801 0.3404613 0.2074857 -0.639023 0.7545623 0.1492829 -0.404194 0.9096106 0.09610384 -0.3160105 0.9441747 0.09312152 -0.8572028 0.4258561 0.2895686 -0.8806666 0.3751821 0.289249 -0.7448669 0.6210358 0.2439016 -0.8076352 0.460332 0.3685374 -0.5549764 0.7917459 0.2552252 -0.6172498 0.7389452 0.2701163 -0.4089761 0.8955726 0.1751806 -0.8437361 0.3218739 0.4295426 -0.779451 0.4311897 0.4544576 -0.6247863 0.6941658 0.3574576 -0.27512 0.9463632 0.1694279 -0.2295274 0.9645411 0.130299 -0.7834377 0.364293 0.5035038 -0.5369719 0.7710234 0.3423218 -0.733027 0.440761 0.5180746 -0.5823292 0.6942438 0.4229874 -0.7413526 0.3227568 0.5884084 -0.6461417 0.4887317 0.5862101 -0.5076732 0.7443313 0.433865 -0.4335715 0.8121091 0.3905055 -0.2782974 0.9295237 0.2419425 -0.6445993 0.4186469 0.6397082 -0.599506 0.4734941 0.6452876 -0.4328103 0.7703084 0.468295 -0.5918556 0.359954 0.7212074 -0.07513463 0.9933134 0.08765459 -0.5320098 0.4590097 0.7115306 -0.4141122 0.7082625 0.5717302 -0.3498729 0.8309417 0.4325793 -0.1842741 0.949856 0.2526199 -0.4846588 0.3822878 0.7867414 -0.4583933 0.4467306 0.7683147 -0.3696102 0.6890752 0.6233488 -0.337402 0.7339849 0.5894286 -0.2314277 0.8869885 0.3996158 -0.3612996 0.3793213 0.8518087 -0.379642 0.3175694 0.8689199 -0.2827113 0.6672664 0.6890789 -0.2437189 0.7221419 0.6473888 -0.1601476 0.873775 0.4592058 -0.1256576 0.9383233 0.3221174 -0.2651556 0.4105985 0.8724114 -0.2357429 0.5806922 0.7792444 -0.2457873 0.2385284 0.9395174 -0.1624813 0.4532315 0.8764594 -0.1676495 0.6252864 0.7621751 -0.09878522 0.8553068 0.5086175 -0.1318212 0.405023 0.9047539 -0.08539181 0.8698449 0.4858787 -0.1030847 0.4433412 0.8904057 -0.04999351 0.7235532 0.6884559 -0.0502122 0.331633 0.9420714 -0.02222573 0.9789987 0.2026515 -0.001955807 0.4369277 0.8994945 -0.006746351 0.7303177 0.6830744 0.01711857 0.791767 0.6105834 0.05341398 0.3174619 0.9467655 0.1084491 0.5367391 0.8367497 0.04648476 0.7929598 0.6074981 0.06495028 0.8874374 0.4563292 0.1639866 0.4741469 0.8650394 0.1884433 0.5375063 0.8219345 0.1648175 0.7856111 0.5963643 0.1175882 0.8730221 0.4732921 0.2831649 0.3544595 0.8911656 0.3191435 0.4587796 0.829258 0.2400653 0.7214556 0.6495156 0.3568355 0.3933305 0.847325 0.06610423 0.9810872 0.1819291 0.2382829 0.8409264 0.4858645 0.4538355 0.3650181 0.8128932 0.4120678 0.4655411 0.7832443 0.3248308 0.7456641 0.5817819 0.2726717 0.8183913 0.5058517 0.5063743 0.4359714 0.7439853 0.4819648 0.5583565 0.6752392 0.1923301 0.9416864 0.2761088 0.6154538 0.3545317 0.7039346 0.4941545 0.6154558 0.6140241 0.4699173 0.6787207 0.5643723 0.3355743 0.8549553 0.3955268 0.6812501 0.3176028 0.6595657 0.655816 0.4509744 0.6054152 0.5818468 0.5929818 0.556621 0.315441 0.9125029 0.2604528 0.3448963 0.8866078 0.3081772 0.7273924 0.4236141 0.5398626 0.7082123 0.4946725 0.5037206 0.414381 0.8561987 0.3085647 0.42125 0.851641 0.3118591 0.7458626 0.5024282 0.4373269 0.7227428 0.5587614 0.4067292 0.5460149 0.7805023 0.3044407 0.4527491 0.8635508 0.2220324 0.2331725 0.9631788 0.1338557 0.7856819 0.5163094 0.3407766 0.7241712 0.6333262 0.2728993 0.5020828 0.8402055 0.20486 0.333871 0.9373326 0.09968936 0.8219366 0.5201885 0.2320002 0.8185124 0.5322943 0.2161027 0.7261559 0.6691475 0.1579221 0.4626142 0.8810196 0.09895694 0.9552569 0.2390331 0.1742053 0.8836275 0.4586593 0.09399002 0.7840346 0.6127875 0.09890133 0.9117709 0.4043579 0.07189291 0.5424435 0.8395079 0.03133064 0.4172115 0.9077854 0.04313236 -0.004299402 0.9999819 0.004236996 -0.005189061 0.9999694 0.005865514 -0.004499435 0.999985 0.003138244 -0.002953767 0.999987 0.004182457 -0.006031572 0.9999765 0.003280162 -0.001931667 0.9999893 0.004206418 -0.005405187 0.9999824 0.0024634 -0.005190849 0.9999831 0.002634406 -0.002235114 0.9998684 0.01607519 -0.003017306 0.9999952 7.55319e-4 -0.002403736 0.999827 0.01844745 -0.002859354 0.999863 0.01630645 -0.004851996 0.9999881 -5.68767e-4 -0.005816876 0.9999831 -1.25446e-4 7.5371e-4 0.9999002 0.01411163 -0.009189546 0.9999548 -0.002433419 -0.003418326 0.9999562 0.008725941 0.001885414 0.9999793 0.006173431 -0.008013486 0.9999646 -0.002597033 0.008254706 0.9998549 0.01490217 -0.008452355 0.9999582 -0.003474533 0.007984161 0.9998437 0.0157786 0.006104409 0.9999246 0.01066637 -0.001840412 0.9999977 -0.001067399 -0.001154422 0.9999989 -9.60155e-4 0.006110072 0.9999614 0.006319105 0.006455838 0.9999587 0.006402492 -0.001090884 0.9999986 -0.001359343 0.006330728 0.9999706 0.0043388 -0.002467453 0.9999885 -0.004131495 -0.001902341 0.9999909 -0.003844082 0.01340758 0.9998977 0.004999816 0.01341611 0.9998975 0.005020439 -0.002290785 0.9999645 -0.008112847 -0.001138687 0.9999781 -0.006524264 0.01413208 0.9998878 0.004981935 -4.41602e-4 0.9999625 -0.008664011 0.01301246 0.999915 8.79072e-4 0.01339858 0.9999097 0.001042485 0.003269553 0.9997131 -0.02373141 6.30881e-4 0.999748 -0.02244263 0.001576781 0.999949 -0.009979784 0.01586252 0.999871 -0.002576291 0.008438766 0.9999642 5.80795e-4 0.002932608 0.9999663 -0.007675528 0.005467295 0.9999353 -0.00998795 0.004269063 0.9999896 -0.001608252 0.00502175 0.9999837 -0.00273019 0.004792273 0.9999846 -0.002829134 0.005113363 0.9999291 -0.01075756 0.002144515 0.9999929 -0.003148734 0.005037903 0.999982 -0.003272354 0.002376496 0.9999946 -0.002246856 0.6635954 0.7422884 0.09300118 0.8403633 0.534412 0.09051734 0.2746943 0.7456128 0.6071282 0.3238995 0.531073 0.7829754 -0.408725 0.7483087 0.5224731 -0.4997982 0.5310752 0.6842228 -0.6650191 0.7438779 -0.06629753 -0.8363902 0.5369355 -0.1102347 -0.2524834 0.7411186 -0.6220896 -0.3396059 0.5427577 -0.768168 0.3892441 0.7445581 -0.5423305 0.5145745 0.5350252 -0.6700456 -0.3883049 0.01965922 -0.9213212 -0.3938124 0.02546662 -0.9188381 0.5950888 0.0246787 -0.8032811 0.5984385 0.02060365 -0.8009038 0.9920333 0.01987767 0.1243984 0.9926723 0.02606022 0.117994 -0.002160549 0.999841 0.0177083 -0.002039909 0.9998332 0.01815211 0.001176357 0.9999623 -0.008609116 0.001021802 0.9999592 -0.00897926 1.43407e-4 0.9999459 0.01040303 -0.004894316 0.9999535 0.008321702 0.002891361 0.9999687 0.007379412 0.002541899 0.999985 0.004879236 6.48221e-4 0.9999775 0.006695806 -0.006507515 0.9999562 0.006731688 -0.004959464 0.9999601 0.007433831 -0.009210109 0.9999574 7.87709e-4 0.00258547 0.9999966 3.34948e-4 0.0083341 0.99996 -0.003263354 0.005063354 0.9999748 0.004988193 -0.003881514 0.9999421 -0.01003801 -0.007802188 0.999969 -0.001165151 -0.006496727 0.9999784 0.001109898 0.003663718 0.999982 -0.004752337 -2.46591e-6 0.9999502 -0.009986877 0.003741204 0.999942 -0.01010423 -0.003925442 0.9999528 -0.008892655 -0.006379485 0.9999797 3.03287e-4 0.004895925 0.9999472 -0.009036839 -0.06264495 0.9931517 -0.09861707 0.0144996 0.9994059 -0.03126758 -0.01880395 0.9993875 -0.02951759 2.05688e-4 1 4.88591e-4 -0.006712973 0.9996211 -0.02669596 -0.01231998 0.9998212 -0.0143522 -0.00143671 0.999998 -0.001423239 0.06765729 0.9948064 -0.07604485 -0.003299117 0.9999918 -0.002328455 0.06843459 0.9948223 -0.07513529 0.02799135 0.9996059 0.002135455 3.30664e-4 0.9997873 0.02062129 -0.06736624 0.9975929 -0.0164408 0.02391022 0.9997119 -0.002087652 0.03905886 0.999235 -0.001987397 0.04020535 0.999179 0.004986286 0.02511489 0.9996581 0.007288336 0.05620884 0.9975958 0.04053747 0.05587196 0.9975939 0.04104602 0.01070892 0.9998934 0.009929239 0.006157517 0.999889 0.01356875 0.008275985 0.9998069 0.01782536 0.30208 0.8976118 0.3209998 0.3842042 0.6775156 0.6271841 0.08661258 0.9137891 0.3968473 0.01210588 0.792266 0.6100558 -0.1050282 0.9041584 0.4140855 -0.2247254 0.8324986 0.5064037 -0.299686 0.8826962 0.3619887 -0.4664245 0.7894538 0.3990127 -0.4369156 0.8643661 0.2489501 -0.6179853 0.77643 0.1234933 -0.5135504 0.8580275 -0.007411181 -0.6130966 0.7828017 -0.1064622 -0.455164 0.8502227 -0.2644755 -0.4519384 0.8532529 -0.2602136 -0.405488 0.7996987 -0.4427887 -0.2579962 0.8685805 -0.4230908 -0.2091593 0.8095825 -0.5484784 -0.07892352 0.8602188 -0.5037804 -0.01368457 0.8046091 -0.5936472 0.115415 0.8487199 -0.5160949 0.1729607 0.8102956 -0.559916 0.3039534 0.852559 -0.4251535 0.3444204 0.8284118 -0.441711 0.4498134 0.840173 -0.3029477 0.4635177 0.8323324 -0.3039315 0.5506971 0.8269713 -0.1133639 0.4833871 0.8662471 -0.1263061 0.5242086 0.8423954 0.1248008 0.5269982 0.8407953 0.1238391 0.4636113 0.8325964 0.3030641 0.4269393 0.850487 0.3072375 0.4197005 0.8369054 0.3513417 0.2279306 0.8595218 0.4574603 0.1914688 0.8766938 0.4413025 0.1258001 0.7965807 0.5912983 -0.0386554 0.8472424 0.5297983 -0.08906191 0.8011309 0.5918256 -0.2478587 0.8508688 0.463237 -0.2953565 0.8177717 0.4939777 -0.4508385 0.8236897 0.3439188 -0.4328248 0.8516139 0.2956629 -0.5622919 0.8128991 0.1517334 -0.5004354 0.8628205 0.07145208 -0.5808405 0.8138716 -0.01540559 -0.448793 0.8792707 -0.1595869 -0.5209725 0.8136518 -0.2579891 -0.3383613 0.8874598 -0.3129324 -0.3385281 0.8277472 -0.4474745 -0.2270987 0.8628358 -0.4515977 -0.2099557 0.8180868 -0.5353996 -0.03541707 0.8208522 -0.5700417 -0.02499628 0.8306815 -0.5561867 0.1798008 0.8230231 -0.5387994 0.1884313 0.8423568 -0.5049048 0.3810288 0.807309 -0.4506323 0.3664999 0.8748783 -0.3166481 0.5255108 0.7991585 -0.2918631 0.4242285 0.9047858 -0.03732472 0.5684751 0.8226934 0.003422915 0.5534342 0.8041143 0.2170506 0.4320747 0.8647791 0.2558685 0.4616682 0.8195523 0.3394064 0.2971759 0.8389774 0.4558546 0.3087017 0.8320175 0.4609233 0.1030395 0.8425254 0.5287098 0.1256861 0.8262198 0.5491483 -0.09058195 0.8341766 0.5440076 -0.08186286 0.8431614 0.531392 -0.2841243 0.8208676 0.4954291 -0.2549529 0.8430576 0.4735537 -0.4054873 0.8022397 0.4381687 -0.3969916 0.8708345 0.2899051 -0.5425527 0.8064392 0.2351438 -0.4995732 0.8571027 0.125705 -0.6025643 0.7970814 0.03972089 -0.4479037 0.8912734 -0.0708093 -0.5175558 0.8146596 -0.2616597 -0.4066525 0.8668383 -0.2884879 -0.4264153 0.7966344 -0.4284198 -0.2529946 0.8584735 -0.4461132 -0.236688 0.8137298 -0.5308696 -0.07243043 0.835204 -0.5451497 -0.07482618 0.8333191 -0.5477045 0.1243297 0.872859 -0.4718679 0.1028639 0.8291882 -0.5494233 0.3550793 0.8509005 -0.3871529 0.3548284 0.8483883 -0.392854 0.4704954 0.800762 -0.3706945 0.4711083 0.8573578 -0.2073518 0.5607601 0.8082942 -0.1794676 0.5054371 0.8627458 -0.01424878 0.5957062 0.8014436 0.05312615 0.5569415 0.8183664 0.1417492 0.4025718 0.8951025 0.1916449 0.452826 0.8250123 0.3380878 0.274214 0.8879926 0.3691557 0.2796442 0.8337286 0.476126 0.1406272 0.819675 0.5552992 0.1444601 0.8352048 0.5306264 -0.06263393 0.820635 0.56801 -0.08692926 0.8484104 0.5221524 -0.2640501 0.8180601 0.5109357 -0.2779178 0.856327 0.4352768 -0.4297323 0.8097794 0.399484 -0.4202786 0.8630179 0.2802966 -0.5407235 0.806758 0.2382431 -0.5108687 0.8523116 0.1121528 -0.5956832 0.8016055 0.05089437 -0.5077651 0.8572805 -0.08511716 -0.5674402 0.8081371 -0.1578806 -0.4335976 0.8584591 -0.2739363 -0.4661322 0.8150069 -0.3442162 -0.2426968 0.8908999 -0.3839215 -0.2286939 0.8334861 -0.5029911 -0.09935057 0.8860425 -0.4528335 -0.01814317 0.8121683 -0.583141 0.09973561 0.8631687 -0.4949672 0.1761353 0.8094579 -0.5601377 0.3210465 0.8609729 -0.3945311 0.3084284 0.8687744 -0.3874313 0.5036448 0.7889028 -0.3521 0.4829334 0.8592884 -0.1685199 0.5615449 0.8140142 -0.1484867 0.536696 0.8413753 0.06360107 0.5368911 0.841245 0.06367754 0.5398166 0.7861995 0.3008128 0.3955093 0.8630468 0.3142018 0.3908531 0.8393808 0.3777221 0.19845 0.8830466 0.4252603 0.1982237 0.8282454 0.5241346 -0.02979403 0.8964014 0.4422409 -0.09013515 0.8205039 0.5644901 -0.2687301 0.8248328 0.4974284 -0.2866209 0.8771148 0.3853805 -0.4334259 0.8021734 0.410682 -0.4779638 0.8439556 0.2434945 -0.5512882 0.8009614 0.233543 -0.5249617 0.8503921 0.0353356 -0.5806253 0.8141419 0.006883919 -0.5226405 0.8343949 -0.17502 -0.4413526 0.8778237 -0.186101 -0.338881 0.851836 -0.3994184 -0.342516 0.8467537 -0.4070516 -0.214442 0.8030583 -0.5559785 -0.1049636 0.8686551 -0.4841705 0.007863759 0.8103287 -0.5859229 0.09588336 0.8432882 -0.5288398 0.143162 0.8142364 -0.5626046 0.2758325 0.849164 -0.4503742 0.3205524 0.8198677 -0.4744082 0.4461182 0.8430371 -0.3004451 0.4598072 0.8351023 -0.3019629 0.5437809 0.8322164 -0.1082511 0.500265 0.8580262 -0.1163014 0.602065 0.7950429 0.07365083 0.4202893 0.897372 0.1344631 0.4585444 0.8043633 0.3778051 0.3367236 0.8674249 0.3663212 0.2951573 0.8064362 0.5123895 0.1781646 0.8582498 0.4813157 0.1037346 0.8110481 0.5757083 -0.02241337 0.871165 0.4904786 -0.09233611 0.8212511 0.5630459 -0.248646 0.8423234 0.4781909 -0.2451628 0.844871 0.4754873 -0.4182713 0.8034728 0.4236518 -0.409412 0.8458701 0.3418856 -0.5368784 0.810464 0.2343287 -0.4997564 0.849029 0.171445 -0.5742945 0.8172871 0.04720157 -0.4893338 0.8706552 -0.05012142 -0.5693467 0.812484 -0.1253564 -0.4561788 0.8279272 -0.3262478 -0.4205533 0.8498446 -0.317646 -0.2281053 0.8853762 -0.4050644 -0.2227978 0.8212122 -0.5253301 -0.0513522 0.8917698 -0.4495663 0.01787286 0.824757 -0.5652047 0.164846 0.8429514 -0.512112 0.1795474 0.8305742 -0.5271709 0.3321438 0.8101541 -0.4830433 0.3353232 0.8575682 -0.3900454 0.4655915 0.8275611 -0.3136355 0.4511645 0.8597484 -0.2393394 0.5856716 0.7914522 -0.1749064 0.4856936 0.8740317 -0.01305341 0.627829 0.7733229 0.08833318 0.3769794 0.8980311 0.2267747 0.4433795 0.8225873 0.3560405 0.2671439 0.8899663 0.3695865 0.2403733 0.8220202 0.5162398 0.1643319 0.8172912 0.5522956 0.1064128 0.8566951 0.5047277 -0.04702985 0.7874405 0.6145939 -0.1453254 0.8812578 0.4497392 -0.2906481 0.7956541 0.531468 -0.3848314 0.8515588 0.3560234 -0.4629835 0.804111 0.3728967 -0.4146642 0.8982834 0.145399 -0.5777304 0.8131415 0.07091313 -0.4507992 0.8914956 -0.0448988 -0.5318036 0.8293633 -0.1712937 -0.4511331 0.8607075 -0.2359269 -0.4831055 0.8158244 -0.3178675 -0.3548136 0.8464763 -0.3969702 -0.3573818 0.8111675 -0.4629099 -0.1685546 0.8572399 -0.4865483 -0.1627514 0.8281297 -0.536389 0.03628134 0.7989962 -0.6002407 0.1112949 0.8998379 -0.4217881 0.2827764 0.8280316 -0.4841502 0.3639664 0.8374987 -0.4075837 0.3518255 0.8453666 -0.4019629 0.5192367 0.8076326 -0.2795049 0.4359351 0.8856894 -0.1597344 0.5534138 0.8326344 0.02128911 0.5206335 0.8526218 0.04446399 0.5504584 0.8099431 0.202454 0.434008 0.8686074 0.2390781 0.4718952 0.7706053 0.4283486 0.2355797 0.8629416 0.4470282 0.2341755 0.8773435 0.4188439 0.05243259 0.8347187 0.5481747 -0.04577749 0.9069643 0.4187126 -0.1727792 0.8181086 0.548494 -0.3023231 0.8681692 0.3935518 -0.2967233 0.8854442 0.3576923 -0.4838119 0.8316937 0.2724186 -0.4664595 0.8536068 0.2318859 -0.5826321 0.8082996 0.08480542 -0.4932893 0.8698599 -0.003099858 -0.6106999 0.7809019 -0.1312928 -0.4340009 0.8641161 -0.2548468 -0.474867 0.8099043 -0.3443203 -0.3028063 0.8494119 -0.4322128 -0.3070567 0.8312885 -0.4633311 -0.03642141 0.8855329 -0.463147 -0.02510625 0.859125 -0.5111497 0.2038587 0.84018 -0.5025329 0.2381979 0.886182 -0.3974205 0.3990223 0.7807835 -0.4807892 0.4163997 0.8913519 -0.1791729 0.5724731 0.801882 -0.1710559 0.5125431 0.8586612 7.82152e-4 0.5805985 0.8126633 0.04983752 0.4726913 0.8540842 0.2170327 0.4921067 0.8350595 0.2459811 0.3709364 0.8448112 0.3856168 0.3718045 0.8430548 0.3886129 0.2158787 0.8171344 0.5344977 0.2111536 0.8638299 0.4573972 0.1086282 0.7849122 0.6100107 -0.08605909 0.8717416 0.4823488 -0.1342297 0.8261863 0.5471733 -0.3220666 0.8173586 0.4777011 -0.3161839 0.8740512 0.3688663 -0.5457792 0.785601 0.2914726 -0.4910824 0.8475648 0.2011767 -0.555978 0.8287031 0.06434184 -0.5105282 0.8596618 0.01851093 -0.5485878 0.8248039 -0.1369306 -0.4938392 0.8533442 -0.1671127 -0.4951536 0.8080464 -0.319193 -0.3923368 0.8584899 -0.330253 -0.360464 0.7985214 -0.4821094 -0.1987866 0.8634541 -0.4636067 -0.195789 0.8520924 -0.485392 0.07337385 0.8338485 -0.547095 0.09114307 0.8583274 -0.5049427 0.2446701 0.819819 -0.5177195 0.265044 0.8887826 -0.3739216 0.4367623 0.8332407 -0.339041 0.3949866 0.8925647 -0.2175178 0.5372793 0.8277453 -0.1617679 0.45475 0.8904052 -0.01952344 0.5599105 0.8263251 0.060723 0.5202109 0.8309534 0.1972233 0.5029808 0.8452163 0.1806095 0.4747142 0.8030148 0.3602967 0.2968528 0.893602 0.3366808 0.2283085 0.8266022 0.5143968 0.1691153 0.8573396 0.4861781 0.05748385 0.8197767 0.569791 -0.02509427 0.8666474 0.4982896 -0.1479488 0.7833541 0.6037117 -0.2395946 0.9057987 0.3494611 -0.3840125 0.8232385 0.4181063 -0.4503636 0.8661494 0.2166981 -0.4270812 0.8851997 0.1844537 -0.5506765 0.8342545 0.02783799 -0.5084668 0.8609378 -0.01574367 -0.4758952 0.8558378 -0.2026462 -0.5638255 0.811799 -0.1519321 -0.5121608 0.7910793 -0.3344922 -0.3583297 0.8564999 -0.3714939 -0.3403827 0.8116595 -0.474709 -0.2124624 0.8630567 -0.45825 -0.1571499 0.8195343 -0.5510603 -0.0351904 0.8607947 -0.5077344 0.04109859 0.7942129 -0.6062481 0.1466888 0.8928633 -0.4257673 0.3434674 0.8073657 -0.4797822 0.3459307 0.8769155 -0.3336934 0.5088018 0.7881698 -0.346279 0.5016206 0.8595316 -0.09788995 0.5108379 0.853248 -0.1049402 0.4851655 0.8691568 0.09581726 0.5646732 0.8104766 0.1557949 0.4216019 0.8602883 0.2866284 0.4432186 0.8335404 0.3297996 0.4047058 0.8263417 0.3916283 0.2103632 0.884842 0.4156947 0.2081937 0.8426824 0.4965297 0.0504387 0.8276374 0.5589922 0.05892646 0.8448981 0.5316718 -0.1418955 0.7931815 0.5922237 -0.1818379 0.851358 0.4920616 -0.3446188 0.8072333 0.4791789 -0.3473045 0.8700353 0.3498831 -0.4935279 0.7974233 0.3471981 -0.5409192 0.8149233 0.208102 -0.4494529 0.8905435 0.0701754 -0.6217918 0.7831679 -0.004794418 -0.5368353 0.8213236 -0.1929654 -0.407776 0.8900615 -0.2037382 -0.3441916 0.8355236 -0.4282903 -0.3426419 0.8364168 -0.4277893 -0.1723759 0.8320798 -0.5271905 -0.182904 0.8246961 -0.5351846 0.03288507 0.829373 -0.5577267 0.05716514 0.8539416 -0.5172196 0.2523097 0.781414 -0.5707295 0.3052363 0.8768815 -0.371362 0.4134958 0.8130286 -0.4098848 0.5124266 0.8276605 -0.2289038 0.4436348 0.8841547 -0.1464873 0.5185469 0.8536399 0.04907441 0.5325331 0.8446578 0.05442243 0.5528275 0.7905256 0.263536 0.3951821 0.8705786 0.2931281 0.4122461 0.7973752 0.4407334 0.2408974 0.8570678 0.4554155 0.2185187 0.7896679 0.5733011 0.05475968 0.8495394 0.5246754 0.06194931 0.8541674 0.5162948 -0.1389032 0.8683192 0.4761595 -0.1512646 0.8571298 0.4923897 -0.3387995 0.7899417 0.5110841 -0.3194564 0.8711517 0.3728839 -0.4143028 0.8788074 0.2367506 -0.4943877 0.8359808 0.238153 -0.4712445 0.8790121 0.07257115 -0.5598225 0.8279088 0.03414487 -0.5241728 0.8442107 -0.1120322 -0.5646371 0.811581 -0.1500716 -0.4672178 0.8280705 -0.3098497 -0.4547012 0.8349882 -0.3099057 -0.3054764 0.8533903 -0.422385 -0.3320914 0.8367113 -0.435465 -0.09941214 0.888779 -0.4474253 -0.04764139 0.796462 -0.602809 0.07587176 0.860001 -0.5046207 0.1508616 0.8129941 -0.5623891 0.255209 0.9014599 -0.3496263 0.4324863 0.78818 -0.4378677 0.5141976 0.8241649 -0.2373883 0.4781724 0.8581652 -0.1868247 0.5735924 0.8172685 -0.05535292 0.5156576 0.8563526 0.02752411 0.5632142 0.8220133 0.08416694 0.4667766 0.8469635 0.2545043 0.4706071 0.8433887 0.2592766 0.3837785 0.8001224 0.4609972 0.3067615 0.8446645 0.4386792 0.2408221 0.8281415 0.5061486 0.091955 0.8857696 0.454925 0.01612883 0.8243536 0.5658456 -0.08228933 0.9013883 0.4251208 -0.2909629 0.7854192 0.5463126 -0.3087569 0.8749806 0.3729318 -0.4560964 0.8176785 0.3512519 -0.4423117 0.8646488 0.2382073 -0.5921404 0.7832337 0.189512 -0.4422864 0.8968737 5.177e-4 -0.5737991 0.8074312 -0.1371477 -0.444994 0.8724777 -0.2018987 -0.5087637 0.7894594 -0.3433853 -0.3125581 0.8475349 -0.428943 -0.2910884 0.8596287 -0.4198883 -0.1596531 0.8292361 -0.5356103 -0.09199011 0.8765371 -0.4724622 0.08287167 0.8472048 -0.5247633 0.1123129 0.8907996 -0.4402974 0.3442741 0.8094898 -0.4756065 0.3279672 0.896619 -0.2975096 0.4945365 0.820016 -0.2881103 0.4839242 0.8578874 -0.1727623 0.5751205 0.8081567 -0.1269615 0.5025851 0.8639258 0.03225809 0.5741778 0.8143367 0.08470904 0.4611189 0.845438 0.2694517 0.5019326 0.8220556 0.2688652 0.326258 0.8353312 0.4424679 0.319254 0.8539426 0.4109246 0.240896 0.7988909 0.5511283 0.1323344 0.8561633 0.4994719 0.03042888 0.8083004 0.5879834 -0.05076467 0.8847024 0.4633839 -0.2712351 0.8293598 0.4884607 -0.274412 0.8486562 0.4521957 -0.438687 0.8131414 0.3825635 -0.4201069 0.8533256 0.3087812 -0.5654048 0.8050482 0.1794849 -0.5092604 0.8546549 0.1010892 -0.590285 0.8064767 -0.03404593 -0.4889881 0.8657777 -0.1063948 -0.5598523 0.7941446 -0.2364314 -0.3223278 0.899465 -0.2950723 -0.3478477 0.8153604 -0.4628062 -0.1959668 0.8648763 -0.4621538 -0.1855466 0.8074504 -0.5599969 0.03788745 0.8073609 -0.5888403 0.08735668 0.8634562 -0.496802 0.2508045 0.8043804 -0.5385808 0.2865814 0.8631615 -0.4157202 0.4491552 0.7830729 -0.430182 0.3741619 0.9104908 -0.176095 0.6004636 0.7906213 -0.11984 0.5050362 0.8613175 0.05541425 0.5444721 0.834826 0.0813378 0.5218967 0.8076526 0.274447 0.432977 0.8545305 0.2868948 0.3924555 0.8095921 0.4365084 0.2408859 0.8783228 0.4129445 0.2226369 0.7941051 0.5655353 -0.03672355 0.893607 0.4473455 -0.1069014 0.8064378 0.5815758 -0.2512405 0.8716093 0.4209222 -0.2499563 0.8446859 0.4733156 -0.3939661 0.8693029 0.2985019 -0.4022077 0.8558502 0.3251915 -0.4976803 0.8549389 0.1462671 -0.4979447 0.8547121 0.1466909 -0.5282242 0.8480017 -0.04327249 -0.586032 0.8100951 0.01767265 -0.5735426 0.8036983 -0.1584866 -0.4521546 0.8657164 -0.2146891 -0.4499083 0.803246 -0.3903571 -0.3344403 0.8714588 -0.3587611 -0.1737824 0.8762613 -0.4494059 -0.1701337 0.8318676 -0.5282527 0.02613151 0.8801351 -0.4740036 0.06808173 0.8403299 -0.5377832 0.2067686 0.8388636 -0.503542 0.2315158 0.8195404 -0.5241698 0.333524 0.8852228 -0.3242566 0.4334345 0.8346245 -0.3399069 0.4910617 0.8451088 -0.2113044 0.5343758 0.8191682 -0.2083415 0.4547775 0.8899682 0.03367841 0.5193955 0.8521119 0.06429547 0.4530964 0.8347511 0.3128808 0.4097742 0.8579925 0.3097323 0.3503004 0.8199226 0.4527876 0.2198531 0.88612 0.4079901 0.07011348 0.8248842 0.5609368 0.06963604 0.8253173 0.560359 -0.1146237 0.876827 0.4669431 -0.08669245 0.8423053 0.5319834 -0.2886353 0.8411538 0.4573292 -0.2903153 0.88384 0.3668023 -0.4423984 0.8598302 0.2549036 -0.4448578 0.8426662 0.3033404 -0.5727375 0.7886061 0.2237685 -0.515591 0.8559429 0.03908526 -0.5794805 0.8149771 -0.003845989 -0.4790375 0.8610712 -0.1705275 -0.5272591 0.8198708 -0.2231808 -0.2977212 0.8921821 -0.3396666 -0.3447708 0.8004305 -0.490351 -0.1141162 0.8522666 -0.5105087 -0.1104819 0.8415039 -0.5288336 0.07668465 0.8115528 -0.579225 0.1274604 0.8916737 -0.4343637 0.3529947 0.8248803 -0.441551 0.351446 0.8636347 -0.3614154 0.521316 0.783576 -0.3379919 0.4672662 0.8740395 -0.1331065 0.6057078 0.7900655 -0.09441697 0.5879017 0.8073474 0.05061304 0.3918505 0.906694 0.1560741 0.4604198 0.8573073 0.2302996 0.3539506 0.8333583 0.4245383 0.2822304 0.8680596 0.4084345 0.225659 0.8005415 0.555168 0.0769509 0.8649864 0.49586 0.03190445 0.8063976 0.5905126 -0.194577 0.8819425 0.4293218 -0.2091827 0.8715376 0.4434693 -0.3701752 0.8462634 0.3831561 -0.361405 0.8681576 0.3401309 -0.4672047 0.8569635 0.2175629 -0.4439334 0.877085 0.1834256 -0.4730296 0.8791403 0.05792695 -0.3898327 0.9207806 -0.01391172 -0.561277 0.8017626 -0.2052928 -0.3466118 0.9177699 -0.193801 -0.501909 0.6469439 -0.5740654 -0.08821797 0.9733517 -0.2116701 -0.9921702 0.002371668 0.1248714 -0.9190969 0.1440997 -0.3667373 -0.8424647 -0.3663821 -0.3949905 -0.6131278 0.3243969 -0.7203062 -0.575603 -0.2551744 -0.7768959 -0.224393 0.04794704 -0.9733186 -0.1876718 0.2257645 -0.9559339 0.1312319 -0.2556331 -0.9578256 0.2938565 0.5240129 -0.7994116 0.4506684 -0.4475647 -0.7723885 0.7753012 0.2273086 -0.5892698 0.7793089 0.1325531 -0.6124602 0.9629219 -0.03441232 -0.2675769 0.9661058 0.07923197 -0.2456865 0.9773946 -0.1431089 0.1556267 0.9794514 0.05127233 0.1950544 0.8510928 -0.01883023 0.5246778 0.8282655 0.1364066 0.543479 0.4716187 -0.1542479 0.868207 0.4709648 -0.1452689 0.8701087 0.0356099 0.2582781 0.9654141 0.00138992 -0.1040264 0.9945736 -0.4023409 -0.1015081 0.9098451 -0.4404451 0.173225 0.8809094 -0.7731549 -0.1227114 0.6222326 -0.7726074 0.3848647 0.5049328 -0.8480273 -0.48775 0.2072434 -0.9081249 0.4184628 0.01407247 -0.930653 -0.2802752 -0.2352251 -0.9103529 0.2146295 -0.3538245 -0.7852274 -0.1470594 -0.6014911 -0.6944604 0.2787197 -0.6633553 -0.4778439 -0.4434285 -0.7583116 -0.2661462 0.4349301 -0.8602338 -0.1179962 -0.2727873 -0.954811 0.1180669 0.380232 -0.9173244 0.2342643 -0.4586074 -0.8572045 0.582485 0.3357279 -0.7402689 0.6358901 -0.382311 -0.6704343 0.795897 0.4155755 -0.4402785 0.8648529 -0.4695132 -0.1777274 0.9243557 -0.3442404 -0.1645148 0.8445979 0.497262 0.1984567 0.7902243 -0.4929766 0.3640328 0.745727 0.3378157 0.5742577 0.5706847 -0.3661571 0.7350157 0.4165003 0.3477057 0.8400168 0.2623725 -0.2239822 0.9386122 0.08841568 0.2640767 0.9604407 -0.07992506 -0.3098084 0.9474338 -0.2750182 0.2688778 0.9230763 -0.40811 -0.3047378 0.8605703 -0.6045584 0.4162503 0.6791502 -0.7114874 -0.3155334 0.6278729 -0.9054579 0.2054244 0.371412 -0.9260079 -0.2076116 0.3152888 -0.9724453 0.2328709 -0.01102042 -0.982191 -0.1774437 -0.06176161 -0.8450086 0.2583369 -0.4682121 -0.8543401 -0.1224681 -0.5050787 -0.5522235 -0.1841846 -0.8130962 -0.3399308 0.5733516 -0.745463 -0.2019097 -0.4034919 -0.8924275 0.1829221 0.225117 -0.9570068 0.1261065 -0.1709087 -0.9771834 0.5054308 0.3434478 -0.7915703 0.5715252 -0.3470243 -0.7435948 0.8294773 0.2075146 -0.5185607 0.8593363 -0.2114796 -0.4656366 0.9552052 0.2695669 -0.1221339 0.9945356 0.0146839 -0.10336 0.9021134 -0.2849215 0.3240541 0.8431816 0.3449792 0.4123522 0.6517651 -0.2369158 0.7204675 0.4979891 0.4305176 0.7527692 0.2938423 -0.4465605 0.8451275 -0.009340047 0.5099627 0.8601459 -0.08711361 -0.1786084 0.9800564 -0.4613494 -0.1676095 0.8712428 -0.4948608 0.5813735 0.6458466 -0.6732795 -0.4911464 0.5526935 -0.8867365 0.3919652 0.2450749 -0.9405473 0.1494969 0.3049944 -0.9921778 -0.08772796 -0.08880871 -0.9943689 -0.006548583 -0.1057717 -0.8776437 -0.03842049 -0.4777713 -0.8808266 0.03073602 -0.4724402 -0.6069477 0.007617056 -0.7947053 -0.5851498 0.116635 -0.8024936 -0.2958194 -0.2011705 -0.9338208 -0.2407452 0.08229124 -0.9670936 0.1488347 0.004108309 -0.9888536 0.1299238 0.2252753 -0.9655936 0.5116111 -0.3953143 -0.7628766 0.6055569 0.4495121 -0.6566885 0.8632507 -0.3172765 -0.3925991 0.8573535 0.4632163 -0.2244455 0.8435891 -0.5365927 0.02063202 0.8385443 0.4812747 0.2553786 0.7999388 -0.2918893 0.5243077 0.7446415 0.2385174 0.6233928 0.4722051 -0.378436 0.796121 0.3635331 0.2836751 0.88734 0.03002697 -0.2145606 0.9762491 0.02995502 -0.2141391 0.9763438 -0.3429584 0.4257943 0.8373046 -0.4182815 -0.5568535 0.7176035 -0.7045355 0.4186637 0.5730187 -0.824417 -0.2517036 0.5069339 -0.909623 0.3349595 0.2457401 -0.905178 -0.4002388 0.1430445 -0.9303861 0.282691 -0.2333831 -0.930971 -0.2144706 -0.295458 -0.7643237 0.3028713 -0.5692789 -0.6393088 -0.4458271 -0.6265162 -0.4775604 0.3438279 -0.8085287 -0.2868351 -0.2802403 -0.9160738 -0.1754211 0.2142193 -0.9609045 0.1013644 -0.1466802 -0.9839767 0.2013933 0.2784264 -0.9391057 0.3959271 -0.4434304 -0.8041214 0.5935021 0.4350294 -0.6771298 0.7517141 -0.2728338 -0.6004062 0.8433307 0.3802493 -0.3797419 0.8529114 -0.4587385 -0.2492015 0.9355552 0.3360989 0.1085087 0.9202126 -0.3429962 0.18858 0.8021914 0.3906702 0.4515151 0.6865886 -0.3802349 0.6196916 0.6429302 0.1302946 0.7547609 0.4162634 -0.1312768 0.8997174 0.3137022 0.277267 0.9081377 0.04610514 -0.3036754 0.9516595 -0.09863728 0.3339604 0.937412 -0.3632243 -0.3427894 0.8663508 -0.5021981 0.3148015 0.8054174 -0.699478 -0.2000534 0.6860826 -0.7777191 0.2313113 0.5845067 -0.8730506 -0.2990742 0.3851459 -0.9331685 0.2578611 0.2504079 -0.9337347 -0.357864 -0.008545279 -0.8956768 0.4151893 -0.1593146 -0.8106493 -0.2863128 -0.510757 -0.8126192 0.01777666 -0.5825239 -0.5621198 -0.03194987 -0.8264386 -0.5347948 0.105933 -0.8383154 -0.2022108 -0.0285812 -0.9789249 -0.2110753 -0.08004188 -0.9741871 0.2084041 0.07681918 -0.9750213 0.2323989 -0.156859 -0.9598886 0.5658406 0.2510643 -0.7853607 0.5946044 0.09130871 -0.7988169 0.7677637 -0.3947566 -0.5046842 0.8532506 0.3797007 -0.3574786 0.9295052 -0.3512373 -0.1124836 0.9558017 0.2936871 0.01382499 0.8928242 -0.1466774 0.4258528 0.893646 -0.1417667 0.4257922 0.6329054 0.1311482 0.7630406 0.6280439 0.2263352 0.7445356 0.2737709 -0.3810059 0.8831104 0.1046062 0.4762414 0.8730704 -0.1852737 -0.4557031 0.8706368 -0.3528257 0.359879 0.8637136 -0.6780635 -0.1989052 0.7075781 -0.6813985 -0.02650493 0.7314326 -0.9016448 -0.1266012 0.4135321 -0.9182677 0.1695541 0.3578209 -0.9996325 0.02352499 0.01347196 -0.9894988 -0.1444631 -0.004748404 -0.9339672 0.0916472 -0.3454073 -0.9016119 -0.2059832 -0.3803511 -0.7338516 0.2247357 -0.6410582 -0.7176879 -0.08671152 -0.6909453 -0.4650527 0.09600472 -0.8800621 -0.3798655 -0.3710625 -0.8473576 -0.053541 0.4994791 -0.86467 0.1169639 -0.5157314 -0.8487288 0.3581307 0.4107404 -0.8384716 0.5438116 -0.4208887 -0.7260314 0.7071241 0.259356 -0.657807 0.8896542 -0.1740524 -0.4221627 0.9166792 0.175939 -0.3588103 0.9807664 -0.1951485 0.003788113 0.9033383 0.4100626 0.1258121 0.7797986 -0.5333386 0.3278173 0.6175187 0.5714191 0.5405099 0.4792499 -0.4921646 0.7267006 0.4413323 0.05859011 0.895429 0.07952845 0.0890907 0.9928435 0.008403241 -0.4488595 0.8935628 -0.2444202 0.4154952 0.8761407 -0.5483122 -0.3441814 0.7621634 -0.5648883 -0.1120949 0.8175182 -0.8377993 0.1158967 0.5335357 -0.8539789 -0.1046108 0.509683 -0.9570259 0.2372698 0.1667473 -0.8881646 -0.4517793 0.08401924 -0.8568443 0.4193462 -0.2999446 -0.8617072 -0.3018229 -0.4078773 -0.7293087 0.2593716 -0.6331155 -0.5912779 -0.3970523 -0.7019544 -0.4446685 0.3086092 -0.8408509 -0.1688555 -0.2849971 -0.9435383 -0.0979194 0.1578723 -0.9825926 0.4245354 -0.2011624 -0.8827817 0.3611454 -0.4288397 -0.8280522 0.6605615 0.5209337 -0.5406355 0.7586862 -0.4865255 -0.4332301 0.892451 0.4243221 -0.1532388 0.9600318 -0.2679358 -0.0809291 0.9237768 0.148739 0.3528643 0.8420698 0.3938445 0.3685175 0.685227 -0.4197121 0.5952359 0.534967 0.3335263 0.7762542 0.4207212 -0.3333492 0.843725 0.1740309 0.4523613 0.8746899 -0.06766349 -0.4698858 0.8801301 -0.2321062 0.3147588 0.9203552 -0.5430657 -0.3343218 0.7702654 -0.6444181 0.251442 0.7221511 -0.8958235 -0.09444725 0.4342581 -0.8958198 0.01160609 0.444266 -0.9734741 -0.1983641 0.1140171 -0.9491966 0.3146249 -0.006082177 -0.9507877 -0.1998631 -0.2367643 -0.9053032 0.231113 -0.3563888 -0.7779388 -0.3126954 -0.5450074 -0.7025794 0.2557186 -0.664071 -0.4470581 -0.3318296 -0.8306795 -0.3596997 0.2707439 -0.8929244 0.06933188 -0.01306825 -0.9975081 0.08846038 -0.2669742 -0.9596351 0.4311803 0.2044449 -0.878798 0.4897374 -0.1956229 -0.8496405 0.6994625 0.304553 -0.646529 0.7305125 -0.4485323 -0.5149468 0.8832966 0.3601982 -0.3000739 0.9477676 -0.2893673 -0.1341758 0.9022835 0.4246757 0.07439827 0.8361251 -0.4973514 0.2313795 0.7390922 0.4120436 0.5328817 0.6977225 -0.3055454 0.6479394 0.4743647 0.359338 0.8036507 0.3938409 -0.273192 0.877642 0.09241902 0.1390296 0.9859663 0.03554624 -0.274633 0.960892 -0.2706264 0.365419 0.8906348 -0.4101617 -0.4673835 0.7831475 -0.5825716 0.4045739 0.7049329 -0.7803608 -0.4455296 0.4387944 -0.8854104 0.331568 0.3257471 -0.9841535 -0.1692613 0.052845 -0.9798782 0.1954712 -0.0403707 -0.9063048 -0.2991968 -0.2984845 -0.8879164 0.199095 -0.4146877 -0.7446663 -0.09418964 -0.6607575 -0.6899586 0.1800967 -0.7010865 -0.487706 -0.1689308 -0.8565076 -0.3610557 0.2993597 -0.8831889 -0.1474088 -0.4035355 -0.9030115 0.11461 0.4494097 -0.8859434 0.222779 -0.2423617 -0.9442618 0.5460022 0.2017379 -0.8131319 0.5637466 -0.4865015 -0.6674624 0.7405 0.4388957 -0.5089503 0.9126022 -0.3103311 -0.2661802 0.951342 0.2699429 -0.1485912 0.946859 -0.3056423 0.1002047 0.9319797 0.2545666 0.2580887 0.8345754 -0.2924137 0.4668812 0.6960137 0.44165 0.5661362 0.4802166 -0.4748188 0.7375223 0.2775261 0.4626836 0.8419639 0.1600199 -0.3296134 0.9304562 -0.1646909 0.3651198 0.9162775 -0.2592687 -0.2524229 0.9322353 -0.5394253 0.2058501 0.816484 -0.5657276 -0.4411325 0.6966739 -0.7041749 0.6094133 0.3643532 -0.7031324 -0.6820043 0.2011844 -0.8543812 0.515389 -0.06638479 -0.8791242 -0.3433457 -0.3305367 -0.826529 0.3269966 -0.4581735 -0.6251283 -0.4291967 -0.651924 -0.4202503 0.4480412 -0.789081 -0.3728337 -0.203858 -0.9052276 0.04630279 0.1782251 -0.9828997 0.03019744 0.06877571 -0.997175 0.5615149 -0.07006418 -0.8244951 0.5613723 -0.1171404 -0.819231 0.8753936 0.2302662 -0.4250453 0.897473 -0.204279 -0.3909121 0.9978857 0.05008858 -0.04141515 0.9563755 -0.2919703 0.009965717 0.841694 0.456869 0.2877882 0.7565709 -0.476845 0.4474588 0.6652169 0.3637918 0.6520292 0.5077027 -0.3525474 0.7860969 0.3387406 0.331757 0.88045 0.1803938 -0.2252675 0.9574512 0.005215942 0.2617616 0.9651185 -0.1749906 -0.3640407 0.9147965 -0.3509977 0.3100457 0.8835567 -0.5627097 -0.2504146 0.7878136 -0.6714724 0.3588521 0.6483441 -0.7857623 -0.2763879 0.5533421 -0.9155049 0.2394902 0.3232575 -0.932583 -0.2752367 0.2335248 -0.9651999 0.2594734 -0.03260231 -0.9679999 -0.2157131 -0.1282344 -0.8691586 0.3221483 -0.3752117 -0.8261892 -0.3145875 -0.4673822 -0.6579006 0.1376121 -0.7404255 -0.6417012 -0.06455171 -0.7642335 -0.2987791 0.2116619 -0.9305537 -0.2950125 0.1007378 -0.9501682 0.05090504 -0.3958351 -0.9169097 0.2206914 0.3817505 -0.897531 0.4654258 -0.3678826 -0.8050102 0.58429 0.2627293 -0.7678402 0.8861474 -0.01244533 -0.4632365 0.8637577 -0.2674633 -0.4270668 0.974386 0.2048216 -0.09284472 0.9802243 -0.1959634 -0.0275492 0.9170113 0.3047618 0.2573146 0.8212611 -0.4484906 0.3526845 0.7182033 0.3602609 0.5953119 0.6104958 -0.2893887 0.7372578 0.4091917 0.4245533 0.8076614 0.2754866 -0.4010997 0.8736282 -0.1091578 0.2315988 0.9666678 -0.08692026 0.0643478 0.9941349 -0.5656171 0.09260231 0.8194524 -0.5735846 0.007479071 0.8191122 -0.8269994 -0.1676401 0.5366274 -0.8551881 -0.004361808 0.5182994 -0.9553409 0.2416723 0.1700534 -0.9579428 -0.2685357 0.1011644 -0.9597876 0.224662 -0.1683302 -0.8478785 -0.4445462 -0.2889302 -0.7636334 0.4279692 -0.4834322 -0.6113401 -0.3037804 -0.7307399 -0.5263391 0.2483385 -0.8132007 -0.2681974 -0.2868226 -0.9196755 -0.1036314 0.3684119 -0.9238686 0.1188675 -0.5106956 -0.8515049 0.3328821 0.5433796 -0.7706674 0.6146956 -0.3775881 -0.6925147 0.7253746 0.01133871 -0.6882609 0.9139951 -0.01138824 -0.4055655 0.9159007 0.1663829 -0.3652983 0.9836207 -0.1793479 -0.0180217 0.9998627 0.003261923 0.01624709 0.9140064 0.1231138 0.3865687 0.8739967 -0.2438362 0.4203256 0.6689657 0.3187441 0.6714813 0.6403704 -0.2101829 0.7387483 0.3239945 -0.005012452 0.9460457 0.3048198 0.09340584 0.9478186 -0.02154022 -0.1043375 0.9943087 -0.1111778 0.3435248 0.9325397 -0.4049162 -0.3894736 0.8272565 -0.5582078 0.3271335 0.762488 -0.7141959 -0.3114558 0.626833 -0.8099851 0.3489931 0.4713047 -0.9337427 -0.2376958 0.2676291 -0.9510731 0.2773545 0.1361414 -0.8785734 -0.4666955 -0.1015098 -0.8395913 0.4497649 -0.3046279 -0.7800199 -0.231956 -0.5811758 -0.7501148 0.1004924 -0.6536278 -0.4530965 -0.246268 -0.8567705 -0.4472018 -0.1496121 -0.8818315 -0.06643593 0.4490344 -0.8910412 0.06983059 -0.4198566 -0.9049001 0.3068197 0.3322861 -0.8918788 0.4357602 -0.4407878 -0.7847416 0.6549461 0.4323826 -0.6197507 0.7582824 -0.4496697 -0.4720224 0.8466539 0.4444552 -0.2926378 0.858537 -0.5127215 0.005579829 0.9042779 0.3836611 0.1873115 0.855583 -0.2141898 0.4712753 0.8267008 0.126029 0.5483454 0.5656005 -0.2096942 0.7975741 0.5620959 -0.3395808 0.754144 0.1925892 0.5094568 0.8386675 0.03002661 -0.5219972 0.8524186 -0.2072013 0.3636305 0.9082073 -0.4039184 -0.3525789 0.8441197 -0.5725827 0.3316906 0.7497537 -0.7213062 -0.2252084 0.6549799 -0.8194573 0.2616584 0.5099263 -0.8791547 -0.3276108 0.3460612 -0.9430818 0.2882211 0.1659081 -0.9599243 -0.2802592 -2.87683e-4 -0.8932507 0.3813817 -0.2380154 -0.9141873 -0.2201385 -0.3402951 -0.7527588 0.1019566 -0.6503531 -0.7352553 -0.1100354 -0.6687989 -0.4606702 0.1049351 -0.8813465 -0.4352886 -0.1055079 -0.8940872 -0.1080623 0.241883 -0.9642693 -0.03976017 -0.2700555 -0.9620236 0.2921844 0.1029901 -0.9508004 0.3151324 -0.06493204 -0.9468239 0.6361398 0.212129 -0.7418406 0.6552499 0.09992021 -0.7487747 0.8079096 -0.395595 -0.4367914 0.8802504 0.3815715 -0.2820681 0.9296211 -0.3676767 -0.02486896 0.9727135 0.2149674 0.08727842 0.8689537 0.1190712 0.4803559 0.7915989 -0.363094 0.4914611 0.6132522 0.2570437 0.7468938 0.5413892 -0.2169423 0.8123016 0.2915822 0.3264853 0.8991035 0.1928657 -0.3166264 0.9287361 -0.121705 0.1422142 0.9823254 -0.1567733 -0.1105807 0.9814246 -0.4624495 0.2548721 0.8492236 -0.5280116 -0.2284292 0.8179389 -0.7474452 0.2053935 0.6317746 -0.7678601 -0.3486924 0.5374053 -0.9011061 0.3501947 0.2556786 -0.9501249 -0.2706959 0.1548761 -0.959048 0.2713528 -0.08120661 -0.8918819 -0.3910556 -0.2272054 -0.8618321 0.2897319 -0.4162943 -0.7102639 -0.2316891 -0.6647146 -0.67297 0.1429265 -0.7257296 -0.2893779 -0.1409041 -0.9467875 -0.3046522 -0.2997407 -0.9040701 0.03386539 0.3072369 -0.9510304 0.1560071 -0.4439705 -0.8823559 0.423519 0.4429399 -0.7902127 0.5561463 -0.4561794 -0.6946955 0.7515532 0.3077666 -0.5834788 0.8749482 -0.3437205 -0.3410599 0.9471405 -0.06692993 -0.3137599 0.9068215 0.4141215 0.07860141 0.7350101 -0.6528912 0.1830118 0.7008297 0.5390221 0.4672184 0.6011478 -0.3527588 0.7170653 0.535233 0.1624632 0.8289339 0.2307754 -0.2871455 0.9296722 0.1613675 0.1524109 0.9750546 -0.2984068 0.1503919 0.9425156 -0.3222247 -0.1981419 0.925695 -0.6647453 0.04867857 0.7454826 -0.6756101 -0.07152897 0.733781 -0.8857213 0.07885819 0.4574705 -0.8729177 0.269049 0.4069735 -0.9110044 -0.4037138 0.08417981 -0.930805 0.3573238 -0.07695335 -0.8781949 -0.3076696 -0.3662149 -0.8801195 0.118255 -0.4597886 -0.6579123 0.1568318 -0.7365835 -0.5089133 -0.5123632 -0.6917307 -0.2995478 0.4137005 -0.8597227 -0.009484648 -0.3478181 -0.9375141 0.09035527 0.3120393 -0.9457629 0.481038 -0.3962185 -0.7820571 -0.3447074 -0.8867193 -0.3080678 -0.2016561 -0.8192172 -0.5368596 -0.1264369 -0.9015156 -0.4138642 0.05365502 -0.7877435 -0.6136624 0.09326666 -0.9062864 -0.4122454 0.3892518 -0.7556049 -0.5268247 0.341529 -0.8845294 -0.3177513 0.4553897 -0.8437069 -0.2842167 0.4391817 -0.8852287 -0.1532632 0.5135569 -0.8488835 -0.1251256 0.4911372 -0.8688451 0.06239181 0.5014979 -0.8631021 0.05962055 0.4714248 -0.833431 0.2883602 0.4397395 -0.8656838 0.2392084 0.3856523 -0.8103889 0.4410692 0.2425875 -0.8961347 0.37161 0.1425761 -0.8337701 0.533385 0.06095647 -0.8914192 0.4490617 -0.06195366 -0.8236276 0.5637369 -0.161379 -0.8935644 0.4189266 -0.2435054 -0.8503412 0.466503 -0.3758029 -0.8630661 0.3374745 -0.3487446 -0.8933355 0.2834237 -0.5880433 -0.7884862 0.1802625 -0.4909501 -0.8693587 0.05642491 -0.5849202 -0.8101817 -0.03839492 -0.4948589 -0.8564628 -0.1469227 -0.5317357 -0.8170346 -0.2229611 -0.4002109 -0.8587279 -0.3200275 -0.4187784 -0.8171827 -0.3960269 -0.2750273 -0.8074792 -0.5218595 -0.1943683 -0.8627009 -0.4668708 -0.08663278 -0.8135051 -0.5750689 0.01415222 -0.8747635 -0.4843434 0.1414288 -0.7912407 -0.5949254 0.2905446 -0.8264184 -0.4823035 0.284739 -0.8548074 -0.4338525 0.4434181 -0.8148193 -0.3734303 0.4245452 -0.8572552 -0.2913334 0.5403237 -0.8151912 -0.2085993 0.4497981 -0.8860943 -0.1118866 0.5295501 -0.844619 0.07871097 0.5179703 -0.8524578 0.07087075 0.5198225 -0.8185017 0.2446213 0.4173257 -0.8705827 0.2606245 0.4131023 -0.7757452 0.477039 0.2624315 -0.8641604 0.4293678 0.192269 -0.8166573 0.5441539 0.08986359 -0.8681588 0.4880828 -0.03383713 -0.804681 0.5927426 -0.1012159 -0.8653379 0.4908621 -0.2624867 -0.799893 0.5396962 -0.293856 -0.8663796 0.4037761 -0.4335103 -0.7989463 0.4168376 -0.4536129 -0.8605055 0.2318744 -0.5323699 -0.8201785 0.209499 -0.5149991 -0.8564234 0.03626251 -0.5712466 -0.8207786 -2.86959e-5 -0.5748507 -0.806782 -0.1365632 -0.3972478 -0.9024545 -0.1666436 -0.4652069 -0.7705298 -0.4357365 -0.2447784 -0.8751945 -0.4172749 -0.2472681 -0.8735315 -0.4192864 -0.1043925 -0.7873313 -0.6076281 0.02638322 -0.8762703 -0.481097 0.1407099 -0.8069423 -0.5736244 0.2358324 -0.8585327 -0.4553074 0.3317242 -0.8059668 -0.4902822 0.4199171 -0.8521322 -0.3123145 0.4603767 -0.8314621 -0.3110046 0.4551534 -0.884382 -0.1034602 0.5780972 -0.813697 -0.06083512 0.5616945 -0.8161593 0.1355853 0.4464583 -0.8790672 0.1670805 0.4932164 -0.8141475 0.3064333 0.3483191 -0.8404269 0.4151583 0.3232082 -0.8563486 0.402745 0.1925494 -0.7845212 0.58945 0.04731959 -0.874563 0.4825978 -0.01130568 -0.8217162 0.5697849 -0.2021913 -0.8036206 0.5597434 -0.2330507 -0.8911443 0.389293 -0.3754428 -0.8162163 0.4391283 -0.5256742 -0.7872149 0.3224273 -0.4404971 -0.8778918 0.1877986 -0.577893 -0.8101454 0.09851026 -0.4556892 -0.8900884 -0.009489715 -0.5397589 -0.8188918 -0.1951328 -0.4669287 -0.8583255 -0.2127329 -0.4679917 -0.7936586 -0.3887029 -0.3294044 -0.8627564 -0.3835939 -0.3002287 -0.8145984 -0.4962785 -0.164325 -0.8533133 -0.494827 -0.1304305 -0.8200866 -0.5571767 0.04122883 -0.8491513 -0.5265381 0.02116346 -0.8666012 -0.4985526 0.2732793 -0.824135 -0.4961048 0.273828 -0.8880428 -0.3693217 0.4424633 -0.8093783 -0.3861777 0.5165243 -0.8265939 -0.2234843 0.4708659 -0.8648074 -0.1743373 0.6073529 -0.7935566 -0.0372892 0.4879677 -0.8674861 0.09672367 0.5261905 -0.8375893 0.1468599 0.3783173 -0.8883691 0.2601471 0.4325841 -0.7968779 0.4217307 0.2299107 -0.8670712 0.44196 0.2022509 -0.808924 0.5520296 0.04817998 -0.8505296 0.5237158 -0.003828823 -0.8089742 0.5878318 -0.1500759 -0.8556318 0.4953499 -0.2109674 -0.816222 0.5378425 -0.3797137 -0.8125964 0.4421591 -0.3605705 -0.862817 0.3543103 -0.5011261 -0.8132543 0.2957872 -0.4626564 -0.8694518 0.1732124 -0.5917361 -0.7989819 0.1071279 -0.5255113 -0.8453647 -0.09589892 -0.5418012 -0.8354545 -0.09201788 -0.5156627 -0.8272591 -0.2230122 -0.3991122 -0.8852224 -0.2389369 -0.3798599 -0.8254933 -0.4174534 -0.2736054 -0.8866828 -0.3727381 -0.117614 -0.8110932 -0.5729703 -0.1346709 -0.8538269 -0.5028355 0.06259572 -0.8599026 -0.5066057 0.13601 -0.8033047 -0.5798302 0.2912263 -0.8092309 -0.5102278 0.2912226 -0.86681 -0.4047589 0.4344506 -0.8157228 -0.381902 0.4276884 -0.8700994 -0.2449691 0.5491114 -0.807177 -0.2166606 0.5381077 -0.8427062 0.01692479 0.5363641 -0.8438031 0.01760619 0.5396053 -0.815572 0.2089703 0.478406 -0.8517653 0.2135971 0.3750963 -0.8461175 0.3786661 0.3789448 -0.834576 0.3998547 0.1951957 -0.8809792 0.4310153 0.1782064 -0.8443394 0.5053054 -0.001307487 -0.880953 0.4732021 -0.06861448 -0.8180661 0.5710166 -0.2031377 -0.8061901 0.555691 -0.2283644 -0.8641493 0.4484371 -0.3633321 -0.8166836 0.44835 -0.3687444 -0.8681723 0.3321211 -0.522876 -0.8047939 0.280905 -0.4713109 -0.8652498 0.1709068 -0.5972443 -0.7999323 0.05837571 -0.4978386 -0.866396 -0.03892034 -0.5868723 -0.7940108 -0.1585176 -0.3812661 -0.8967889 -0.2245131 -0.4026296 -0.8154203 -0.4159076 -0.3119089 -0.8538379 -0.4167418 -0.2668409 -0.7981696 -0.5401122 -0.1461207 -0.855652 -0.496496 -0.0859999 -0.8149787 -0.5730739 0.08658492 -0.8520187 -0.5163016 0.07778328 -0.8361518 -0.5429551 0.270416 -0.8257357 -0.495011 0.2688685 -0.8536866 -0.4460148 0.4839695 -0.778408 -0.399818 0.443843 -0.8639908 -0.2377463 0.5425291 -0.8157805 -0.2004106 0.5191137 -0.8538906 -0.03730797 0.4945693 -0.8675147 -0.05309844 0.5104857 -0.8454954 0.1566592 0.4359774 -0.8840723 0.168345 0.4168722 -0.8367348 0.355095 0.3547675 -0.8614335 0.3634179 0.3559013 -0.798452 0.4856014 0.1414251 -0.8315068 0.5372108 0.1103984 -0.8578628 0.5018801 -0.01172548 -0.7995323 0.6005088 -0.1626522 -0.8628506 0.4785742 -0.1597803 -0.8442601 0.5115616 -0.3469306 -0.8313243 0.4342108 -0.3412148 -0.8492186 0.4029891 -0.505082 -0.817564 0.2765527 -0.4748029 -0.8496859 0.2293384 -0.571151 -0.8153085 0.09517771 -0.531935 -0.8455663 0.04541891 -0.5926691 -0.803466 -0.05644369 -0.4910119 -0.8598088 -0.14013 -0.517827 -0.8223562 -0.235766 -0.3752692 -0.8872436 -0.2682756 -0.3755216 -0.8243946 -0.4235059 -0.2477434 -0.8906607 -0.381244 -0.1092548 -0.8164336 -0.5670094 -0.08330464 -0.8437108 -0.5302947 0.1011481 -0.8153909 -0.570006 0.1429235 -0.8787263 -0.4554263 0.3270368 -0.8025161 -0.499014 0.3627024 -0.84303 -0.3971744 0.4204894 -0.8172117 -0.3941496 0.5298615 -0.8194644 -0.2184603 0.4717113 -0.8514302 -0.2292492 0.5412071 -0.8407857 -0.01320606 0.4610023 -0.8872708 0.01508289 0.5273573 -0.8143047 0.2424917 0.3666669 -0.8955994 0.2519073 0.3862698 -0.820229 0.4219242 0.2545356 -0.8679917 0.4263828 0.2096785 -0.8081853 0.5503376 0.07942521 -0.8547675 0.5128979 0.003263115 -0.798203 0.6023797 -0.09035617 -0.8564634 0.5082385 -0.2188822 -0.8001195 0.5584794 -0.268625 -0.864746 0.4243288 -0.368988 -0.8261775 0.4257685 -0.3681156 -0.8856226 0.2831317 -0.506042 -0.8270484 0.2447704 -0.4218693 -0.8988077 0.119042 -0.6299729 -0.7744376 -0.05814212 -0.4840396 -0.8668788 -0.1192761 -0.5169776 -0.8156722 -0.2596404 -0.411081 -0.8615467 -0.2979092 -0.4060195 -0.8068345 -0.4291463 -0.2780422 -0.8589547 -0.4299879 -0.2244874 -0.8015074 -0.5542485 -0.09035176 -0.8641556 -0.4950472 -0.100275 -0.8724479 -0.4783092 0.1451948 -0.8167119 -0.5584803 0.1691492 -0.8721016 -0.4591596 0.3472216 -0.8078646 -0.4762269 0.3547547 -0.8646742 -0.3556512 0.4701666 -0.8124811 -0.3446998 0.4141607 -0.9019398 -0.1223753 0.5948894 -0.8016819 -0.05841994 0.5459556 -0.8259584 0.140446 0.4661472 -0.8713284 0.1532762 0.5051507 -0.783589 0.3616784 0.313467 -0.8721395 0.3756479 0.2973971 -0.8037325 0.5153341 0.1358557 -0.8945592 0.4258018 0.01447504 -0.8191927 0.5733357 -0.06285274 -0.8971357 0.4372609 -0.2530098 -0.8049896 0.5366358 -0.2574314 -0.8991578 0.3538991 -0.4689304 -0.8162091 0.3375012 -0.442865 -0.85921 0.2561816 -0.594887 -0.7891573 0.1527752 -0.5060063 -0.8615911 0.04023283 -0.5972483 -0.7988281 -0.0718894 -0.4908801 -0.8588551 -0.146304 -0.5237862 -0.7989789 -0.2954331 -0.3963282 -0.8620972 -0.3157732 -0.3802459 -0.8122122 -0.4424075 -0.2093856 -0.893182 -0.3979744 -0.1688055 -0.8310117 -0.530023 -0.006490767 -0.8863849 -0.4629036 0.1042211 -0.7994464 -0.5916279 0.1856227 -0.8617292 -0.472194 0.2359922 -0.8424042 -0.4844202 0.3101077 -0.8832836 -0.3516297 0.4036411 -0.8391824 -0.3644815 0.428813 -0.8824238 -0.1935143 0.5303055 -0.8313705 -0.1661304 0.539135 -0.8422145 -0.002875864 0.5309932 -0.8473436 -0.007415175 0.5759365 -0.7849208 0.2284659 0.4461127 -0.8558548 0.2617177 0.459204 -0.8140046 0.3557081 0.3034585 -0.8541302 0.4223444 0.3027631 -0.8434402 0.4437829 0.1326835 -0.8206544 0.5558071 0.088808 -0.8545457 0.5117273 -0.07763171 -0.801863 0.5924435 -0.1107486 -0.847011 0.5199107 -0.2831256 -0.8080867 0.5165616 -0.284837 -0.8601865 0.4230216 -0.3531356 -0.8390706 0.4138308 -0.4630628 -0.8565124 0.2279461 -0.4539431 -0.8649616 0.213956 -0.5860202 -0.8039903 0.100897 -0.5373973 -0.8431033 0.01952123 -0.5911618 -0.8051418 -0.04769247 -0.4826145 -0.8575134 -0.1781973 -0.5227366 -0.8088998 -0.2691236 -0.3933304 -0.853996 -0.3405614 -0.3970382 -0.8206272 -0.4110131 -0.2350955 -0.8574018 -0.4578127 -0.2297146 -0.8408018 -0.4901871 0.01169818 -0.8749699 -0.4840362 0.03439456 -0.8502139 -0.5253127 0.2323193 -0.79298 -0.5632144 0.2271267 -0.8814958 -0.4139794 0.3836228 -0.8652994 -0.3226309 0.4400187 -0.8337608 -0.3335066 0.458217 -0.8812231 -0.1161172 0.567204 -0.8197558 -0.07924777 0.5161349 -0.8509517 0.09739607 0.5478646 -0.8255637 0.1352376 0.4237908 -0.8694003 0.2540562 0.4480385 -0.8417007 0.3013327 0.2720426 -0.8250232 0.4953074 0.2015467 -0.8680518 0.4537236 0.1325417 -0.8043977 0.5791177 -0.01869171 -0.8427958 0.5379089 -0.03886032 -0.876811 0.4792624 -0.2168472 -0.8494189 0.481108 -0.2208531 -0.8834376 0.4132336 -0.413572 -0.8264819 0.3819501 -0.3514351 -0.9045436 0.2414423 -0.6209158 -0.769123 0.1513718 -0.4940493 -0.8693262 0.01368933 -0.573427 -0.8152311 -0.08111637 -0.4648312 -0.8609767 -0.2065219 -0.4980667 -0.8268218 -0.2613335 -0.3776178 -0.807412 -0.453311 -0.278818 -0.8656336 -0.4158594 -0.2364602 -0.8106799 -0.5356163 -0.08732467 -0.8396739 -0.5360245 -0.02681976 -0.897079 -0.4410558 0.1221771 -0.821174 -0.557446 0.3082624 -0.8457544 -0.4355158 0.2221177 -0.8927052 -0.3920986 0.4769847 -0.7902871 -0.3846192 0.434609 -0.8622502 -0.2600761 0.5813843 -0.7931978 -0.1811896 0.4526131 -0.889788 -0.05847221 0.5197636 -0.8448712 0.126644 0.5045897 -0.8557243 0.1145652 0.5097978 -0.8129602 0.2814289 0.3800382 -0.8734382 0.3044286 0.3761826 -0.773194 0.5105468 0.221948 -0.8628575 0.4541102 0.1445989 -0.8166853 0.5586737 0.04734939 -0.8682299 0.4938976 -0.08532643 -0.8046926 0.5875281 -0.143335 -0.8652678 0.4803819 -0.3081077 -0.7999095 0.5149897 -0.3270949 -0.8645707 0.3814795 -0.4357407 -0.8162575 0.3792807 -0.5018801 -0.8286492 0.2479048 -0.4831629 -0.8484091 0.2162306 -0.5919865 -0.8026352 0.07299888 -0.5203287 -0.8535871 0.02544265 -0.526704 -0.8312849 -0.1776185 -0.5050247 -0.8492738 -0.1538967 -0.3462364 -0.8637339 -0.3661753 -0.3927743 -0.8363042 -0.3825227 -0.2408868 -0.8259592 -0.5096716 -0.1959712 -0.8587384 -0.4734596 -0.030393 -0.7857066 -0.6178524 0.07047837 -0.8704232 -0.4872334 0.1894239 -0.8066582 -0.5598403 0.2742116 -0.8585212 -0.4333006 0.3727096 -0.8060364 -0.459775 0.4453326 -0.8521925 -0.2746764 0.485727 -0.8314165 -0.2698446 0.4659604 -0.8805701 -0.08647084 0.5818325 -0.8131642 -0.01532405 0.497685 -0.8626226 0.09050947 0.5652171 -0.7992428 0.2043055 0.4244583 -0.85656 0.2934964 0.4411883 -0.8085923 0.3892707 0.273992 -0.857138 0.4361684 0.2708884 -0.8264657 0.4935321 -0.00976783 -0.8369919 0.5471281 -0.008984088 -0.8353266 0.5496805 -0.2097917 -0.8228446 0.5281231 -0.2186365 -0.8947166 0.3894617 -0.422856 -0.8197033 0.386367 -0.3753128 -0.8861782 0.2717142 -0.5100199 -0.8494482 0.1353424 -0.5525844 -0.8239651 0.1254274 -0.5427579 -0.8383336 -0.05109661 -0.5562371 -0.8285388 -0.06421643 -0.4645869 -0.8528956 -0.2381766 -0.4797275 -0.8361428 -0.2659449 -0.3778014 -0.8134337 -0.4422578 -0.3077506 -0.8650754 -0.3961493 -0.1014426 -0.8730571 -0.4769495 -0.0813499 -0.8338994 -0.5458883 0.1058709 -0.8029527 -0.586565 0.1312246 -0.8910643 -0.4344936 0.3546525 -0.8239759 -0.4419111 0.3472461 -0.8570421 -0.3806559 0.4992268 -0.8174428 -0.2873323 0.4691178 -0.8518977 -0.2328065 0.5736081 -0.8106797 -0.1173557 0.5200178 -0.8536664 -0.02890092 0.5727469 -0.8191546 0.03077143 0.5393732 -0.8141343 0.2150861 0.5152161 -0.8389369 0.1753214 0.4127186 -0.8307474 0.3735268 0.4043476 -0.847912 0.3428534 0.1999939 -0.8477959 0.4911667 0.2008073 -0.8505263 0.486088 -0.01918452 -0.8635223 0.5039458 -0.01189005 -0.8708958 0.4913239 -0.2669494 -0.8390389 0.47408 -0.2693971 -0.8542166 0.4446789 -0.4247273 -0.7955332 0.4321269 -0.4164592 -0.859936 0.2950792 -0.481545 -0.8338902 0.2697063 -0.4466373 -0.8879299 0.109981 -0.5344409 -0.8425485 0.06697064 -0.4787451 -0.8674873 -0.1351627 -0.4945353 -0.8595402 -0.1289402 -0.5265665 -0.8024708 -0.2806569 -0.4120574 -0.8588238 -0.3043526 -0.391697 -0.7961705 -0.461179 -0.2723293 -0.8432269 -0.4634709 -0.2778748 -0.8497158 -0.448072 -0.06533044 -0.847342 -0.5270139 -0.08500838 -0.871568 -0.4828487 0.108314 -0.8820813 -0.4584764 0.1864601 -0.8267964 -0.530698 0.2943344 -0.8915701 -0.3441949 0.4629714 -0.8013612 -0.3787849 0.4590843 -0.8629536 -0.2110749 0.5617206 -0.8069686 -0.1824057 0.5874889 -0.8092044 0.006726145 0.4870812 -0.8716933 0.05387693 0.54695 -0.8000481 0.2465137 0.4669786 -0.8451049 0.2602477 0.4318192 -0.818115 0.3797635 0.3241086 -0.8640963 0.3850861 0.2772341 -0.8073195 0.5209382 0.1616563 -0.8620958 0.4802688 0.09466785 -0.8028199 0.588658 -0.04765582 -0.9019711 0.4291589 -0.2340533 -0.799759 0.5528152 -0.2738761 -0.8597798 0.4310112 -0.4127652 -0.7988599 0.4375476 -0.4097082 -0.8589102 0.3072664 -0.5491935 -0.7988995 0.2452471 -0.4896776 -0.8621008 0.1303763 -0.6031637 -0.7973517 0.02058422 -0.4951183 -0.8649126 -0.08236533 -0.5512438 -0.8184079 -0.1622924 -0.3759028 -0.8862559 -0.2706431 -0.410609 -0.8091949 -0.420243 -0.2733318 -0.8559182 -0.438969 -0.2441381 -0.8078165 -0.5364974 -0.1015484 -0.862497 -0.495769 -0.0220828 -0.7993893 -0.6004075 0.1142619 -0.8563215 -0.5036445 0.1954821 -0.808876 -0.5545327 0.3029482 -0.8567625 -0.4173495 0.3287146 -0.8427172 -0.4263502 0.4726049 -0.8649436 -0.1688711 0.5340795 -0.8161661 -0.2205269 0.5370139 -0.8435477 0.006591558 0.5388683 -0.8423705 0.005738019 0.5236836 -0.8242343 0.2153908 0.481296 -0.8484406 0.2202333 0.4171775 -0.8153014 0.4015554 0.378013 -0.8375723 0.3944349 0.3358327 -0.8255579 0.4535091 0.1869879 -0.8880402 0.4200239 0.1389008 -0.8339374 0.5340929 -0.01675873 -0.8853721 0.464581 -0.09255146 -0.8310633 0.5484232 -0.2188912 -0.842548 0.4921377 -0.2711536 -0.8100954 0.5198283 -0.3101966 -0.8955988 0.3188745 -0.5364173 -0.7898442 0.2973263 -0.4748864 -0.8608821 0.1826606 -0.5718156 -0.8154639 0.08969688 -0.5065035 -0.8622355 0.00205928 -0.5876569 -0.7992151 -0.1261532 -0.490627 -0.8506466 -0.1889058 -0.4999652 -0.8306779 -0.2449675 -0.3361625 -0.8932495 -0.2984965 -0.3561351 -0.8091154 -0.4674401 -0.1744632 -0.8919878 -0.4170378 -0.06096816 -0.8051178 -0.589973 -0.02541929 -0.8427358 -0.537727 0.1223773 -0.8215813 -0.5568017 0.1663187 -0.8954506 -0.4129243 0.3815354 -0.7975322 -0.4673041 0.3715249 -0.8615444 -0.3459922 0.459737 -0.8342376 -0.3044495 0.4277712 -0.8855736 -0.1810283 0.5345621 -0.8364417 -0.1208671 0.452589 -0.8916771 -0.008671402 0.5462853 -0.8333898 0.08386743 0.4595671 -0.840852 0.2859478 0.4190933 -0.8819794 0.2155762 0.3836569 -0.8108708 0.4419227 0.3047764 -0.8663759 0.3956061 0.1188754 -0.8749797 0.4693391 0.09964162 -0.8376277 0.5370769 -0.1030048 -0.8183749 0.5653783 -0.1106227 -0.8650879 0.4892706 -0.303402 -0.8655235 0.398518 -0.3842554 -0.817925 0.42819 -0.4493821 -0.8552026 0.2582332 -0.4924748 -0.8320393 0.2553024 -0.5775708 -0.8155841 0.03513997 -0.5262009 -0.8503558 0.002797007 -0.5471466 -0.8355348 -0.05012053 -0.4381622 -0.8800371 -0.1831628 -0.4756362 -0.8416479 -0.2557322 -0.3418353 -0.8841692 -0.3184233 -0.344923 -0.8187872 -0.458929 -0.2140315 -0.8548016 -0.4727631 -0.182488 -0.8038907 -0.5660901 -0.006090283 -0.8580375 -0.5135511 0.004744708 -0.8478897 -0.5301516 0.2666162 -0.8563734 -0.4421996 0.2762259 -0.8030564 -0.528015 0.4740589 -0.7957234 -0.3769515 0.4546112 -0.8254974 -0.334489 0.5230855 -0.838162 -0.1544862 0.5323355 -0.8326932 -0.15245 0.5769406 -0.8118186 0.08994597 0.4280493 -0.898248 0.09962129 0.4622654 -0.7958894 0.390987 0.3837297 -0.8528156 0.3541993 0.3479778 -0.6634965 0.6623322 0.111445 -0.9223741 0.3698731 0.6084101 0.7520059 -0.253622 0.8526692 -0.4930272 -0.1728571 0.8975939 0.4399998 0.02693367 0.9725984 -0.1415107 0.1844644 0.9023346 0.3414357 0.2630856 0.8383756 -0.1805448 0.5143246 0.4251541 0.5841005 0.6914266 0.1886222 -0.5690388 0.8003853 0.03014373 0.6193114 0.7845667 -0.1160302 -0.5512321 0.8262447 -0.3207521 0.5346778 0.7818171 -0.4368849 -0.4817327 0.759648 -0.5995718 0.5939851 0.5363724 -0.7364189 -0.3212335 0.5953959 -0.9472283 -0.1383118 0.289186 0.9572004 0.1494687 -0.247844 0.9347376 0.3274504 0.1379926 0.4346371 -0.745222 0.5057024 -0.7336837 0.5829433 -0.349121 -0.6091907 -0.5487884 -0.5724668 0.8328167 -0.3018898 -0.4639818 0.990311 -0.09572958 -0.1005983 -0.9877039 0.141669 0.06611329 -0.9302734 -0.1360846 -0.340694 0.1809393 0.1281921 -0.975104 0.4464721 -0.4252086 -0.7873122 0.8133991 -0.5093185 0.2810276 0.6955653 0.5290917 0.4860565 0.5059327 -0.7047062 0.4974146 -0.6316401 0.6232131 -0.461125 -0.4812789 -0.6813948 -0.5514271 -0.328039 0.6577324 -0.6780697 -0.1616933 -0.5567306 -0.8148046 0.5061795 -0.6370612 0.5813221 0.2970278 0.6175776 0.7282668 0.2516934 -0.5395808 0.8034321 -0.08515012 0.3511992 0.9324209 -0.8516574 -0.4405075 -0.2839595 -0.6305826 0.4353579 -0.6425178 0.7345153 0.6728901 0.0877847 0.7615854 -0.5929797 0.2614629 0.6079982 0.6425036 0.4663984 -0.6124334 0.6615844 -0.4327026 -0.4734302 -0.6837301 -0.5553173 -0.2864772 0.7089706 -0.6444312 -0.1244271 -0.7449418 -0.6554233 0.8587833 0.4989756 0.1162534 0.7549019 -0.5394012 0.3730543 0.6287781 0.6119008 0.4798079 0.5316635 -0.6088736 0.5887332 -0.5839064 0.6599473 0.4727821 -0.6663656 -0.6802614 0.3052893 -0.701274 0.7062004 0.09744679 -0.663832 -0.7453183 -0.06186842 0.04510408 0.6078359 -0.7927808 0.1980291 -0.6330976 -0.7483128 0.8257465 0.3400459 -0.4500129 0.9671826 -0.2375015 -0.0902819 0.3830376 -0.5619587 0.7331336 0.1042327 0.5653166 0.8182621 0.002338647 -0.6460828 0.7632638 -0.2285412 0.543546 0.8076675 -0.3713071 -0.5634531 0.7380052 -0.5333244 0.3365246 0.7760905 -0.8127578 0.009312093 0.5825273 -0.5385821 0.2419557 -0.8070853 -0.2295059 -0.5377259 -0.8112818 -0.06359517 0.6335524 -0.7710819 0.1322925 -0.6610017 -0.7386308 0.4281569 0.7410973 -0.517162 0.6026457 -0.6114696 -0.5127604 0.7022251 0.6728655 -0.2326631 -0.5281501 0.8016647 0.2799844 -0.3262478 -0.3604617 -0.8738591 0.05448579 0.4101818 -0.9103748 0.3724258 -0.4963757 -0.7841622 0.660763 0.5098886 -0.550823 0.6404039 -0.6163647 -0.4582331 0.7795955 0.5698588 -0.259792 0.7488126 -0.6551601 -0.1002247 0.7853904 -0.1471705 0.6012511 0.4890258 0.1003167 0.8664816 -0.1837551 0.6242386 0.7593156 -0.367622 -0.5601454 0.7423552 -0.5378196 0.5708169 0.6204177 -0.6210639 -0.5674822 0.5405957 -0.7363755 0.5519458 0.391289 -0.7609779 -0.6222899 0.1834887 0.04615414 0.7067478 -0.7059586 0.201129 -0.5608528 -0.8031135 0.4303968 0.6205815 -0.6554672 0.9596041 -0.1860077 -0.211095 0.8243428 0.5360925 0.1818349 0.3661875 -0.7881389 0.4947161 -0.8064061 -0.5073233 -0.3038623 -0.6472738 0.3420199 -0.6812188 0.8700839 -0.3013801 -0.3900309 0.9946426 -0.1012036 -0.02107185 -0.01081734 -0.8284164 0.5600084 -0.3710494 0.7393067 0.5619146 -0.5421659 -0.691766 0.4769864 -0.7077364 0.6035362 0.367224 -0.8683432 -0.4561557 0.1946848 -0.5093101 -0.5507531 -0.6612673 -0.1325535 0.3689541 -0.919947 0.256661 -0.1585124 -0.9534144 0.6304402 0.1193787 -0.7670032 0.2609592 -0.630653 0.7308743 0.04200893 0.6118972 0.789821 -0.05427843 -0.6395091 0.7668651 -0.3367019 0.663139 0.6684897 -0.743109 0.6246194 0.2400827 -0.8251333 -0.5599961 0.07456314 -0.7275123 0.6695904 -0.1495816 -0.2516897 0.5225331 -0.8146235 -0.07392644 -0.5480691 -0.8331598 0.09784054 0.6309316 -0.7696444 0.2438269 -0.7144377 -0.6558409 0.4368262 0.6416755 -0.6304249 0.6770092 -0.4887672 -0.5502411 0.05798578 0.05272531 0.9969242 -0.3940032 0.07680761 0.9158942 -0.9222732 0.02430689 -0.385774 -0.6762794 -0.2385495 -0.6969507 0.6732332 0.3446213 -0.6542119 0.800176 -0.5309748 -0.2788982 0.3007251 0.5908693 0.7486241 0.1798036 -0.5906286 0.7866566 -0.1110873 0.6725279 0.731687 -0.3552216 -0.6871532 0.6337493 -0.6071057 0.5940794 0.5277237 -0.6498496 -0.6705073 0.3579323 -0.5055108 0.7448108 -0.4355637 -0.4072563 -0.7311481 -0.547325 -0.2290264 0.7093009 -0.6666628 -0.06713396 -0.7441939 -0.6645815 0.3017227 0.6587391 -0.6892216 0.4625031 -0.6846262 -0.563363 0.6838011 0.678464 -0.2685194 0.8281023 -0.5377604 -0.1583046 0.8143035 0.5761249 0.07064116 0.8535019 -0.494773 0.1635068 0.7407 0.5043352 0.4438576 0.5300105 -0.4961565 0.6876901 0.1426252 0.5829789 0.7998712 -0.1423491 -0.7182745 0.6810423 -0.4088388 0.5896893 0.6965038 -0.5067003 -0.6557344 0.5597028 -0.6803188 0.6762998 -0.2824625 -0.6841451 -0.613741 -0.3940401 -0.4930789 0.586419 -0.6426398 0.123046 0.1263979 -0.9843187 0.5194867 -0.135806 -0.8436174 0.6919676 -0.7112995 0.1234263 0.7507292 0.5653296 0.3417721 0.6634783 -0.4869391 0.5680554 0.04833823 0.2392496 0.9697541 -0.1626731 -0.3409184 0.9259115 -0.3613271 0.1319907 0.92305 -0.643859 0.1972784 0.7392745 -0.05366933 -0.9966033 0.06246137 -0.522156 -0.5729776 0.631704 -0.2616659 -0.851406 0.4545753 -0.1335251 -0.9564821 0.2594476 -0.4422357 -0.3410063 0.8295435 -0.2694343 -0.6818966 0.6800163 -0.4612753 -0.2174419 0.8602 -0.3156246 -0.5387662 0.7810969 -0.1094062 -0.8442058 0.5247351 -0.1279259 -0.7958578 0.5918155 -0.2064666 -0.3413143 0.916993 -0.2006249 -0.16189 0.9661994 -0.07520055 -0.6400122 0.764676 0.02788805 -0.9456927 0.3238635 0.02694636 -0.6347458 0.7722511 0.029895 -0.9490379 0.3137413 0.01804345 -0.1633979 0.9863952 0.04027742 -0.6065449 0.7940284 0.05902767 -0.2956137 0.9534823 0.1959925 -0.8620779 0.4673423 0.2502687 -0.574319 0.7794379 0.280955 -0.140128 0.9494359 0.2800569 -0.6647435 0.6925924 0.3377069 0.1181144 0.933811 0.1940577 -0.934152 0.2995024 0.2907294 -0.8906574 0.3495795 0.4929879 -0.4220078 0.7608366 0.5045607 -0.6075345 0.6134496 0.5101938 -0.4212374 0.7498409 0.3644227 -0.8797678 0.3052948 0.6960807 0.04515486 0.7165422 0.4990112 -0.7836659 0.3699399 0.6142151 -0.6067638 0.5045568 0.7282987 -0.414476 0.545702 0.1309868 -0.9896538 0.05854713 0.5805113 -0.7606009 0.2906768 0.8648891 -0.3397591 0.3695008 0.8054725 -0.440521 0.3964285 0.3697165 -0.9229716 0.1069259 0.8817948 -0.386618 0.2701196 0.5654841 -0.822781 0.05708968 0.9802612 -0.09120768 0.1754117 0.7209661 -0.688768 0.07620048 0.9040451 -0.4274009 0.005585253 0.4511651 -0.8903605 -0.06089621 0.9213711 -0.3722985 -0.1116653 0.6453215 -0.7444503 -0.17133 0.1401664 -0.9888966 -0.04936611 0.7464922 -0.6378041 -0.1896192 0.2785933 -0.948819 -0.1487566 0.9553257 0.1820757 -0.2328117 0.5318972 -0.8136404 -0.2346807 0.846446 -0.3576124 -0.3945158 0.8282345 -0.4057921 -0.386472 0.6799592 -0.5996475 -0.4219932 0.3199847 -0.9027932 -0.2873575 0.6543233 -0.5966209 -0.4646553 0.6741256 -0.4267251 -0.6028769 0.7975004 -0.107857 -0.5935992 0.2693616 -0.9150699 -0.3001521 0.2888601 -0.8869503 -0.3603874 0.6312975 -0.4371001 -0.6406302 0.4819153 -0.6279605 -0.6110838 0.4207238 -0.5579547 -0.7153168 0.5460098 0.1200873 -0.8291276 0.1853038 -0.8989098 -0.3970187 0.06620293 -0.9637587 -0.2584306 0.4850391 -0.1530528 -0.8609947 0.3046972 -0.6563005 -0.6902386 0.2450799 -0.5012054 -0.829897 0.2557381 -0.3558316 -0.8988782 0.01896619 -0.7803973 -0.6249963 0.1169175 0.06432181 -0.9910566 -0.02265465 -0.7365202 -0.6760362 -0.03099763 -0.5601682 -0.8277987 0.03515833 -0.1638552 -0.9858577 -0.111738 -0.7882413 -0.6051368 -0.2469657 -0.6722813 -0.6978868 -0.1792321 -0.2306002 -0.9563992 -0.1015725 -0.9640839 -0.2454082 -0.2653458 -0.1480639 -0.9527165 -0.3405944 -0.3869836 -0.8568777 -0.2720725 -0.8430221 -0.4639942 -0.4826396 -0.3018807 -0.8221479 -0.5311824 -0.1690661 -0.8302181 -0.4043171 -0.7607272 -0.5077616 -0.4245297 -0.7659843 -0.4827449 -0.1833194 -0.9745434 -0.1290713 -0.5971755 -0.62326 -0.5049044 -0.6474195 -0.5480495 -0.5296128 -0.7163956 -0.2912918 -0.6339768 -0.429031 -0.8759531 -0.2205421 -0.7924546 0.1495156 -0.5913214 -0.8375496 -0.3695001 -0.4024681 -0.8488025 -0.3421671 -0.4030585 -0.6012792 -0.7739518 -0.1986504 -0.9478954 -0.0961194 -0.3037361 -0.6215603 -0.7727561 -0.128495 -0.6002163 -0.788222 -0.1358184 -0.8841926 -0.454746 -0.1068158 -0.1571916 -0.9875565 0.004785656 -0.9178592 -0.3947927 -0.04090654 -0.498825 -0.8616744 0.09322619 -0.9770641 -0.2127031 0.0101521 -0.5375734 -0.8355264 0.1136248 -0.7830691 -0.6115671 0.1130872 -0.9898361 -0.04608273 0.1345399 -0.5523571 -0.8099306 0.1972663 -0.9338273 -0.2868332 0.21376 -0.6398723 -0.7101036 0.2937965 -0.8974725 -0.2799869 0.340809 -0.622886 -0.6702888 0.4033932 -0.2103066 -0.9632741 0.166956 -0.8916093 -0.04999727 0.450037 -0.6882292 -0.5446151 0.4793069 -0.8599154 -0.1518322 0.4873321 -0.373448 -0.8677466 0.3279522 -0.4093309 -0.7627759 0.5006208 -0.6662611 -0.3769411 0.6434373 -0.6992153 -0.2457314 0.6713525 0.001229822 -0.9999834 -0.005643606 4.54005e-4 -0.9999979 0.001995623 -0.001014471 -0.9999994 -5.41749e-4 -7.82224e-4 -0.9999961 -0.002693116 -0.003696918 -0.9999907 0.002263247 -6.09703e-4 -0.999993 -0.003712177 -4.36277e-4 -0.9999997 -7.01086e-4 0.003265082 -0.9999865 0.004055619 0.5862972 -0.6008186 -0.54339 0.4688053 -0.7709084 -0.4311869 0.6279667 -0.540791 -0.5596454 0.7668554 -0.4004586 -0.5015635 0.7586902 -0.4788834 -0.4416558 0.3429602 -0.9161209 -0.2076076 0.8787508 -0.2917657 -0.3777167 0.5395576 -0.8001853 -0.2618803 0.7998861 -0.5307071 -0.2802361 0.6193249 -0.7506269 -0.2302083 0.910686 -0.3629913 -0.1972018 0.8615687 -0.49325 -0.1200167 0.5181632 -0.8482573 -0.1093924 0.7289814 -0.6794755 -0.08306193 0.08615517 -0.9962798 -0.001974284 0.7792246 -0.6205364 0.08799707 0.6805022 -0.73177 0.03780615 0.7855454 -0.6022917 0.1419978 0.2771279 -0.9600203 0.0395134 0.6978491 -0.6924329 0.1831484 0.4548526 -0.8800768 0.1362863 0.8206909 -0.4581286 0.3414452 0.6933071 -0.6030085 0.394596 0.3792234 -0.9072135 0.1820814 0.622194 -0.6960052 0.3584013 0.7730239 -0.3519917 0.527765 0.1526591 -0.983263 0.0994451 0.6201279 -0.47224 0.626443 0.3497641 -0.873748 0.3379787 0.3797889 -0.8486354 0.3682097 0.5180302 -0.6401433 0.5673281 0.4719496 -0.7110428 0.5212308 0.469016 -0.3280699 0.8199964 0.3854528 -0.546315 0.7436169 0.3183465 -0.7769783 0.5431026 0.06989359 -0.9889859 0.1304681 0.1707628 -0.918364 0.3569983 0.2067701 -0.6224003 0.7548934 0.2126712 -0.6345258 0.7430667 0.2384956 -0.6176 0.7494599 0.06031847 -0.3688749 0.9275199 0.05825996 -0.8256084 0.5612279 0.03872644 -0.4616593 0.8862116 0.0494917 -0.8083891 0.5865644 -0.115284 -0.5009046 0.8577904 -0.0634967 -0.8074942 0.5864481 -0.1279573 -0.604101 0.786568 -0.198962 -0.6236841 0.7559315 -0.3251681 -0.2765884 0.9043034 -0.06966656 -0.9653183 0.251609 -0.3898169 -0.4058645 0.8266298 -0.212355 -0.8172734 0.5356954 -0.2666785 -0.7724534 0.5763666 -0.4744954 -0.2567131 0.8419932 -0.5305721 -0.4282798 0.7314846 -0.6019331 -0.3335538 0.725547 -0.3260831 -0.8005669 0.5027551 -0.6110593 -0.4990329 0.6144696 -0.2778424 -0.8975703 0.342303 -0.4303858 -0.8025467 0.4131427 -0.7486491 -0.3346104 0.572329 -0.4710303 -0.812348 0.3438333 -0.6613819 -0.6165934 0.4270674 -0.7487416 -0.5550361 0.3623822 -0.6985359 -0.669788 0.2518567 -0.1848093 -0.9788702 0.08751368 -0.8049414 -0.5442123 0.2364369 -0.5046764 -0.8467534 0.168257 -0.854779 -0.5041964 0.1230403 -0.02791076 -0.9995819 0.007564067 -0.7743431 -0.6296373 0.06284731 -0.5339947 -0.844437 0.04214155 -0.8785253 -0.47595 -0.04080635 -0.3910351 -0.9203675 0.003892898 -0.7862108 -0.6067538 -0.1171426 -0.5725588 -0.8153658 -0.08576202 -0.8828389 -0.4227486 -0.2046444 -0.7919021 -0.5076925 -0.339322 -0.378015 -0.9163465 -0.1319621 -0.6924045 -0.6411198 -0.3309706 -0.6551276 -0.6557182 -0.3752886 -0.0998575 -0.9936321 -0.05219072 -0.3445168 -0.902547 -0.2582964 -0.7185866 -0.4430216 -0.5360645 -0.6570472 -0.5038942 -0.5606958 -0.6545969 -0.3479698 -0.6711334 -0.4291163 -0.7972123 -0.4246314 -0.447718 -0.6631984 -0.5997636 -0.3724031 -0.8088929 -0.4549816 -0.4507994 -0.5725173 -0.6848386 -0.1655424 -0.9552344 -0.2451998 -0.3034993 -0.6302954 -0.7145739 -0.2485329 -0.7169882 -0.6512752 -0.1661813 -0.8913707 -0.4217133 -0.1359205 -0.6381073 -0.7578554 -0.04686909 -0.9773094 -0.2065661 -0.06680732 -0.7302817 -0.6798717 0.002221107 -0.6729292 -0.7397037 0.06379002 -0.736373 -0.673562 0.163847 -0.5434786 -0.8232771 0.07751899 -0.9192236 -0.3860296 0.3093369 -0.3570945 -0.8813593 0.2594938 -0.5213487 -0.8129321 0.2329798 -0.7556318 -0.6121611 0.4392037 -0.3492742 -0.8277124 0.4110827 -0.6182978 -0.6698648 0.3046312 -0.7855491 -0.5386209 0.540261 -0.4586147 -0.7055428 0.2073018 -0.9340524 -0.2908127 0.6798745 0.004301011 -0.7333159 0.7357384 -0.002887189 -0.6772597 0.7959553 0.004425466 -0.6053394 0.8708604 0.004453957 -0.4915104 0.8315151 -0.00125724 -0.5555007 0.9244663 -0.001641213 -0.3812603 0.9225339 -6.12988e-4 -0.3859159 0.9726364 -0.001760303 -0.2323262 0.9763546 0.001002848 -0.2161732 0.9949843 0.004136264 -0.09994554 0.9996136 -0.005275905 -0.02729237 0.9976907 -0.004363358 0.06778162 0.9991717 -4.31077e-4 0.04069125 0.9748264 6.8247e-4 0.2229641 0.9740798 2.00888e-4 0.2262049 0.9348415 -8.82656e-4 0.3550642 0.9373568 5.62727e-4 0.3483704 0.8346533 4.46102e-4 0.5507756 0.8284509 -0.001646161 0.5600594 0.7289212 0.005233108 0.6845776 0.6867382 -0.003450095 0.7268967 0.5891561 0.005902469 0.8079978 0.4973644 -0.008403718 0.8675011 0.4021283 0.005904436 0.9155643 0.2786534 -0.005938887 0.9603734 0.1863995 0.005939066 0.9824561 0.07221978 -0.001202344 0.9973881 0.05622816 0.001511752 0.9984169 -0.1372734 6.9945e-4 0.990533 -0.1603674 -0.002681493 0.9870538 -0.2637797 0.002277255 0.9645803 -0.3177858 3.13897e-5 0.9481625 -0.3068832 0.00221771 0.9517446 -0.4952055 0.002144455 0.8687734 -0.4981395 0.001425564 0.8670958 -0.6415546 -0.003109574 0.7670712 -0.6685916 0.003438532 0.7436219 -0.8010801 -9.30465e-4 0.5985564 -0.8024488 -4.13837e-4 0.596721 -0.9105076 -3.7722e-4 0.4134923 -0.9214482 0.004075109 0.38848 -0.9556778 -0.004076063 0.2943868 -0.9802253 0.002350866 0.1978709 -0.9901409 -0.00519675 0.1399791 -0.9998611 0.001842021 -0.01656925 -0.9992823 -8.30048e-4 -0.03787243 -0.9900614 0.00483191 -0.1405531 -0.9780074 -0.00389868 -0.2085335 -0.9351727 0.007079303 -0.3541214 -0.907607 -0.003995895 -0.4198019 -0.8289276 0.004745364 -0.5593357 -0.8125796 5.15874e-4 -0.5828502 -0.7710826 0.003739953 -0.6367241 -0.6553226 0.002248406 -0.7553458 -0.6847569 -0.002838492 -0.728766 -0.5680002 0.002486824 -0.8230246 -0.5561259 5.11123e-4 -0.8310979 -0.4596214 0.005799651 -0.8880961 -0.3606374 -0.007546484 -0.9326757 -0.2647613 0.001722574 -0.9643124 -0.1850659 -0.008217573 -0.9826918 -0.04272371 0.002083659 -0.9990848 0.01762354 -0.00677365 -0.9998218 0.1308549 -0.001940131 -0.9913997 0.1624642 0.003490507 -0.9867083 0.2721101 0.001534819 -0.962265 0.3131076 -0.004867076 -0.9497053 0.4662408 0.004918456 -0.8846442 0.4983811 4.38024e-4 -0.8669579 0.5326961 0.001583218 -0.8463051 0.6016411 -0.005152583 -0.79875 0.001280963 -0.9996787 -0.02531343 -0.0195837 -0.9997944 0.00527966 0.001832783 -0.999836 0.01801687 -0.01224124 -0.9998964 -0.007575809 -0.007315158 -0.9998303 0.01690864 -0.005202531 -0.9999406 0.009587645 0.01429295 -0.9998068 0.01349616 0.006066977 -0.9997718 -0.02048593 -0.004695713 -0.999989 1.16344e-4 3.7776e-4 -0.9999893 0.00461632 -5.38301e-4 -0.999999 -0.00131911 -0.001850008 -0.9999841 0.005349159 0.006255865 -0.9999436 -0.008584678 0.004263579 -0.9999716 0.006233215 -0.002849996 -0.9999508 -0.009501457 2.63154e-4 -0.9999825 -0.005902528 0.001747012 -0.9999709 0.007440865 -0.004844486 -0.9999631 0.007111966 -9.14887e-4 -0.9999794 -0.006364345 -0.008557081 -0.9998783 0.01305162 0.003792405 -0.9999679 -0.007058858 0.01170474 -0.9999109 0.006427526 0.01618564 -0.9997301 -0.01666933 0.008328437 -0.99996 -0.003290116 0.008262813 -0.9999575 0.004106163 0.01148796 -0.9998841 -0.009998023 0.003267228 -0.9999902 -0.003007769 0.5430483 0.4812923 -0.6880816 0.4297909 0.6623796 -0.6136229 0.2794877 0.9112833 -0.3024059 0.3413512 0.7155824 -0.6094433 0.3396061 0.7593143 -0.5550763 0.4120954 0.2850711 -0.865397 0.0686587 0.9910004 -0.1149099 0.1082254 0.9686573 -0.2235856 0.3058148 0.3991682 -0.8643739 0.2227008 0.6408817 -0.7346258 0.212138 0.6541442 -0.7260116 0.1259406 0.863211 -0.4888821 0.1309415 0.4733875 -0.8710675 0.03131622 0.9161849 -0.3995305 0.01205164 0.6275157 -0.7785107 0.002698183 0.7452352 -0.6667962 -0.04994612 0.385962 -0.9211616 -0.005762338 0.9891062 -0.1470909 -0.1194228 0.8251044 -0.5522145 -0.2262411 0.4927224 -0.8402616 -0.2255997 0.4813546 -0.8469963 -0.1135535 0.8617711 -0.4944252 -0.3415568 0.5250979 -0.7794942 -0.3147286 0.7588365 -0.5701872 -0.1956294 0.9022063 -0.3843867 -0.4508013 0.6351758 -0.6271603 -0.08891391 0.9874517 -0.1305122 -0.5340668 0.6572884 -0.5317374 -0.5352791 0.6450413 -0.5453421 -0.4923135 0.7425414 -0.4541583 -0.505528 0.7522439 -0.4225763 -0.7068344 0.5472972 -0.4481641 -0.2865275 0.9415858 -0.1769696 -0.6959205 0.6624283 -0.2772787 -0.7905684 0.5423409 -0.2843732 -0.6879197 0.6688934 -0.2816883 -0.8583154 0.4877514 -0.1593526 -0.3302299 0.9426787 -0.04801142 -0.6701332 0.7411582 -0.04007667 -0.5401762 0.8410668 -0.02857393 -0.9009162 0.4320366 0.04116559 -0.8939784 0.4214495 0.15226 -0.4555532 0.8855335 0.09111422 -0.7739027 0.6062968 0.1829726 -0.326349 0.9412152 0.08723741 -0.8609066 0.3509805 0.3683103 -0.7890327 0.5300765 0.3105581 -0.5591182 0.7812539 0.2775417 -0.5133641 0.797895 0.3159444 -0.6874799 0.5450783 0.4798553 -0.5268558 0.7781922 0.3418185 -0.7188932 0.4402577 0.5379273 -0.3529531 0.8762989 0.3279095 -0.6137364 0.3505563 0.7074164 -0.443345 0.7398702 0.5060014 -0.5841352 0.5089823 0.6322366 -0.07931184 0.9918149 0.1000646 -0.3399912 0.8078238 0.4814838 -0.4874532 0.3080842 0.8169906 -0.1704133 0.9456541 0.2769437 -0.3841879 0.5688886 0.7271627 -0.3047227 0.6229645 0.7204577 -0.2346272 0.7318796 0.6397674 -0.1799073 0.8665072 0.4656165 -0.1460849 0.5428013 0.8270587 -0.1444815 0.6901937 0.7090541 -0.1007804 0.367413 0.9245816 -0.07418757 0.8135403 0.576757 -0.02597653 0.9804958 0.1948159 -7.13289e-4 0.4248109 0.9052819 0.02877259 0.6689893 0.742715 -0.007308959 0.9920263 0.1258193 0.09471338 0.7634986 0.6388265 0.1878297 0.5669894 0.8020243 0.1044488 0.755478 0.6467949 0.3645468 0.4586405 0.810404 0.3339302 0.5335764 0.7770373 0.2550985 0.802563 0.539275 0.1767295 0.8961766 0.4069818 0.1111166 0.9683207 0.2236256 0.5015267 0.4846537 0.7166463 0.4754299 0.6011032 0.6423718 0.4718953 0.7018768 0.5335577 0.2665517 0.9183202 0.2926401 0.6155766 0.5423903 0.5717328 0.2200571 0.9505767 0.2190409 0.6896487 0.5816689 0.4313305 0.6730147 0.6215022 0.4009817 0.4639248 0.8405848 0.2796264 0.7736722 0.5375023 0.3354438 0.1871075 0.9801626 0.06536233 0.8416861 0.5141329 0.1650211 0.7004439 0.6782485 0.2221652 0.3942714 0.9142879 0.09288549 0.7948666 0.6023329 0.07336324 0.8917365 0.4509513 0.0380674 0.5556019 0.8303278 0.04315507 0.9104763 0.4062417 -0.07746446 0.451552 0.8919181 -0.02414494 0.8111225 0.5707521 -0.1277589 0.8396883 0.4978593 -0.2169327 0.2067722 0.9777051 -0.03658199 0.7833775 0.5564719 -0.2768734 0.3945374 0.9064502 -0.1506267 0.8306887 0.4869669 -0.2698513 0.6792652 0.6216565 -0.390054 0.694593 0.6043105 -0.39032 0.3834655 0.8946395 -0.2292914 0.349639 0.9107217 -0.2198604 0.6917671 0.4932623 -0.5273999 0.3887828 0.8580982 -0.3354335 0.6024063 0.5996389 -0.5268204 0.5943902 0.4242302 -0.6831757 -0.9932214 0.02548336 -0.113411 -0.992805 0.02104514 -0.1178789 -0.6005772 0.02098745 0.7992914 -0.6039913 0.02530598 0.796589 0.3981829 0.02519553 0.9169601 0.3943322 0.02098894 0.9187283 0.6612176 0.7459048 0.0801087 0.6706433 0.7374722 0.07982623 0.2631891 0.7447878 0.6132069 0.2653912 0.73689 0.6217401 -0.3888598 0.7449836 0.5420217 -0.5145973 0.5349972 0.6700505 -0.5817413 0.8089501 -0.08471703 -0.8353669 0.5426945 -0.08743524 -0.2451472 0.809061 -0.5341566 -0.3210802 0.5331192 -0.7827462 0.4097589 0.7466179 -0.5240797 0.4994803 0.5318679 -0.6838393 -0.401349 0.02832514 -0.9154872 -0.3939989 0.02030462 -0.9188866 0.603618 0.0193687 -0.7970384 0.5983713 0.0255773 -0.8008106 0.9925855 0.0252847 0.1188893 0.9926701 0.0261476 0.1179938 4.16852e-4 0.9999988 0.001525402 0.003911256 0.9997901 -0.02011328 0.001573085 0.9999988 -2.79044e-5 -0.01767885 0.9998016 0.00917989 -0.002559781 0.9999553 0.009110391 0.002530455 0.9999755 0.006541609 0.00255835 0.9999752 0.006570756 9.64565e-4 0.9999741 0.007132649 0.003174424 0.9999769 -0.006005823 0.004945635 0.9999764 0.004788041 -0.01101893 0.9999263 -0.005110025 -0.004579424 0.9999683 0.00651592 -0.007104873 0.9999544 0.006391644 0.005497336 0.9999848 6.79371e-4 0.005268335 0.9999858 9.02337e-4 0.003086209 0.9999685 -0.007311701 -0.006843566 0.999972 -0.003035843 -0.004536569 0.9999896 -2.71016e-4 -0.007324755 0.9999732 3.93369e-5 0.004570662 0.9999719 -0.005964159 0.004683673 0.9999614 -0.007429838 -0.009838998 0.9999496 0.001997649 5.59471e-4 0.9999995 9.20676e-4 9.34115e-4 0.9999415 -0.01077681 0.006815314 0.999879 -0.01398736 0.002667725 0.9999918 0.003049969 -0.001632332 0.9999933 -0.003299415 0.01029014 0.9999087 -0.008761763 0.05192446 0.9923475 -0.112028 -0.01310539 0.9991523 -0.03902387 -0.002575159 0.9999924 -0.002964079 0.06623077 0.9913932 -0.1129306 -0.00239098 0.999994 -0.002504289 -0.06164109 0.9979252 -0.01859366 0.06311184 0.9976018 -0.02842181 -0.08845835 0.9946093 -0.05410611 0.03856658 0.9989665 0.02405887 0.03088885 0.9992307 -0.02416527 0.01529926 0.999882 0.001454234 0.05158442 0.9986249 0.009352266 0.06945681 0.9975497 -0.008397042 0.001637756 0.9999971 0.001739382 7.51419e-5 1 8.36689e-5 -0.02460199 0.9996662 0.00788635 0.06564611 0.996003 0.06056922 0.08080595 0.9835939 0.1612874 0.07568448 0.9849275 0.1555309 0.3119047 0.8901339 0.3322305 0.3744193 0.6889877 0.6205693 0.08662688 0.9137575 0.3969169 0.01206153 0.791808 0.610651 -0.1191579 0.8748764 0.46946 -0.2021794 0.8139916 0.544556 -0.2997021 0.8826946 0.3619793 -0.4663128 0.7894879 0.3990755 -0.4368749 0.8643888 0.2489425 -0.6083034 0.7827746 0.1312674 -0.4895496 0.8719738 0.001713514 -0.5237984 0.8425831 -0.1252562 -0.5015236 0.853957 -0.1386783 -0.5288282 0.7991827 -0.285741 -0.4113563 0.8568412 -0.3108206 -0.3841791 0.8078701 -0.4469367 -0.2544881 0.8659698 -0.4305025 -0.2042949 0.8196195 -0.5352454 -0.07874125 0.8606837 -0.5030145 -0.03197997 0.8158665 -0.5773553 0.1156772 0.8476427 -0.5178039 0.1627956 0.8113722 -0.5614027 0.3118383 0.8427848 -0.4387147 0.3473024 0.8202173 -0.45456 0.4451605 0.8440122 -0.2991251 0.478035 0.8254356 -0.3002307 0.5063016 0.8565696 -0.0997368 0.5198537 0.8488753 -0.09572368 0.6033135 0.7962461 0.04477816 0.4946641 0.8608477 0.119369 0.5293319 0.8168774 0.2291706 0.4197055 0.8555898 0.3030074 0.4357784 0.8311209 0.3454497 0.3042632 0.8120887 0.4979317 0.1941623 0.8736783 0.4460799 0.1142809 0.791828 0.5999569 -0.03855663 0.8446055 0.5339992 -0.05811399 0.8282918 0.5572751 -0.2541936 0.8404821 0.4785138 -0.2458146 0.8469025 0.4715203 -0.4336453 0.7980547 0.4184025 -0.4067366 0.8683927 0.283654 -0.526941 0.8235478 0.2100051 -0.5040348 0.8548457 0.123239 -0.5989951 0.7989213 0.05412697 -0.492234 0.8661903 -0.08614075 -0.5701493 0.8057861 -0.1601206 -0.3515309 0.8863499 -0.3013471 -0.3957042 0.8221219 -0.4093091 -0.2438374 0.8438883 -0.477908 -0.24305 0.8148917 -0.5261922 -0.03297466 0.8329511 -0.5523633 -0.02233988 0.8430629 -0.5373509 0.1905162 0.8371644 -0.5126983 0.1674531 0.8574316 -0.4865906 0.3627335 0.8007035 -0.4767584 0.3845922 0.8597753 -0.335969 0.4534528 0.8216105 -0.3454515 0.5604323 0.8151537 -0.1464245 0.4970632 0.8641313 -0.07877397 0.586276 0.808529 0.05061048 0.4356623 0.8914462 0.1245883 0.4660297 0.8116813 0.3521219 0.356828 0.8692306 0.3422163 0.3310532 0.8028346 0.4958431 0.1350855 0.8667913 0.4800261 0.1193972 0.8328009 0.5405434 -0.066554 0.8354507 0.5455206 -0.07735168 0.8242186 0.5609637 -0.2561154 0.8433582 0.4723894 -0.2644934 0.8373364 0.4784466 -0.4109145 0.7958815 0.4446596 -0.4000976 0.873252 0.278124 -0.5406739 0.8079612 0.2342448 -0.5030289 0.8554748 0.1229826 -0.589283 0.8062756 0.05162674 -0.5142471 0.8544547 -0.07387238 -0.5534832 0.8250795 -0.1135796 -0.4756381 0.8265747 -0.300903 -0.3967193 0.8676129 -0.2997694 -0.3825222 0.781998 -0.4920936 -0.146323 0.8998818 -0.4108557 -0.07923138 0.8079385 -0.583916 0.03227698 0.8599455 -0.5093644 0.1189597 0.7997254 -0.5884624 0.2479667 0.8720269 -0.4219973 0.340569 0.8081082 -0.4805974 0.4896633 0.7907797 -0.3672839 0.4406176 0.8716074 -0.2148416 0.559098 0.8110834 -0.1719112 0.5033596 0.8638619 -0.0192787 0.5734817 0.8182681 0.03944867 0.5324857 0.8297734 0.1671381 0.4615174 0.8657026 0.1938058 0.5077771 0.781211 0.3631419 0.2931107 0.8767017 0.3814189 0.284702 0.7977696 0.5315154 0.1028162 0.8929987 0.4381577 -0.03597098 0.8112533 0.5835875 -0.08851957 0.8669763 0.4904247 -0.2866038 0.7763187 0.5614159 -0.3399219 0.8719819 0.3522794 -0.4280691 0.8211569 0.3774363 -0.5408881 0.8188983 0.1919519 -0.4962863 0.85732 0.1367571 -0.5406209 0.8383473 0.07002162 -0.4593698 0.8815 -0.1092572 -0.5374992 0.8250739 -0.1742064 -0.3653063 0.8944234 -0.2579885 -0.3881442 0.820879 -0.4189295 -0.2617748 0.8825585 -0.3905951 -0.1188287 0.8582339 -0.4993139 -0.1592956 0.8429078 -0.5139373 -0.04587274 0.7902495 -0.6110659 0.09937387 0.8653593 -0.4912009 0.1922174 0.8038868 -0.5628664 0.3125407 0.8282973 -0.4650183 0.3141877 0.8681679 -0.3841494 0.4995092 0.7783482 -0.3803482 0.4703409 0.8673849 -0.1625516 0.5492691 0.8235203 -0.1418377 0.5273201 0.8472969 0.0634163 0.5204399 0.851804 0.05976837 0.5689325 0.7762078 0.2716935 0.3718966 0.8787562 0.2991331 0.3771087 0.8181089 0.4341508 0.2382851 0.8378431 0.4911611 0.2382596 0.8403351 0.4868977 0.05885607 0.8143283 0.5774127 -0.02623063 0.8949936 0.4453071 -0.237413 0.8047338 0.5440942 -0.2793711 0.8725457 0.4007689 -0.4138917 0.7946588 0.4440846 -0.4694234 0.8488749 0.2430085 -0.5363204 0.8100232 0.2371141 -0.5240226 0.8506269 0.04282712 -0.587727 0.8090173 0.00826174 -0.5038308 0.8497458 -0.1551985 -0.4856287 0.8639728 -0.1331002 -0.4138453 0.8576352 -0.3052772 -0.3749321 0.8755401 -0.3047219 -0.272945 0.8443774 -0.4610077 -0.2824388 0.8393754 -0.4644106 -0.1503766 0.8167359 -0.5570722 -0.1003253 0.8465555 -0.5227608 0.006093621 0.8178318 -0.5754251 0.09328073 0.8623813 -0.4975916 0.2068421 0.8047153 -0.5564617 0.2668797 0.8615595 -0.4318455 0.4194198 0.7795914 -0.4651068 0.4320477 0.8543658 -0.2887801 0.4309794 0.8548141 -0.2890494 0.486858 0.8678728 -0.09882348 0.5165099 0.8513036 -0.09219366 0.4884917 0.8652759 0.1125774 0.5758392 0.8165876 0.0399239 0.5743724 0.7852052 0.2314072 0.3941926 0.8407205 0.3712161 0.352543 0.8633825 0.360949 0.2679049 0.8013803 0.5348052 0.1387123 0.8549175 0.4998751 0.1097853 0.8181022 0.5644962 -0.09496217 0.8381839 0.5370568 -0.09111899 0.8327882 0.5460414 -0.2685473 0.833314 0.4831875 -0.2762741 0.8279941 0.4879534 -0.403736 0.8271318 0.3909608 -0.4025207 0.8519697 0.3348501 -0.5100126 0.8126519 0.281929 -0.4846212 0.8598862 0.1604309 -0.5921303 0.7984334 0.1090227 -0.4896679 0.8704811 -0.0498808 -0.5720056 0.8084623 -0.1385582 -0.4335058 0.8625663 -0.2608678 -0.4618093 0.8307129 -0.3108832 -0.265337 0.8627673 -0.4303822 -0.2550476 0.8688616 -0.4242999 -0.06016492 0.8708725 -0.4878129 -0.04256296 0.8288904 -0.5577896 0.1378134 0.8163148 -0.5609258 0.1612493 0.8534476 -0.4956067 0.3292962 0.8128746 -0.4804154 0.3442161 0.8481091 -0.4027731 0.4564282 0.8069942 -0.3747448 0.4508422 0.8599708 -0.239148 0.5779683 0.7907547 -0.2016425 0.4897767 0.8717424 -0.01356834 0.6143683 0.7867004 0.0604487 0.5433451 0.8178176 0.1896064 0.3824071 0.8951012 0.2292574 0.4172661 0.8348534 0.3590389 0.2472111 0.8953944 0.3703452 0.2465929 0.8157327 0.5232325 0.1798675 0.7832932 0.5950626 0.04112243 0.8664929 0.4974929 -0.04779374 0.7992134 0.5991441 -0.1694291 0.8607054 0.4800834 -0.2695508 0.7948061 0.5437147 -0.406103 0.831077 0.3799886 -0.3975465 0.8474773 0.3517658 -0.5071696 0.8386025 0.198809 -0.5186175 0.8271895 0.2163182 -0.5510033 0.8345013 -0.001776695 -0.5342335 0.845314 0.006241142 -0.5724553 0.8102029 -0.1259616 -0.4735982 0.8584814 -0.1967604 -0.5118115 0.8025582 -0.3065117 -0.3516381 0.8674644 -0.3519322 -0.3573557 0.7991179 -0.4834333 -0.1625269 0.8556883 -0.4913069 -0.1516562 0.8246978 -0.5448614 0.07370674 0.8276871 -0.5563285 0.05512171 0.8535068 -0.5181581 0.315234 0.7775713 -0.5440686 0.3343074 0.8676701 -0.3679497 0.3687605 0.8512573 -0.373332 0.4444559 0.8814267 -0.1598316 0.5670038 0.8097234 -0.1511778 0.5428633 0.8386605 0.04413586 0.5641965 0.8235886 0.05817264 0.4882822 0.8378236 0.2441969 0.4701766 0.8545228 0.2207372 0.4262397 0.8150275 0.3924921 0.3117821 0.8619549 0.3997822 0.2874604 0.8043955 0.5199177 0.1173843 0.8681159 0.4822821 0.09020739 0.8159063 0.5711039 -0.1159816 0.813459 0.5699411 -0.1615157 0.8715918 0.4628613 -0.3295565 0.7952017 0.5089665 -0.3168662 0.8837519 0.3443522 -0.4524337 0.8609949 0.232361 -0.4896241 0.8394764 0.235686 -0.4711837 0.8807131 0.0482763 -0.5434394 0.8393656 0.01179492 -0.4406495 0.8873977 -0.135475 -0.5117556 0.8358027 -0.1988471 -0.5422067 0.7666048 -0.3439902 -0.3165354 0.8691923 -0.3798819 -0.3323973 0.8163954 -0.4722402 -0.1340685 0.8242098 -0.5501852 -0.09537458 0.8529786 -0.5131582 0.0699473 0.8215063 -0.5658931 0.1063494 0.8736129 -0.4748584 0.2841373 0.8701552 -0.4026116 0.3071426 0.8537644 -0.4204161 0.4807394 0.8420335 -0.2446818 0.4364812 0.8801992 -0.1863694 0.5062978 0.8623577 0.001385748 0.5225148 0.8526012 0.007053732 0.4584056 0.8634778 0.2104058 0.4545418 0.8654189 0.2108125 0.3396298 0.8631718 0.3736122 0.3425303 0.8589774 0.3805663 0.2739856 0.8040451 0.5276775 0.156898 0.8504511 0.5021117 0.1138374 0.8008366 0.5879641 -0.07261073 0.8625684 0.500703 -0.1198898 0.8146725 0.5673934 -0.3101317 0.8035243 0.5081015 -0.323202 0.8728878 0.3655234 -0.4403188 0.8142352 0.3783392 -0.5025892 0.8404036 0.202796 -0.4868693 0.8491455 0.2047201 -0.4861176 0.8737607 0.01523548 -0.541014 0.8408854 -0.01468718 -0.4205566 0.8909973 -0.1710439 -0.5321929 0.7938489 -0.2942361 -0.37496 0.8310496 -0.4108063 -0.2817772 0.8849299 -0.3708111 -0.1083949 0.8494272 -0.5164532 -0.1072705 0.8421978 -0.5283901 -9.38601e-5 0.8003174 -0.5995768 0.1094203 0.8594357 -0.4993972 0.1874008 0.8128604 -0.551488 0.2873542 0.8675127 -0.4060164 0.396297 0.8042854 -0.442802 0.4814855 0.811006 -0.3323268 0.4438934 0.8649142 -0.2342692 0.5603511 0.8123772 -0.1614001 0.4939875 0.8692035 -0.02148854 0.5812155 0.8121891 0.05037397 0.4189271 0.8945707 0.1557031 0.4595187 0.8294191 0.317658 0.3404821 0.8882509 0.3083541 0.2896102 0.8145868 0.5025678 0.1042155 0.908663 0.404315 0.0323925 0.7770232 0.6286381 -0.1456521 0.844608 0.5151923 -0.1550369 0.8754894 0.4576918 -0.3541629 0.8581395 0.371706 -0.4222902 0.8103588 0.4061892 -0.4859023 0.8412929 0.2369081 -0.4482433 0.8746957 0.1843516 -0.5077379 0.8615028 0.003907263 -0.5448687 0.8384387 -0.01177668 -0.4276035 0.889155 -0.1629688 -0.5276357 0.7925652 -0.3056815 -0.3421409 0.872974 -0.3476434 -0.3621953 0.8062142 -0.4677963 -0.1658283 0.8273212 -0.5366942 -0.09642261 0.8704375 -0.4827436 0.007311642 0.8055962 -0.5924199 0.1195003 0.8505411 -0.5121518 0.1882363 0.8012505 -0.5679478 0.3469295 0.8566843 -0.3817484 0.3603097 0.8480445 -0.388584 0.5428845 0.7910029 -0.2821184 0.4523937 0.885563 -0.105443 0.557051 0.8285159 -0.05705869 0.5831949 0.8078022 0.08567088 0.4484743 0.8839043 0.1326056 0.4500949 0.8299449 0.3295543 0.4069954 0.8521689 0.3288816 0.2931813 0.8158476 0.498435 0.238372 0.8483796 0.4726848 0.1008036 0.8143221 0.5715928 0.04196929 0.8571499 0.5133544 -0.1371073 0.8037449 0.578961 -0.1801304 0.8555394 0.485392 -0.3337028 0.8033125 0.4932864 -0.3177334 0.8823601 0.3471114 -0.4831038 0.8509922 0.2059692 -0.4368954 0.8772892 0.1987109 -0.5651738 0.8249651 -0.003393292 -0.467755 0.8796013 -0.08664256 -0.5524165 0.8169878 -0.1654306 -0.4842709 0.8042705 -0.3444281 -0.3752205 0.861314 -0.3425606 -0.3280466 0.8042704 -0.4955144 -0.2093768 0.8610576 -0.463402 -0.1513472 0.8090084 -0.5679784 2.06782e-4 0.8531932 -0.521595 0.03197461 0.8232012 -0.5668488 0.215061 0.8302655 -0.5142064 0.2189913 0.8269658 -0.5178517 0.3902987 0.8225618 -0.4135931 0.3843869 0.8580036 -0.3407002 0.5031889 0.8136667 -0.2911145 0.4748589 0.8644921 -0.1648107 0.5884381 0.8037689 -0.08772832 0.4930294 0.8694521 0.03122591 0.594644 0.7943491 0.1241288 0.4142013 0.8629857 0.2892979 0.4683333 0.7915883 0.3924947 0.2675377 0.8587737 0.436957 0.2619857 0.8183943 0.5114629 0.06332266 0.8518755 0.5199024 0.05345022 0.8376117 0.5436449 -0.07524216 0.8151358 0.5743626 -0.1526805 0.8694721 0.4697948 -0.2664176 0.7911201 0.5505914 -0.4085438 0.835616 0.3672029 -0.3919062 0.8643232 0.3152065 -0.5580163 0.8034694 0.2074967 -0.4768599 0.8758838 0.07370299 -0.6081375 0.7938247 0.003326654 -0.5798407 0.8001723 -0.1533275 -0.4240266 0.881097 -0.2094508 -0.4749985 0.8131723 -0.3363443 -0.3255077 0.8464992 -0.4212886 -0.3319828 0.817509 -0.4706023 -0.1775755 0.8267382 -0.5338268 -0.1439464 0.8462424 -0.5129849 -0.01706093 0.817812 -0.5752327 0.06107008 0.8640528 -0.4996833 0.1714541 0.7923013 -0.5855443 0.2891784 0.8614836 -0.4173991 0.3609345 0.8168463 -0.4499874 0.4811281 0.8388264 -0.2547273 0.461356 0.8505708 -0.252349 0.5912262 0.800922 -0.09473985 0.4419997 0.8968559 0.01690495 0.5307077 0.8217351 0.2076072 0.4252545 0.871347 0.2447715 0.4728479 0.7932268 0.3836746 0.2644843 0.8522408 0.4513691 0.2652074 0.8434342 0.4672085 0.05533266 0.876141 0.4788689 0.0278595 0.8379313 0.5450642 -0.1319941 0.8099789 0.5714123 -0.09309607 0.8527254 0.5139968 -0.3232889 0.8533508 0.408995 -0.3361907 0.8108388 0.4790785 -0.4056188 0.8835626 0.2340736 -0.5477051 0.8036308 0.2328024 -0.493694 0.8652727 0.08700287 -0.5896498 0.8076592 -1.30107e-4 -0.4990229 0.8599824 -0.1068022 -0.563183 0.8022891 -0.1978818 -0.4211464 0.8550456 -0.3025442 -0.445519 0.8146082 -0.3713843 -0.2468032 0.8731434 -0.4203675 -0.2319834 0.7657697 -0.5998171 -0.04824769 0.8632755 -0.5024216 -0.01857781 0.842432 -0.5384826 0.1377717 0.8863535 -0.4420368 0.2204543 0.8324846 -0.5083005 0.3071541 0.8869494 -0.3449309 0.3874712 0.8415448 -0.376389 0.5291938 0.8021411 -0.2766289 0.4338746 0.8878702 -0.1530994 0.5667183 0.8227422 0.04388314 0.477371 0.8737624 0.09303897 0.5680973 0.7821622 0.2559061 0.3740329 0.8598384 0.3475306 0.3321574 0.8818705 0.3346281 0.2092736 0.8358979 0.5074241 0.08978092 0.9027385 0.420717 0.008554816 0.8132674 0.5818274 -0.1336049 0.7997893 0.5852239 -0.1757582 0.8657978 0.4685119 -0.3396138 0.7997194 0.4950872 -0.3636506 0.8687963 0.3360825 -0.4973878 0.7946752 0.3479896 -0.5421416 0.8265316 0.1514201 -0.5080608 0.8538677 0.1130676 -0.5829632 0.8111347 -0.04705804 -0.4799776 0.8700058 -0.1127459 -0.567658 0.7793941 -0.2651593 -0.3451316 0.8678148 -0.3574655 -0.3658375 0.8222692 -0.4359319 -0.1982194 0.8392346 -0.5063541 -0.1951397 0.8276869 -0.5261701 0.01096737 0.8445789 -0.5353187 0.006242156 0.8509019 -0.5252876 0.1803398 0.7884585 -0.5880568 0.250396 0.8702166 -0.4242936 0.3780486 0.7939845 -0.4760966 0.4470111 0.8495665 -0.2800316 0.4816114 0.8305187 -0.2798019 0.5297803 0.8425945 -0.09678584 0.5470933 0.8321585 -0.09056031 0.5409111 0.8372606 0.08006244 0.5641887 0.8198228 0.09788674 0.5274475 0.813912 0.2436112 0.4428308 0.8564696 0.2652558 0.4067933 0.8085899 0.4250899 0.327311 0.8495469 0.413688 0.2565108 0.8235237 0.5059755 0.1392853 0.8850483 0.4441725 6.51921e-4 0.8347394 0.5506449 -0.03394603 0.8719037 0.4884993 -0.2232211 0.8679965 0.4435701 -0.2856085 0.8159012 0.5027257 -0.4224982 0.8407927 0.3384714 -0.4258125 0.8388694 0.3390898 -0.528932 0.8151209 0.2362394 -0.492501 0.8582437 0.1444317 -0.6018234 0.7968105 0.05386883 -0.5089421 0.8595021 -0.04726612 -0.5563205 0.8188081 -0.1416364 -0.4081181 0.8875512 -0.2137585 -0.4272357 0.8348451 -0.347136 -0.3139714 0.8844083 -0.3453172 -0.2661741 0.8330782 -0.4849044 -0.1578765 0.8908495 -0.4259837 0.01097637 0.8133262 -0.5817044 0.06477183 0.8687381 -0.4910182 0.2135878 0.7984941 -0.5628387 0.3085863 0.8651328 -0.3953729 0.3687248 0.8305796 -0.4173483 0.4753273 0.8443818 -0.2471505 0.4677506 0.848787 -0.2465162 0.5976234 0.7958301 -0.09747302 0.4883902 0.8722692 0.02493017 0.5909876 0.7996203 0.1064946 0.4963474 0.8131753 0.3039497 0.3993983 0.8651087 0.3034269 0.3715902 0.8159027 0.4429715 0.2446531 0.8583221 0.4510301 0.2270225 0.8158469 0.5318409 0.06841021 0.8259679 0.5595508 0.04320341 0.8462855 0.530975 -0.08584952 0.8327902 0.5468914 -0.1278845 0.8784237 0.4604536 -0.2806239 0.8476008 0.4503591 -0.2848013 0.8774642 0.3859337 -0.4341639 0.8557821 0.2813162 -0.4365325 0.8449453 0.3090419 -0.5693553 0.7874997 0.2359638 -0.4858774 0.8723998 0.05331128 -0.5935294 0.8047984 -0.004736483 -0.5044013 0.8363733 -0.2146137 -0.4493316 0.8671461 -0.2148461 -0.3159607 0.8779463 -0.3596932 -0.3477027 0.7969117 -0.4939987 -0.1680274 0.8630399 -0.4763708 -0.1286587 0.8052149 -0.5788576 0.05656522 0.8604529 -0.5063804 0.07334107 0.842373 -0.5338811 0.2834385 0.8110556 -0.5117143 0.3134273 0.8718563 -0.3763377 0.4081677 0.8172703 -0.406778 0.5358882 0.8069646 -0.2482579 0.4795536 0.864506 -0.1505252 0.5930033 0.8026856 -0.06358534 0.5063563 0.8581568 0.08467853 0.5603532 0.8176887 0.1318702 0.4674386 0.8305722 0.3027392 0.4011768 0.8626384 0.3080783 0.3838822 0.8083276 0.4463643 0.2191188 0.8638755 0.4535483 0.2085487 0.8116283 0.5456805 -0.004002451 0.8242684 0.5661853 -0.0161181 0.8434525 0.536962 -0.2103634 0.886728 0.4116561 -0.2920295 0.8357232 0.465065 -0.3477955 0.8793417 0.325264 -0.3915088 0.8593261 0.3290586 -0.4947474 0.8322351 0.2502198 -0.4356769 0.8845686 0.1665059 -0.4813526 0.8733797 0.07421386 -0.3926457 0.9184168 -0.04837524 -0.6186616 0.7565261 -0.2119579 -0.3677543 0.9051107 -0.213381 -0.4223288 0.7671824 -0.482773 -0.2665411 0.8965256 -0.3538332 -0.06546008 0.912048 -0.4048253 -0.918644 0.3720112 0.1330445 -0.9140347 -0.370647 -0.1648069 -0.9145208 0.2359877 -0.3285753 -0.7991549 -0.3305722 -0.5020694 -0.5948613 0.4260932 -0.6816045 -0.5650537 -0.2450188 -0.7878326 -0.2244531 0.047876 -0.9733082 -0.1877135 0.2255968 -0.9559653 0.1313819 -0.255362 -0.9578775 0.2668638 0.3299745 -0.9054836 0.4942854 -0.263454 -0.8284165 0.5913426 0.09810256 -0.800431 0.7741919 -0.1685713 -0.6100908 0.8178572 0.2189667 -0.5321311 0.950005 -0.157185 -0.2697841 0.969702 0.1167866 -0.214567 0.9816264 -0.09385216 0.1661366 0.9860006 -0.04175496 0.1614291 0.8495785 0.0336216 0.5263897 0.8316816 0.1403236 0.537229 0.4716184 -0.1540104 0.8682493 0.4710462 -0.1454084 0.8700413 0.03563684 0.2583089 0.9654049 0.001395583 -0.1041927 0.9945562 -0.4024243 -0.1013151 0.9098296 -0.4403615 0.173116 0.8809726 -0.7647282 -0.1125528 0.6344467 -0.7585853 0.4258199 0.4931791 -0.8556997 -0.4246661 0.2956969 -0.9506445 0.3096066 0.02046579 -0.9300304 -0.3595233 -0.07606887 -0.8380812 0.4294441 -0.3364489 -0.7789782 -0.3142992 -0.5425947 -0.6944834 0.2787154 -0.6633329 -0.4778351 -0.4433836 -0.7583432 -0.2661705 0.434916 -0.8602334 -0.1180077 -0.2727812 -0.9548113 0.07454043 0.2620221 -0.9621788 0.250048 -0.3664545 -0.8962071 0.4154973 0.2536689 -0.8735069 0.6758098 -0.227603 -0.701055 0.6863843 -0.1893354 -0.7021601 0.842172 0.42954 -0.3259474 0.8430925 -0.4904447 -0.2205886 0.9189338 0.3431588 0.1944295 0.988024 -0.05471336 0.1442741 0.8104249 0.2206368 0.5427072 0.6965131 -0.4680063 0.5439115 0.4114988 0.418014 0.809897 0.3394941 -0.3023586 0.8906869 0.08838403 0.2645708 0.9603075 -0.03836107 -0.3022865 0.9524449 -0.2755315 0.2516256 0.9277753 -0.3766434 -0.3369565 0.8629022 -0.5929944 0.4401059 0.6742882 -0.7132746 -0.3556488 0.6039481 -0.8785895 0.3110087 0.3624283 -0.9290971 -0.2042189 0.3083398 -0.9966365 0.03863745 -0.07226979 -0.9819801 0.1644939 -0.0930432 -0.8533731 -0.05647873 -0.5182322 -0.8225935 -0.2428201 -0.5141776 -0.4006882 0.3140555 -0.8607079 -0.4075816 0.1591746 -0.8991889 -0.02794778 -0.395078 -0.9182224 0.1422868 0.3798437 -0.9140424 0.3942347 -0.3681581 -0.8420444 0.5156871 0.2638243 -0.8151464 0.8427471 -0.008749127 -0.5382387 0.8231977 -0.2705869 -0.4991278 0.9552088 0.2695698 -0.1221 0.9904313 0.08441817 -0.1091762 0.8822278 -0.3820797 0.2751165 0.8029553 0.4433956 0.3983255 0.6508121 -0.2899712 0.701684 0.482719 0.4613744 0.7443897 0.2993382 -0.4540193 0.8392038 -0.01532763 0.3867814 0.922044 -0.08662509 -0.2936056 0.9519937 -0.460037 0.4296912 0.7770016 -0.5221999 -0.5269705 0.6705291 -0.767203 0.34148 0.5429465 -0.8870056 -0.3206657 0.3322569 -0.9568904 0.1359627 0.2566611 -0.9921575 0.06180787 -0.108643 -0.9635867 -0.2292246 -0.1376842 -0.8643382 0.1500513 -0.4800044 -0.8641199 -0.01954317 -0.5029065 -0.6262269 -0.0419321 -0.7785125 -0.5629571 0.2334382 -0.7928342 -0.2991349 -0.2985426 -0.9063061 -0.1957371 0.1960957 -0.9608505 0.1169038 -0.1245368 -0.9853041 0.1487729 0.03350323 -0.9883037 0.5074246 0.113476 -0.8541917 0.5070281 -0.4112316 -0.7575033 0.7681934 0.4980039 -0.4023323 0.8894362 -0.2225813 -0.3992002 0.9873207 -0.1523616 0.04453974 0.9747935 0.2005766 0.09770792 0.8227702 0.06033754 0.5651624 0.8209139 0.1093719 0.5604803 0.477142 -0.3458561 0.8079103 0.3742436 0.3018807 0.876818 0.03751635 -0.204527 0.9781417 -0.02230107 0.1400101 0.989899 -0.4929372 -0.1538501 0.8563545 -0.4945939 -0.1458099 0.856806 -0.8038936 0.2580553 0.5358756 -0.846667 -0.1046636 0.5217285 -0.9825406 -0.101764 0.1557503 -0.9583209 0.2744517 0.07935571 -0.9319083 -0.3011323 -0.2021541 -0.776371 0.5077689 -0.3733885 -0.7891275 -0.317012 -0.5261 -0.5762781 -0.01502078 -0.8171156 -0.5388113 0.1748735 -0.8240762 -0.2596746 -0.1310561 -0.9567619 -0.1752691 0.2143959 -0.9608929 0.1013882 -0.1469554 -0.9839333 0.1797583 0.1753912 -0.9679489 0.4247582 -0.317708 -0.8477276 0.5457623 0.2707288 -0.7930004 0.7797403 -0.1229165 -0.6139191 0.8040461 0.3003666 -0.5131179 0.8611558 -0.4341614 -0.2644137 0.8881543 0.4593713 -0.01265382 0.8961498 -0.4284018 0.1157045 0.7588322 0.5048199 0.4114978 0.6532747 -0.5237146 0.5467681 0.6057893 0.2263109 0.76276 0.3335319 -0.08692669 0.9387227 0.3380918 -0.04337525 0.940113 -0.09175133 0.07501327 0.9929525 -0.09800308 0.007943809 0.9951545 -0.4125066 -0.1988382 0.8889891 -0.5023053 0.3150006 0.8052726 -0.6994317 -0.2002609 0.6860691 -0.7777354 0.231393 0.5844528 -0.8715411 -0.3130022 0.37742 -0.9336289 0.2561337 0.2504651 -0.9658228 -0.2588846 -0.01285058 -0.9201542 0.3600913 -0.1537882 -0.8302926 -0.3886132 -0.3994923 -0.7427083 0.389576 -0.5446238 -0.5568469 -0.3775515 -0.7398489 -0.3200873 0.5477486 -0.7729914 -0.1991109 -0.4522164 -0.8693993 0.1752885 0.2929039 -0.9399369 0.2324134 -0.1564697 -0.9599485 0.5659459 0.2507263 -0.7853928 0.5945194 0.09194284 -0.7988073 0.7677501 -0.3950372 -0.5044853 0.8532596 0.3796944 -0.3574639 0.9294589 -0.3513593 -0.1124846 0.9556851 0.2940582 0.01398795 0.8926802 -0.1473959 0.4259068 0.8937009 -0.14117 0.4258753 0.6264294 0.1353747 0.7676327 0.6257875 0.03275203 0.7793057 0.1610036 -0.1155574 0.9801655 0.09774714 0.2469701 0.9640805 -0.2377218 -0.2978326 0.9245454 -0.3668322 0.5092242 0.7785402 -0.5859637 -0.4723737 0.6584145 -0.7716772 0.3597519 0.524493 -0.8713323 -0.2516599 0.421245 -0.9353778 0.3080955 0.1736249 -0.9678882 -0.2405529 0.07298523 -0.9286589 0.3087033 -0.2056574 -0.9047443 -0.315696 -0.2859617 -0.7535215 0.09326082 -0.6507749 -0.7436902 0.1422146 -0.6532227 -0.4269343 0.06188446 -0.9021627 -0.3778898 -0.2734112 -0.8845596 -0.03966909 0.2239696 -0.9737886 0.04215621 -0.4090896 -0.91152 0.3470508 0.5200504 -0.7804509 0.5112251 -0.5098216 -0.6919038 0.7097774 0.3447576 -0.6142951 0.8349928 -0.3793026 -0.3986433 0.8812183 0.4254568 -0.206012 0.9339002 -0.3575119 -0.003961682 0.9565215 0.2312837 0.177692 0.8881081 -0.288703 0.3576514 0.8147285 0.3024961 0.4946853 0.6687361 -0.1604694 0.7259764 0.6197267 0.13494 0.77313 0.3071651 -0.3299033 0.8926442 0.2372287 0.1579494 0.9585273 -0.1689968 0.304375 0.9374412 -0.2248582 -0.3453048 0.9111551 -0.5852913 0.1256973 0.8010209 -0.6099606 -0.08131772 0.7882484 -0.8414701 0.1196563 0.5268875 -0.853357 0.02514111 0.5207204 -0.9823317 -0.02910894 0.1848706 -0.9687368 0.2101843 0.1318014 -0.8830109 -0.4369524 -0.1713612 -0.8323051 0.4423893 -0.3340059 -0.710238 -0.1313786 -0.6915935 -0.6704891 -0.3168589 -0.6708537 -0.290192 0.2108967 -0.9334405 -0.2575383 -0.1336959 -0.9569742 0.0821346 0.1950013 -0.977358 0.1320325 -0.1651473 -0.9773913 0.4545671 0.04672592 -0.8894861 0.4734115 -0.3215343 -0.8200593 0.6655948 0.5094746 -0.5453617 0.7706047 -0.4693139 -0.4311764 0.8925579 0.4241901 -0.1529807 0.9601833 -0.2674266 -0.08081692 0.9238895 0.1478512 0.3529425 0.8418498 0.3942587 0.3685773 0.6588848 -0.4603461 0.5949391 0.5160193 0.4042479 0.7551873 0.3615421 -0.2757025 0.8906601 0.1709983 0.3780922 0.9098384 -0.03796565 -0.5194264 0.8536714 -0.2631215 0.4593214 0.848405 -0.5811045 -0.320232 0.7481772 -0.5978392 -0.05249488 0.7998954 -0.8939887 0.07515978 0.4417411 -0.8991628 0.007968068 0.437542 -0.9733899 -0.1987836 0.1140054 -0.9490765 0.3149815 -0.006364345 -0.9179775 -0.289236 -0.2714039 -0.9273322 0.1053435 -0.3591071 -0.7178751 0.1745377 -0.6739377 -0.6336767 -0.3771981 -0.6754077 -0.3416509 0.373802 -0.8622916 -0.2747153 -0.2715478 -0.9223846 0.07708781 0.1853076 -0.9796523 0.1291676 -0.2175753 -0.9674589 0.4313979 0.2041418 -0.8787617 0.4912118 -0.2306052 -0.8399598 0.690346 0.3473466 -0.6346438 0.7399656 -0.4598394 -0.490916 0.8923034 0.3334233 -0.3043411 0.9571173 -0.2606949 -0.1263518 0.9022297 0.4247445 0.07465702 0.8886262 -0.4009156 0.2227336 0.7668564 0.2296767 0.5993161 0.8054866 -0.2350705 0.5439974 0.4620591 0.4069634 0.7879608 0.296641 -0.5989264 0.7438356 0.06971609 0.4410721 0.8947597 -0.2799794 -0.3970312 0.8740583 -0.2370908 0.443185 0.8645086 -0.5491826 -0.4513452 0.7033392 -0.6966123 0.4978524 0.5165989 -0.8327058 -0.3408371 0.4363843 -0.9138439 0.3932039 0.1013907 -0.9922223 0.095627 0.07969027 -0.8908837 -0.386231 -0.2390645 -0.8338701 0.3735258 -0.4063734 -0.7062034 -0.3891457 -0.5914747 -0.5789939 0.4183062 -0.6998471 -0.2724696 -0.2988435 -0.9145781 -0.228549 0.01426106 -0.973428 0.1559587 -0.01425218 -0.9876608 0.1483296 -0.05486041 -0.9874152 0.5043133 0.264135 -0.8221319 0.5068339 -0.52823 -0.6812434 0.7679562 0.4788649 -0.4253609 0.8316974 -0.4711481 -0.2937671 0.9463813 0.3012779 -0.1165948 0.9460373 -0.2652896 0.1861045 0.9650688 0.04716002 0.2577174 0.8211333 -0.02273935 0.5702834 0.8145065 0.03306311 0.5792117 0.5328075 0.113685 0.8385655 0.5134494 -0.1200303 0.8496838 0.1593647 -0.1675578 0.9728963 0.009720563 0.529969 0.8479613 -0.2251718 -0.4755127 0.8504031 -0.4987856 0.3439956 0.7955376 -0.5911481 -0.2178805 0.7765771 -0.8007968 0.2781468 0.5304328 -0.8130369 -0.3838609 0.4377464 -0.8578863 0.5076686 0.07939749 -0.7881678 -0.6129988 -0.05499196 -0.7019382 0.6105329 -0.3667865 -0.7195835 -0.4385688 -0.5383838 -0.5171071 0.237677 -0.8222591 -0.4774513 -0.1828509 -0.8594217 -0.1124982 0.2889191 -0.9507208 -0.0752108 -0.1050999 -0.9916135 0.3192139 -0.1011779 -0.9422662 0.3652884 0.2136136 -0.906054 0.6757125 -0.2022892 -0.7088665 0.7005106 0.4668949 -0.5397167 0.8251097 -0.4198741 -0.3780208 0.9621793 0.25214 -0.1031344 0.9465202 -0.3215985 -0.0259639 0.813093 0.5095534 0.2814878 0.7707532 -0.4693413 0.430881 0.5976682 0.4242129 0.6803207 0.5715812 -0.267396 0.7757542 0.1829693 0.1479254 0.9719261 0.1267285 0.3941521 0.9102659 -0.1793705 -0.5124909 0.8397495 -0.3694165 0.4317244 0.8228886 -0.7127081 -0.0844056 0.696364 -0.7044463 -0.2247031 0.6732488 -0.9378849 0.1723182 0.3011288 -0.8820101 -0.4129821 0.2269451 -0.8520497 0.4967878 -0.164965 -0.8283661 -0.4710242 -0.3032259 -0.793088 0.3032129 -0.5282739 -0.6291552 -0.3660279 -0.6857021 -0.4842122 0.3476821 -0.8029046 -0.3384987 -0.2239513 -0.9139282 -0.1670842 0.263801 -0.9499958 0.02531808 -0.380948 -0.9242498 0.1974512 0.3106654 -0.929785 0.4793531 -0.2652038 -0.8365928 0.568202 0.3029702 -0.7650853 0.7861763 -0.3561877 -0.505032 0.8817996 0.1294149 -0.4535211 0.9920107 0.07717591 -0.09979432 0.9664023 -0.2498322 -0.06042045 0.9170379 0.3043494 0.2577072 0.7918426 -0.4994324 0.3515005 0.7014225 0.4071235 0.5850275 0.5566144 -0.2500455 0.7922486 0.4275507 0.344709 0.835689 0.1947759 -0.4432527 0.8749798 -0.06520521 0.3209237 0.9448578 -0.154573 -0.2136985 0.9645934 -0.4491723 0.3946265 0.8015699 -0.533897 -0.2504589 0.8076041 -0.8063615 -0.1668354 0.5674039 -0.8379166 0.2276331 0.4960636 -0.9587609 -0.1340501 0.2506158 -0.9612622 0.2266121 0.1569136 -0.965059 -0.232824 -0.1202255 -0.8811075 0.4013591 -0.2501209 -0.755801 -0.4832155 -0.4418911 -0.5791277 0.4697671 -0.6662807 -0.5695019 -0.2078107 -0.7952876 -0.2496138 0.2129867 -0.944632 -0.1732124 -0.2990994 -0.9383694 0.1258694 0.2789316 -0.9520264 0.2033994 -0.1974384 -0.9589822 0.525343 0.2681554 -0.8075317 0.5664176 -0.2782807 -0.7757132 0.8839372 0.1881069 -0.4281015 0.90559 -0.08900278 -0.4147109 0.9860774 0.1646779 0.02307617 0.8850856 -0.4580208 0.0827071 0.809292 0.4360556 0.3935761 0.7044371 -0.4174425 0.5740298 0.6690111 0.2026135 0.7151027 0.2971325 -0.2435133 0.9232625 0.3011272 -0.3013775 0.9047066 -0.117349 0.4951179 0.8608644 -0.2216829 -0.4877399 0.8443735 -0.6123984 0.3145068 0.7252956 -0.6680985 -0.1426783 0.7302652 -0.9126815 0.2471253 0.3254871 -0.9373043 -0.1940898 0.2894647 -0.9895597 0.1180866 -0.08262634 -0.9278862 -0.3504852 -0.1272301 -0.7013106 0.5262361 -0.4808732 -0.6939276 -0.4081947 -0.5931624 -0.4523881 0.1680499 -0.875845 -0.4276559 -0.08135443 -0.9002734 -0.06028765 0.1361925 -0.9888463 -0.04874271 -0.00128436 -0.9988105 0.4344997 -0.07878494 -0.8972196 0.4200941 -0.1534539 -0.8944121 0.7557263 0.2635186 -0.5995297 0.8008764 -0.1052162 -0.5895139 0.9627752 -0.1020449 -0.2503014 0.9141324 0.3829709 -0.1330241 0.9254864 -0.3744485 0.05712527 0.8248617 0.4309287 0.3659287 0.8931139 -0.01275277 0.4496497 0.6632722 -0.2312217 0.711763 0.5816758 0.2450577 0.7756289 0.377355 -0.2056428 0.9029475 0.2065889 0.3818691 0.9008314 0.0258482 -0.3738234 0.9271398 -0.2672954 0.4171774 0.8686289 -0.3539574 -0.2738828 0.8942608 -0.7322539 0.1482098 0.664709 -0.7092483 0.3940547 0.5845408 -0.8370252 -0.4325093 0.3351485 -0.9242316 0.3612348 0.1237153 -0.9701462 -0.2423444 -0.009250879 -0.8924237 0.3694807 -0.2589674 -0.8923568 -0.2718788 -0.3602517 -0.7279812 0.0628553 -0.6827098 -0.7322616 0.03579992 -0.6800819 -0.427226 -0.02126264 -0.9038949 -0.3644322 0.2605795 -0.8940289 0.03061735 -0.4050021 -0.9138031 0.1578822 0.3387587 -0.9275322 0.5395504 -0.1724004 -0.8241139 0.5886728 0.3967556 -0.7043078 0.7241561 -0.5048469 -0.4698167 0.8519798 0.4493731 -0.2686899 0.891532 -0.4509773 -0.04230934 0.9723117 0.2165579 0.08782219 0.8688596 0.1170392 0.4810249 0.7918116 -0.3620749 0.4918702 0.6128678 0.2565095 0.7473928 0.5324708 -0.245561 0.8100461 0.2854033 0.3610357 0.8878054 0.1577275 -0.3758794 0.9131466 -0.1239695 0.2254642 0.966332 -0.1848055 -0.123317 0.9750077 -0.4663969 0.206593 0.8601124 -0.5162048 -0.1247599 0.8473297 -0.7557246 0.1254333 0.6427651 -0.7691436 -0.2388471 0.592765 -0.9402629 0.2025342 0.2736523 -0.9106286 -0.3675092 0.1889252 -0.8927278 0.4412866 -0.09112197 -0.8574038 -0.4094235 -0.3118193 -0.8780798 0.1363245 -0.4586846 -0.716533 -0.1159421 -0.6878502 -0.6403468 0.2368458 -0.7306573 -0.4027857 -0.2327729 -0.8852008 -0.2482252 0.4012926 -0.8816738 0.006810128 -0.5565046 -0.8308168 0.2490521 0.5852106 -0.7716875 0.4674001 -0.5426712 -0.6978862 0.6641143 0.3811905 -0.6431531 0.8785347 -0.3065183 -0.3663648 0.903273 0.3530552 -0.2438238 0.9206737 -0.3842838 0.06845492 0.9508953 0.2344599 0.2020564 0.8202258 -0.1157891 0.5601989 0.8300946 0.1034912 0.5479348 0.5000399 -0.1622781 0.8506621 0.3844478 0.3898434 0.8367927 0.05620378 -0.4613191 0.8854524 -0.1376011 0.4271272 0.8936601 -0.3548197 -0.2616685 0.8975704 -0.4944984 0.1993628 0.8460059 -0.6390837 -0.3016784 0.7075042 -0.7504253 0.3891592 0.5342444 -0.8332768 -0.3481821 0.4294406 -0.8982965 0.4238839 0.1156983 -0.9091131 -0.4165487 6.78882e-4 -0.9095086 0.2894301 -0.2983694 -0.8907667 -0.2164344 -0.3996135 -0.7061687 0.3592315 -0.6101465 -0.6305805 -0.3837062 -0.6746392 -0.3269118 0.2419161 -0.9135674 -0.2434774 -0.3950997 -0.8857849 0.06503319 0.421247 -0.9046114 0.2883285 -0.5604245 -0.7763963 -0.2560487 -0.9462748 -0.1974919 -0.344398 -0.6567171 -0.6709044 -0.1191558 -0.919475 -0.3746568 0.02690917 -0.7774341 -0.6283886 0.08332931 -0.8910754 -0.4461402 0.2407824 -0.8598272 -0.4502456 0.3223304 -0.7982283 -0.5088563 0.4128866 -0.8514487 -0.3233575 0.4078624 -0.858596 -0.3105823 0.5241305 -0.829535 -0.1927668 0.4707872 -0.8701168 -0.1457955 0.4990838 -0.8652446 0.0476132 0.514414 -0.8554989 0.05916088 0.4698728 -0.8352774 0.2855368 0.4348972 -0.8702231 0.2314655 0.3509798 -0.8180857 0.4555755 0.2527931 -0.8845983 0.3918948 0.0786789 -0.8311981 0.5503812 0.06284242 -0.8480994 0.5260972 -0.1019184 -0.8147642 0.5707644 -0.152427 -0.902997 0.4016997 -0.3550557 -0.8140125 0.4596946 -0.3338318 -0.9019992 0.2737769 -0.5143722 -0.8142242 0.2691848 -0.4496608 -0.891444 0.05597186 -0.5855769 -0.8102797 -0.02338063 -0.4991655 -0.8536561 -0.1486778 -0.5406588 -0.8104255 -0.2256073 -0.3971532 -0.8612135 -0.3171448 -0.418748 -0.8042088 -0.4217801 -0.283122 -0.8089218 -0.5152547 -0.1922546 -0.866926 -0.4598671 -0.09865367 -0.8156687 -0.5700458 -0.005356788 -0.8615513 -0.5076424 0.1019064 -0.8075897 -0.5808736 0.1773918 -0.8622477 -0.4744061 0.3213083 -0.8011138 -0.5049532 0.3392235 -0.8545244 -0.3933389 0.4768112 -0.7994952 -0.3653199 0.4463573 -0.8658586 -0.2259516 0.5220875 -0.82982 -0.1970362 0.5810986 -0.8138203 -0.004598915 0.5015112 -0.8643748 0.03664416 0.5537688 -0.8141906 0.1744533 0.4369025 -0.8597258 0.2645519 0.4779692 -0.8363466 0.2684581 0.3573776 -0.8080613 0.4683144 0.2703014 -0.8624973 0.4278264 0.18412 -0.8159912 0.5479583 0.09005773 -0.8667465 0.490551 -0.02878785 -0.8107293 0.5847131 -0.1071358 -0.8536252 0.5097512 -0.2065814 -0.8012131 0.5615886 -0.3007639 -0.8576952 0.4170132 -0.3916051 -0.8078112 0.4405524 -0.472861 -0.8332527 0.2865177 -0.4412228 -0.8671242 0.2311237 -0.5997697 -0.7931762 0.1055842 -0.500119 -0.8659337 -0.006313145 -0.5591936 -0.8258118 -0.07305818 -0.3937783 -0.8989136 -0.1920754 -0.4811025 -0.7896354 -0.3808103 -0.2819564 -0.8446425 -0.45506 -0.2468845 -0.8697528 -0.4272915 -0.07749617 -0.7805769 -0.6202371 0.1060749 -0.8135902 -0.571681 0.03170168 -0.857526 -0.513463 0.2543842 -0.8458725 -0.4688162 0.2403107 -0.8536213 -0.4621489 0.431564 -0.8211774 -0.37339 0.412296 -0.8574898 -0.3077719 0.5597168 -0.8017289 -0.2096374 0.4884232 -0.8659847 -0.1073005 0.6285485 -0.7777702 6.22969e-4 0.3888134 -0.9108476 0.1384955 0.4934558 -0.8065457 0.325554 0.3194475 -0.857252 0.4038222 0.3226063 -0.8440512 0.4283725 0.2301551 -0.7758514 0.5874379 0.04021912 -0.8761071 0.480436 -0.02518355 -0.8145306 0.5795738 -0.1909344 -0.8221837 0.5362445 -0.2068014 -0.8714866 0.4446848 -0.3878192 -0.8027051 0.4530573 -0.4028351 -0.8499373 0.3396035 -0.5061168 -0.8035185 0.3133748 -0.4698699 -0.8662261 0.1699256 -0.5781832 -0.8099355 0.09853351 -0.5243746 -0.8505828 -0.03924673 -0.5622732 -0.8266115 -0.02371478 -0.5050232 -0.8262975 -0.2493672 -0.4905679 -0.8414396 -0.2265449 -0.3987988 -0.8208409 -0.4088762 -0.3109365 -0.8782622 -0.3632825 -0.143567 -0.8594066 -0.4907228 -0.1304095 -0.8287827 -0.5441623 0.04456478 -0.83608 -0.5467945 0.06477302 -0.8188502 -0.5703411 0.2384779 -0.8417653 -0.4843137 0.2441228 -0.8382287 -0.4876234 0.4308391 -0.8232301 -0.3696889 0.3981586 -0.8773535 -0.267807 0.5723212 -0.7871927 -0.2297305 0.5721985 -0.8190181 -0.04240715 0.4960327 -0.8682667 0.008033871 0.5666984 -0.8161603 0.1128511 0.4572849 -0.8458669 0.2745905 0.4684851 -0.8391526 0.2763053 0.4100812 -0.8137829 0.4118143 0.2181393 -0.8930826 0.3934702 0.1974458 -0.8458554 0.4955239 0.03122532 -0.8811545 0.4717963 -0.01436185 -0.832116 0.5544157 -0.2103571 -0.8055679 0.5539047 -0.2208625 -0.8642599 0.4519675 -0.4055707 -0.8046954 0.4335643 -0.3909605 -0.8654718 0.3132231 -0.5460676 -0.7916198 0.2741318 -0.4683379 -0.8795667 0.08379799 -0.5973095 -0.802007 0.002475857 -0.413989 -0.8988425 -0.1438585 -0.5011439 -0.8240374 -0.2642295 -0.2922959 -0.882553 -0.368325 -0.3032864 -0.8159523 -0.4921781 -0.09799879 -0.8114439 -0.5761554 -0.134851 -0.8530373 -0.5041255 0.0508874 -0.860785 -0.5064185 0.1165706 -0.8198036 -0.5606544 0.2627899 -0.8382643 -0.4777598 0.2633559 -0.8485699 -0.4588822 0.4316703 -0.8125629 -0.3916662 0.4066055 -0.858278 -0.3130988 0.5873994 -0.7790981 -0.2190164 0.4769487 -0.8785808 -0.02481353 0.5525907 -0.8315643 -0.05607753 0.5258679 -0.8245884 0.208607 0.4965738 -0.8421601 0.2101925 0.4474805 -0.8169332 0.3638425 0.345847 -0.8635671 0.3669357 0.2959289 -0.8101337 0.5060727 0.2060714 -0.8549439 0.4760309 0.1436304 -0.8128229 0.5645257 0.002744197 -0.899667 0.4365681 -0.1715149 -0.7936214 0.5837362 -0.2309507 -0.8613954 0.4523932 -0.3567286 -0.8028888 0.4776132 -0.3743697 -0.8641915 0.336185 -0.5221595 -0.8000075 0.2955291 -0.4718845 -0.864918 0.1710029 -0.602624 -0.7954463 0.06410682 -0.5012257 -0.8645721 -0.03588747 -0.5857489 -0.7949923 -0.1577516 -0.3747767 -0.9017048 -0.2155712 -0.4212486 -0.7814133 -0.4603726 -0.2234905 -0.887376 -0.4032565 -0.1916949 -0.8155766 -0.5459742 -0.0480374 -0.7954695 -0.6040866 0.0484696 -0.8636767 -0.5017104 0.1420229 -0.806627 -0.5737441 0.2659506 -0.8567396 -0.4418909 0.3160544 -0.8274039 -0.4642333 0.4938074 -0.835717 -0.2402733 0.5253404 -0.8066682 -0.2707473 0.5225548 -0.8519461 -0.03353393 0.5283172 -0.8482411 -0.03698682 0.5603239 -0.8119589 0.1635844 0.4706321 -0.8624334 0.1863176 0.4605465 -0.8073254 0.3689479 0.3503015 -0.8630297 0.3639625 0.3401783 -0.8062162 0.4840395 0.1474447 -0.8296641 0.53844 0.09250658 -0.8721446 0.480423 -0.0392422 -0.7933109 0.6075507 -0.1687089 -0.8635821 0.4751455 -0.210185 -0.8376746 0.5041068 -0.3838865 -0.8070796 0.4486132 -0.4501423 -0.8325391 0.3228787 -0.3956069 -0.8586831 0.3258199 -0.5458184 -0.8249341 0.1468541 -0.5449457 -0.8256525 0.1460555 -0.5575641 -0.8276789 -0.06379747 -0.5327008 -0.8431728 -0.07272934 -0.5365552 -0.8144184 -0.2209779 -0.3582918 -0.8974812 -0.2572057 -0.3879712 -0.8176345 -0.4253847 -0.2282522 -0.8928288 -0.3882755 -0.1231461 -0.8131149 -0.5689282 -0.06320554 -0.8582474 -0.5093296 0.08658897 -0.793678 -0.6021443 0.1565452 -0.8646348 -0.4773891 0.2661753 -0.8144723 -0.5155442 0.3634012 -0.8523947 -0.3759825 0.379542 -0.8439258 -0.3791268 0.547709 -0.7975766 -0.2527582 0.4743479 -0.8655675 -0.1605837 0.5983907 -0.8010907 -0.01351058 0.4998391 -0.8646873 0.0497663 0.5283877 -0.821592 0.2139929 0.4448539 -0.8691239 0.2161687 0.3535662 -0.8528122 0.3843207 0.3626391 -0.8474509 0.3877113 0.2014459 -0.827393 0.5242524 0.1640979 -0.8539112 0.4938699 0.01505041 -0.8062192 0.5914255 -0.0445525 -0.8656622 0.4986423 -0.2159922 -0.7939569 0.5683131 -0.2632471 -0.8635263 0.4301434 -0.39768 -0.8048838 0.4404687 -0.4111142 -0.859089 0.3048795 -0.5272282 -0.8032612 0.2771317 -0.4990165 -0.8593994 0.1114234 -0.5479766 -0.8319878 0.08670705 -0.5906217 -0.8036325 -0.07308161 -0.4820866 -0.8645741 -0.1417899 -0.5371142 -0.8022935 -0.2604486 -0.3921349 -0.8576471 -0.3326735 -0.4049469 -0.8031749 -0.4369535 -0.2133677 -0.8335258 -0.5096167 -0.1961783 -0.8474869 -0.4932342 -0.005528032 -0.8243195 -0.5660979 0.003108799 -0.8364126 -0.5480917 0.2183064 -0.8337724 -0.5071153 0.2163609 -0.8350538 -0.505839 0.3840733 -0.841731 -0.3794427 0.3323923 -0.8694183 -0.3655505 0.5164137 -0.8336129 -0.195976 0.4585803 -0.8791199 -0.1298162 0.6254202 -0.7802184 0.01043635 0.4782092 -0.8637648 0.1588286 0.4967046 -0.8487234 0.1815302 0.502014 -0.7921797 0.3470354 0.2832028 -0.8706498 0.4022004 0.3686412 -0.8088656 0.458083 0.142442 -0.8444137 0.5164067 0.146344 -0.840941 0.5209623 -0.05664545 -0.8083018 0.5860373 -0.1027326 -0.8616613 0.4969767 -0.1603885 -0.84286 0.5136758 -0.2649663 -0.881077 0.3917861 -0.3376798 -0.8442017 0.4162883 -0.4035681 -0.8811392 0.2464277 -0.4939719 -0.8350878 0.242116 -0.4571886 -0.88843 0.04087764 -0.5929422 -0.8038886 -0.04671978 -0.4845948 -0.8628351 -0.143818 -0.5267758 -0.8082687 -0.2630761 -0.3862875 -0.8700476 -0.306267 -0.3840957 -0.7988432 -0.4629472 -0.2288661 -0.864136 -0.4482069 -0.1979136 -0.8081491 -0.5547299 8.92523e-4 -0.8426238 -0.538502 -0.003907203 -0.8467379 -0.531996 0.1767961 -0.8729934 -0.4545612 0.2187469 -0.8487483 -0.4814313 0.3119816 -0.8820272 -0.3531227 0.4025208 -0.837673 -0.3691626 0.4290476 -0.8823369 -0.1933905 0.5079166 -0.8439394 -0.1725898 0.4684825 -0.883428 -0.008900165 0.5318048 -0.8463602 0.02929741 0.4149844 -0.8649601 0.282192 0.5064837 -0.8059825 0.3063766 0.3068628 -0.8517456 0.4246939 0.3036886 -0.8536779 0.4230924 0.1572852 -0.810981 0.5635346 0.08773314 -0.8619363 0.4993683 -0.06853091 -0.8039419 0.5907462 -0.124931 -0.8659146 0.4843388 -0.26199 -0.792942 0.5500948 -0.3855447 -0.8217607 0.4196007 -0.3584095 -0.8738622 0.328493 -0.5384733 -0.7968606 0.2739703 -0.4108455 -0.9069907 0.09259653 -0.5892669 -0.8078003 -0.0149483 -0.431198 -0.8885078 -0.1569153 -0.4894319 -0.8360323 -0.2480049 -0.3743246 -0.8652729 -0.3334424 -0.3936078 -0.8275449 -0.4003027 -0.1861917 -0.8419258 -0.506452 -0.1511488 -0.8643642 -0.479613 -0.04362565 -0.8177371 -0.5739364 0.03939813 -0.8587052 -0.5109534 0.1538249 -0.7989949 -0.5813303 0.232691 -0.8538527 -0.4656078 0.2869262 -0.8262532 -0.4847463 0.4379707 -0.8318309 -0.3409383 0.4157223 -0.863553 -0.2853967 0.5597364 -0.804872 -0.1971706 0.5239183 -0.8447215 -0.1093398 0.5618019 -0.8238109 -0.0755943 0.4495235 -0.8898442 0.07814115 0.5220782 -0.8321508 0.1869745 0.3999832 -0.8855609 0.2362109 0.414996 -0.8364472 0.3579588 0.2764178 -0.8916662 0.3585031 0.2576572 -0.8333228 0.4890664 0.05882179 -0.8850217 0.4618189 0.04046571 -0.8587082 0.510865 -0.1474248 -0.7683205 0.622856 -0.1901796 -0.9016461 0.388415 -0.38956 -0.8210245 0.4173271 -0.3874639 -0.8687132 0.3085599 -0.5582038 -0.7855782 0.2669746 -0.4199908 -0.9029376 0.09116792 -0.5765901 -0.8166278 -0.02575004 -0.4240369 -0.8913384 -0.1603397 -0.4883517 -0.8380572 -0.2432548 -0.3939623 -0.80589 -0.4419672 -0.3134874 -0.8528353 -0.4176096 -0.2545963 -0.8036188 -0.5379384 -0.1030553 -0.8640199 -0.4927973 -0.06706875 -0.8283076 -0.5562448 0.1340278 -0.8249494 -0.5490857 0.1484138 -0.8627925 -0.483283 0.3668956 -0.7903776 -0.4906027 0.3554984 -0.8724662 -0.3352963 0.5158874 -0.7915446 -0.3275935 0.5342407 -0.8319023 -0.1500846 0.4798448 -0.872066 -0.0961762 0.5752769 -0.8174239 0.02957499 0.4305107 -0.8974475 0.09617018 0.5045948 -0.8054515 0.310857 0.3554675 -0.8751551 0.3282478 0.3671915 -0.7915001 0.4885672 0.1468163 -0.8350045 0.5302947 0.1149052 -0.8645367 0.4892578 -0.06873822 -0.780785 0.6210073 -0.1575834 -0.8700115 0.4671696 -0.2472398 -0.8283449 0.5027099 -0.305104 -0.8852704 0.3510102 -0.4190028 -0.8319082 0.3638207 -0.4067608 -0.8964881 0.1756551 -0.6117243 -0.7824099 0.1167401 -0.4879389 -0.8696067 -0.0754987 -0.5612373 -0.8255924 -0.05839681 -0.4782176 -0.8345072 -0.273689 -0.4695644 -0.8447584 -0.2566954 -0.3650614 -0.8156065 -0.4489058 -0.307681 -0.8514586 -0.4246773 -0.1981742 -0.8143857 -0.5454385 -0.1351539 -0.8476489 -0.5130544 -0.06316441 -0.8134567 -0.5781856 0.05727487 -0.8734996 -0.4834439 0.1930298 -0.7977647 -0.5712364 0.2620229 -0.864169 -0.4296 0.347755 -0.8206663 -0.4534019 0.4694915 -0.8154007 -0.3386731 0.4416337 -0.8547697 -0.2726328 0.5789303 -0.8014795 -0.1499016 0.5232305 -0.8473364 -0.09083515 0.5855505 -0.8076816 0.06914603 0.5204725 -0.8482961 0.09748005 0.5208741 -0.8353475 0.1757409 0.3876501 -0.8835741 0.2627247 0.4142328 -0.8320357 0.368955 0.2844146 -0.8424735 0.4575445 0.2841131 -0.8469908 0.4493178 0.1469101 -0.7912533 0.5935788 -0.009890377 -0.8676887 0.4970096 0.008468508 -0.8410678 0.5408636 -0.1989611 -0.8221302 0.5334011 -0.2078828 -0.8586036 0.4685987 -0.4219954 -0.7750859 0.4702785 -0.4102771 -0.8639766 0.2919198 -0.5329078 -0.8047968 0.2613646 -0.5053786 -0.8535497 0.1266711 -0.5691636 -0.8181601 0.08165019 -0.5017428 -0.8601793 -0.09135496 -0.5251883 -0.8434655 -0.1128872 -0.558317 -0.7738273 -0.2991212 -0.3342638 -0.8758037 -0.3481889 -0.3906457 -0.8396503 -0.3773372 -0.2083898 -0.8326262 -0.5131347 -0.1757122 -0.8510008 -0.4948968 -0.0865786 -0.8094007 -0.5808398 0.0233404 -0.8594565 -0.5106757 0.1160548 -0.8002843 -0.5882825 0.2433779 -0.8571668 -0.453908 0.2982119 -0.8247064 -0.4805508 0.4739289 -0.8178444 -0.3263769 0.4349074 -0.8624986 -0.2587505 0.5699736 -0.8041179 -0.1688925 0.4446487 -0.8951376 -0.03187882 0.5817832 -0.8019469 0.1356819 0.4798082 -0.8586609 0.1802375 0.4933294 -0.8038899 0.3322459 0.3766713 -0.861276 0.3410609 0.3678067 -0.8340776 0.411136 0.1807732 -0.8794192 0.4403896 0.1519712 -0.8215487 0.5495112 -0.04769575 -0.8280464 0.5586271 -0.01934868 -0.8553422 0.5177021 -0.2287538 -0.8081214 0.5427814 -0.2332929 -0.90818 0.3475393 -0.430698 -0.8190689 0.3789798 -0.4227657 -0.8845188 0.1972205 -0.5200477 -0.8359345 0.1753969 -0.592699 -0.8013409 0.08099877 -0.5040234 -0.8636893 -0.001133978 -0.5958134 -0.7885382 -0.1523613 -0.4431762 -0.8630404 -0.2423968 -0.4852787 -0.8054711 -0.3401781 -0.3782288 -0.8260301 -0.4178725 -0.2443146 -0.8925021 -0.3791446 -0.1844416 -0.8289976 -0.5279624 -0.07093733 -0.8621589 -0.5016474 -0.01525121 -0.8017547 -0.5974587 0.1559168 -0.8941061 -0.4198384 0.3285261 -0.7876827 -0.5211782 0.3609201 -0.8677077 -0.3417894 0.3891223 -0.855431 -0.341792 0.4967613 -0.8498167 -0.1761817 0.4255323 -0.8983138 -0.1093385 0.5812425 -0.8128947 0.03687167 0.4987795 -0.8503577 0.167663 0.4925876 -0.8553217 0.1605691 0.4641386 -0.7885536 0.4034337 0.3109138 -0.8869433 0.3415614 0.1620469 -0.8504698 0.5004419 0.1576534 -0.828876 0.5367588 -0.07334822 -0.8305494 0.5520941 -0.09603625 -0.8705065 0.4826962 -0.3060219 -0.7791655 0.547039 -0.3516703 -0.8682432 0.3499742 -0.3923122 -0.8475732 0.3573664 -0.5571199 -0.801882 0.2158766 -0.4836782 -0.8682095 0.1107597 -0.5940537 -0.8043904 0.007509469 -0.4958031 -0.8633027 -0.09427547 -0.5731952 -0.7913938 -0.2124692 -0.4265961 -0.8144721 -0.3932569 -0.4133885 -0.8477945 -0.3321967 -0.24014 -0.8474915 -0.4733827 -0.2381576 -0.8343171 -0.4971883 -0.08834403 -0.7973483 -0.5970185 0.03510659 -0.8760771 -0.4808914 0.1213359 -0.816908 -0.5638609 0.2927967 -0.8320341 -0.4711576 0.2824918 -0.8670871 -0.410315 0.512847 -0.7846197 -0.3483678 0.4735376 -0.8574014 -0.2015566 0.5511502 -0.817151 -0.1688128 0.5311511 -0.8472612 0.00519824 0.540178 -0.8414648 0.0120365 0.51943 -0.8306527 0.200521 0.4694377 -0.8567284 0.2136464 0.4576507 -0.803829 0.3800197 0.3571714 -0.8581916 0.368695 0.2728788 -0.8117076 0.5163992 0.195039 -0.8732579 0.4465205 8.53713e-4 -0.8476241 0.5305966 -0.01960188 -0.8754628 0.4828879 -0.2241401 -0.8431231 0.4887787 -0.223623 -0.8367073 0.4999138 -0.3891503 -0.8377578 0.3830456 -0.3701228 -0.8480693 0.3791933 -0.5087291 -0.81075 0.2896189 -0.4751248 -0.8607874 0.1824873 -0.5876563 -0.8013479 0.1118115 -0.5081191 -0.8612844 -0.002078711 -0.5985942 -0.7901228 -0.131876 -0.4182173 -0.8918467 -0.1723482 -0.388534 -0.8406 -0.3774032 -0.3745245 -0.8623792 -0.3406372 -0.216392 -0.857792 -0.4662268 -0.170886 -0.8891349 -0.4245435 4.02858e-4 -0.8042595 -0.5942783 0.1028287 -0.8679006 -0.4859784 0.1588141 -0.8307228 -0.5335519 0.3354969 -0.8029121 -0.492721 0.3284509 -0.8624481 -0.3851017 0.4977468 -0.7940181 -0.348975 0.5278629 -0.8348341 -0.1562464 0.4698415 -0.8653173 -0.1745709 0.5575937 -0.8286696 0.04895055 0.5166008 -0.8536357 0.06655764 0.5188703 -0.8166511 0.2526949 0.4437528 -0.8578261 0.2592642 0.4254209 -0.7982882 0.4263251 0.2857242 -0.8474274 0.4474689 0.2453885 -0.8733497 0.4207671 0.1243488 -0.7858921 0.6057319 -0.03149265 -0.8584122 0.5119931 -0.08443874 -0.816838 0.5706539 -0.1874597 -0.893091 0.4089589 -0.3896681 -0.8051786 0.4470419 -0.3740307 -0.8689657 0.3240367 -0.5447135 -0.7890918 0.2839391 -0.4816782 -0.8693897 0.1102165 -0.6003435 -0.7987931 0.0389564 -0.5657697 -0.8225711 -0.05728483 -0.4553763 -0.8845376 -0.1011214 -0.4794664 -0.8386542 -0.2584013 -0.3708826 -0.8919117 -0.2587268 -0.3586123 -0.8023235 -0.4771524 -0.2097033 -0.8627372 -0.4601185 -0.1789615 -0.8099482 -0.5585309 0.007335901 -0.8377831 -0.5459539 -0.007309317 -0.8153476 -0.5789256 0.2149071 -0.803178 -0.5556259 0.1454771 -0.8445695 -0.5153045 0.4029918 -0.7836255 -0.4727882 0.3909084 -0.8398233 -0.3766797 0.5318845 -0.7839894 -0.3200933 0.4810584 -0.8630314 -0.1541424 0.5615904 -0.8179476 -0.1248116 0.5720317 -0.8151687 0.09099423 0.4851483 -0.8670892 0.1130824 0.5875728 -0.7561464 0.2880992 0.3949966 -0.8432242 0.3646242 0.3949621 -0.8432313 0.3646451 0.3253765 -0.6894528 0.6471361 0.2040256 -0.8450422 0.4942442 5.9337e-4 0.4350824 0.9003904 0.825132 -0.5032933 -0.2566191 0.880217 0.4738229 0.02664852 0.9568647 -0.2419058 0.1609083 0.902065 0.3423011 0.2628853 0.8329775 -0.1949763 0.5178154 0.511609 0.1685378 0.8425267 0.1253629 -0.4102923 0.9032964 -0.2769193 0.5995757 0.7508826 -0.5793669 -0.4219749 0.6973316 -0.6123495 0.5676144 0.550311 -0.6574571 -0.6778638 0.3290151 -0.7413344 0.6486371 0.1723175 -0.8460828 -0.5316885 -0.03809744 -0.9059898 0.3419676 -0.2494809 -0.7575323 -0.243961 -0.6054982 0.9843639 -0.1586597 0.07651847 0.7177229 0.5023311 0.4822213 -0.6160881 0.03670132 -0.7868219 -0.2283865 0.07249712 -0.9708676 0.30922 0.7582494 0.5739696 0.2793317 -0.5639503 0.7771319 -0.01257687 0.5709151 0.8209128 -0.6701623 -0.7421807 -0.007099628 -0.6922701 0.6903488 -0.2101924 -0.5989735 -0.7310076 -0.3268924 -0.4881743 0.7086315 -0.5094383 -0.3738259 -0.6965437 -0.6124387 0.1018126 0.3336526 0.937182 -0.2779939 -0.2418662 0.9296344 -0.7488548 -0.620887 -0.2317667 -0.6911036 0.5492402 -0.4697989 -0.5462346 -0.5777612 -0.6064816 0.5036966 -0.828608 -0.2443329 -0.6775171 0.5796787 -0.4527065 -0.552231 -0.5318663 -0.6419962 -0.5318499 0.3171147 -0.7852222 -0.1997561 -0.238907 -0.9502742 0.7227863 -0.6072691 0.3298549 0.6759619 0.4998658 0.5414885 0.5314501 -0.6091185 0.5886727 0.6314128 -0.5012102 -0.5916979 0.9256634 0.1613117 -0.3422366 -0.3674975 0.7347077 0.5702194 -0.5165557 -0.6122986 0.5985488 -0.748809 0.5329377 0.3940336 -0.7688116 -0.538348 0.3451237 -0.7881066 0.6142636 0.03959983 -0.710579 -0.7011322 -0.05908548 0.1157854 -0.002712249 -0.9932705 0.4254049 -0.3577921 -0.8312734 0.4713571 0.5385224 -0.6984384 0.645866 -0.5272505 -0.552145 0.6702346 0.6462388 -0.3649124 0.7414716 -0.6308436 -0.2285962 0.8111142 0.5846575 -0.01641458 0.8135988 -0.5768622 0.0727142 0.7260074 0.6178329 0.3019865 0.5521829 -0.7422084 0.3797643 -0.9050872 -0.1985351 0.3760333 -0.8714358 0.4904253 0.009102761 -0.8104435 -0.5843595 -0.0412988 -0.7723767 0.5114108 -0.3766875 -0.6505446 -0.2573621 -0.7145324 -0.3388876 -0.01863634 -0.9406422 0.8332977 0.5493171 0.0621764 0.763287 -0.5724338 0.2995207 0.6558462 0.6215513 0.4284153 0.61851 -0.5403247 0.5705214 0.4282523 0.5738845 0.6980378 0.3763279 -0.4949334 0.7832102 0.08340108 0.5034696 0.8599783 -0.2379781 -0.4946958 0.8358483 -0.5591715 0.5814603 0.5909578 -0.6445207 -0.7056826 0.2942876 -0.7576369 0.6526681 0.003277778 -0.8605291 -0.5051359 -0.06578296 -0.8173532 0.4039171 -0.4108344 0.9829711 0.1051889 0.150676 0.8126647 0.3011348 0.4988928 -0.525672 0.3395701 0.7799751 -0.6136786 -0.6077144 0.5040652 -0.6530938 0.6842221 0.3245132 -0.7392414 -0.6589699 0.1388556 0.457776 0.8013964 0.3849741 0.9613259 0.2240477 -0.1601725 0.9112704 -0.3496454 0.2175647 0.4066295 0.5771272 0.7082208 0.2176593 -0.5630608 0.7972372 -0.3956767 0.7208958 0.5689896 -0.5898177 -0.6369231 0.4964315 -0.6663138 0.6811197 0.303483 -0.2085949 0.807004 -0.5524787 -0.003909409 -0.7231972 -0.6906306 0.2887335 0.6336166 -0.7177487 0.3563977 -0.7450663 -0.5637881 0.6252901 0.7076398 -0.3290264 0.7901598 -0.5603622 -0.2482775 0.7846717 0.6194312 0.02440285 0.5922232 -0.5811848 0.5581183 0.3216602 0.6131798 0.7214884 0.1878632 -0.7338039 0.6528702 0.3381793 -0.6216445 0.7065359 0.02228379 0.629196 0.7769272 -0.03284364 -0.4930273 0.8693937 -0.4106621 0.2331141 0.8814843 -0.7842606 -0.585381 -0.2055839 -0.6284065 0.6103119 -0.4823119 -0.5693303 -0.6070222 -0.554425 -0.4205007 0.56193 -0.7123299 -0.3081606 -0.6102753 -0.7297953 -0.01103985 0.6710343 -0.7413441 -0.1297649 -0.6862302 0.7157159 -0.4028301 0.5924983 0.69762 -0.5162795 -0.6239238 0.5866641 -0.6800762 0.6764128 -0.2827757 -0.6842013 -0.6135147 -0.3942947 -0.4931796 0.5853469 -0.6435394 -0.002114057 0.4626434 0.886542 -0.164656 -0.3038514 0.9383831 -0.480596 0.1782733 0.8586305 -0.2077755 -0.9276474 0.3103223 -0.3035653 -0.8077386 0.5053777 -0.4989419 -0.5392637 0.6784185 -0.4324557 -0.3408585 0.834744 -0.4283663 -0.1339831 0.8936167 -0.2305346 -0.7103804 0.6649914 -0.08116781 -0.9159424 0.3930159 -0.1697096 -0.7296875 0.6623858 -0.1353291 -0.6039592 0.7854422 -0.01942276 -0.9613951 0.2744855 -0.1898154 -0.2499146 0.9494803 0.008193254 -0.9957619 0.09160375 0.02225589 -0.6234474 0.7815486 0.07076573 -0.7602382 0.6457786 0.003321468 -0.01057744 0.9999386 0.0967707 -0.22675 0.9691337 0.1945945 -0.7417856 0.6417843 0.1776009 -0.1579048 0.9713516 0.2097396 -0.8204399 0.531872 0.2953431 -0.4229994 0.856647 0.4462386 -0.2958323 0.8446031 0.3033825 -0.7946264 0.5258595 0.4917372 -0.4389171 0.7520282 0.3041604 -0.8714174 0.3848615 0.227572 -0.9454824 0.232968 0.5899034 -0.5693208 0.572615 0.6237328 -0.3949184 0.6745346 0.7103671 -0.1642113 0.6844072 0.5459591 -0.7766717 0.3141812 0.6211884 -0.6538086 0.4320411 0.5555202 -0.7846997 0.2750341 0.8375981 -0.2077947 0.5052235 0.7124425 -0.6562913 0.2484099 0.8747454 -0.1223351 0.4688867 0.192448 -0.9805792 0.03779101 0.8889271 -0.2534047 0.3815689 0.741508 -0.6448872 0.1851662 0.9200766 -0.3619174 0.1499163 0.3140852 -0.9490781 0.02452242 0.5686789 -0.8212979 0.04554337 0.9617113 -0.1274093 0.2426484 0.9492948 -0.3142868 0.007959723 0.7222361 -0.6907393 -0.0354157 0.9957042 0.001761078 -0.09257483 0.3121163 -0.9466802 -0.07987457 0.6790876 -0.7142353 -0.1694339 0.5704792 -0.798111 -0.1938362 0.9194271 -0.3089272 -0.2433472 0.5822181 -0.7506456 -0.3123356 0.4241573 -0.856345 -0.2945572 0.6529759 -0.6613335 -0.369135 0.8932623 -0.2120103 -0.3964017 0.8460599 0.1925715 -0.4970903 0.04224759 -0.9981399 -0.04395425 0.7291903 -0.3557221 -0.5845882 0.644483 -0.4107666 -0.6449128 0.4503726 -0.7175137 -0.5313554 0.3768843 -0.75471 -0.537002 0.5921661 -0.182846 -0.7847973 0.1534995 -0.9411501 -0.301122 0.4111663 -0.440438 -0.7980958 0.4372971 -0.4634829 -0.7706848 0.1104518 -0.8535049 -0.5092444 0.3382638 -0.1350587 -0.9313092 0.1515215 -0.7194306 -0.6778355 0.1145778 -0.8070428 -0.5792701 0.1474773 -0.4034226 -0.9030508 -0.01172542 -0.7668932 -0.6416678 -0.03890138 -0.6324365 -0.7736347 0.07504636 -0.3417121 -0.9368035 -0.01277798 -0.9726381 -0.2319741 -0.05838036 -0.9066808 -0.4177581 0.003964543 -0.04316926 -0.9990599 -0.1853389 -0.5042605 -0.843428 -0.2020671 -0.2636381 -0.94322 -0.1672087 -0.8462273 -0.5059059 -0.2465696 -0.6582939 -0.7112333 -0.166635 -0.9499376 -0.2642945 -0.3027087 0.05061542 -0.9517382 -0.4395642 -0.4578937 -0.7727333 -0.4555199 -0.4020369 -0.794272 -0.4432725 -0.7040458 -0.5548234 -0.3452903 -0.8478444 -0.4024107 -0.6294783 -0.01016551 -0.7769517 -0.7014514 -0.3920472 -0.5952017 -0.7030957 -0.3867989 -0.5966935 -0.4361436 -0.8395599 -0.3239103 -0.2332627 -0.9664049 -0.1079364 -0.6051329 -0.6876114 -0.4012541 -0.8509625 -0.06988126 -0.5205568 -0.4020769 -0.9067373 -0.1271281 -0.7445271 -0.5877779 -0.3165386 -0.8497856 -0.3899381 -0.3547009 -0.6582479 -0.7251969 -0.2019882 -0.9456839 -0.1908594 -0.2631627 -0.7609176 -0.641119 -0.0998544 -0.5405396 -0.8412612 0.009835124 -0.9517894 -0.267988 -0.1492633 -0.7218096 -0.6916913 -0.02353894 -0.9903767 -0.1200646 -0.06883627 -0.4080423 -0.9108837 0.06158328 -0.2645495 -0.9626975 0.05680906 -0.9113829 -0.4003239 0.0955103 -0.9170188 -0.3676352 0.154664 -0.7592448 -0.6076515 0.233039 -0.8773809 -0.42886 0.2151324 -0.6762329 -0.6316127 0.3791764 -0.8832802 0.07237529 0.4632257 -0.3714072 -0.8872444 0.2735948 -0.5045326 -0.7845507 0.3604542 -0.8209493 -0.2418895 0.5172348 -0.1677039 -0.9682195 0.1855435 -0.6334671 -0.416629 0.6520275 -0.609906 -0.3765411 0.6973031 -0.6561482 -0.2171199 0.722723 0.00370121 -0.999966 -0.007375299 -0.007678329 -0.9999136 -0.01066845 -0.005788803 -0.9999729 -0.004562437 0.02766245 -0.9993185 -0.02443808 -0.00135076 -0.9999971 -0.002009272 0.005820512 -0.9999641 0.006162285 -0.001338899 -0.9999977 0.00170648 4.19908e-4 -0.9999937 0.003529489 0.5928374 -0.4881299 -0.6405256 0.1672472 -0.9663239 -0.1955672 0.514996 -0.7563859 -0.4033107 0.7094631 -0.5247663 -0.4704067 0.5240095 -0.7514283 -0.400961 0.3863289 -0.9003378 -0.2003548 0.8145076 -0.4093893 -0.4110693 0.6381114 -0.7371129 -0.2224375 0.5570035 -0.8067733 -0.1971399 0.8194821 -0.5368221 -0.2006769 0.02320122 -0.9996932 -0.008680462 0.8653398 -0.4895393 -0.1074175 0.8115965 -0.5804635 -0.06613302 0.3105133 -0.9492654 -0.04976731 0.3837787 -0.9226599 -0.03758323 0.8251231 -0.5648314 0.01171821 0.7150101 -0.694872 0.07689875 0.4530499 -0.8906556 0.03845131 0.7754849 -0.6141599 0.1463934 0.2990531 -0.9526042 0.05579012 0.7224092 -0.6566072 0.2167764 0.5669931 -0.8014612 0.190207 0.8416713 -0.4389468 0.3145078 0.7978969 -0.4069946 0.4446527 0.7246046 -0.5225384 0.4493348 0.439502 -0.8680534 0.2309138 0.5149183 -0.79618 0.3177369 0.7232586 -0.3412937 0.6003462 0.05461287 -0.9977699 0.03837603 0.5810177 -0.5588821 0.5916665 0.3451735 -0.8835865 0.3164337 0.4377623 -0.7549189 0.4883253 0.4615382 -0.4521586 0.7632399 0.4128248 -0.761163 0.5002067 0.3226714 -0.569929 0.7556879 0.1605036 -0.9368131 0.3108376 0.3127344 -0.4772856 0.8212161 0.1788638 -0.8947297 0.4092268 0.1509304 -0.5784235 0.8016524 0.1162915 -0.3336169 0.9355085 0.05562156 -0.8914428 0.4497066 0.05553549 -0.8885844 0.455339 -0.03688246 -0.4870999 0.8725672 -0.06142902 -0.7317195 0.6788322 -0.1061072 -0.7681618 0.6314021 -0.2012901 -0.6180327 0.7599459 -0.3232166 -0.5186132 0.7915627 -0.07188463 -0.9651591 0.2515961 -0.03181195 -0.9962077 0.08098322 -0.3504315 -0.6021736 0.7173457 -0.2861957 -0.7999535 0.527415 -0.5075793 -0.3642398 0.7808282 -0.2665644 -0.8689953 0.416882 -0.5575537 -0.4838022 0.6745884 -0.5506623 -0.5172092 0.6551837 -0.3820495 -0.8031559 0.457142 -0.327163 -0.8961574 0.2997771 -0.7126529 -0.4277577 0.5560119 -0.6496415 -0.6156696 0.4460011 -0.4903033 -0.7983629 0.349599 -0.7602117 -0.5072484 0.4059279 -0.7096816 -0.6483211 0.2757387 -0.3911201 -0.9010699 0.1873447 -0.7892022 -0.5623474 0.2468308 -0.7556502 -0.6069945 0.2460702 -0.1862758 -0.9803548 0.06485241 -0.9354044 -0.3253041 0.1385495 -0.4551427 -0.8865033 0.08340942 -0.8658616 -0.498409 0.04326868 -0.893924 -0.4482185 -2.42479e-4 -0.5063555 -0.8613324 0.04136025 -0.3737682 -0.9272567 -0.02219134 -0.6939754 -0.7089374 -0.1257225 -0.747824 -0.6377118 -0.1846155 -0.7521752 -0.6344416 -0.1780915 -0.8619506 -0.3259757 -0.3883052 -0.6040301 -0.7652525 -0.2225677 -0.1725381 -0.9809201 -0.08959126 -0.7302841 -0.5502901 -0.4048036 -0.6697959 -0.6482392 -0.3621593 -0.7682197 -0.3656917 -0.5254599 -0.3604986 -0.8990609 -0.248456 -0.5596441 -0.6120789 -0.558711 -0.5893628 -0.4833419 -0.6473269 -0.3935486 -0.8345029 -0.3856479 -0.5454709 -0.4466459 -0.7092031 -0.2067734 -0.9375572 -0.2796986 -0.3698495 -0.6695967 -0.6440898 -0.3523136 -0.6201009 -0.7009636 -0.04490458 -0.994768 -0.09176212 -0.251483 -0.6602296 -0.7077099 -0.2421321 -0.6732234 -0.6986719 -0.07787555 -0.9591949 -0.27181 -0.1056805 -0.6219893 -0.7758616 -0.0989257 -0.6321684 -0.7684901 -0.04969346 -0.8874767 -0.4581658 0.006547391 -0.5715083 -0.8205702 0.07240957 -0.7131052 -0.6973076 0.01824116 -0.9272622 -0.3739682 0.1624863 -0.6311408 -0.7584587 0.2004709 -0.6688546 -0.7158526 0.02744156 -0.9909918 -0.1310812 0.3304498 -0.4952108 -0.8034732 0.3655372 -0.5562564 -0.7462986 0.1334025 -0.9283629 -0.3469095 0.1942498 -0.9020566 -0.3854362 0.4917352 -0.4405863 -0.7510527 0.5002806 -0.5525805 -0.6666139 0.2163583 -0.9255586 -0.3106937 0.6946074 1.97941e-4 -0.719389 0.7145029 -0.00413531 -0.6996202 0.7765381 -4.20554e-4 -0.6300702 0.7943266 -0.003412067 -0.6074815 0.8774634 0.004336357 -0.4796243 0.9086007 -0.00576657 -0.4176262 0.9514715 0.00122863 -0.3077347 0.9527716 6.63218e-4 -0.3036873 0.9932135 3.61159e-4 -0.1163057 0.9936494 -4.06232e-4 -0.1125206 0.9978147 -0.001940548 0.06604772 0.9984992 -4.65936e-4 0.05476438 0.9860396 0.001164674 0.1665071 0.9878317 -4.59179e-4 0.1555261 0.9466893 0.001714527 0.3221438 0.9460059 0.001361548 0.3241469 0.9020773 0.002714693 0.4315661 0.8752447 -0.003158688 0.4836701 0.8247051 0.004157543 0.5655477 0.7630239 -8.08929e-4 0.6463699 0.7643663 -4.14157e-4 0.6447823 0.6395511 0.003232717 0.7687419 0.6214615 -0.001292765 0.7834438 0.5525008 -0.007884144 0.8334751 0.454082 0.005229353 0.8909446 0.3531401 -0.0064314 0.9355484 0.2565062 0.005415022 0.9665274 0.1312046 -0.004577159 0.9913448 0.09112441 0.001988351 0.9958376 -0.04354989 0.002647876 0.9990478 -0.09710919 -0.005906164 0.9952563 -0.253906 0.003469884 0.9672228 -0.2071485 -0.003355205 0.9783037 -0.4003883 0.005931079 0.9163264 -0.358197 -9.23706e-4 0.9336457 -0.5791171 0.004693925 0.8152309 -0.5286158 -0.002778708 0.8488567 -0.6663267 -0.001482307 0.7456585 -0.70916 0.004665374 0.7050321 -0.7910329 -0.004788458 0.6117549 -0.8214685 0.00172615 0.5702512 -0.8878673 -5.78e-4 0.4600993 -0.8864656 3.09012e-6 0.4627948 -0.9368934 -0.00304085 0.3496022 -0.9670425 0.008805811 0.2544631 -0.9880722 -0.003142833 0.1539589 -0.997259 0.004932105 0.07382547 -0.9975763 -0.002662181 -0.06952953 -0.9981257 -7.12437e-4 -0.06119322 -0.9801219 -0.007862627 -0.1982406 -0.95367 0.007614791 -0.3007584 -0.9261732 0.003654241 -0.3770807 -0.9164485 -0.001241683 -0.4001508 -0.8118355 -9.85504e-4 -0.5838854 -0.8163267 8.22758e-4 -0.5775899 -0.6722066 0.004280328 -0.7403513 -0.7041448 -0.002116322 -0.7100532 -0.5555924 -0.001916408 -0.8314527 -0.5691077 0.00140506 -0.8222618 -0.456238 -0.004807233 -0.8898448 -0.389887 0.002566754 -0.9208592 -0.3067305 -0.006382524 -0.9517751 -0.2034307 2.78048e-4 -0.9790893 -0.16576 -0.005332827 -0.9861518 0.03454613 9.41202e-4 -0.9994027 0.01338684 -0.003565132 -0.999904 0.1050267 0.003504753 -0.9944633 0.1846759 -0.004255354 -0.9827903 0.2870125 0.003581166 -0.9579202 0.3638514 -0.004641413 -0.9314455 0.4393809 0.00339055 -0.8982945 0.5583472 5.2649e-5 -0.8296075 0.5442236 -0.002615213 -0.8389362 -0.01115429 -0.9995434 -0.02808248 -0.005013644 -0.9999339 -0.01035565 -0.01641535 -0.9998338 0.007938981 -0.01648139 -0.9997361 0.01600641 -0.01640731 -0.999858 0.003854334 -0.003153264 -0.999774 0.02102875 -0.00994718 -0.9999318 0.0061329 0.01149302 -0.9997661 -0.01832067 0.01076227 -0.9997782 0.01810681 -4.46388e-4 -0.9999938 0.003499686 4.71143e-4 -0.9999994 0.001111328 7.7248e-4 -0.9999995 -7.08271e-4 -0.001446545 -0.9999919 0.003759026 -9.08691e-4 -0.9999921 0.003871917 1.91088e-5 -0.9999998 -6.99678e-4 7.55248e-4 -0.9999955 0.00291419 3.90718e-4 -0.9999995 -9.41936e-4 0.003048479 -0.9999912 0.0028795 -0.002803981 -0.9999899 -0.00353384 -0.007146537 -0.9998679 0.01459598 0.005943655 -0.9999794 -0.00242114 0.01552301 -0.9998295 0.01000553 -0.00113517 -0.999787 -0.02061218 0.0220434 -0.9996449 -0.01496964 0.004774689 -0.9999634 0.007115721 0.03689485 -0.9992036 0.01520228 6.63819e-4 -0.9999973 -0.002256393 0.003010571 -0.9999429 -0.01025283 0.5189541 0.5699694 -0.6370412 0.188959 0.9528477 -0.2374359 0.4940328 0.4749904 -0.7282278 0.3785095 0.564784 -0.7333142 0.3832768 0.5568666 -0.7368843 0.2204485 0.8639934 -0.4526789 0.1520828 0.8998721 -0.40878 0.2415691 0.5259641 -0.8154792 0.2114207 0.5820787 -0.785166 0.02902179 0.9858076 -0.1653521 0.1228309 0.565588 -0.8154894 0.05753123 0.6881575 -0.7232769 0.03106832 0.9911782 -0.1288435 -0.04960066 0.7253825 -0.6865567 -0.07217466 0.5375278 -0.8401516 -0.0368883 0.741066 -0.670418 -0.2033706 0.243217 -0.9484124 -0.1082517 0.815941 -0.5679101 -0.2752529 0.4214065 -0.8640905 -0.3635279 0.2501125 -0.8973802 -0.222135 0.7065129 -0.6719343 -0.2566694 0.8006157 -0.54142 -0.396337 0.5787465 -0.7127198 -0.05791467 0.9891329 -0.1351372 -0.1859701 0.9187992 -0.3481715 -0.4895706 0.4686052 -0.7353433 -0.5487223 0.5679251 -0.6134859 -0.5233768 0.6519584 -0.5486593 -0.3999001 0.8077783 -0.4330984 -0.5972409 0.615309 -0.5144884 -0.8039311 0.1871896 -0.5644953 -0.1938114 0.9695927 -0.1494233 -0.7957893 0.4369627 -0.419265 -0.509667 0.8035747 -0.3074203 -0.615664 0.7256893 -0.3071368 -0.5805187 0.7905111 -0.1951674 -0.8362241 0.5126515 -0.1947246 -0.6530627 0.7361903 -0.1775755 -0.9361848 0.3428253 -0.07764691 -0.81805 0.5740343 0.03576236 -0.4927711 0.8700156 -0.01579535 -0.7892546 0.612631 0.04196041 -0.7543514 0.6425256 0.1345919 -0.1855649 0.9824857 0.01695716 -0.8559926 0.463222 0.2295696 -0.4675216 0.8758851 0.1193693 -0.6881988 0.6556653 0.310621 -0.529916 0.8159061 0.2312714 -0.3797274 0.9050621 0.1914932 -0.7345774 0.5665368 0.3734062 -0.6853261 0.5431029 0.4851468 -0.604249 0.6315299 0.485853 -0.6814315 0.2657827 0.681917 -0.3981695 0.8402915 0.3679283 -0.3483535 0.8821631 0.3169201 -0.07898378 0.9922091 0.0963478 -0.4949938 0.535465 0.6842941 -0.4719125 0.5805352 0.6635341 -0.3922129 0.6482103 0.6526811 -0.3800739 0.4435388 0.8116756 -0.2191146 0.8712378 0.4392423 -0.1892367 0.7141528 0.6739253 -0.1578572 0.8468524 0.5078604 -0.1630954 0.5496031 0.8193512 -0.02694225 0.9727911 0.2301122 -0.05360877 0.5506314 0.8330254 -0.02920508 0.5995601 0.7997968 -3.12662e-4 0.9097058 0.4152532 0.06818187 0.524814 0.848482 0.1407677 0.6639111 0.734443 0.1065511 0.8380535 0.5350823 0.2520353 0.4356794 0.8640959 0.3739456 0.4941692 0.7848321 0.1164093 0.9375251 0.3278654 0.3523527 0.6793231 0.6437141 0.3459789 0.6774227 0.6491512 0.6001856 0.3635783 0.7124522 0.380153 0.8114572 0.4438704 0.5302215 0.6557027 0.5375121 0.4599405 0.7464039 0.480974 0.6327328 0.5391755 0.555823 0.7105766 0.5604274 0.4254434 0.3228286 0.9222323 0.2127658 0.7303231 0.5256655 0.4362385 0.6319668 0.7018738 0.3286202 0.5033154 0.8230676 0.2631224 0.79991 0.5403392 0.2611083 0.7356536 0.659059 0.1563816 0.3585746 0.9268746 0.1110306 0.7443627 0.6506525 0.1502513 0.1554794 0.987392 0.0297231 0.8540655 0.5200735 -0.009786427 0.6912137 0.7226381 -0.004221856 0.6381282 0.769397 0.02864724 0.9377485 0.3323434 -0.100875 0.5501576 0.8309154 -0.08310395 0.7888268 0.5876818 -0.1799508 0.3588806 0.9293416 -0.08676898 0.8142658 0.5174114 -0.2631669 0.7475808 0.5995513 -0.2857644 0.4660779 0.8623084 -0.1979791 0.7892223 0.4323893 -0.4360823 0.3894796 0.8977025 -0.2060005 0.637889 0.6238914 -0.4515055 0.556801 0.7310689 -0.3943489 0.6793454 0.4969782 -0.5399097 0.6115252 0.441642 -0.6564978 0.3026362 0.8914697 -0.3371844 -0.9925147 0.02094495 -0.1203162 -0.9913723 0.02855682 -0.1279283 -0.600382 0.02580767 0.7992969 -0.5956586 0.02004647 0.8029877 0.3937176 0.02539455 0.9188807 0.3942841 0.02599197 0.918621 0.6601664 0.748277 0.06528437 0.8383231 0.533792 0.1108184 0.2501707 0.7439329 0.61966 0.3421421 0.5331751 0.7737333 -0.3935233 0.7394284 0.5462464 -0.5098704 0.5468084 0.6641031 -0.7276529 0.6791602 -0.0962429 -0.832111 0.5468198 -0.09262526 -0.2616726 0.7371111 -0.6230528 -0.290736 0.6826444 -0.6704247 0.402819 0.7403172 -0.5382075 0.4031436 0.7399253 -0.5385033 -0.3917719 0.02293354 -0.9197766 -0.394088 0.0253793 -0.9187223 0.6002168 0.02519726 -0.7994404 0.6001893 0.0251652 -0.799462 0.9932209 0.02529168 0.1134572 0.99281 0.02091693 0.1178598 -0.001960098 0.9999966 0.001750886 0.002681791 0.9998469 -0.01729488 -5.28932e-4 0.9999564 0.009318411 -0.002364516 0.9999846 0.005034208 0.005674064 0.9999834 9.96141e-4 -1.36522e-4 0.9999938 0.003522157 -0.001386106 0.9999964 0.002317845 0.006338953 0.999953 0.007343411 0.002965509 0.999967 0.007557809 0.005911827 0.9999391 0.009331822 -0.002006828 0.9999779 -0.006343483 -0.009006977 0.9999582 0.001599371 -0.001393496 0.9999964 0.002271234 -0.006350755 0.9999339 0.009587466 -0.001277983 0.9999772 -0.006627559 0.007227182 0.9999734 0.001121401 0.007239222 0.9999719 -0.001973628 -0.008244991 0.9999658 -7.30293e-4 -0.008081495 0.9999673 -1.02408e-4 4.56265e-4 0.9999868 -0.005125164 0.003516137 0.9999796 -0.005345284 0.00689423 0.9999404 -0.008474469 0.006138384 0.999981 -6.77103e-4 -0.003148972 0.9999601 -0.008359909 -6.87003e-4 0.9999852 -0.005406618 -0.00606215 0.9999799 -0.001874625 -0.008323013 0.9991385 -0.04065859 -0.0165674 0.999027 -0.04087352 0.007182538 0.9999598 -0.005368769 -0.0196734 0.9951964 -0.09590142 0.001071691 0.9999976 -0.001966297 -0.07288819 0.9940292 -0.08119857 4.44194e-4 0.9993148 -0.03701275 -0.05364304 0.998423 -0.0165534 0.06680911 0.9963234 -0.05363148 -0.0091331 0.9999182 -0.0089522 0.05865889 0.9980736 -0.02020436 -0.1353753 0.990656 -0.01655954 -0.001977562 0.9999977 8.55324e-4 0.02798855 0.9992558 -0.02654063 0.01264435 0.9999191 0.001414179 0.07608771 0.9969054 0.01975661 0.05580419 0.9983673 -0.01219493 0.00151968 0.9999975 0.001676976 0.002270698 0.9999948 0.002311408 0.002874791 0.9999949 0.001463651 0.01920521 0.9997505 0.01140791 0.4354628 0.8835186 0.1725314 0.6564607 0.6403988 0.3986838 0.3232583 0.8676958 0.377635 0.3407697 0.8550716 0.3908051 0.1464749 0.845681 0.5131949 0.09687191 0.890895 0.443759 -0.01954853 0.8274963 0.5611308 -0.1050117 0.9042082 0.413981 -0.2553706 0.8098021 0.5282108 -0.3363086 0.8474231 0.4108169 -0.4343168 0.7900652 0.432627 -0.4857733 0.8282501 0.2793315 -0.5788528 0.7719359 0.2627632 -0.4898691 0.8717194 -0.01155871 -0.5853228 0.808802 -0.05689054 -0.4043382 0.8822448 -0.2411532 -0.4416292 0.8501555 -0.286704 -0.3737738 0.8121995 -0.4479119 -0.2742981 0.8528095 -0.4443834 -0.2546641 0.8137216 -0.5224972 -0.06319344 0.8483583 -0.5256375 -0.05991345 0.8416463 -0.5366955 0.1454678 0.8000855 -0.5819814 0.2006438 0.8702798 -0.4498392 0.337327 0.8080565 -0.4829651 0.3788314 0.858034 -0.3467917 0.468907 0.8096768 -0.3529163 0.5197803 0.8372794 -0.1696813 0.5088409 0.8473243 -0.1520612 0.592394 0.805096 -0.0298289 0.5040896 0.8617222 0.05769306 0.5719421 0.8044899 0.1602446 0.4064096 0.8704828 0.2776525 0.4411686 0.8300465 0.3411647 0.3548679 0.7910441 0.4983151 0.1946097 0.8731873 0.4468458 0.153108 0.796147 0.5854127 -0.03906017 0.8576633 0.5127261 -0.09195291 0.8101282 0.5789965 -0.2488602 0.8492481 0.4656677 -0.2840319 0.8241475 0.4900072 -0.4513298 0.8153821 0.3625653 -0.4130079 0.8758554 0.2496035 -0.6079824 0.7724591 0.183479 -0.5242314 0.8512973 -0.02177983 -0.4838928 0.8740924 -0.04254615 -0.5602768 0.7995632 -0.2163073 -0.3810672 0.8746705 -0.2995651 -0.4168095 0.8114948 -0.4095681 -0.2437006 0.8481112 -0.470444 -0.2427862 0.8156755 -0.5250985 -0.02306646 0.8397875 -0.5424252 -0.0180152 0.8329933 -0.5529899 0.1898855 0.8387672 -0.510307 0.1680441 0.8572321 -0.4867386 0.3520072 0.7954094 -0.4933709 0.3630111 0.8776586 -0.3129513 0.5189988 0.7917727 -0.3220814 0.5706441 0.8005244 -0.1831014 0.4885052 0.8691968 -0.07654964 0.588372 0.8083357 0.02029347 0.4773939 0.8687637 0.1316996 0.5370233 0.8121696 0.2280057 0.4554365 0.8241288 0.3367334 0.3889822 0.8568195 0.338457 0.3399785 0.808627 0.4801428 0.2544746 0.8519131 0.4576973 0.1447825 0.8123432 0.5649217 0.0733003 0.8551545 0.5131645 -0.05880934 0.8170403 0.5735736 -0.1133036 0.859244 0.498861 -0.2491103 0.8044282 0.5392954 -0.3100198 0.8601334 0.4050414 -0.4168301 0.7950264 0.4406651 -0.4985398 0.8238611 0.2696497 -0.4261456 0.8904372 0.1597548 -0.5405117 0.8393653 0.05755972 -0.450101 0.8923937 -0.03229165 -0.5623062 0.8087224 -0.1725685 -0.3548095 0.9042063 -0.2377422 -0.4152733 0.8142285 -0.4056848 -0.2229856 0.8902737 -0.3971024 -0.2046436 0.8402958 -0.5020201 -0.05578052 0.8829229 -0.4661929 -8.90738e-4 0.8292791 -0.5588341 0.1303493 0.8495743 -0.5111091 0.1536912 0.8287491 -0.5381022 0.2718357 0.8041871 -0.5285722 0.3078247 0.8922832 -0.3302645 0.4864259 0.8038386 -0.3423935 0.4536287 0.8681144 -0.2014901 0.5169503 0.837513 -0.1770156 0.4895406 0.8713107 0.03417229 0.4913707 0.8703158 0.03324818 0.4700097 0.8539761 0.2231945 0.443286 0.865658 0.2326667 0.4657379 0.7919155 0.3949152 0.2684168 0.8902021 0.3680937 0.2099954 0.8264564 0.5223712 0.1289423 0.8428524 0.5224691 0.1240314 0.8342751 0.5372163 -0.05524677 0.8133091 0.5792031 -0.08693552 0.848521 0.5219716 -0.2467097 0.8191754 0.5177703 -0.2748202 0.8603969 0.4291748 -0.4009819 0.8077403 0.4321679 -0.4294446 0.8559939 0.2878399 -0.51403 0.81012 0.2819198 -0.50938 0.8532789 0.1115675 -0.5903003 0.8040848 0.07066476 -0.5102302 0.8545844 -0.09669876 -0.5609653 0.8157782 -0.140798 -0.4675539 0.8259241 -0.3150284 -0.4116978 0.8538452 -0.3185175 -0.3806585 0.8068413 -0.4517814 -0.2231465 0.8656619 -0.4481463 -0.2067412 0.7978446 -0.5663057 -0.02470618 0.8224405 -0.5683145 0.04941481 0.8876588 -0.457843 0.1808297 0.8083734 -0.5602081 0.3432931 0.8407548 -0.4186661 0.3245767 0.8537522 -0.4071328 0.4700576 0.8657183 -0.1719821 0.5322322 0.8286995 -0.1731653 0.5355241 0.8436889 0.03745675 0.550658 0.8334375 0.04645472 0.5059963 0.8316429 0.2287749 0.5034614 0.8340512 0.2255778 0.43145 0.8163699 0.3839158 0.3505426 0.8562027 0.3795219 0.3082263 0.8159244 0.4891462 0.1060697 0.8960592 0.4310768 0.09333324 0.8598982 0.5018606 -0.129335 0.8298695 0.5427606 -0.1764464 0.8506755 0.4951947 -0.2057628 0.8293437 0.5194718 -0.3756705 0.8310948 0.4100649 -0.3765035 0.8305718 0.4103608 -0.4841158 0.8421868 0.2373889 -0.5305212 0.8146141 0.2344173 -0.5417674 0.8398357 0.03411847 -0.566767 0.8235247 0.02412992 -0.5448629 0.8155502 -0.1949419 -0.4649757 0.8591617 -0.2136324 -0.4475153 0.7997859 -0.4000907 -0.3032701 0.8671863 -0.3949877 -0.287176 0.7925241 -0.5379922 -0.09764337 0.8343588 -0.5425046 -0.06386154 0.8631901 -0.5008239 0.1248034 0.8428782 -0.5234315 0.1395859 0.8289505 -0.5416243 0.3199738 0.8270491 -0.4621759 0.3196606 0.8330569 -0.4514791 0.4680434 0.8292227 -0.3054916 0.4685376 0.8284171 -0.3069165 0.5362734 0.8378753 -0.1018632 0.4696505 0.8753561 -0.1148047 0.537453 0.8395474 0.07940119 0.4099435 0.8997508 0.1496493 0.4911136 0.8301721 0.2638596 0.4318845 0.8095336 0.3976573 0.3194757 0.8681648 0.3797699 0.256071 0.8037461 0.5370476 0.1315387 0.883009 0.4505473 -0.06291836 0.8300598 0.5541137 -0.08480179 0.856712 0.5087763 -0.2610424 0.8013965 0.5381643 -0.3030986 0.8693744 0.3902812 -0.4293359 0.8075078 0.4044774 -0.4465263 0.8590427 0.2503198 -0.5534103 0.8029104 0.2215225 -0.5013008 0.8631047 0.06122183 -0.602646 0.7979538 0.009360969 -0.5610557 0.8132215 -0.1545557 -0.4594566 0.8672889 -0.1915974 -0.4744068 0.8049867 -0.3562792 -0.3660975 0.8570751 -0.3624843 -0.3379117 0.8334106 -0.4373129 -0.1877617 0.8838896 -0.4283514 -0.1625247 0.8447027 -0.5099641 -0.007862269 0.8794955 -0.4758424 0.05321276 0.8110249 -0.5825865 0.1943721 0.8528332 -0.4846597 0.1657438 0.8726568 -0.4593463 0.4086888 0.8230795 -0.3943524 0.3553857 0.9035228 -0.2394738 0.5639061 0.81008 -0.1605624 0.4680933 0.8830742 -0.03269118 0.6113252 0.7886334 0.06587153 0.5728189 0.7921296 0.210735 0.4256738 0.8710978 0.2449297 0.4488542 0.8050609 0.3878235 0.2926858 0.8630229 0.4117362 0.2845445 0.8131584 0.5077478 0.08226364 0.8545517 0.5128101 0.06554925 0.8231627 0.5640093 -0.1121745 0.8517222 0.511846 -0.1262483 0.8411382 0.5258783 -0.2600753 0.8873656 0.3807141 -0.3992407 0.8093655 0.4307371 -0.4216321 0.853325 0.306697 -0.5317235 0.7966762 0.2873629 -0.4912932 0.8596767 0.1399537 -0.5818781 0.8105407 0.06664484 -0.5127236 0.8572298 -0.04766094 -0.5658913 0.8165117 -0.1143493 -0.4578254 0.8547685 -0.2444725 -0.484092 0.829136 -0.2796221 -0.3592672 0.8095654 -0.4642531 -0.2452113 0.8705298 -0.4266723 -0.1751676 0.8117488 -0.5571179 -0.0341469 0.8933202 -0.4481217 0.0715689 0.8122439 -0.5789108 0.2194576 0.8455489 -0.4867088 0.2190874 0.8766919 -0.4282666 0.4303116 0.8396593 -0.3313671 0.3880423 0.8908568 -0.2362145 0.5387013 0.8308318 -0.1397123 0.4521015 0.8914167 -0.0313155 0.5527062 0.8293989 0.08132332 0.4770804 0.8633571 0.1643437 0.5291329 0.8145266 0.2378337 0.4432848 0.8105831 0.3826929 0.392468 0.8396041 0.3755449 0.2135039 0.8431255 0.4935136 0.2447716 0.8228833 0.5127865 0.04016607 0.8070542 0.5891098 -0.03715634 0.8659114 0.4988156 -0.07740157 0.8465813 0.5266017 -0.2727008 0.8693868 0.4120689 -0.3208522 0.8344657 0.448019 -0.4194042 0.866398 0.2710254 -0.4452354 0.8338394 0.3263089 -0.4842079 0.8697228 0.09552586 -0.5734224 0.8160443 0.07251644 -0.5211632 0.8489479 -0.08761543 -0.5672519 0.8138455 -0.12602 -0.4370627 0.8488407 -0.2973985 -0.4573839 0.8381105 -0.2972723 -0.3318729 0.8334002 -0.4419328 -0.2873254 0.855123 -0.4315195 -0.1920886 0.808025 -0.5569539 -0.1039361 0.8588292 -0.5016072 0.02883744 0.8104552 -0.5850905 0.08778762 0.8520832 -0.5159918 0.2251927 0.803797 -0.5506348 0.2565701 0.857636 -0.4456819 0.3991916 0.8126129 -0.4246249 0.3668664 0.886124 -0.2831843 0.5526463 0.8185892 -0.1565047 0.5169502 0.8481275 -0.1159415 0.5594952 0.8283485 0.02835971 0.5058588 0.8599975 0.06716603 0.5190325 0.8243305 0.2260193 0.4584358 0.8535971 0.247404 0.4359824 0.807729 0.3968542 0.3375735 0.85604 0.3914585 0.2737775 0.8038152 0.5281357 0.1374994 0.8656792 0.4813454 0.09197509 0.8028961 0.5889809 -0.1346665 0.8417392 0.5228193 -0.1369281 0.8508273 0.5072905 -0.2909098 0.8850765 0.3633335 -0.4032346 0.8214086 0.4033485 -0.3979882 0.8916807 0.2156639 -0.5269166 0.8269994 0.1960384 -0.4648622 0.8849855 0.02652847 -0.5455735 0.8378912 -0.01697683 -0.4965993 0.8516091 -0.1677836 -0.5637958 0.8142278 -0.1384474 -0.3875477 0.8619256 -0.3269419 -0.4677004 0.8245221 -0.3184646 -0.3563587 0.805393 -0.4736569 -0.2470167 0.845123 -0.4740781 -0.2226518 0.816034 -0.5333994 -0.06077516 0.8879276 -0.4559506 0.06817328 0.8145244 -0.5761097 0.1137179 0.855904 -0.5044767 0.2684077 0.8035858 -0.5312318 0.289425 0.8626853 -0.4147377 0.4688858 0.8006277 -0.3730168 0.4396692 0.8612631 -0.2547882 0.5775535 0.7958316 -0.1818907 0.5107387 0.8572154 -0.06578749 0.5952144 0.8026336 0.03871935 0.5107575 0.8499181 0.1294841 0.546801 0.8118888 0.2045609 0.405228 0.8592526 0.31221 0.4325676 0.823777 0.3664382 0.2535622 0.8161475 0.5192396 0.1237542 0.891822 0.4351303 0.06533241 0.8154163 0.5751764 -0.1355589 0.8109796 0.5691537 -0.155308 0.8770526 0.4545968 -0.37585 0.8521901 0.3640179 -0.3764948 0.8517224 0.3644457 -0.5649095 0.7836144 0.2585069 -0.4570057 0.8862849 0.07513302 -0.5953219 0.8034597 0.006667077 -0.4134657 0.8943138 -0.1710234 -0.5180785 0.80239 -0.2962518 -0.3255782 0.8731794 -0.3627071 -0.3387861 0.8052498 -0.4866177 -0.15633 0.8477553 -0.5068253 -0.143517 0.818987 -0.5555747 0.06040292 0.8446299 -0.5319323 0.05643177 0.8494643 -0.5246198 0.2191329 0.7824266 -0.5829146 0.315172 0.8628398 -0.3951888 0.3734422 0.8288208 -0.41665 0.4849777 0.8405283 -0.2414726 0.4500363 0.8607385 -0.2379005 0.594956 0.7972114 -0.1023788 0.5323696 0.8457224 0.03655648 0.5205596 0.8527178 0.04347676 0.4624064 0.8541831 0.2378057 0.5450344 0.810519 0.2144685 0.4493707 0.7853913 0.4257071 0.2947224 0.8580098 0.4206637 0.2876548 0.8437234 0.453195 0.1024489 0.8764332 0.4704989 0.08855164 0.8487054 0.5213999 -0.08835828 0.8780333 0.4703726 -0.1422742 0.8325889 0.5353074 -0.3008729 0.8311504 0.467616 -0.2872502 0.8412416 0.4580392 -0.473307 0.8045666 0.3586826 -0.4130403 0.8796907 0.2356734 -0.5073188 0.8583928 0.07608938 -0.5440595 0.836315 0.06764894 -0.5151482 0.8500886 -0.1094156 -0.5685698 0.8182138 -0.08517491 -0.4594772 0.8380566 -0.2941798 -0.4447359 0.853171 -0.2725974 -0.413374 0.7828779 -0.4649991 -0.2365531 0.8732762 -0.4259477 -0.2043882 0.7872748 -0.5817421 0.01280158 0.8565056 -0.515979 0.03132575 0.8366636 -0.5468207 0.2316035 0.8413124 -0.4884192 0.200622 0.8650094 -0.4599016 0.4196163 0.7883198 -0.4499713 0.3680741 0.8845505 -0.2865171 0.5194216 0.8458617 -0.1213227 0.511968 0.8503643 -0.1215297 0.5939318 0.802509 0.05678552 0.4799546 0.8683169 0.1251777 0.5251807 0.8049769 0.2760389 0.3973296 0.8615834 0.3159165 0.4034391 0.7850627 0.4700143 0.2026956 0.8950995 0.3971289 0.09094035 0.8372663 0.5391799 0.04788088 0.8697139 0.4912285 -0.1351586 0.8543937 0.5017405 -0.1495248 0.8680738 0.4733817 -0.3028883 0.7866786 0.5379551 -0.3958125 0.852317 0.3418892 -0.3853687 0.8583303 0.3387628 -0.5452932 0.8098292 0.2164073 -0.4889678 0.8656752 0.1073163 -0.5892122 0.8075761 0.0254954 -0.5140134 0.8525741 -0.09438151 -0.5680878 0.8080031 -0.1562282 -0.4069561 0.8563914 -0.3177745 -0.3974216 0.8668987 -0.3009034 -0.3522564 0.8003002 -0.4852165 -0.2181431 0.8575425 -0.4658696 -0.1724184 0.7967815 -0.5791469 -0.02229738 0.85609 -0.5163456 0.05284535 0.8027879 -0.5939183 0.1718099 0.8632909 -0.4745631 0.2646294 0.7977029 -0.5418868 0.3915567 0.813439 -0.4301168 0.3722086 0.8843446 -0.2817719 0.5567347 0.783504 -0.275986 0.5401465 0.8389828 -0.06595212 0.4935482 0.8693549 -0.02514767 0.5751742 0.8130018 0.09057033 0.4702525 0.8522964 0.2290275 0.5111693 0.8296361 0.2245213 0.4136418 0.824189 0.3867986 0.2891606 0.8896433 0.3534416 0.1536772 0.8492801 0.505081 0.1521618 0.8165929 0.556797 -0.06332856 0.8856298 0.4600536 -0.02173686 0.8391152 0.5435193 -0.2661607 0.8144334 0.515613 -0.2945659 0.8744578 0.3854275 -0.4299812 0.8112166 0.3962875 -0.44606 0.8552641 0.2637305 -0.544961 0.8032853 0.2403134 -0.4981968 0.8626868 0.08701485 -0.5943381 0.804162 0.009263634 -0.4884402 0.864396 -0.1193562 -0.5543097 0.8098586 -0.1920152 -0.4426761 0.823859 -0.3539695 -0.3276563 0.8874982 -0.324019 -0.1982027 0.8304958 -0.5205693 -0.1239423 0.8823074 -0.4540617 0.05946677 0.8485375 -0.5257833 0.05595916 0.8535369 -0.5180187 0.2009283 0.7978157 -0.5684347 0.2629622 0.8637914 -0.4297851 0.3745061 0.8128175 -0.446176 0.408683 0.8605851 -0.3039271 0.5207421 0.7988843 -0.3010175 0.5302851 0.8397089 -0.1169898 0.5805693 0.808319 -0.09777402 0.5211843 0.8477882 0.09809291 0.5531706 0.8237407 0.1243135 0.4754558 0.8297604 0.2923002 0.3992594 0.8654367 0.3026738 0.3952416 0.8108081 0.4317108 0.2900502 0.8370946 0.4638356 0.2137971 0.8790693 0.4260613 0.1008916 0.846719 0.5223867 0.03621608 0.8880473 0.4583236 -0.121037 0.8236822 0.5539835 -0.1704072 0.8907067 0.4214299 -0.3487002 0.8293741 0.4365167 -0.3554658 0.859975 0.3661791 -0.5007566 0.7902595 0.3531754 -0.4932585 0.8518646 0.176133 -0.5232584 0.8357089 0.1667076 -0.5364561 0.8427604 -0.04438489 -0.4903575 0.8711831 -0.02428257 -0.5956066 0.7789629 -0.1961371 -0.4168405 0.8522851 -0.3159971 -0.4111999 0.8552538 -0.3153662 -0.3281672 0.8031891 -0.4971857 -0.1739665 0.8796378 -0.4426884 -0.1327971 0.7915946 -0.596442 0.1112822 0.8929418 -0.436201 0.2006393 0.8071457 -0.5552114 0.3248363 0.8439849 -0.426815 0.317192 0.8724955 -0.3716732 0.4512986 0.8549574 -0.2556905 0.4372056 0.8701784 -0.2272462 0.5191383 0.8521186 -0.06625235 0.5165955 0.8538866 -0.06330066 0.5751668 0.8138893 0.082264 0.5172399 0.8477222 0.1176012 0.5160961 0.806719 0.2878358 0.4508579 0.8403173 0.3009884 0.4015945 0.8058627 0.4350947 0.3034235 0.8547275 0.4211593 0.2556499 0.8327257 0.4911327 0.1191027 0.8847716 0.4505485 0.06171286 0.8396506 0.5396096 -0.06022584 0.8877304 0.4564074 -0.1460425 0.8252764 0.5455186 -0.275574 0.8419646 0.4638476 -0.2928011 0.8297808 0.4751119 -0.4403154 0.8053854 0.3968336 -0.4158382 0.861292 0.2919843 -0.5039479 0.854619 0.1251515 -0.5369132 0.8251919 0.1754502 -0.596239 0.8024242 -0.02479344 -0.4906313 0.8684123 -0.07170176 -0.4182219 0.8759771 -0.240322 -0.4569866 0.8378966 -0.2984839 -0.3032568 0.8810427 -0.3630415 -0.3108277 0.8380656 -0.4483662 -0.1790434 0.8441674 -0.5052968 -0.173882 0.8260299 -0.5361341 0.05376654 0.8824136 -0.4673922 0.1025704 0.8209546 -0.5617054 0.2395018 0.8060464 -0.5412283 0.2773255 0.8936535 -0.3528087 0.3732193 0.849404 -0.3731223 0.4241943 0.8788521 -0.2183538 0.5046682 0.8346391 -0.2206523 0.4446203 0.895664 0.00994569 0.5501765 0.8334491 0.05165636 0.4406917 0.8548744 0.273826 0.3825513 0.8838588 0.2691622 0.3166717 0.84275 0.4353063 0.2511696 0.8770436 0.4095222 0.07974815 0.8540332 0.5140697 0.07393866 0.8282491 0.5554608 -0.1182813 0.8171074 0.5642209 -0.1576225 0.866239 0.4741151 -0.3197605 0.807426 0.495799 -0.3442459 0.8551383 0.3875995 -0.4687395 0.8009697 0.372466 -0.4562025 0.8605702 0.2264915 -0.5184919 0.8307909 0.2023679 -0.4612475 0.8864841 0.03737318 -0.5466051 0.8371072 -0.02178877 -0.4354892 0.8865359 -0.156216 -0.5085136 0.8288899 -0.233143 -0.2876333 0.8936253 -0.3445301 -0.3172686 0.847783 -0.4249761 -0.1128079 0.8459931 -0.521124 -0.05931371 0.8859766 -0.4599211 0.09167391 0.8411776 -0.5329319 0.1232377 0.8543399 -0.5048919 0.2201452 0.8029789 -0.5538601 0.3087928 0.866275 -0.3927019 0.3727381 0.8299235 -0.4150825 0.5000938 0.8076956 -0.3123043 0.4245541 0.8854663 -0.1889536 0.5484735 0.8356178 -0.03033179 0.4786463 0.8779214 0.01232647 0.470996 0.8543393 0.219698 0.4651074 0.8589639 0.2141405 0.3379912 0.8665665 0.3671846 0.355 0.8329786 0.4244075 0.2108669 0.8328245 0.5117994 0.2098585 0.825724 0.523583 0.006594061 0.8277034 0.561127 0.0236845 0.8546258 0.518704 -0.2345705 0.8621014 0.4491749 -0.2347993 0.8719592 0.4296005 -0.4215069 0.8502013 0.3154197 -0.3354427 0.8987594 0.2823292 -0.4742866 0.8454301 0.2455611 -0.4788417 0.8679886 0.1315538 -0.3677541 0.9297603 0.01740187 -0.670382 0.7165927 -0.192569 -0.4011202 0.8969182 -0.1861193 -0.3594823 0.8455336 -0.3947725 -0.9921741 0.002411365 0.1248389 -0.916819 0.1455293 -0.3718389 -0.8480622 -0.3492444 -0.398521 -0.6197068 0.2629947 -0.7394575 -0.5756167 -0.2551271 -0.7769014 -0.1851845 0.07845139 -0.9795673 -0.2046539 -0.05074185 -0.9775183 0.3052406 0.2349918 -0.9228256 0.3333809 -0.04442054 -0.9417452 0.6596544 -0.2388664 -0.7126001 0.7217671 0.2320154 -0.6520899 0.9431779 -0.05112385 -0.3283318 0.9200465 0.195502 -0.339549 0.9397145 -0.3411328 0.0237739 0.9458941 0.285013 0.1550875 0.8530179 -0.2044845 0.4801529 0.8315303 0.1410164 0.5372819 0.4715998 -0.1548233 0.8681148 0.4708903 -0.1450908 0.8701788 0.06620657 0.2332968 0.9701492 0.006189107 -0.2127621 0.9770844 -0.2786493 0.2124153 0.9366079 -0.3616035 -0.3855389 0.8488832 -0.5782662 0.3396266 0.7417966 -0.7350584 -0.3944687 0.5514377 -0.8369133 0.2661215 0.4782839 -0.9641151 -0.2654753 0.002263665 -0.9986324 -0.04183924 -0.03135281 -0.8204755 0.2349225 -0.5211827 -0.8336912 -0.03164178 -0.5513238 -0.5085783 -0.2976018 -0.8079488 -0.4096844 0.3029486 -0.8604539 -0.1148184 -0.1231609 -0.9857221 -0.0161814 0.300671 -0.9535908 0.2335043 -0.4621128 -0.8555277 0.4404204 0.4056092 -0.800944 0.6327157 -0.392251 -0.6676902 0.7562347 0.2449706 -0.6067114 0.9715806 -0.0290082 -0.2349249 0.9703771 -0.06783199 -0.2318775 0.9740254 -0.1319692 0.1840075 0.9349944 0.2526041 0.2489515 0.7918975 -0.09602141 0.6030574 0.8008884 0.01288765 0.598675 0.5414735 -0.1990212 0.8168214 0.4230253 0.3150637 0.849579 0.2183967 -0.2001911 0.9551055 0.09070783 0.2314804 0.9686016 -0.1295319 -0.3006157 0.9449083 -0.2753683 0.2578884 0.9261025 -0.4970316 -0.3571673 0.7908169 -0.6101323 0.3721497 0.6994593 -0.88401 -0.1823745 0.4304255 -0.882501 -0.1939213 0.4284703 -0.9845734 0.1564494 0.07835167 -0.9712084 -0.2369877 0.02431529 -0.8740118 0.3710361 -0.3137446 -0.7794814 -0.4847286 -0.3967958 -0.6665977 0.3600727 -0.652683 -0.5478417 -0.2894536 -0.7849116 -0.3410663 0.4247918 -0.8385857 -0.2019256 -0.403488 -0.8924257 0.1829314 0.225248 -0.9569742 0.1260463 -0.1711839 -0.977143 0.5053566 0.3435571 -0.7915702 0.5757038 -0.3066303 -0.7579862 0.8380949 0.1384029 -0.5276756 0.8412989 -0.2740614 -0.4659469 0.8916002 0.4385926 -0.1126303 0.9346159 -0.3547235 -0.02578002 0.9033528 0.1571294 0.3990791 0.9051086 0.1487696 0.3983041 0.6534182 -0.1647555 0.7388507 0.481885 0.4803912 0.7328104 0.2907721 -0.4735658 0.8313766 0.01487052 0.3628928 0.9317123 -0.08352029 -0.2359763 0.9681631 -0.372402 0.3318569 0.8667109 -0.449947 -0.2485346 0.8577752 -0.7627721 0.1170459 0.6359867 -0.7793571 -0.1196693 0.6150463 -0.9460262 0.1244333 0.2992506 -0.9584407 -0.01166224 0.2850536 -0.9905486 0.07199072 -0.1167514 -0.9914327 0.05595493 -0.1180267 -0.8061995 -0.2811763 -0.5205596 -0.707656 0.3728429 -0.600176 -0.4997276 -0.3080679 -0.8095471 -0.4365103 0.1504571 -0.8870295 -0.04018956 0.02689486 -0.99883 0.003874719 -0.406968 -0.9134343 0.3155507 0.4445921 -0.8383113 0.4719768 -0.5290394 -0.7052342 0.667545 0.387772 -0.635623 0.8521564 -0.3342981 -0.4025844 0.8533022 0.4746255 -0.215884 0.89619 -0.44326 -0.01908439 0.9169017 0.2951828 0.2686234 0.9301148 -0.1294617 0.343695 0.7377884 0.2491307 0.6273773 0.7288944 -0.1369023 0.6707986 0.3237726 -0.0423873 0.9451851 0.2953821 0.1462098 0.9441251 -0.2647074 -0.04666286 0.9631992 -0.3060497 0.2995094 0.9036746 -0.5648834 -0.3831054 0.7308469 -0.7112774 0.3964081 0.5804699 -0.8400169 -0.2180817 0.4968018 -0.9212177 0.2594299 0.289921 -0.9076604 -0.3969786 0.1362375 -0.9492418 0.308502 -0.06137388 -0.9153984 -0.2323882 -0.3286967 -0.8507262 0.3153132 -0.4205266 -0.6039376 -0.4686629 -0.6446817 -0.5022571 0.3656344 -0.7836132 -0.246012 -0.198228 -0.9487802 -0.1533722 0.2334548 -0.9601958 0.1429367 -0.2874221 -0.9470786 0.3012195 0.4467223 -0.8424406 0.4605607 -0.4207465 -0.7815729 0.7242066 0.4156255 -0.5502547 0.7806585 0.2494085 -0.5730337 0.8705601 -0.426528 -0.245355 0.9117667 0.4031285 -0.07854419 0.9171937 -0.3279041 0.2263508 0.9373403 0.134053 0.3215948 0.7285286 0.0412926 0.6837698 0.6847445 -0.2529625 0.6834727 0.4161869 0.1930676 0.8885458 0.3592999 -0.1909799 0.9134716 0.05767184 0.3242741 0.9442035 -0.05888891 -0.4762704 0.8773248 -0.3472027 0.3999445 0.8482304 -0.5115368 -0.3163254 0.7989171 -0.6512045 0.423582 0.6296913 -0.7518687 -0.4047991 0.5204146 -0.9550159 0.2357176 0.1799498 -0.9402444 -0.2344969 0.2468839 -0.8977282 0.4055795 -0.1720161 -0.8796858 -0.3898023 -0.2724096 -0.7877441 0.2201989 -0.5753015 -0.7498704 -0.1984922 -0.6311063 -0.4696766 0.2700985 -0.8405063 -0.4709097 0.0848053 -0.8780958 -0.1091932 -0.3512148 -0.9299059 0.07053685 0.4562954 -0.8870283 0.2556741 -0.4474733 -0.8569705 0.4692556 0.4994751 -0.7282335 0.7008445 -0.3893936 -0.5976535 0.8185936 0.1313246 -0.5591588 0.9392822 -0.3056577 -0.1559565 0.9895646 0.1068807 -0.09663629 0.8861051 0.3322703 0.323132 0.821995 -0.4336651 0.3691324 0.6264646 0.1561983 0.7636389 0.6290026 0.1443572 0.7638828 0.2249387 0.04694736 0.9732413 0.2257366 0.05950009 0.9723697 -0.1211931 -0.3415763 0.9320074 -0.307826 0.5757393 0.7574744 -0.4700806 -0.2227303 0.8540582 -0.7467648 -0.1756716 0.6414685 -0.7543674 0.4354725 0.4912165 -0.884025 -0.3236966 0.3372248 -0.9318578 0.3577247 0.06061512 -0.9864937 -0.1634358 -0.01091158 -0.9427419 0.04885172 -0.3299261 -0.8596533 -0.3580688 -0.3643941 -0.6752714 0.4663006 -0.5714651 -0.5402293 -0.3528949 -0.7639486 -0.4651963 0.1629683 -0.8700769 -0.1665052 -0.2714146 -0.9479505 -0.07504272 0.2283191 -0.97069 0.3727628 -0.1283025 -0.9190137 0.3597114 -0.1913216 -0.9132381 0.7096866 0.2412187 -0.6619355 0.727995 -0.403927 -0.5539552 0.8669883 0.3511691 -0.3535698 0.9436976 -0.288163 -0.162472 0.9837659 0.1743088 -0.04267531 0.9381735 -0.2545474 0.2345981 0.9311801 0.1673237 0.3238929 0.7678118 -0.0671125 0.6371507 0.6737127 0.326514 0.6629479 0.4241318 -0.463267 0.7781361 0.2342321 0.4132139 0.8799941 0.01909005 -0.3572407 0.9338173 -0.1342538 0.3290128 0.9347334 -0.4491961 -0.3194575 0.834368 -0.547829 0.1164618 0.8284444 -0.7919912 -0.07605236 0.6057771 -0.813693 0.159694 0.558929 -0.9539984 -0.1230977 0.2733755 -0.9398742 0.296878 0.1688199 -0.8944604 -0.4421048 -0.06696414 -0.8490876 0.4364477 -0.2975965 -0.837322 -0.2738728 -0.4731655 -0.7295075 0.2597807 -0.6327188 -0.5897837 -0.3301513 -0.7369907 -0.436369 0.2909185 -0.8514391 -0.2753252 -0.2986291 -0.9137926 -0.04271155 0.3886001 -0.9204161 0.08097243 -0.2743145 -0.958225 0.3894438 0.234238 -0.8907672 0.4308537 -0.07227557 -0.8995229 0.72759 -0.13072 -0.6734427 0.756537 0.2511464 -0.6038026 0.9555994 -0.09927105 -0.2774436 0.9576124 0.01366418 -0.287736 0.9791496 -0.1967279 0.0506373 0.934055 0.3166242 0.165198 0.8972514 -0.2018728 0.3926669 0.8330119 0.2291351 0.5035758 0.6825382 -0.3008068 0.6660757 0.5801231 0.2598501 0.7719684 0.3399364 -0.3563117 0.8703362 0.1876052 0.4082643 0.8933782 -0.1724192 -0.281587 0.9439176 -0.2376117 0.02066403 0.9711405 -0.5569622 -0.03048121 0.8299784 -0.5779467 0.107272 0.8089934 -0.8323648 -0.03244984 0.5532774 -0.8249087 -0.08152914 0.5593557 -0.9822413 0.07817423 0.1705603 -0.9777382 -0.153562 0.142992 -0.9401304 0.249827 -0.2318218 -0.9633138 0.08875793 -0.2532756 -0.7546879 -0.3955178 -0.5234615 -0.6494493 0.3816135 -0.6577134 -0.5177527 -0.2117057 -0.8289227 -0.3571355 0.294603 -0.8863766 -0.2203515 -0.259332 -0.940315 0.003286957 0.2546262 -0.967034 0.1280742 -0.3151872 -0.9403478 0.3490144 0.2769096 -0.895271 0.4795438 -0.2666891 -0.8360112 0.628179 0.4011453 -0.6666885 0.7226148 -0.4586111 -0.5172076 0.8862007 0.3373689 -0.3175386 0.9477559 -0.2453031 -0.2039242 0.9457415 0.3226435 0.03839445 0.951626 -0.2638328 0.1574811 0.8575853 0.2800588 0.4314101 0.76002 -0.4415455 0.4768724 0.4117684 0.5870168 0.6970353 0.2957674 -0.644671 0.7049261 -0.02618759 0.4986758 0.8663929 -0.210069 -0.374482 0.9031247 -0.3728868 0.2482442 0.8940528 -0.6203574 -0.3295594 0.7117214 -0.7104654 0.08422964 0.6986733 -0.9064086 0.2409274 0.3469545 -0.843021 -0.4832345 0.2362201 -0.9290704 0.3698735 -0.004683673 -0.8898525 -0.3745532 -0.2605237 -0.8634071 0.3051331 -0.4017738 -0.6809629 -0.3781971 -0.6271017 -0.462752 0.5429744 -0.7007421 -0.3425959 -0.4425894 -0.8286994 -0.01565384 0.3120393 -0.9499403 0.03403162 -0.1880922 -0.9815616 0.4277883 0.3748274 -0.8224973 0.502211 -0.400845 -0.7662293 0.7469369 0.2585647 -0.6125599 0.7791889 -0.4071485 -0.4765444 0.8095924 0.5545165 -0.1925407 0.878861 -0.4769058 -0.01281565 0.9284334 0.287248 0.2355844 0.8796895 -0.3074359 0.3628083 0.7378789 0.4001201 0.5435429 0.6163039 -0.2882282 0.732867 0.5596202 0.1071102 0.8217985 0.2924394 -0.2046982 0.9341188 0.2203642 0.1498583 0.9638372 -0.102327 -0.05963677 0.9929617 -0.1417545 0.1279093 0.9816032 -0.4743449 -0.1479828 0.8678122 -0.481751 -0.1158092 0.868622 -0.7705122 0.2127575 0.6008704 -0.805557 -0.1877173 0.5619966 -0.9340348 0.2123597 0.2871978 -0.9524963 -0.2028653 0.2271485 -0.9872053 0.1299196 -0.09244775 -0.980404 -0.1457641 -0.1325176 -0.8752035 0.1723831 -0.4519988 -0.8767095 -0.03979915 -0.479371 -0.5964537 0.05571776 -0.8007113 -0.5325053 -0.3431377 -0.7737537 -0.1773441 0.398 -0.9000807 -0.05988085 -0.3381853 -0.9391725 0.1567388 0.259549 -0.9529256 0.3259326 -0.3665602 -0.8714366 0.4880878 0.2503304 -0.8361251 0.7186838 -0.1672321 -0.6749275 0.7581267 0.2982148 -0.579924 0.856311 -0.4323472 -0.2825019 0.8654316 0.4931077 -0.08872961 0.9011492 -0.4088882 0.1440165 0.8507 0.3866572 0.3560981 0.7923831 -0.3201444 0.5192656 0.6669151 0.3050377 0.6798356 0.507892 -0.352871 0.7858294 0.3394299 0.3315328 0.8802689 0.1804043 -0.2249125 0.9575327 0.005955934 0.261534 0.9651759 -0.188581 -0.4159492 0.88962 -0.3508687 0.3019159 0.8864187 -0.6997094 -0.1041473 0.7067958 -0.6991773 -0.1219362 0.7044734 -0.9342663 0.1174732 0.3366697 -0.9273279 -0.2370969 0.2895653 -0.9806376 0.1937323 -0.02859729 -0.9686238 -0.2286913 -0.09730535 -0.8522872 0.3707371 -0.3689997 -0.734209 -0.4959982 -0.4635981 -0.6074624 0.3806705 -0.697194 -0.4783481 -0.2882618 -0.8295109 -0.2786678 0.4014053 -0.8724782 -0.1246499 -0.3927235 -0.91117 0.18849 0.212354 -0.9588416 0.2473121 -0.2664989 -0.9315659 0.5223565 0.5029698 -0.6885965 0.5472941 -0.6510449 -0.525937 0.7912902 0.5394062 -0.2879251 0.8975136 -0.4195748 -0.1357443 0.9590677 0.2800838 0.0417416 0.9069242 -0.2801476 0.314652 0.8949063 0.172136 0.4117183 0.6917606 -0.1586637 0.7044808 0.6501101 0.1417327 0.7465043 0.360462 -0.04761582 0.9315578 0.2986094 0.2199651 0.9286807 -0.02708822 -0.4485634 0.8933405 -0.1927377 0.3947027 0.8983663 -0.5431122 -0.1285738 0.8297579 -0.5410259 -0.03706586 0.8401888 -0.8175349 -0.07797914 0.5705752 -0.8305562 0.01361745 0.5567685 -0.9691107 -0.009447216 0.2464452 -0.9640861 0.1666776 0.2067766 -0.9697956 -0.1894556 -0.1536331 -0.9740328 -0.160511 -0.1596761 -0.8121376 0.3289558 -0.4818928 -0.6711655 -0.5187722 -0.5295398 -0.4613215 0.4997705 -0.7330839 -0.3291443 -0.4248089 -0.8433277 -0.1148617 0.2666268 -0.9569311 0.02996933 -0.2883638 -0.9570519 0.2314734 0.3513698 -0.9071711 0.4269831 -0.2718914 -0.8624156 0.551256 0.1870182 -0.813106 0.7134963 -0.2960194 -0.6350556 0.8041044 0.1871848 -0.56425 0.9602575 -0.02639126 -0.2778654 0.9597446 0.002677619 -0.2808616 0.9951215 0.004993259 0.09853082 0.9865088 -0.121185 0.1100667 0.8545263 0.07645738 0.5137502 0.8348748 -0.1469506 0.530462 0.5980732 0.2692483 0.7548603 0.5039183 -0.3370477 0.7952769 0.2743089 0.2162569 0.93701 0.1654988 -0.3059421 0.9375551 -0.07603245 0.3786188 0.9224244 -0.2664943 -0.2957621 0.9173361 -0.4277926 0.3206759 0.8450802 -0.5506407 -0.4691161 0.6904528 -0.7371976 0.4549246 0.4995832 -0.8688428 -0.2966107 0.3964018 -0.9249388 0.3381861 0.1735468 -0.8578686 -0.5137876 0.009162962 -0.8291517 0.4935986 -0.2624273 -0.7824433 -0.3895398 -0.485841 -0.7754725 0.1282985 -0.6182087 -0.4890625 -0.08723759 -0.8678753 -0.4135352 -0.4237859 -0.80585 -0.08493518 0.5267147 -0.8457883 0.1160665 -0.5013362 -0.8574326 0.3237151 0.3542094 -0.8773507 0.5368855 -0.3624704 -0.7618197 0.680719 0.3508703 -0.6430487 0.8206933 -0.2263296 -0.5246309 0.8938459 0.2594152 -0.3657097 0.9289377 -0.3111143 -0.2007052 0.9741028 0.2248745 -0.02356547 0.9608049 -0.2408469 0.137283 0.8487631 0.4117508 0.3317568 0.8283199 -0.3222661 0.4582911 0.6313304 0.1314465 0.764293 0.5973516 0.2588617 0.7590533 0.3318743 -0.297206 0.895281 0.08932024 0.5158361 0.8520183 -0.02476531 -0.363874 0.9311189 -0.4205825 0.1622071 0.8926361 -0.4479217 -0.07944566 0.8905361 -0.7513101 0.2118154 0.625034 -0.771713 0.09630602 0.6286368 -0.870548 -0.388706 0.3017514 -0.9167973 0.377209 0.1311337 -0.9675939 -0.2467162 -0.05378788 -0.8952901 0.368394 -0.2504823 -0.8599044 -0.3282474 -0.39092 -0.7353693 0.2204417 -0.64081 -0.6931785 -0.1969514 -0.6933352 -0.4264914 0.2362231 -0.8731001 -0.4002178 -0.0893715 -0.9120518 0.01751744 -0.05694019 -0.998224 0.03359234 0.04991382 -0.9981884 0.580812 0.09950006 -0.8079339 0.4998396 0.4706853 -0.7270596 0.7218514 -0.5022143 -0.4761422 0.805993 0.5457316 -0.2292435 0.8421917 -0.5336009 -0.07735157 0.8148053 0.5426301 0.2040713 0.7849869 -0.4395424 0.4365755 0.7381475 0.29609 0.6061923 0.5702727 -0.3209578 0.7561582 0.3477292 0.4131075 0.8416809 0.2212626 -0.4047331 0.8872621 -0.05493229 0.3799059 0.9233927 -0.2114996 -0.3537139 0.9111281 -0.4271315 0.4565705 0.78045 -0.5533463 -0.3615423 0.7503967 -0.8562476 0.1224998 0.5018308 -0.8397395 0.2914173 0.4581634 -0.9398195 -0.2973774 0.1682438 -0.910404 0.4131529 -0.02166199 -0.8779882 -0.4279164 -0.214533 -0.7776598 0.4664045 -0.4215592 -0.5959513 -0.5744997 -0.5610635 -0.4239002 0.5502731 -0.7193805 -0.2089838 -0.4028843 -0.8910724 -0.04243499 0.335449 -0.9411023 0.1436646 -0.3254748 -0.934573 0.3990128 0.4060649 -0.8221314 0.497901 -0.3855636 -0.776811 0.7384558 0.3412339 -0.5815861 0.8113717 -0.358671 -0.4615531 0.904788 0.3180475 -0.2832043 0.9587719 -0.276422 -0.0659362 0.9432244 0.3218531 0.08208757 0.8496514 -0.4311358 0.3036683 0.7619681 0.3993858 0.5097997 0.7199919 -0.2200565 0.6581693 0.5471652 0.2546414 0.7973507 0.4321842 -0.3056575 0.8484047 0.227997 0.2221868 0.9479718 0.08577764 -0.333556 0.9388198 -0.1115775 0.3734261 0.9209253 -0.3845865 -0.2465136 0.8895642 -0.468497 0.1465699 0.8712221 -0.7022048 -0.3509559 0.6194663 -0.7775654 0.3697089 0.5086329 -0.96244 -0.2087858 0.1735447 -0.9532022 -0.2442354 0.1781983 -0.9107163 0.3071474 -0.2761458 -0.9314597 -0.1505129 -0.3312532 -0.7651561 -0.05510401 -0.6414826 -0.6966304 0.2461187 -0.673893 -0.4246524 -0.05598956 -0.9036237 -0.3411992 0.2851204 -0.8957061 0.03028184 -0.2861002 -0.9577211 0.129927 0.3668077 -0.9211792 0.4595111 -0.4291517 -0.7776108 -0.4975434 -0.7031954 -0.5079043 -0.1193162 -0.9190769 -0.3755815 -0.07575011 -0.6735773 -0.7352249 0.0774253 -0.9211953 -0.3813195 0.3465267 -0.7640858 -0.5441434 0.3183733 -0.8830335 -0.344805 0.4743124 -0.8276243 -0.3001097 0.4677495 -0.8606576 -0.2011938 0.5120336 -0.8382765 -0.1873876 0.4774299 -0.8780782 0.03224259 0.5492184 -0.8311413 0.08696782 0.4764383 -0.8399914 0.259656 0.459556 -0.8570885 0.2328258 0.4166823 -0.7865335 0.4557862 0.2427201 -0.8959973 0.3718546 0.1274651 -0.8228179 0.5538262 0.07560974 -0.8754513 0.4773554 -0.09842342 -0.8695656 0.4839097 -0.1744323 -0.8103671 0.5593556 -0.2826223 -0.8542786 0.4362713 -0.3881635 -0.8004789 0.4566866 -0.4291414 -0.8537181 0.294963 -0.3872904 -0.8732699 0.2956451 -0.5636051 -0.819822 0.1011996 -0.4278353 -0.9034832 0.02598452 -0.5533592 -0.8021197 -0.2244942 -0.4418984 -0.8673062 -0.2291417 -0.4420961 -0.7998723 -0.4059006 -0.2758343 -0.8462322 -0.4558579 -0.2619702 -0.8552955 -0.4470362 -0.1251218 -0.8097728 -0.5732474 -0.05375909 -0.8633531 -0.5017284 0.09532898 -0.7826132 -0.6151658 0.2242248 -0.8627452 -0.4532043 0.2303593 -0.8258128 -0.5147503 0.3803408 -0.8512034 -0.3616544 0.42323 -0.8278988 -0.368049 0.5136773 -0.8126517 -0.2751961 0.456754 -0.8769218 -0.1496126 0.5894092 -0.8047175 -0.07089895 0.5290172 -0.8422411 0.1037828 0.5413552 -0.8347552 0.1005901 0.5099887 -0.8159891 0.2721645 0.4262356 -0.8609375 0.2776869 0.3846685 -0.8015274 0.4578037 0.264354 -0.86163 0.4332559 0.2062048 -0.7988963 0.5650172 0.09109312 -0.8588623 0.5040413 -0.02623331 -0.7989179 0.6008679 -0.1027542 -0.8621743 0.4960818 -0.251806 -0.7973363 0.5484968 -0.2944869 -0.8632968 0.4098733 -0.420484 -0.8021163 0.4240317 -0.4453556 -0.8585152 0.2541853 -0.5358853 -0.8135567 0.225727 -0.5028308 -0.8606482 0.08028632 -0.57109 -0.8203043 0.03093701 -0.5092621 -0.8505915 -0.1309439 -0.5345513 -0.8295722 -0.1614465 -0.4726517 -0.8070774 -0.3538738 -0.4146865 -0.8426635 -0.3434438 -0.2952652 -0.8195627 -0.4910556 -0.2345588 -0.8610706 -0.4511536 -0.07193058 -0.7803036 -0.6212506 0.1028738 -0.8208091 -0.5618625 0.0309444 -0.8600772 -0.5092245 0.2851616 -0.824989 -0.4879305 0.2433547 -0.8502137 -0.4668141 0.4276324 -0.8238651 -0.3719903 0.4005633 -0.8655101 -0.3007348 0.5308584 -0.8240129 -0.1979699 0.4876462 -0.8659571 -0.1109944 0.6124514 -0.789928 -0.03028357 0.5398374 -0.8296424 0.1423701 0.466402 -0.8699901 0.1599578 0.5048283 -0.810447 0.2971937 0.3594128 -0.8377987 0.4109939 0.3147861 -0.8654669 0.389714 0.2127158 -0.7795168 0.5891567 0.01546537 -0.8761493 0.4817917 0.0556215 -0.814884 0.5769492 -0.1591686 -0.8441913 0.5118659 -0.1623082 -0.854293 0.4938012 -0.3646544 -0.8014301 0.4740645 -0.3497067 -0.8715347 0.3437045 -0.5290367 -0.8009586 0.280331 -0.446154 -0.875522 0.1854941 -0.4733447 -0.8808772 4.78407e-4 -0.5186651 -0.8547044 -0.02161061 -0.5180006 -0.8183892 -0.2488268 -0.3656378 -0.8965222 -0.250114 -0.3786574 -0.8281147 -0.4133336 -0.2347794 -0.8954464 -0.3782253 -0.1248273 -0.797286 -0.5905535 -0.05824226 -0.8557317 -0.5141315 0.0759685 -0.8202214 -0.5669795 0.1276854 -0.8679317 -0.4799908 0.2621933 -0.8112927 -0.5225505 0.2817988 -0.899561 -0.3337357 0.460685 -0.8191658 -0.3416677 0.4926307 -0.8522466 -0.1760422 0.49176 -0.852719 -0.176189 0.5237382 -0.8443548 0.1129751 0.5347644 -0.837671 0.1110609 0.4742735 -0.8380386 0.2697332 0.3729898 -0.8907278 0.2597742 0.3276925 -0.8105635 0.4853911 0.1837896 -0.8768783 0.4441915 0.1715754 -0.8512054 0.4959952 6.43991e-4 -0.7772573 0.6291825 -0.10917 -0.8801196 0.4620298 -0.1966876 -0.827257 0.5262696 -0.3570534 -0.7947459 0.4908074 -0.3571726 -0.8652908 0.3517094 -0.4912486 -0.8040587 0.3349097 -0.478688 -0.8555549 0.1971896 -0.5778177 -0.8039553 0.1406508 -0.5074814 -0.8615778 0.01210021 -0.5892096 -0.8022342 -0.09618937 -0.4707537 -0.8630627 -0.1830676 -0.5089393 -0.8218082 -0.2561489 -0.4265172 -0.8043887 -0.4135722 -0.3055642 -0.8690236 -0.3891382 -0.2591798 -0.8047227 -0.5340855 -0.1215219 -0.8620101 -0.492109 -0.05629903 -0.8005058 -0.596675 0.08382177 -0.8189988 -0.5676397 0.1150653 -0.8730522 -0.4738562 0.2579969 -0.8162555 -0.5168799 0.3422087 -0.884537 -0.3169979 0.3443411 -0.8823462 -0.3207717 0.5469153 -0.8194262 -0.1715355 0.5029584 -0.8595929 -0.09018319 0.5933828 -0.8045719 -0.02368444 0.527116 -0.8358606 0.153251 0.5104309 -0.8497848 0.1316288 0.4550688 -0.8254696 0.3339348 0.4079601 -0.8512044 0.3301812 0.3364791 -0.8124526 0.4761331 0.2411593 -0.8769016 0.4157953 0.07711732 -0.8617831 0.5013809 0.05820405 -0.8308915 0.553382 -0.1586387 -0.8401312 0.5186651 -0.1596239 -0.843317 0.5131633 -0.3461099 -0.8187431 0.4581131 -0.3349969 -0.8578301 0.3897497 -0.5327202 -0.780691 0.3266971 -0.4553152 -0.8767917 0.1546754 -0.5915759 -0.8028898 0.07352536 -0.5083463 -0.8597855 -0.04850828 -0.5807483 -0.8025923 -0.1362974 -0.4418181 -0.8555452 -0.2698875 -0.4628695 -0.8214198 -0.3331986 -0.2956604 -0.8485602 -0.4387832 -0.2954964 -0.849933 -0.4362291 -0.1284947 -0.7932451 -0.5951902 -0.009982585 -0.8696743 -0.4935252 0.07293736 -0.8073509 -0.5855466 0.2553967 -0.8399439 -0.4788181 0.2564685 -0.8328602 -0.4904772 0.4313784 -0.8346058 -0.3425578 0.4095085 -0.8469122 -0.3391793 0.5793077 -0.795531 -0.1775761 0.4511631 -0.8883246 -0.08562386 0.5406793 -0.8305355 0.1337036 0.5122346 -0.8475283 0.1389655 0.4814647 -0.7947334 0.3695818 0.3421707 -0.8615391 0.3750595 0.3453881 -0.8696395 0.3527525 0.1780405 -0.8591085 0.4798274 0.143186 -0.8854181 0.4421907 -0.04678267 -0.8133129 0.5799428 -0.1313782 -0.8773435 0.4615283 -0.1953901 -0.8363854 0.5121349 -0.4013946 -0.7834548 0.4744269 -0.3741577 -0.8765294 0.3028241 -0.5351641 -0.7966808 0.2808902 -0.5267662 -0.845803 0.08446723 -0.5196132 -0.8506336 0.08015513 -0.5477772 -0.829696 -0.107447 -0.4951997 -0.8585271 -0.1330738 -0.493194 -0.7957622 -0.3514575 -0.4469097 -0.8541838 -0.2657855 -0.3550642 -0.8039954 -0.4769916 -0.2706101 -0.8671126 -0.4181935 -0.08032071 -0.8742882 -0.4787157 -0.04174917 -0.8132216 -0.5804546 0.1600943 -0.8535988 -0.4957206 0.1812726 -0.8389877 -0.5130691 0.3166165 -0.8793593 -0.3556421 0.3776946 -0.8501904 -0.366774 0.5429071 -0.8141794 -0.205825 0.4318401 -0.8732043 -0.2258948 0.5207371 -0.8513279 -0.06382441 0.5530881 -0.8322783 -0.037503 0.497563 -0.8579269 0.1280333 0.5303041 -0.8309022 0.1684615 0.4760361 -0.8153768 0.3294697 0.3891546 -0.8639887 0.3195033 0.3454455 -0.7789748 0.523322 0.2388784 -0.8274182 0.5082483 0.1660156 -0.8832795 0.4384703 0.01268321 -0.8401386 0.5422235 -0.02950906 -0.8525421 0.5218251 -0.07716685 -0.81816 0.569789 -0.2203657 -0.8853983 0.4092786 -0.3441872 -0.8194037 0.4583806 -0.4076765 -0.8516098 0.3294857 -0.4851971 -0.8109605 0.3269967 -0.4922783 -0.8599676 0.1346029 -0.5498092 -0.8276617 0.1126323 -0.6048973 -0.7948888 -0.0474472 -0.4866094 -0.8653476 -0.1199363 -0.5457834 -0.799317 -0.251422 -0.4189991 -0.8553293 -0.3047155 -0.4164025 -0.7993295 -0.4332222 -0.2723298 -0.8576401 -0.4362227 -0.2648453 -0.847113 -0.460713 -0.07019424 -0.8793827 -0.4709128 -0.02218967 -0.8160505 -0.5775547 0.1005172 -0.829272 -0.5497312 0.1379754 -0.8942283 -0.4258154 0.3098598 -0.8246746 -0.4731795 0.3290886 -0.889112 -0.3180888 0.4515478 -0.8327339 -0.3204045 0.4133643 -0.8962431 -0.1608672 0.6266517 -0.7779211 -0.0463289 0.5013346 -0.8641138 0.04439902 0.546735 -0.8228699 0.15481 0.4507678 -0.8647862 0.221254 0.4772313 -0.8092836 0.3425065 0.3314054 -0.8681351 0.3694752 0.30792 -0.7959913 0.5211364 0.150609 -0.8639265 0.4805705 0.1096697 -0.8166633 0.5665984 -0.08891314 -0.8483582 0.5219031 -0.08876311 -0.8484546 0.521772 -0.2508825 -0.8725906 0.4190984 -0.3199181 -0.8347236 0.4482066 -0.4253273 -0.8173834 0.3885632 -0.38433 -0.870651 0.3070138 -0.5117527 -0.8516522 0.113128 -0.5320459 -0.8366174 0.1303791 -0.560588 -0.8258334 -0.06115812 -0.5058953 -0.8588088 -0.08073037 -0.5431907 -0.7830967 -0.3028258 -0.359457 -0.8678985 -0.3428452 -0.4373266 -0.8169653 -0.3759166 -0.2282107 -0.8431485 -0.4868474 -0.2513963 -0.8250675 -0.5060271 -0.04599338 -0.8364995 -0.5460341 -0.04162073 -0.8412898 -0.5389797 0.1692743 -0.8341326 -0.5249469 0.1662647 -0.8236026 -0.5422497 0.2832844 -0.8303994 -0.4797779 0.2776187 -0.8874623 -0.3678838 0.4466523 -0.8275206 -0.3401642 0.4151227 -0.888346 -0.1962518 0.5314294 -0.8329825 -0.1540228 0.5385389 -0.8422811 -0.02320897 0.5678355 -0.8231338 -0.003704011 0.5760327 -0.804418 0.1452516 0.4597488 -0.8692331 0.1818376 0.4936718 -0.7862803 0.3715528 0.2959924 -0.870133 0.3940269 0.2982323 -0.8499433 0.4343432 0.1367647 -0.7872428 0.6012856 0.01301288 -0.8485327 0.5289831 0.03411489 -0.8589758 0.5108783 -0.1434415 -0.8752613 0.4618899 -0.1855303 -0.8499995 0.4930309 -0.3857648 -0.8371025 0.3878725 -0.3188665 -0.8727692 0.3695917 -0.4058253 -0.8914142 0.2017093 -0.5879507 -0.7955415 0.1463825 -0.5027115 -0.8633354 0.04396879 -0.5877512 -0.8036179 -0.0935257 -0.4718818 -0.8653202 -0.1689637 -0.5176538 -0.8121134 -0.2692703 -0.3907483 -0.8336572 -0.3902965 -0.3012133 -0.8822354 -0.3618442 -0.2637256 -0.8090435 -0.5252596 -0.05283766 -0.8966682 -0.4395389 0.01745492 -0.8197007 -0.572526 0.2045023 -0.822421 -0.5308509 0.2061756 -0.8424761 -0.4977204 0.4032341 -0.8210186 -0.4041419 0.3949788 -0.83668 -0.3794184 0.5280383 -0.8172977 -0.2306516 0.4738347 -0.8648165 -0.1660518 0.599703 -0.7997903 -0.02630257 0.4996594 -0.8625011 0.08020353 0.5460096 -0.8246109 0.147954 0.4588049 -0.8434338 0.2794952 0.4794912 -0.8103311 0.3368261 0.3284936 -0.8498495 0.4121262 0.3153812 -0.7949672 0.5182294 0.13622 -0.8489561 0.5106053 0.1669802 -0.8204654 0.5467671 -0.007218301 -0.8425857 0.5385141 -0.02938628 -0.8733633 0.4861823 -0.2083342 -0.8554235 0.4741809 -0.2087275 -0.8679401 0.4506805 -0.3818687 -0.853424 0.3547449 -0.3816217 -0.8555965 0.3497423 -0.524969 -0.7972652 0.2979529 -0.4818814 -0.8544977 0.1939691 -0.5717513 -0.8126542 0.112666 -0.4635638 -0.8860614 -0.001947224 -0.5318579 -0.839986 -0.1074755 -0.4236179 -0.889586 -0.1708353 -0.4830074 -0.8169078 -0.315223 -0.3962582 -0.8161241 -0.4206196 -0.3465875 -0.8484529 -0.4000061 -0.1997005 -0.8124983 -0.5476917 -0.146463 -0.8516363 -0.5032536 -0.01921039 -0.8168935 -0.5764687 0.03913801 -0.8583077 -0.5116407 0.1574828 -0.8138868 -0.5592743 0.2187634 -0.8610247 -0.4591071 0.3597818 -0.8014179 -0.4777933 0.3772538 -0.8590888 -0.3458989 0.4933596 -0.8000079 -0.3414437 0.5373862 -0.8269276 -0.1655505 0.4809339 -0.8710369 -0.09998738 0.5700857 -0.8210812 -0.02877581 0.5451897 -0.8247554 0.1501566 0.4968803 -0.853336 0.1578855 0.458156 -0.8202903 0.3423695 0.3946377 -0.8554308 0.3354091 0.2998673 -0.808008 0.5071516 0.2153127 -0.8740682 0.4354828 0.04777806 -0.8710365 0.4888893 -0.01556473 -0.7960574 0.605021 -0.1423469 -0.8660942 0.4791851 -0.2709345 -0.7982273 0.537985 -0.3318198 -0.8605512 0.3864548 -0.3786656 -0.8381299 0.3926203 -0.4282783 -0.8816474 0.1981807 -0.559239 -0.812175 0.1662038 -0.5182614 -0.8548367 0.02567905 -0.5963878 -0.8012928 -0.04744905 -0.4932906 -0.8535863 -0.1674961 -0.5071493 -0.8456763 -0.1662263 -0.394451 -0.8353044 -0.3829817 -0.3930386 -0.8361623 -0.3825615 -0.2380706 -0.8255903 -0.5115889 -0.2033021 -0.8515887 -0.4831821 -0.01610791 -0.7883071 -0.6150712 0.05713498 -0.8554323 -0.5147536 0.1472685 -0.8147552 -0.5607904 0.2635486 -0.8626258 -0.4317624 0.2114456 -0.8886237 -0.4069876 0.4541997 -0.8127524 -0.3648784 0.3966745 -0.8963026 -0.1982195 0.547273 -0.8237492 -0.1480872 0.5500403 -0.8348604 -0.02153724 0.5720797 -0.8201752 -0.006121397 0.5157043 -0.8348783 0.1924248 0.5155711 -0.8349652 0.1924052 0.4389747 -0.8271868 0.3508041 0.3390471 -0.8820748 0.327095 0.2580747 -0.8381407 0.4805392 0.1797335 -0.8907533 0.4174383 -0.02574098 -0.8038618 0.5942589 -0.06054896 -0.8583641 0.5094557 -0.2273289 -0.8156825 0.5319622 -0.2490813 -0.8601648 0.4450564 -0.410973 -0.8018999 0.4336565 -0.4101468 -0.8542525 0.3194253 -0.5198067 -0.8078194 0.2779006 -0.4869449 -0.8607532 0.1482857 -0.5604777 -0.8217784 0.1026897 -0.5105427 -0.8584209 -0.04959654 -0.5779436 -0.8056057 -0.1303097 -0.4756446 -0.844635 -0.2456708 -0.5028337 -0.8285796 -0.2461996 -0.3876782 -0.8239167 -0.4133604 -0.3006988 -0.8730247 -0.383938 -0.219996 -0.800173 -0.5579651 -0.1043734 -0.8618008 -0.4963927 -0.00395894 -0.8021774 -0.5970726 0.08248859 -0.8568411 -0.5089393 0.1839603 -0.8115548 -0.5545607 0.2448095 -0.8653278 -0.4373516 0.35029 -0.8230848 -0.4470217 0.3952415 -0.8578856 -0.3283542 0.5050755 -0.804497 -0.3125437 0.4822662 -0.8577476 -0.1780124 0.5651733 -0.8155005 -0.1246526 0.540376 -0.8412773 0.01570051 0.5230791 -0.8522822 0.001850903 0.5543594 -0.808125 0.199047 0.4479405 -0.8653979 0.2245792 0.440348 -0.8050004 0.3975777 0.344162 -0.8667966 0.3608549 0.1810981 -0.8653126 0.4673731 0.1701956 -0.8351533 0.5230225 0.003858864 -0.8344168 0.5511204 5.46954e-4 -0.831103 0.5561183 -0.1661709 -0.8868717 0.4310984 -0.266331 -0.8263337 0.4962261 -0.3986133 -0.7830359 0.4774539 -0.3859052 -0.8652949 0.3199092 -0.5262728 -0.7994135 0.2897849 -0.4896758 -0.8607134 0.1392489 -0.5929618 -0.8012182 0.08028542 -0.515794 -0.8479402 -0.1222869 -0.5356449 -0.8361166 -0.1182941 -0.4987934 -0.8293751 -0.2516786 -0.3892598 -0.8849362 -0.2556657 -0.3439022 -0.8278155 -0.44323 -0.2663993 -0.8777535 -0.3982215 -0.09947478 -0.8687443 -0.4851683 -0.07170313 -0.815568 -0.5742018 0.1350222 -0.8415284 -0.5230669 0.1374961 -0.8481636 -0.5115792 0.3301942 -0.8020086 -0.497749 0.335056 -0.8631758 -0.3777105 0.462036 -0.8125172 -0.3554413 0.4402286 -0.8683488 -0.228406 0.571237 -0.8069965 -0.1498171 0.5021554 -0.863079 -0.05417484 0.5816051 -0.809823 0.07695585 0.4789258 -0.8674306 0.134886 0.533199 -0.8039783 0.2632828 0.4453625 -0.816847 0.3666243 0.3308782 -0.8767293 0.3490923 0.3066367 -0.7948328 0.5236552 0.09505444 -0.9038908 0.4170684 0.01617336 -0.8105677 0.5854217 -0.1548569 -0.8907939 0.4272066 -0.285301 -0.8100777 0.5122281 -0.3651194 -0.8593307 0.3581042 -0.4077757 -0.8369048 0.3651158 -0.5588999 -0.8022255 0.209917 -0.5676146 -0.82025 0.07073539 -0.5033284 -0.855715 0.1200518 -0.5325791 -0.8390914 -0.110839 -0.5185576 -0.8495833 -0.09646898 -0.4900397 -0.8173682 -0.3029363 -0.414503 -0.8575509 -0.3046208 -0.3729383 -0.8033919 -0.4641966 -0.2604981 -0.8610324 -0.4367657 -0.1861058 -0.7851085 -0.5907363 -0.03350532 -0.9109159 -0.4112296 0.173073 -0.7896462 -0.5886465 0.2477386 -0.8771362 -0.4114097 0.3367148 -0.8261111 -0.451845 0.4600713 -0.872443 -0.1648564 0.5002782 -0.8429689 -0.1978014 0.5879389 -0.8087535 0.01567548 0.4894835 -0.8693081 0.0686255 0.5455999 -0.8078863 0.2228014 0.4044435 -0.8721399 0.2753138 0.4267228 -0.8149721 0.3920819 0.2464892 -0.8492166 0.4669841 0.2451944 -0.8400837 0.4838793 -0.04345756 -0.8122344 0.5817103 0.01734054 -0.8741415 0.4853619 -0.2005544 -0.8533999 0.4811306 -0.2006924 -0.8610849 0.4671784 -0.4377516 -0.7920823 0.4254165 -0.4119371 -0.868215 0.2766056 -0.5268059 -0.8103181 0.2566329 -0.5461139 -0.8326869 0.09160894 -0.459925 -0.887174 0.03730124 -0.5385764 -0.8324941 -0.1299583 -0.4057304 -0.899317 -0.1631311 -0.469996 -0.7703296 -0.4309248 -0.2897566 -0.8744887 -0.3889868 -0.2669435 -0.837122 -0.4774599 -0.06640106 -0.8912116 -0.4487013 0.008602619 -0.8009456 -0.5986753 0.1756209 -0.8651189 -0.4698158 0.2522884 -0.8153329 -0.5211363 0.3237228 -0.8923146 -0.314608 0.4618189 -0.8294057 -0.3143398 0.4275779 -0.8855698 -0.1815029 0.5345064 -0.8364341 -0.121165 0.4511549 -0.8924148 -0.007434308 0.5716409 -0.8133188 0.108348 0.3891342 -0.8983548 0.2037971 0.4426282 -0.8256874 0.3497436 0.2984101 -0.8858357 0.3553122 0.2681506 -0.8395114 0.4725633 0.1507911 -0.8842029 0.4420942 0.08092683 -0.8306352 0.5509049 -0.01706051 -0.8539204 0.5201239 -0.07327973 -0.8150012 0.5748071 -0.2189313 -0.840962 0.4948252 -0.2268112 -0.8361158 0.4994667 -0.4226841 -0.8130784 0.4003021 -0.3961113 -0.8628283 0.3140436 -0.5561441 -0.7964129 0.2375509 -0.4413049 -0.8896127 0.1176407 -0.5425339 -0.8380323 -0.05795621 -0.4494196 -0.8888835 -0.08892869 -0.5013608 -0.8213568 -0.2720482 -0.3524058 -0.8931988 -0.279296 -0.3459045 -0.8189627 -0.4578757 -0.1952778 -0.9008666 -0.3876931 -0.06294465 -0.7845192 -0.6169018 0.02140313 -0.8709127 -0.4909714 0.1734772 -0.8016674 -0.5720447 0.3458348 -0.791226 -0.5043409 0.2289701 -0.8468887 -0.4799502 0.4536886 -0.8088481 -0.3740742 0.4148097 -0.8578104 -0.3034703 0.4686565 -0.8724457 -0.138563 0.5033702 -0.8539304 -0.1319911 0.5280073 -0.8440893 0.0933901 0.4276444 -0.8984465 0.09957057 0.462924 -0.7954944 0.3910115 0.3080375 -0.8969843 0.3170682 0.42925 0.03574919 0.902478 0.169512 -0.5462259 0.8203067 -0.03415429 0.8213365 0.5694207 0.8436254 0.5107876 -0.1655066 0.9573198 -0.2424293 0.1573752 0.5127809 -0.6101191 0.6039955 0.2659682 0.515361 0.8146558 0.1569156 -0.6282683 0.7620083 -7.44549e-4 0.4937292 0.8696155 -0.2763784 -0.4160459 0.8663262 -0.7809819 0.5107001 0.3595175 -0.7411273 -0.6611581 0.1166209 -0.7018495 0.7099227 -0.05845558 -0.7114149 -0.6392726 -0.2919239 -0.6693001 -0.6650975 0.3311837 -0.8153058 0.5678276 0.1133503 -0.793137 -0.6081865 -0.03229641 -0.7528904 0.6228393 -0.2126672 -0.6915904 -0.6307132 -0.3519995 -0.5935075 0.5863733 -0.551285 -0.5334613 -0.5773418 -0.6181387 -0.3274324 0.5929363 -0.7356729 -0.1513636 -0.6694828 -0.7272427 0.4468328 -0.4489555 -0.7738084 0.6287404 0.6099089 -0.4823864 0.698768 -0.6830349 -0.2125718 0.8453799 0.5337998 0.01976907 0.729058 -0.6653443 0.1605969 0.6164743 0.5909771 0.5202938 0.5043609 -0.4288962 0.7494452 0.421031 0.7342658 -0.5325287 0.5799211 -0.6459125 -0.4964762 0.6951054 0.6722941 -0.2546549 0.4775606 -0.3868491 0.7888496 0.1884711 0.5271482 0.8286094 0.06944447 -0.7003965 0.7103676 0.8912023 -0.3993852 -0.2150583 0.8850401 0.4554775 0.09614795 0.6854711 -0.7072964 0.1728039 0.3132383 0.6910977 0.6513568 0.2581331 -0.5572595 0.7891953 -0.05086994 0.6265686 0.7777044 -0.4123964 -0.6978657 -0.5855876 -0.2953515 0.4973419 -0.8157319 -0.05353516 -0.4030319 -0.9136189 0.3018447 -0.6057323 -0.7361917 0.5611178 0.598977 -0.5712912 0.674537 -0.4289399 -0.6008415 0.9329712 0.02924203 -0.3587614 0.102491 0.6698293 0.7354076 -0.2124727 -0.2880152 0.9337574 -0.6015734 0.06897974 0.7958338 -0.2479901 0.5738111 -0.7805394 -0.03373861 -0.5061855 -0.8617644 0.3073523 0.6537053 -0.691523 0.4707837 -0.5673375 -0.6756412 0.6457763 0.5466524 -0.5330517 0.6807002 -0.5764359 -0.4520719 0.7556048 0.6175723 -0.2183254 0.6665642 -0.7438631 -0.04857879 -0.175233 -0.6213135 0.7637165 -0.4351462 0.5896569 0.6804061 -0.790126 -0.1681984 0.5894152 -0.9609518 0.1795049 0.2105937 0.557938 0.5733546 -0.5999748 0.688848 -0.5341652 -0.4900571 0.717029 0.6568315 -0.2333278 -0.1765624 0.6828135 0.7089369 -0.3054975 -0.5992531 0.7399778 -0.575481 0.5417675 0.6126252 -0.6134646 -0.5409568 0.5753494 -0.7310971 0.6158483 0.2936458 -0.6644176 -0.7292357 0.1635991 -0.3679403 -0.110639 -0.9232438 0.02932399 0.1610634 -0.9865083 -0.1623875 0.7039195 0.6914678 -0.3512839 -0.5898001 0.7271421 -0.5068544 0.6710464 0.5411057 -0.8674191 0.4972626 0.01772004 -0.8343803 -0.5137118 -0.1997739 -0.6373349 0.6888756 -0.3453327 0.3635551 -0.6559913 0.6614402 0.1523137 0.6315563 0.7602218 -0.01973569 -0.7308569 0.6822453 -0.7324185 0.3869037 0.5602399 -0.8854761 -0.3867205 0.2576419 0.4567108 0.7416897 -0.4912348 0.6517456 -0.5743775 -0.4952961 0.8010647 0.5454741 -0.2464821 0.5049651 0.6346704 0.5849819 0.3301563 -0.6838637 0.6506361 0.1392675 0.6789638 0.7208417 -0.03454977 -0.6694517 0.7420518 0.5315508 -0.677563 0.5082935 0.2547414 0.5750826 0.7774233 -0.04893791 -0.5090534 0.8593427 -0.3480554 0.5302106 0.7731328 -0.6201459 0.6114594 -0.4914636 -0.4361143 -0.6816681 -0.5874803 -0.2635396 0.7074547 -0.6557856 -0.08886456 -0.6640194 -0.742416 0.3750731 -0.610803 0.6973091 0.1844129 0.5634959 0.8052729 0.005618274 -0.6496365 0.7602243 -0.1537135 0.5358795 0.830184 -0.4359219 -0.4621541 0.7722603 -0.2238255 -0.1792346 -0.9580069 0.2492853 0.5083855 -0.8242579 0.4536803 -0.6883952 -0.5659384 0.6850388 0.5946875 -0.4207952 0.7010551 -0.6692448 -0.246238 0.3037244 -0.6799947 0.6673521 0.1322987 0.4885486 0.8624485 -0.06398087 -0.5680086 0.820532 -0.7398195 0.6722017 -0.02849602 -0.7428824 -0.6387236 -0.2003946 -0.652293 0.6428832 -0.401516 -0.5112968 -0.7197489 -0.469614 -0.2474743 0.6103672 -0.7524681 0.02446699 -0.4042047 -0.9143414 0.3243774 -0.7063884 -0.6291222 0.5884115 0.4972656 -0.6375727 0.7976816 -0.3434578 -0.4957228 0.8052444 0.4487207 -0.3875968 0.7893792 -0.5941556 -0.1544666 0.7410427 0.6694848 0.05143904 0.7517838 -0.6397114 0.1599704 0.6475611 0.6620075 0.3773736 0.611617 -0.6056777 0.5089981 0.5328248 0.5066682 0.6777796 0.390604 -0.5352516 0.7489555 0.1307739 0.6590801 0.7406157 -0.7638021 -0.57767 0.2879304 -0.8171342 0.5764122 -0.006395339 -0.8181383 -0.5636318 -0.1138821 -0.7292219 0.6092521 -0.3115243 -0.6839646 -0.6144611 -0.3932304 -0.5286506 0.5396054 -0.6552516 -0.485116 -0.5423145 -0.6859719 -0.1904117 0.6130056 -0.7667905 -0.0680471 -0.7304024 -0.6796191 0.8127309 0.2884392 -0.5062325 0.9287594 -0.3108257 -0.2019742 0.8180223 0.5707151 -0.07158178 0.7274562 -0.6701873 0.1471617 0.7202666 0.6237533 0.303559 0.665445 -0.4830895 0.569041 0.04369425 0.01174253 0.9989759 -0.191853 -0.3303653 0.9241489 -0.4028323 0.1820675 0.8969825 -0.4367346 -0.650705 0.621165 -0.09630203 -0.9760754 0.1949437 -0.5750761 -0.2453665 0.7804376 -0.3269245 -0.6389041 0.6963634 -0.1457747 -0.8818771 0.4483777 -0.3336862 -0.5119249 0.7915721 -0.4622179 -0.1123469 0.8796209 -0.2262968 -0.380787 0.896544 -0.2150171 -0.2442165 0.9455824 -0.04588484 -0.765752 0.6414971 -0.05967026 -0.1422758 0.9880269 0.03034937 -0.7689711 0.6385629 0.03540366 -0.7616252 0.64705 0.01976585 -0.9986363 0.04832142 0.05743467 -0.3001593 0.9521585 0.2014725 -0.6986519 0.6865088 0.2467648 -0.6097059 0.753237 0.2007448 -0.07108324 0.9770613 0.2697976 -0.2225736 0.9368405 0.06970655 -0.9912015 0.1125189 0.1907541 -0.9267515 0.3236427 0.4443034 0.01274144 0.8957859 0.4878057 -0.4711154 0.7349122 0.4246907 -0.7451853 0.5141369 0.5228464 -0.3616489 0.7719079 0.5336361 -0.7049202 0.4672474 0.7279698 -0.03612381 0.6846569 0.7160398 -0.08728259 0.6925812 0.5512674 -0.7382853 0.3886374 0.4913766 -0.821717 0.2886701 0.3818325 -0.8968444 0.2233253 0.6684735 -0.6187715 0.412632 0.8096014 -0.2654519 0.5235274 0.9035692 -0.05830776 0.424456 0.8414893 -0.4565668 0.2888646 0.1396599 -0.9894332 0.03895133 0.8907828 -0.3349971 0.3070554 0.5898304 -0.7988237 0.118241 0.4520882 -0.890298 0.05464458 0.724267 -0.67335 0.1484488 0.9931854 -0.00602144 0.11639 0.9175054 -0.397457 0.01455372 0.5289921 -0.8442766 -0.08581745 0.6073521 -0.7849269 -0.122529 0.9006398 -0.4320094 -0.04707437 0.6272889 -0.7591053 -0.1739767 0.9616326 -0.2138466 -0.1718502 0.9205381 -0.2675346 -0.2846664 0.5564669 -0.7819166 -0.2809823 0.641541 -0.6529936 -0.4025228 0.9096712 -0.09743213 -0.4037392 0.7708188 -0.4130261 -0.4850234 0.1809073 -0.9723476 -0.1476911 0.02852231 -0.9990676 -0.03240847 0.4219981 -0.7685621 -0.4808637 0.4271501 -0.7334375 -0.5287837 0.6970818 -0.08144658 -0.7123507 0.6316344 -0.2570089 -0.7314264 0.3679935 -0.7442153 -0.5574266 0.105376 -0.9513181 -0.2896376 0.3417391 -0.602546 -0.7212162 0.1044366 -0.94451 -0.3114387 0.2336752 -0.6280665 -0.7422455 0.4423207 -0.2510138 -0.8610137 0.2185475 -0.5926948 -0.7752097 0.3504675 0.1012327 -0.9310879 0.2690744 -0.1936635 -0.9434477 0.07735514 -0.6101661 -0.7884882 0.01539468 -0.9245836 -0.3806685 -0.004061877 -0.7388861 -0.6738182 0.05382329 -0.2842394 -0.9572414 -0.03960335 -0.9890514 -0.1421583 -0.09430718 -0.6782925 -0.728715 -0.03626239 -0.1063941 -0.9936627 -0.1596564 -0.3608817 -0.9188441 -0.1708051 -0.7781004 -0.6044713 -0.06020855 -0.981364 -0.1824817 -0.2607809 -0.2964184 -0.9187653 -0.2817152 -0.6774893 -0.6794444 -0.321917 -0.5674687 -0.757858 -0.3634357 0.2673062 -0.8924471 -0.2926132 -0.8390893 -0.4585923 -0.4865365 -0.3537768 -0.7988269 -0.4480682 -0.7586133 -0.4730125 -0.5857121 -0.3939874 -0.7083186 -0.4778725 -0.7227041 -0.4993362 -0.6838529 -0.1752449 -0.7082617 -0.3160582 -0.9201444 -0.2311741 -0.7926707 -0.3661109 -0.4874795 -0.7556026 -0.3898324 -0.5263987 -0.6550869 -0.699249 -0.2862028 -0.8679926 -0.1213743 -0.4815155 -0.9126452 -0.2198296 -0.3446068 -0.4837093 -0.8710351 -0.08557641 -0.6991316 -0.6742244 -0.2379841 -0.694162 -0.6888915 -0.2087292 -0.9559145 -0.09052813 -0.2793424 -0.9067738 -0.4085924 -0.1039885 -0.500694 -0.8655279 -0.0129252 -0.9130269 -0.4007183 -0.07620239 -0.8372783 -0.5466942 0.009523034 -0.3675379 -0.9287788 0.04781019 -0.999234 -0.03898257 0.003448367 -0.6270921 -0.7531892 0.1986493 -0.8643552 -0.4754168 0.163918 -0.9269831 -0.3193746 0.196729 -0.9503818 -0.1685632 0.2614589 -0.2498307 -0.9504866 0.184824 -0.5899088 -0.7286518 0.3479573 -0.6278814 -0.6996365 0.3409894 -0.8612112 -0.2019729 0.466393 -0.8618094 -0.1770372 0.4753341 -0.2867181 -0.8992219 0.3304433 -0.5781071 -0.6475442 0.4964662 -0.4287372 -0.7549387 0.4962379 -0.7337007 -0.167906 0.6584002 -0.7095574 -0.04786556 0.7030202 -0.08541184 -0.9953759 -0.04395264 -0.002753496 -0.9998142 -0.01908469 -2.87815e-4 -0.9999777 0.0066908 0.008352339 -0.9999472 -0.006003141 -0.002767801 -0.9999866 0.004388272 -7.44885e-4 -0.9999998 -8.17284e-5 -9.57312e-4 -0.9999594 0.008966922 -0.004100263 -0.999979 -0.005032241 0.5535755 -0.5525771 -0.6230673 0.5940076 -0.4982418 -0.6315933 0.2532585 -0.9213021 -0.2950637 0.6538541 -0.4876067 -0.5785453 0.5554119 -0.7405853 -0.3782208 0.5602254 -0.7479137 -0.3560515 0.5402105 -0.7822006 -0.3103786 0.7066233 -0.6473047 -0.2857974 0.8943721 -0.3766098 -0.2413793 0.7173869 -0.6445302 -0.2644558 0.9119607 -0.3879716 -0.1334387 0.4698555 -0.8792963 -0.07793569 0.4764332 -0.8758937 -0.07630097 0.8011668 -0.5945855 -0.06782126 0.8325017 -0.5537081 0.01866775 0.753302 -0.6529196 0.07894396 0.6713516 -0.7354274 0.09183418 0.4538395 -0.8900815 0.04224616 0.6771264 -0.7105474 0.1913701 0.8037074 -0.5236493 0.2825703 0.09404134 -0.9952159 0.02648693 0.3122261 -0.9395547 0.1405411 0.7197712 -0.5519734 0.4210166 0.7325369 -0.5237328 0.4348492 0.7379344 -0.3379301 0.5841713 0.4406324 -0.8511144 0.2853901 0.3562527 -0.8890613 0.2874963 0.5549547 -0.5891005 0.5873551 0.4750057 -0.7265123 0.4965376 0.5704275 -0.4878701 0.6607536 0.0703004 -0.9940908 0.08271312 0.2216563 -0.912191 0.3446391 0.4357507 -0.4753157 0.7643274 0.4008818 -0.5297092 0.7474638 0.2611719 -0.8279724 0.4962368 0.3243681 -0.379911 0.866287 0.1354916 -0.8641532 0.4846457 0.1706581 -0.6498442 0.7406608 0.1319733 -0.5768383 0.8061269 0.03263068 -0.9727903 0.2293783 0.02703762 -0.6575168 0.7529547 -0.03361129 -0.467539 0.8833333 -0.008869171 -0.8444441 0.5355704 -0.1363819 -0.5979626 0.7898359 -0.220966 -0.4153963 0.8823944 -0.09205043 -0.811598 0.576919 -0.114048 -0.9068863 0.4056481 -0.317266 -0.4818247 0.8168153 -0.3170811 -0.5747696 0.754387 -0.07255792 -0.9841558 0.1617799 -0.4089719 -0.6761422 0.6128408 -0.425458 -0.5701916 0.7027569 -0.2609253 -0.8799914 0.3969048 -0.5799726 -0.5632377 0.5885534 -0.5647461 -0.6193502 0.5454056 -0.4136214 -0.8176038 0.4005514 -0.7066479 -0.5016495 0.4989954 -0.2557287 -0.9510304 0.1736209 -0.6642993 -0.6461825 0.3757057 -0.7934026 -0.4798441 0.3745156 -0.428017 -0.8728201 0.234492 -0.8589498 -0.4360829 0.2683972 -0.850004 -0.4513763 0.2715746 -0.4986695 -0.8533283 0.1521824 -0.8455104 -0.5170361 0.1333643 -0.4068557 -0.9107283 0.07101184 -0.899921 -0.4245931 0.09931355 -0.3864424 -0.9201881 0.0625801 -0.84924 -0.5272306 -0.02862519 -0.4920982 -0.8704797 -0.01024019 -0.7665752 -0.6396107 -0.05710399 -0.8010573 -0.5723604 -0.1752452 -0.7670823 -0.6105489 -0.1970146 -0.8430518 -0.4167203 -0.3400115 -0.4047794 -0.9013267 -0.1541548 -0.1665441 -0.9849066 -0.04714065 -0.7203047 -0.5747352 -0.388382 -0.7807736 -0.3921163 -0.4864539 -0.5401263 -0.7849666 -0.3034654 -0.7268918 -0.4009429 -0.5575601 -0.4257079 -0.8438099 -0.3267381 -0.5849 -0.632828 -0.5073665 -0.2551128 -0.940438 -0.2247087 -0.5590201 -0.5615221 -0.6100734 -0.4251058 -0.6774221 -0.6003203 -0.3834567 -0.7462053 -0.5441862 -0.4357724 -0.6288153 -0.6439673 -0.4028732 -0.481121 -0.7785986 -0.2691045 -0.5909786 -0.7604782 -0.1271144 -0.9461598 -0.297697 -0.1688057 -0.8250055 -0.5393241 -0.2508365 -0.3704078 -0.8943597 -0.111552 -0.4895595 -0.864805 -0.04164749 -0.7389945 -0.672423 -0.04896378 -0.7596587 -0.6484761 -0.03234863 -0.7491321 -0.6616303 0.07303392 -0.462098 -0.8838165 0.007716834 -0.9969294 -0.07792472 0.1970799 -0.7236309 -0.6614515 0.09841758 -0.8820297 -0.4608011 0.1632535 -0.758538 -0.6308475 0.2940534 -0.3996277 -0.868234 0.2603867 -0.8211014 -0.5079286 0.4404897 -0.4737249 -0.7625967 0.4772753 -0.4081405 -0.7782222 0.1750662 -0.956035 -0.2352634 0.6694489 -5.81273e-4 -0.7428579 0.7611334 0.003246665 -0.6485872 0.7865336 -0.001201927 -0.6175464 0.8201466 0.001532435 -0.5721514 0.8563143 -0.005420744 -0.5164269 0.9252582 0.004529833 -0.379311 0.8986454 -0.004772365 -0.4386502 0.9553177 -0.005478322 -0.2955304 0.9945505 0.005457401 -0.1041129 0.9949595 0.004548251 -0.1001743 0.9994882 -0.004639387 0.03165251 0.9999091 -0.00187689 0.01335328 0.9801287 -0.002718091 0.1983441 0.9816377 -0.001508295 0.1907495 0.9479088 -0.00546813 0.3184949 0.9560779 -8.96572e-6 0.2931126 0.878546 -9.72063e-4 0.477657 0.8637167 0.003834724 0.5039631 0.7823132 -5.73963e-4 0.6228851 0.7610394 0.005144894 0.6486853 0.7062407 0.005524039 0.7079503 0.6381087 -0.003332614 0.7699391 0.5810815 0.002459347 0.8138418 0.5262155 -0.003543257 0.8503439 0.4201585 0.00685513 0.9074249 0.3282592 -0.005700588 0.9445705 0.2305622 0.003020226 0.9730529 0.1465737 0.002140223 0.9891974 0.1434339 0.001504719 0.9896588 -0.02264857 -0.001922845 0.9997417 -0.02741801 -0.002607762 0.9996207 -0.1391728 0.003778517 0.9902609 -0.2173789 -0.004713296 0.976076 -0.3338014 0.005656123 0.9426265 -0.4072999 -0.003201663 0.9132889 -0.4851887 0.0012784 0.8744086 -0.5780997 0.001531898 0.8159648 -0.5444418 -0.003767192 0.8387902 -0.7009685 -0.004569172 0.7131776 -0.7361189 0.003150165 0.676845 -0.8207501 -0.004602134 0.571269 -0.8530407 0.002155482 0.5218401 -0.8834714 -0.003485262 0.4684723 -0.9420164 0.003643512 0.335547 -0.9760845 0.003701806 0.2173598 -0.9566992 -0.002042055 0.2910714 -0.9961032 0.002355635 0.08816397 -0.9929385 -0.001796901 0.1186173 -0.9948921 -0.001423358 -0.1009339 -0.9966751 0.002564489 -0.08143848 -0.9796655 -0.003744065 -0.200603 -0.9553749 0.007337987 -0.295305 -0.9259272 -0.003763496 -0.3776835 -0.8816129 0.001221239 -0.4719717 -0.8715807 -0.001062631 -0.490251 -0.7863579 0.003976941 -0.6177586 -0.7590613 -0.003638207 -0.6510089 -0.6828602 -0.005388736 -0.7305293 -0.6245642 0.004242956 -0.7809621 -0.5752581 -0.001348733 -0.8179709 -0.4719092 0.002255618 -0.8816443 -0.4720737 0.002219915 -0.8815563 -0.3456391 0.004006564 -0.938359 -0.2334508 0.005634963 -0.9723523 -0.2785483 -0.001304507 -0.9604214 -0.078408 0.00289303 -0.9969173 -0.07163393 0.003862679 -0.9974235 0.05686324 -3.04214e-4 -0.998382 0.08562844 -0.005454838 -0.9963122 0.2299845 -1.96605e-4 -0.9731944 0.2871985 -0.006545782 -0.9578488 0.3715113 0.005737483 -0.9284107 0.4508951 0.01046013 -0.8925157 0.5365462 -0.005958855 -0.84385 0.6389109 0.003799676 -0.7692714 -0.005278825 -0.9996863 -0.02448594 -0.01606267 -0.9998587 0.004975736 -0.002893686 -0.9999811 -0.005435645 -0.008673608 -0.9996647 0.02440178 -0.00921911 -0.9999393 0.006049573 -0.0222125 -0.9996945 0.01083612 -0.0137965 -0.9998796 -0.007104337 0.009670555 -0.9997628 0.01951301 -0.001530051 -0.999997 0.001947164 0.007513225 -0.9998638 -0.01469999 5.58446e-4 -0.9999859 -0.005276203 -9.60124e-4 -0.9999979 0.001849353 -8.94091e-4 -0.9999853 -0.005347728 4.22337e-4 -0.9999974 0.002262294 2.59452e-4 -0.9999805 -0.006246089 5.85567e-4 -0.9999976 0.002146422 8.083e-4 -0.9999976 0.00207436 0.001013278 -0.9999315 -0.0116682 0.001596152 -0.9999829 -0.005637526 9.23157e-4 -0.9999989 0.001207292 0.00434643 -0.9999679 -0.006730973 1.66854e-5 -0.9999967 0.002567291 0.004563868 -0.9999896 4.14568e-4 0.02240592 -0.9997321 0.00580722 0.02158945 -0.9997629 0.002851247 0.00279802 -0.99987 -0.01587992 0.483471 0.5810324 -0.6547191 0.3615819 0.7780341 -0.5137332 0.2660585 0.8472273 -0.4598031 0.4368537 0.4007635 -0.8053246 0.2647144 0.7416337 -0.616365 0.220794 0.5152967 -0.8280818 0.2178614 0.748114 -0.626787 0.1969767 0.4491913 -0.8714513 0.1218863 0.8743867 -0.4696719 0.108592 0.4958457 -0.8615943 0.03021734 0.744634 -0.6667887 0.0152474 0.9948755 -0.0999512 0.004155755 0.7698124 -0.6382567 -0.05032831 0.72299 -0.6890229 -0.1247617 0.7669481 -0.6294643 -0.1627314 0.7253937 -0.6688218 -0.04696232 0.9884939 -0.1437863 -0.3234086 0.6373704 -0.699404 -0.2641304 0.7306702 -0.6295684 -0.1930465 0.8970647 -0.3975023 -0.3822783 0.5598397 -0.7351482 -0.4683421 0.653876 -0.5942239 -0.5552359 0.5362648 -0.6357147 -0.2687238 0.8932838 -0.3603216 -0.6231875 0.5502897 -0.5557146 -0.717203 0.4087769 -0.564377 -0.3091371 0.9237582 -0.2260644 -0.1451563 0.9803136 -0.1338464 -0.7609309 0.4775859 -0.4391991 -0.6881008 0.6396187 -0.3426445 -0.50841 0.8229064 -0.2536617 -0.8664317 0.4202849 -0.269549 -0.7815447 0.5976354 -0.1789408 -0.3588623 0.9271218 -0.1079952 -0.5858994 0.8028781 -0.1100402 -0.962244 0.2600058 -0.08051925 -0.5906038 0.8069448 -0.00522834 -0.8513521 0.5232608 0.03739041 -0.8362273 0.5469201 0.04002916 -0.3950749 0.9183077 0.02503806 -0.7867836 0.5930466 0.1710774 -0.5671446 0.8128036 0.1330321 -0.7915954 0.5870819 0.1694449 -0.8462409 0.4148166 0.3343703 -0.4050137 0.8979051 0.172425 -0.8069621 0.4728494 0.3538725 -0.7886157 0.4003546 0.4666923 -0.2985349 0.9416362 0.155558 -0.6680583 0.5809177 0.4650084 -0.4560298 0.8293316 0.3228713 -0.6804609 0.3538857 0.6416682 -0.5777049 0.5011187 0.6443115 -0.3602265 0.8513904 0.381276 -0.5463804 0.4465277 0.7085772 -0.2526445 0.9154777 0.3131636 -0.3770523 0.6597893 0.6500076 -0.278605 0.8374698 0.4701317 -0.3808132 0.5581299 0.7372059 -0.1750974 0.9158996 0.3612045 -0.2986765 0.4591388 0.8366504 -0.1200798 0.841531 0.5266938 -0.1503913 0.6750241 0.7223053 -0.1269007 0.6237378 0.7712635 -0.0115509 0.6334209 0.7737213 -0.01361554 0.9828636 0.183831 -0.004965364 0.6430013 0.765849 0.1073188 0.4836649 0.868649 0.02905923 0.8723123 0.4880849 0.193258 0.7805635 0.594451 0.1485086 0.7601006 0.6326075 0.3020197 0.4988626 0.8123548 0.3605888 0.4487015 0.8177059 0.126208 0.9384821 0.3214388 0.3783913 0.5714804 0.7281692 0.2028768 0.9000498 0.385683 0.2171616 0.9212474 0.3227139 0.5149555 0.4725743 0.7151883 0.5207124 0.57222 0.6335795 0.4668745 0.7222183 0.5103225 0.4806028 0.7335486 0.4805491 0.6423839 0.5681428 0.5143507 0.3033859 0.9269577 0.2206953 0.663289 0.6372833 0.3923236 0.6970288 0.6024955 0.3887804 0.1191505 0.9903861 0.07027488 0.7911145 0.5456442 0.2764244 0.7135616 0.6408829 0.2830179 0.4355399 0.8897484 0.1365756 0.9068688 0.400463 0.1312193 0.858218 0.4979781 0.1244176 0.4421935 0.8946721 0.06345772 0.7794775 0.6211444 0.08120632 0.3370553 0.9410342 0.02912992 0.8016845 0.5964272 -0.03970819 0.9865394 0.1230596 -0.1076865 0.6321886 0.7703418 -0.08313304 0.8392338 0.5035037 -0.2053552 0.6165927 0.7807521 -0.1011914 0.4597318 0.8803963 -0.1164005 0.4910607 0.853872 -0.1725165 0.8561467 0.381832 -0.3481626 0.8487719 0.4082441 -0.3360403 0.4002264 0.8929238 -0.2061701 0.7259052 0.5377566 -0.4288116 0.594115 0.704428 -0.3883411 0.6047807 0.5523312 -0.5737339 0.5240986 0.7359375 -0.428622 0.08301544 0.9944034 -0.06534814 0.5515832 0.486048 -0.6778742 0.3174413 0.8979452 -0.3048371 -0.9925118 0.02107149 -0.1203179 -0.9921752 0.02339237 -0.1226431 -0.6003788 0.02599245 0.7992934 -0.5955212 0.02005982 0.8030893 0.3886797 0.01989722 0.9211581 0.3942876 0.02581024 0.9186246 0.842438 0.5292802 0.1008011 0.8357504 0.5396678 0.1013906 0.2468537 0.7510415 0.6123723 0.3415321 0.5355566 0.7723568 -0.3847233 0.7511032 0.5364999 -0.5162901 0.5310676 0.6718718 -0.6567397 0.7484017 -0.09267169 -0.8424578 0.5310662 -0.09073936 -0.2729888 0.7495435 -0.6030436 -0.32183 0.5391482 -0.7782961 0.5023115 0.5433874 -0.6726167 0.5088346 0.5300219 -0.6783541 -0.3918414 0.02583718 -0.91967 -0.3979735 0.01949506 -0.9171898 0.5992763 0.01944929 -0.800306 0.5983289 0.02059799 -0.8009859 0.9927043 0.01994228 0.1189143 0.99281 0.02100986 0.1178432 0.001798093 0.9999983 -5.22933e-4 0.008583426 0.9999573 -0.003431677 0.007851362 0.999963 -0.00352025 -0.01722735 0.9998255 0.007225334 5.18001e-4 0.9999806 0.006207227 -0.004099428 0.9999582 0.008184909 -0.004872739 0.999958 0.00777167 0.002027213 0.999992 0.003445208 0.008021533 0.9999655 0.002183616 0.005289733 0.9999794 0.003648698 0.002288758 0.9999794 0.006014347 -0.008259654 0.9999656 -9.08779e-4 -0.005538523 0.9999632 0.006555557 -0.00831288 0.9999643 -0.001557886 0.008075296 0.9999666 0.00123614 0.009817421 0.9999518 2.54714e-4 -0.009035468 0.9999589 -8.27029e-4 0.01085549 0.9998953 0.009574115 -0.01099395 0.9999242 -0.005551099 0.003654479 0.9999841 -0.004319429 -0.00386548 0.9999883 -0.002934455 -0.003597021 0.9999648 -0.007582306 0.003762304 0.9999843 -0.004183173 -0.005399346 0.9999849 -0.001098573 -0.00163871 0.9999883 -0.004561722 -0.01742237 0.9965764 -0.08082002 0.01183134 0.9990967 -0.04081636 0.0102722 0.9992055 -0.03850948 -0.03674042 0.9981601 -0.04823684 -0.007987678 0.9992556 -0.03774511 0.005812406 0.9999542 -0.007612526 -0.009012103 0.9990929 -0.04161947 0.08449685 0.9925462 -0.08782088 -0.005348801 0.9999816 -0.002894699 0.002864956 0.999628 -0.0271272 0.1164772 0.9902954 -0.07581609 0.003006398 0.9999725 0.006782293 0.0530346 0.9984176 0.01870018 0.02717775 0.9995688 -0.01112085 0.01091825 0.9999347 0.003402352 0.006174087 0.9999806 7.80777e-4 0.002433538 0.9999954 0.001839518 -6.81834e-4 0.9999997 -6.6798e-4 0.0198422 0.9997768 -0.00725007 0.01193916 0.9956416 0.09249526 0.4271427 0.8481194 0.3134368 0.4143925 0.7415258 0.5276536 0.1746127 0.9018425 0.3952096 0.1737982 0.7641422 0.6211931 -0.009742259 0.781965 0.6232463 -0.09006869 0.8957607 0.4353168 -0.2309103 0.8088507 0.5407782 -0.3390403 0.8445814 0.4144082 -0.4284048 0.7897741 0.4390063 -0.4901968 0.8247066 0.2820751 -0.5804287 0.7689964 0.2678566 -0.4896793 0.8718251 -0.011635 -0.585493 0.8086555 -0.05722254 -0.4040939 0.8823808 -0.2410652 -0.4387319 0.8527774 -0.2833462 -0.3809603 0.8051244 -0.4545812 -0.2605341 0.8566607 -0.4452579 -0.2485027 0.8176122 -0.5193811 -0.05929344 0.8253052 -0.5615654 0.003308415 0.8755336 -0.4831461 0.1624264 0.7756046 -0.6099634 0.2846738 0.8570345 -0.4294795 0.3324974 0.8271562 -0.4530543 0.4583207 0.8367709 -0.2995941 0.4250252 0.8557456 -0.2950474 0.5516495 0.8110394 -0.194674 0.5064218 0.8589571 -0.07569569 0.5857819 0.8104101 -0.00975579 0.5156756 0.8509927 0.09944939 0.5610032 0.8121387 0.1603317 0.4148433 0.8604922 0.2957336 0.4281466 0.8454251 0.3192912 0.3764566 0.7786308 0.5020107 0.183815 0.8706094 0.4563457 0.1576974 0.8038178 0.5735927 -0.04292756 0.8509033 0.5235655 -0.07551395 0.8208284 0.5661612 -0.2443857 0.8510319 0.4647801 -0.2555198 0.843216 0.4729657 -0.429293 0.8097117 0.4000931 -0.4052141 0.8644071 0.2976607 -0.5401532 0.8164212 0.2041835 -0.500059 0.860848 0.0942443 -0.5973969 0.8007444 0.04387885 -0.5223742 0.8390771 -0.1519047 -0.525452 0.8366286 -0.154767 -0.3931429 0.8583592 -0.3296336 -0.4303987 0.7954899 -0.4265593 -0.2332789 0.8597307 -0.4543611 -0.2247236 0.8153744 -0.5335392 -0.02203124 0.8446109 -0.5349273 -0.02389228 0.842947 -0.5374658 0.1781953 0.8497376 -0.496178 0.1646674 0.8304839 -0.5321478 0.3459096 0.8094009 -0.47457 0.3537306 0.8459477 -0.3990581 0.4478751 0.8143595 -0.3690891 0.410288 0.889645 -0.2004879 0.5359355 0.8355212 -0.1211513 0.4711169 0.8806371 -0.05027329 0.5304425 0.8433952 0.08552998 0.4917756 0.8603332 0.1341034 0.5505257 0.807096 0.2133487 0.4030495 0.846294 0.3483356 0.4255311 0.8055008 0.4124221 0.2114673 0.8940407 0.3949342 0.1303571 0.8176156 0.5608137 0.0735771 0.8544681 0.5142674 -0.07623255 0.8227621 0.5632506 -0.1108438 0.8531907 0.5096855 -0.2688249 0.8062124 0.5270246 -0.2876833 0.8428296 0.454837 -0.4070428 0.8090615 0.4239526 -0.401705 0.8671956 0.2942874 -0.5333945 0.8142846 0.2289782 -0.4985106 0.8546125 0.1453436 -0.5898933 0.8055123 0.05635637 -0.5146417 0.8559663 -0.04965662 -0.5825745 0.8024412 -0.1292097 -0.4516448 0.8490791 -0.2740108 -0.4788362 0.8152105 -0.3258032 -0.3377175 0.8428094 -0.4190697 -0.339246 0.8272586 -0.4478341 -0.1838361 0.8342382 -0.5198567 -0.1648709 0.8451147 -0.5085262 -0.01318484 0.8183298 -0.5745978 0.02791208 0.8523789 -0.5221793 0.1904032 0.8100606 -0.5545707 0.2363932 0.8648084 -0.4429727 0.34345 0.80516 -0.4834868 0.4738664 0.8315781 -0.2897043 0.435755 0.8682193 -0.2373037 0.4795238 0.876678 -0.03863579 0.5588526 0.8292238 -0.008470416 0.4352024 0.8864459 0.15752 0.4914001 0.8432645 0.2177862 0.3309609 0.8691184 0.3675568 0.3653228 0.8558799 0.3660724 0.3370561 0.7855663 0.5189209 0.1920493 0.855204 0.4813972 0.1376071 0.8188085 0.5573303 -0.006551742 0.8859675 0.463701 -0.07324659 0.8425791 0.5335686 -0.1732642 0.8864696 0.4291285 -0.2806025 0.826969 0.4872212 -0.3788956 0.8476884 0.3712985 -0.433596 0.8120108 0.3906831 -0.4379792 0.8906797 0.1219174 -0.605125 0.7912129 0.08835214 -0.501568 0.8616544 -0.07733917 -0.5637212 0.8118247 -0.1521815 -0.4505809 0.8536807 -0.261163 -0.4534152 0.8503996 -0.2668998 -0.2582973 0.8632624 -0.4336594 -0.2825652 0.8491904 -0.4461306 -0.145587 0.8009809 -0.5807186 0.01441633 0.9045748 -0.4260712 0.1534795 0.7953122 -0.5864491 0.228095 0.8642349 -0.4484091 0.3743892 0.7999986 -0.4688656 0.3804235 0.8612062 -0.3370487 0.5282297 0.7918579 -0.3064875 0.4868132 0.8606739 -0.149176 0.6006436 0.7956963 -0.07806771 0.4965644 0.8669783 0.04210054 0.5653373 0.8060424 0.175184 0.4035186 0.8903282 0.2109231 0.4124196 0.8072415 0.4222221 0.2667288 0.8718749 0.4107188 0.2440432 0.8130896 0.5285152 0.08053511 0.8622831 0.499982 0.06077718 0.8332635 0.5495256 -0.08429151 0.8013227 0.5922643 -0.1780543 0.8643136 0.4703814 -0.2973964 0.7897064 0.536581 -0.3105482 0.8934388 0.3245412 -0.4888013 0.8386586 0.2402604 -0.5012426 0.8247022 0.2619584 -0.5326521 0.8457029 0.03268665 -0.5284582 0.8482756 0.03406763 -0.5799551 0.796336 -0.1717591 -0.4143124 0.888728 -0.1962342 -0.3566846 0.8365073 -0.4159709 -0.296644 0.8677887 -0.3986791 -0.2273083 0.780556 -0.5822916 -0.04004555 0.8698295 -0.4917246 0.01748055 0.8088518 -0.5877526 0.2041393 0.8494314 -0.4866142 0.2025802 0.850655 -0.4851262 0.3969144 0.7878007 -0.4709874 0.3988624 0.8726239 -0.2818447 0.4839622 0.8305057 -0.2757552 0.5502228 0.8165596 -0.1746007 0.49677 0.8631532 -0.09047853 0.6141919 0.7889921 0.01611822 0.4609017 0.8718499 0.1656727 0.5268402 0.8159743 0.2379612 0.4324993 0.7988544 0.4180626 0.3069329 0.8669478 0.3926752 0.260605 0.8157417 0.5163822 0.1261603 0.8563705 0.5007129 0.09639197 0.8171796 0.568266 -0.06553417 0.8196499 0.569104 -0.08949309 0.8474667 0.5232505 -0.2374332 0.8284539 0.5072373 -0.2522335 0.8585808 0.4463376 -0.4037824 0.8242552 0.3969423 -0.4003896 0.8537945 0.3327513 -0.5302658 0.8092138 0.2529646 -0.4922827 0.8531833 0.172442 -0.5857619 0.8087894 0.05237287 -0.5331953 0.8459604 -0.007325172 -0.5709515 0.8151313 -0.09785515 -0.4229013 0.8887406 -0.1769029 -0.447031 0.816941 -0.3643772 -0.3716949 0.8566874 -0.3576723 -0.307744 0.8049483 -0.5072985 -0.1960515 0.8468295 -0.4944124 -0.1447706 0.8797037 -0.4529491 0.04255712 0.8527954 -0.5205084 0.03742057 0.8451276 -0.5332533 0.2122873 0.8881155 -0.4076579 0.3354166 0.808379 -0.4837554 0.3824686 0.8600155 -0.3377742 0.4741199 0.8151988 -0.332658 0.4834305 0.8590781 -0.1681669 0.5696434 0.8075422 -0.1529118 0.5919871 0.8059471 8.82855e-4 0.4406473 0.8935834 0.08566623 0.4901855 0.8360193 0.2465562 0.3981861 0.8799571 0.259082 0.352746 0.842807 0.4065056 0.2856799 0.8769522 0.3864478 0.1234512 0.8542872 0.5049291 0.1213263 0.8300137 0.544387 -0.07176035 0.8196432 0.5683621 -0.1162927 0.8661988 0.4859791 -0.2744391 0.8081442 0.5211392 -0.3070647 0.8581355 0.4114791 -0.4463808 0.7990511 0.402817 -0.4399141 0.8569638 0.2684934 -0.5233004 0.8180369 0.2386896 -0.4884999 0.8686929 0.08210086 -0.5673367 0.8225957 0.0382815 -0.5270496 0.8391749 -0.13418 -0.5337095 0.8339917 -0.1400429 -0.439428 0.8309265 -0.3412686 -0.4131873 0.8594961 -0.3009033 -0.3705078 0.7728684 -0.5151684 -0.1604054 0.8687135 -0.4686225 -0.1419993 0.8248702 -0.5471978 0.06186503 0.8918424 -0.448096 0.1542881 0.8200559 -0.5510932 0.2295782 0.887804 -0.3988708 0.3612497 0.8322561 -0.4205335 0.3996201 0.8610265 -0.3145429 0.4610434 0.8255987 -0.3253088 0.5869296 0.7854501 -0.1964223 0.4742192 0.8791877 -0.04631829 0.5948755 0.8020168 0.05378067 0.479869 0.8594285 0.1763756 0.5258312 0.8128879 0.2504293 0.3834741 0.8555274 0.3478804 0.3991094 0.7962595 0.4546236 0.1866384 0.8955259 0.4039794 0.1152071 0.8017139 0.5865001 -0.02599924 0.8714704 0.4897586 -0.06715124 0.8311514 0.5519767 -0.2688685 0.8050445 0.5287848 -0.2697488 0.893775 0.3583322 -0.4348421 0.8353527 0.3363007 -0.4435031 0.8530433 0.274995 -0.539002 0.8041545 0.2506243 -0.5015286 0.8618084 0.07586383 -0.5629861 0.8253339 0.04325056 -0.518003 0.8456014 -0.1289623 -0.5443308 0.8248995 -0.1524626 -0.5041731 0.8137618 -0.2891389 -0.3744502 0.8794653 -0.2938163 -0.310044 0.8466913 -0.4324197 -0.24738 0.8779329 -0.4099234 -0.1329249 0.8455844 -0.517028 -0.0821982 0.8798834 -0.4680263 0.1320825 0.8386895 -0.5283505 0.1402104 0.854112 -0.5008331 0.3585378 0.8075112 -0.4683763 0.3539922 0.8568754 -0.3747721 0.4809479 0.8145284 -0.324396 0.4549462 0.8716253 -0.1824653 0.56243 0.8144394 -0.1426926 0.5268639 0.8480964 0.05609977 0.4933205 0.8689043 0.04050123 0.5940806 0.773764 0.2199033 0.3516022 0.8753 0.3320028 0.3622817 0.8617956 0.3550499 0.2818692 0.7958425 0.5358963 0.1133208 0.8686571 0.4822793 0.08460026 0.8201012 0.5659301 -0.1224439 0.8245978 0.5523098 -0.1433581 0.8543409 0.49955 -0.3070994 0.8076302 0.5034119 -0.2978773 0.894469 0.3334581 -0.5120953 0.8103672 0.2847167 -0.4229103 0.8976941 0.1236624 -0.5423355 0.8373654 0.06849557 -0.4608656 0.8850128 -0.06599539 -0.5408151 0.827581 -0.1504293 -0.4662212 0.8463314 -0.2576062 -0.4950563 0.8100748 -0.3141624 -0.3296778 0.8528781 -0.40486 -0.3404009 0.8189232 -0.4620522 -0.09944373 0.8600162 -0.5004831 -0.1373901 0.8253471 -0.5476554 0.09223097 0.8758658 -0.4736589 0.1696654 0.8029394 -0.5714037 0.2670908 0.870182 -0.4140601 0.4011444 0.7943353 -0.456196 0.4662814 0.8278095 -0.3119505 0.443296 0.8586372 -0.2573535 0.541386 0.8218908 -0.1771914 0.4559156 0.8893074 -0.03568589 0.5509786 0.8330501 0.04949885 0.5355842 0.82951 0.158312 0.5779488 0.7907485 0.2017233 0.4002518 0.8545456 0.3309839 0.4090296 0.8419536 0.3518651 0.2477617 0.8222379 0.5123856 0.1681402 0.8643787 0.473897 0.07441455 0.8027781 0.5916163 -0.03762358 0.869377 0.492715 -0.1524527 0.7841134 0.6016016 -0.2622017 0.8960503 0.3582516 -0.4170242 0.8067615 0.4186009 -0.4365344 0.8677809 0.2374744 -0.5278239 0.8154928 0.2374314 -0.5908476 0.8061572 0.0317794 -0.4957447 0.8675987 -0.0388565 -0.5450313 0.8278446 -0.1327188 -0.390613 0.8907285 -0.2324314 -0.4365874 0.8454275 -0.3076425 -0.2497381 0.8556027 -0.4534037 -0.2505329 0.8552848 -0.4535649 -0.2192138 0.8026437 -0.5547149 -0.04653894 0.8556337 -0.5154855 -0.005858302 0.8096818 -0.58684 0.1727949 0.8531859 -0.4921543 0.2302573 0.8108094 -0.538117 0.3449168 0.8226606 -0.4519537 0.3443065 0.8678097 -0.3582732 0.4627258 0.8156584 -0.3472552 0.4567337 0.8832266 -0.1063261 0.4821488 0.8665558 -0.1288942 0.5074059 0.8571 0.0889877 0.5130919 0.8541017 0.08512926 0.5339762 0.7959232 0.2852647 0.4513369 0.8705599 0.1960113 0.4648832 0.8018643 0.3753631 0.2601683 0.893855 0.3651517 0.2275685 0.8265565 0.5147981 0.1097157 0.8633626 0.4925116 0.06877374 0.8062335 0.5875865 -0.1134391 0.8456175 0.5215964 -0.09875303 0.8247966 0.5567392 -0.2965453 0.8504839 0.4344398 -0.2918786 0.8297278 0.4757717 -0.4535489 0.8087536 0.3744478 -0.4364083 0.8608031 0.2618508 -0.5522859 0.799596 0.2358531 -0.5516858 0.833994 0.009851872 -0.5329575 0.8461394 -0.002130806 -0.5547862 0.8203309 -0.1388153 -0.4506044 0.8710097 -0.1956982 -0.4681849 0.8109936 -0.3508453 -0.3549447 0.8597767 -0.3671491 -0.3396559 0.7740299 -0.5343329 -0.1312504 0.9013937 -0.4126291 0.03280109 0.828164 -0.5595253 0.02395421 0.8448179 -0.5345174 0.2495012 0.813227 -0.5257481 0.1889804 0.8662043 -0.4625759 0.4106129 0.7922795 -0.4513207 0.3578243 0.9048154 -0.2308053 0.540668 0.8160171 -0.2044367 0.5881262 0.8045646 -0.08236151 0.4671473 0.8841302 -0.00933665 0.4717153 0.8599571 0.1948294 0.51812 0.8217846 0.2371114 0.3701322 0.8452758 0.3853715 0.375337 0.834729 0.4029265 0.2281914 0.8340913 0.5022155 0.2263932 0.8211981 0.5238128 0.08031851 0.8189682 0.5681902 0.02896708 0.8546187 0.5184476 -0.1233708 0.8224503 0.5552974 -0.1567186 0.8559981 0.4926527 -0.3172375 0.7992093 0.5105143 -0.3400864 0.8513689 0.3993901 -0.4562568 0.7993011 0.391085 -0.4538548 0.8705173 0.1903037 -0.5656051 0.8063236 0.1730125 -0.4414895 0.8960412 -0.04687458 -0.5475384 0.8271439 -0.1266282 -0.4080704 0.8827323 -0.2329428 -0.44213 0.8319202 -0.3353056 -0.3544307 0.8542987 -0.3802009 -0.3586634 0.8031585 -0.4757071 -0.1978944 0.8430321 -0.5001347 -0.1848495 0.8167045 -0.5466485 0.003426134 0.8507288 -0.5255938 0.02587479 0.8265413 -0.5622811 0.2331271 0.8319258 -0.5035389 0.1871368 0.8710649 -0.4541208 0.443117 0.7721575 -0.4554342 0.3662238 0.9091596 -0.1982654 0.5992063 0.7835676 -0.1642368 0.5054791 0.8628375 0.001595258 0.5766749 0.8141866 0.0674265 0.473287 0.8598659 0.1913904 0.5255114 0.8004939 0.2881795 0.3558984 0.8587628 0.3685957 0.3829689 0.7982097 0.4649689 0.2422826 0.8161005 0.5246705 0.06997156 0.9012596 0.4275923 0.02515363 0.837657 0.5456172 -0.1672459 0.8538423 0.4929323 -0.1215971 0.812781 0.5697378 -0.289264 0.7943992 0.5340939 -0.3462751 0.8625505 0.3689177 -0.478978 0.7910093 0.3806369 -0.4793518 0.8557644 0.1946516 -0.5699026 0.8040184 0.1696038 -0.5295938 0.848166 0.01204711 -0.5127171 0.8581401 0.02677005 -0.4669888 0.8641956 -0.1873166 -0.4352141 0.8856545 -0.1618796 -0.4408646 0.8167606 -0.3722103 -0.246524 0.9030694 -0.351698 -0.2441053 0.8314246 -0.499145 -0.03888297 0.88366 -0.4665118 -0.03518694 0.8759922 -0.4810401 0.1837485 0.8263353 -0.5323594 0.2085158 0.8942141 -0.3961092 0.3842146 0.835227 -0.3934145 0.3889771 0.8674087 -0.3103209 0.5148262 0.8045848 -0.2959684 0.517392 0.8476721 -0.1172925 0.5715332 0.8146415 -0.09853494 0.5352851 0.8388155 0.09928983 0.5598546 0.8201591 0.1179071 0.4676414 0.8252539 0.3166508 0.4267848 0.8478794 0.3145716 0.2938415 0.8233433 0.4855545 0.2485362 0.8495255 0.4653344 0.1201924 0.7960105 0.5932294 0.02239066 0.8629779 0.5047453 -0.1126027 0.8054034 0.5819331 -0.1898249 0.8611052 0.4716614 -0.2815349 0.8084479 0.5168657 -0.4048721 0.8379387 0.3659743 -0.4004669 0.8465276 0.3507384 -0.5265244 0.8317218 0.176099 -0.5423083 0.8160611 0.1998652 -0.5688609 0.8223087 -0.01434314 -0.5331735 0.8452227 -0.03639709 -0.5566529 0.8084468 -0.191184 -0.4231306 0.8666641 -0.264299 -0.4517985 0.8255944 -0.3380417 -0.2791504 0.8416299 -0.4623141 -0.2688778 0.8683521 -0.4167367 -0.1798727 0.7803539 -0.5989106 0.01725929 0.8666158 -0.4986774 0.06527751 0.8182126 -0.5711978 0.2067705 0.8133994 -0.5437164 0.2365921 0.8678518 -0.4368723 0.3504737 0.8159112 -0.4598448 0.4135732 0.8807922 -0.2305696 0.404653 0.8885523 -0.2161735 0.5637221 0.8221558 -0.07922857 0.4975095 0.867253 0.0188899 0.5969531 0.7964386 0.09660542 0.3741197 0.900031 0.223559 0.4293248 0.837608 0.3377767 0.3743191 0.8100545 0.451328 0.2476351 0.8833457 0.3979668 0.1255975 0.8372859 0.5321443 0.07897394 0.8512576 0.5187713 0.04781854 0.8170018 0.574649 -0.1506639 0.8289359 0.5386704 -0.1724951 0.8687478 0.4642442 -0.3406919 0.7921453 0.5063942 -0.4136841 0.8436279 0.3422825 -0.4036427 0.8617389 0.307374 -0.5421504 0.8131848 0.2116686 -0.4810263 0.8716269 0.09423583 -0.6165335 0.7870689 0.02022409 -0.4978598 0.8443582 -0.1979776 -0.4945797 0.8461214 -0.19867 -0.4721165 0.7979056 -0.3747701 -0.3521241 0.8581485 -0.373617 -0.3207419 0.8334627 -0.4499607 -0.1561199 0.8873885 -0.4337839 -0.1388263 0.8464071 -0.514123 0.08692395 0.8644724 -0.495108 0.07214552 0.847174 -0.5263946 0.2440485 0.8112346 -0.5313557 0.2716768 0.8564279 -0.4390023 0.3966934 0.8117339 -0.4286286 0.4197271 0.8625258 -0.2826279 0.5306094 0.7982865 -0.2849426 0.5570946 0.8229123 -0.1116288 0.4501015 0.8927561 -0.01988047 0.537174 0.8377432 0.09813469 0.4079302 0.8938964 0.1858557 0.4782225 0.8255525 0.2996104 0.3383183 0.8290939 0.4451339 0.3101907 0.8761022 0.3690894 0.08305525 0.8299734 0.5515851 0.04360735 0.8611452 0.5064854 -0.11721 0.8093755 0.5754765 -0.1743345 0.8689437 0.4631894 -0.3083118 0.7967832 0.5196926 -0.4206002 0.828312 0.370128 -0.3962093 0.8756382 0.2761813 -0.5621995 0.7914589 0.2398427 -0.4990753 0.8644519 0.06038945 -0.5901547 0.8072882 -0.001853823 -0.4965929 0.8572613 -0.1360096 -0.5391314 0.818028 -0.2004185 -0.4346854 0.8461534 -0.3083391 -0.4566273 0.809955 -0.3680552 -0.2406516 0.8930648 -0.3801606 -0.1877836 0.8043497 -0.5637012 -0.09698635 0.8619777 -0.4975825 0.03263813 0.8041252 -0.5935634 0.1240493 0.8664101 -0.4836791 0.2161598 0.8201346 -0.5297681 0.3273683 0.8486943 -0.4153891 0.3274853 0.8468175 -0.4191104 0.4845016 0.8028399 -0.3474283 0.4055691 0.8965683 -0.1779862 0.5786744 0.8134209 -0.05901241 0.4958566 0.867988 0.02689313 0.6012821 0.7870562 0.1378489 0.434963 0.8518737 0.2917507 0.4075611 0.8649381 0.2928754 0.4133461 0.8039412 0.4275786 0.200996 0.8513551 0.4845567 0.2009373 0.8392667 0.5052284 0.02765494 0.8038012 0.5942549 -0.04524695 0.8849462 0.4634902 -0.2739081 0.8407008 0.4671151 -0.2722404 0.8225043 0.4993717 -0.3779207 0.8353001 0.3993118 -0.3704763 0.8776325 0.3041523 -0.4765369 0.8348729 0.2754993 -0.4355056 0.893994 0.1054022 -0.4849407 0.870782 0.08106338 -0.3893798 0.9197977 -0.04853349 -0.6558626 0.678221 -0.3314524 -0.6803323 0.6500259 -0.3385476 -0.1254522 0.9558951 -0.2655681 -0.9897986 -0.05899447 0.1296858 -0.9206044 0.2085849 -0.3301213 -0.8100955 -0.4506522 -0.3750441 -0.5980793 0.4167934 -0.6845324 -0.5378279 -0.3818936 -0.7515972 -0.1749935 0.3475333 -0.9211938 -0.08617401 -0.4644348 -0.8814048 0.2549099 0.4849578 -0.8365626 0.4344112 -0.4012582 -0.8063987 0.5964707 0.1333224 -0.7914847 0.7680882 -0.2454833 -0.5914209 0.8245049 0.2773362 -0.4932304 0.9672524 -0.115023 -0.2262577 0.9782508 0.1152759 -0.1724438 0.9624542 -0.2496784 0.1065022 0.9603549 0.1817656 0.2113763 0.8494587 -0.1400831 0.5087206 0.8355786 0.0760414 0.5440829 0.4717794 -0.009093284 0.8816698 0.4421065 -0.2421163 0.8636676 0.03418833 0.2925746 0.9556314 -0.006468713 -0.1035255 0.9946058 -0.3953921 -0.1025552 0.9127692 -0.3897995 -0.1290341 0.911815 -0.6619244 0.2528466 0.7056378 -0.7002077 -0.3494168 0.6225891 -0.8848976 0.3207243 0.3377755 -0.903762 -0.3434256 0.2554861 -0.9130274 0.3964627 -0.0959084 -0.9211247 -0.3419391 -0.1860296 -0.7743971 0.2713639 -0.5715515 -0.7426919 0.3557076 -0.5673453 -0.470799 -0.4966001 -0.7292028 -0.2706736 0.4719446 -0.8390496 -0.1179767 -0.272845 -0.954797 0.07468086 0.262124 -0.9621402 0.241746 -0.3297197 -0.9126028 0.4249743 0.2891427 -0.8577841 0.570395 -0.3003361 -0.7644919 0.7125817 0.4089117 -0.570104 0.818575 -0.2737152 -0.5049899 0.9666014 0.1328625 -0.2191559 0.9764249 -0.1036351 -0.1893525 0.9780132 0.1164357 0.1730113 0.9811967 -0.03568482 0.1896833 0.7817923 0.0940566 0.6164042 0.7588739 0.2903166 0.5829465 0.5102975 -0.4181148 0.7515161 0.217613 0.5389683 0.8137308 0.2090368 0.09235584 0.9735369 -0.1147919 -0.3815791 0.9171806 -0.2954987 0.3639475 0.8833022 -0.452867 -0.2285071 0.8617981 -0.6282956 0.3575446 0.6909462 -0.7226577 -0.2726406 0.6351639 -0.9154143 0.1356609 0.3789628 -0.9303898 -0.1082882 0.3502122 -0.9945254 0.1031482 0.0167312 -0.9887757 -0.1484097 -0.01723563 -0.8926852 0.3045275 -0.332229 -0.8420042 -0.3468469 -0.4131902 -0.7067723 0.1924384 -0.6807645 -0.6766951 -0.1233584 -0.7258557 -0.417293 0.206456 -0.88501 -0.3769814 -0.1277421 -0.9173697 -0.07075536 0.1283355 -0.9892036 -0.02740925 -0.2024905 -0.9789006 0.3369643 0.1208423 -0.9337304 0.3707658 -0.3174827 -0.8727757 0.5899174 0.5532162 -0.5881747 0.6648648 -0.5861001 -0.4630783 0.9077147 0.3645731 -0.2077031 0.9845745 -0.06657266 -0.1618061 0.9671142 0.1832024 0.1764287 0.9167046 -0.3269028 0.2297548 0.7967835 0.2754014 0.5378572 0.7312383 -0.2864791 0.6190479 0.5016061 0.4170086 0.7579547 0.4232501 -0.3563054 0.8330102 0.0711044 -0.01728981 0.9973191 6.87034e-4 0.3580414 0.9337055 -0.2714967 -0.2911904 0.9173319 -0.4374357 0.3941664 0.8082593 -0.5858613 -0.4269461 0.6888278 -0.7517108 0.2988736 0.5878821 -0.9122423 -0.2095663 0.3519885 -0.9476345 0.1300028 0.2916986 -0.9936462 -0.08436113 -0.07450217 -0.9942007 0.039384 -0.1000699 -0.8934519 -0.1281616 -0.4304865 -0.8876883 0.01935881 -0.4600378 -0.6408078 0.1703587 -0.7485609 -0.561875 -0.3836103 -0.7328981 -0.1929832 0.4078789 -0.8924083 -0.07217419 -0.4326723 -0.8986576 0.1531909 0.3180528 -0.9356148 0.3622512 -0.242155 -0.900075 0.4990194 0.3480315 -0.7936333 0.6010632 -0.467948 -0.6478794 0.8074136 0.415789 -0.4185724 0.909438 -0.2020325 -0.3634634 0.9735755 0.2094818 -0.09092992 0.9623891 -0.2716429 -0.004183471 0.9456735 0.1893827 0.264265 0.8720268 -0.3430454 0.3491265 0.7334019 0.4162576 0.537449 0.5953916 -0.2832276 0.7518584 0.5142135 0.2151538 0.8302369 0.2249361 -0.4409185 0.8689044 0.02213293 0.5079828 0.8610828 -0.2528593 -0.3189411 0.9134216 -0.3616304 0.1010625 0.9268279 -0.6102545 -0.1756834 0.7724797 -0.666445 0.1178237 0.7361852 -0.8640844 -0.04019039 0.5017399 -0.8509409 0.3475245 0.3938611 -0.8479445 -0.5129879 0.1335427 -0.8847463 0.4545712 -0.102903 -0.8843448 -0.3476106 -0.3116108 -0.7969598 0.3781232 -0.4710393 -0.581947 -0.5046716 -0.6376867 -0.499303 0.3305566 -0.8008925 -0.1764791 -0.02343618 -0.9840254 -0.1639134 -0.1538671 -0.9744011 0.2581961 0.1151238 -0.9592087 0.2861785 -0.3453233 -0.8937861 0.6040906 0.4283923 -0.6719782 0.7076968 -0.3585117 -0.6087977 0.8585922 0.2618229 -0.4407587 0.8893161 -0.3839639 -0.2483723 0.9458075 0.313148 -0.08594518 0.9200165 -0.3130866 0.2356828 0.9367756 0.1385163 0.3213482 0.7017401 0.041933 0.7111979 0.6598247 -0.2526475 0.7076727 0.3764758 0.2052707 0.9033991 0.3162908 -0.1951444 0.9283744 0.0250647 0.3016555 0.9530875 -0.07680118 -0.3356421 0.9388536 -0.3677714 0.1943061 0.9093896 -0.4209692 -0.1202267 0.8990721 -0.6859729 0.2422866 0.6861037 -0.7208721 0.03989946 0.6919187 -0.8658659 -0.3136001 0.3897837 -0.9055525 0.3495698 0.2403658 -0.9641255 -0.2570648 0.06617915 -0.9075772 0.3858745 -0.1655439 -0.9193216 -0.2734193 -0.2830015 -0.8024404 0.1372166 -0.5807419 -0.7469101 -0.2716655 -0.6068964 -0.4371626 0.4394536 -0.7847099 -0.3726015 -0.3557587 -0.8570903 0.01704663 0.1349326 -0.9907081 0.03599655 0.2479456 -0.9681051 0.3568129 -0.2885751 -0.8884869 0.4890538 0.3812927 -0.7845013 0.6641426 -0.2653774 -0.6989203 0.7862855 0.3052954 -0.5371685 0.8025189 -0.4679723 -0.3700883 0.8656547 0.4907826 -0.09886533 0.9370409 -0.3390139 0.08381009 0.8911282 0.3571099 0.2799341 0.8040393 -0.4265931 0.4141731 0.6140276 0.3126156 0.7247356 0.6614402 0.1476829 0.7353141 0.3085631 -0.08649033 0.9472636 0.3187856 -0.1628732 0.933728 -0.1114192 0.2712306 0.9560438 -0.1499483 -0.1467031 0.9777494 -0.5195455 -0.1922118 0.8325427 -0.5773535 0.4206191 0.6998161 -0.7484582 -0.3618776 0.5557473 -0.8698707 0.3172498 0.377727 -0.9346158 -0.2601226 0.2425485 -0.9444245 0.3260855 0.04160338 -0.9332377 -0.3236146 -0.1560162 -0.9373365 0.1748555 -0.3013733 -0.8003968 -0.2887768 -0.5253313 -0.772298 0.1670909 -0.612892 -0.4831485 0.258933 -0.8363739 -0.3673333 -0.4680483 -0.8037394 -0.09873837 0.3843308 -0.9179002 0.03124499 -0.3654949 -0.9302888 0.3600522 0.3139593 -0.8785169 0.4188638 -0.04740709 -0.9068107 0.7335547 -0.08863854 -0.6738255 0.752924 0.1756718 -0.6342279 0.9680492 -0.1710464 -0.1833687 0.9633016 0.2424928 -0.1150973 0.9265261 -0.279258 0.2521198 0.9019878 0.2377973 0.3603754 0.7836855 -0.1373895 0.6057733 0.7173404 0.2076732 0.6650524 0.4907794 -0.2535591 0.8335726 0.4168145 0.1828059 0.89042 0.03636968 -0.2535626 0.966635 -0.05076855 0.2978658 0.9532569 -0.5085247 -0.2212448 0.832138 -0.5663368 0.09568631 0.8186005 -0.8040371 -0.09457248 0.5870099 -0.8197062 0.297928 0.4892042 -0.9190459 -0.3221377 0.227117 -0.9441464 0.3211887 0.07365721 -0.9280247 -0.3405658 -0.1509478 -0.881579 0.3429828 -0.3243167 -0.8179932 -0.2320454 -0.5263479 -0.7369688 0.2273839 -0.6365325 -0.5691479 -0.2874656 -0.7703468 -0.442339 0.2586891 -0.8587295 -0.2541367 -0.3090255 -0.9164703 -0.03203749 0.4487101 -0.893103 0.155752 -0.4765266 -0.8652536 0.3931241 0.475799 -0.7868093 0.5579271 -0.4235983 -0.7136399 0.7497925 0.3832265 -0.5393967 0.8398244 -0.3261804 -0.4339368 0.9185719 0.3357406 -0.2085762 0.864051 -0.503299 0.01030653 0.940085 0.2943821 0.1719869 0.8346138 0.2233275 0.5035322 0.6548988 -0.5713599 0.4946265 0.5551441 0.3673495 0.7462368 0.3014373 -0.3367254 0.8920492 0.2094483 0.2296645 0.950466 -0.1953943 -0.1850997 0.9630987 -0.2369111 0.01883834 0.9713488 -0.5958085 -0.03540521 0.8023458 -0.6143936 0.1727055 0.7698658 -0.9122834 -0.1852611 0.3652634 -0.9295036 0.2086259 0.3041356 -0.9760512 -0.2122823 -0.04754203 -0.8465262 0.4933135 -0.2000883 -0.836897 -0.4052801 -0.3679015 -0.6601181 0.2280032 -0.7157225 -0.6850258 0.1223487 -0.7181717 -0.2676894 -0.02349311 -0.9632189 -0.2427796 0.1085994 -0.9639835 0.1025578 -0.1935907 -0.9757072 0.1777633 0.1376294 -0.9744015 0.4649299 -0.1343178 -0.8750994 0.5121812 0.1346612 -0.8482552 0.8189912 0.04456871 -0.5720727 0.822269 -0.06984347 -0.5647971 0.963777 -0.2069075 -0.1682952 0.8281857 0.5604519 0.001486122 0.9004137 -0.3940244 0.184391 0.7826209 0.2502822 0.5699679 0.8317155 -0.03834891 0.5538762 0.4276056 0.226767 0.8750601 0.4055524 -0.1375464 0.9036638 0.001967549 -0.01720708 0.9998501 -0.006389796 0.03518271 0.9993606 -0.5037314 0.08850717 0.8593143 -0.5144062 -0.05262994 0.8559302 -0.8130488 -0.0216211 0.581794 -0.7900542 -0.3139854 0.5265241 -0.8562915 0.4926488 0.1551191 -0.9054319 -0.4240815 0.01866161 -0.9041513 0.3583297 -0.2326159 -0.7855318 -0.5071615 -0.3545799 -0.6176799 0.5159724 -0.5935016 -0.5250685 -0.3399446 -0.7802185 -0.3840261 0.295072 -0.8749038 -0.1629868 -0.4764114 -0.8639836 0.1041396 0.4453845 -0.8892625 0.2436876 -0.253367 -0.9361739 0.4641389 0.2546979 -0.8483538 0.5566563 -0.4412642 -0.7038606 0.7238379 0.3236362 -0.609359 0.9451444 -0.07686579 -0.3174805 0.940198 0.09667927 -0.3266203 0.9450585 -0.3189354 0.07172727 0.9203909 0.323602 0.2194592 0.8789127 -0.2666975 0.3954556 0.6858971 0.4685964 0.5567428 0.59815 -0.44234 0.6682454 0.3172006 0.2913679 0.9024903 0.2927302 -0.09777194 0.9511834 -0.1264812 0.1366156 0.9825166 -0.1433295 -0.01421052 0.9895731 -0.5021789 -0.001190483 0.864763 -0.503434 -0.01551514 0.8638944 -0.8058614 -0.1326066 0.5770642 -0.8251199 -0.003899812 0.5649443 -0.9207869 0.3588243 0.1529595 -0.9022961 -0.4241497 0.07719397 -0.9412111 0.07831835 -0.3286153 -0.9005744 0.2593318 -0.3488737 -0.7425057 -0.1610659 -0.650187 -0.6659291 0.2632021 -0.6980424 -0.3699395 -0.401825 -0.8376644 -0.2044776 0.3974791 -0.8945386 -0.0172941 -0.22601 -0.9739716 0.1559664 0.2594646 -0.9530755 0.329126 -0.3841289 -0.8626245 0.4878163 0.2467536 -0.8373457 0.7557525 -0.0916168 -0.648417 0.7291883 -0.3389856 -0.594452 0.8474884 0.4665238 -0.2532177 0.8476646 -0.5191131 -0.109483 0.9004343 0.3851937 0.2020989 0.9365906 -0.1816461 0.2996712 0.7562878 0.2844534 0.5891647 0.7276382 -0.2395941 0.6427577 0.4727882 -0.05720055 0.8793177 0.4046791 0.2498927 0.8796526 0.1338086 -0.1334519 0.9819806 0.003736436 0.3563382 0.9343496 -0.1863059 -0.4687942 0.8634363 -0.4799891 0.3554272 0.8020486 -0.5728038 -0.1977871 0.7954722 -0.764586 0.2994366 0.5707416 -0.7947392 -0.4300879 0.4282688 -0.9205259 0.2900188 0.2617655 -0.975224 -0.2211066 -0.007086873 -0.9957463 0.06419444 -0.06609416 -0.9072806 0.06627345 -0.4152708 -0.9070886 0.01871687 -0.4205233 -0.7188038 -0.2252233 -0.65772 -0.6489373 0.2115669 -0.730835 -0.433351 -0.1045314 -0.8951426 -0.3163695 0.3352456 -0.8874237 -0.07805234 -0.4548768 -0.8871273 0.1788799 0.3594802 -0.9158472 0.3071413 -0.4246495 -0.8516672 0.5026895 0.4334868 -0.7479254 0.8049048 -0.1688931 -0.5688614 0.7797375 -0.3182177 -0.5392097 0.9755516 0.205948 -0.07671207 0.9931311 0.09488123 -0.06847196 0.9465808 -0.1231914 0.2980077 0.9423158 0.03547298 0.3328404 0.7724419 -0.009339213 0.6350169 0.7213723 -0.2895628 0.6291069 0.3484586 0.4354153 0.8300543 0.2383928 -0.5155687 0.8230175 -0.05037021 0.3653187 0.9295188 -0.2271463 -0.3159546 0.9211825 -0.3866009 0.2785516 0.8791751 -0.5966811 -0.2609575 0.758863 -0.6823924 0.3502666 0.6416028 -0.7944014 -0.4442258 0.4142343 -0.8892003 0.4098352 0.2033669 -0.9803714 -0.1705878 0.09885263 -0.9660813 0.2049779 -0.15707 -0.8622966 -0.4381338 -0.2539361 -0.7512008 0.4586841 -0.4746645 -0.5993466 -0.4309668 -0.6745749 -0.4956914 0.3465381 -0.7963676 -0.1691234 -0.4249909 -0.8892582 -0.1015936 0.0279482 -0.9944334 0.2752158 0.3866177 -0.8802176 0.344573 -0.3705073 -0.8625507 0.7323846 0.03876131 -0.679787 0.7359757 0.1863566 -0.6508541 0.9532717 -0.08071029 -0.2911339 0.9590509 0.1352078 -0.2488778 0.9836987 -0.1433112 0.1086226 0.9884008 0.0436998 0.1454451 0.8441089 -0.07438564 0.5309869 0.8261249 0.09361499 0.5556562 0.5338744 0.01934629 0.8453425 0.5332129 0.00981158 0.8459242 0.124171 -0.2466071 0.9611278 -0.01808905 0.4626678 0.8863472 -0.2594987 -0.4007603 0.8786647 -0.4516869 0.4430679 0.7743836 -0.6295685 -0.4138843 0.6575282 -0.7795042 0.3498309 0.5196071 -0.8967765 -0.2275571 0.3794862 -0.9191939 0.3574027 0.1653668 -0.877225 -0.4796185 0.0210396 -0.8532474 0.4268617 -0.2995966 -0.8461452 -0.3203442 -0.4259321 -0.7198802 0.2964792 -0.6275928 -0.5278828 -0.4555806 -0.7167888 -0.4118928 0.3490092 -0.8417464 -0.04829198 -0.1768131 -0.9830591 -0.001290261 0.08519136 -0.9963638 0.4001294 -0.1095464 -0.9098879 0.3588749 -0.2848242 -0.8888668 0.671351 0.4020904 -0.6225844 0.7233438 -0.4822353 -0.4941891 0.8917984 0.2662519 -0.3657947 0.9725094 -0.2299439 -0.0367611 0.9874439 -0.1515929 -0.04443073 0.9067496 0.2235108 0.3575586 0.8715258 -0.2802458 0.4023746 0.6627596 0.2968863 0.6874651 0.5669839 -0.365204 0.7383464 0.3671772 0.2830094 0.8860512 0.2248244 -0.2913498 0.9298222 0.04059666 0.3221373 0.9458222 -0.2430499 -0.3619688 0.8999474 -0.3097438 -0.08197063 0.9472801 -0.6905764 0.3156023 0.6507685 -0.7445228 -0.05216538 0.6655558 -0.9078363 -0.3242632 0.2658697 -0.9619703 0.1935083 0.1927894 -0.932703 0.286167 -0.2194849 -0.8947326 -0.3581505 -0.2667995 -0.752423 0.156534 -0.6398099 -0.7346466 -0.1152048 -0.6685973 -0.4620297 0.1095912 -0.8800673 -0.4176194 -0.2019311 -0.8858996 -0.1162766 0.3449113 -0.9314053 0.04299771 -0.4179177 -0.9074668 0.2264739 0.2350755 -0.9452244 0.4410315 -0.2333419 -0.8666273 0.5523453 0.4536146 -0.6993915 0.6478048 -0.5379275 -0.5394285 0.8165153 0.4940337 -0.2987197 0.9078502 -0.3952957 -0.1398199 0.8957091 0.4380357 0.07635593 0.8098244 -0.5242826 0.2632725 0.7012194 0.4836429 0.5238138 0.5884619 -0.4902726 0.6429194 0.3374251 0.5792223 0.7420552 0.1552575 -0.5634983 0.8113968 -0.1480506 0.4081655 0.900823 -0.248521 -0.3425002 0.9060525 -0.5105082 0.5075421 0.6941055 -0.6398698 -0.528168 0.5582162 -0.8433474 0.164423 0.5115958 -0.9807393 -0.02616065 0.193562 -0.9807562 -0.01715326 0.1944814 -0.9756171 0.08266627 -0.2033165 -0.9692832 0.1480978 -0.1963597 -0.7959073 -0.3870494 -0.465537 -0.6627004 0.4212656 -0.6191638 -0.5991516 -0.2210922 -0.7695035 -0.4064917 0.2524939 -0.8780725 -0.2598001 -0.3759925 -0.8894569 -0.04351246 0.3487079 -0.936221 0.1498026 -0.3280539 -0.9327057 0.3432769 0.4087707 -0.8456167 0.4903104 -0.4309836 -0.7575281 0.6960207 0.3791702 -0.6097419 0.8147885 -0.3489131 -0.4630113 0.903995 0.271257 -0.3304736 0.9689776 -0.2449067 -0.03321456 0.9977746 -0.06667178 -0.001012027 0.863586 0.2666183 0.4279415 0.7786723 -0.434494 0.4526416 0.5371986 0.3992878 0.7429583 0.4157802 -0.4608669 0.7840464 0.2212279 0.2966077 0.9290221 -0.001809597 -0.2606908 0.9654207 -0.1082683 0.1967857 0.9744503 -0.4131623 -0.1115037 0.9038053 -0.4707217 0.215938 0.8554483 -0.6461915 -0.4243252 0.634338 -0.7100156 0.5910286 0.3828358 -0.8883465 -0.3239392 0.325429 -0.9998787 -0.003608524 -0.01515936 -0.9300007 0.3587894 -0.07980477 -0.8458526 -0.3904903 -0.363388 -0.7507691 0.4154169 -0.5135897 -0.5563793 -0.3345015 -0.7606253 -0.5322279 0.02392774 -0.8462629 -0.04507875 0.007288992 -0.9989569 -0.01372861 0.2349516 -0.9719102 0.4412851 -0.3125826 -0.8411656 -0.3133131 -0.9126862 -0.2623717 -0.1262481 -0.9019909 -0.4128849 -0.1164802 -0.577408 -0.8081043 0.06991517 -0.9131679 -0.4015426 0.3090647 -0.8180344 -0.4850762 0.3219075 -0.8074159 -0.4944241 0.4952995 -0.822002 -0.2810536 0.404297 -0.8685009 -0.2867929 0.4923737 -0.8607485 -0.1291521 0.6021823 -0.7953567 -0.06916737 0.5778338 -0.8115831 0.08626264 0.5421772 -0.8389335 0.04727131 0.4213738 -0.8779404 0.227299 0.4546614 -0.8434296 0.286199 0.4022101 -0.7996913 0.4457812 0.2734073 -0.8611823 0.4285016 0.2365962 -0.8023527 0.5479531 0.06204783 -0.8613947 0.5041323 0.0198757 -0.8182281 0.5745502 -0.1581238 -0.8021359 0.5758254 -0.1753038 -0.8497074 0.4972586 -0.3512262 -0.8279263 0.4372394 -0.3540278 -0.8261744 0.4382925 -0.4733223 -0.8160729 0.331649 -0.4028145 -0.8922721 0.2039391 -0.5609688 -0.8212112 0.1045283 -0.4317023 -0.9020121 0.002702832 -0.5944208 -0.7725706 -0.2231565 -0.3976696 -0.8841915 -0.2450802 -0.427481 -0.8139324 -0.3934136 -0.2833997 -0.814988 -0.5054497 -0.1997312 -0.8653852 -0.4595825 -0.126129 -0.803603 -0.5816474 -0.00436908 -0.8556731 -0.5174983 0.08672428 -0.8036988 -0.5886827 0.1832088 -0.8644778 -0.4680947 0.3126475 -0.7994201 -0.51301 0.3709518 -0.8564354 -0.3590449 0.420602 -0.8311409 -0.3637288 0.5301402 -0.8044992 -0.2678295 0.4799571 -0.8642594 -0.1506546 0.5809611 -0.8106511 -0.07300108 0.5109459 -0.858138 0.05033296 0.5712136 -0.812549 0.1161 0.4997224 -0.8270536 0.2574101 0.398931 -0.8792153 0.2604509 0.4113024 -0.7831019 0.4664566 0.1959621 -0.8504227 0.4882419 0.1760399 -0.8674542 0.4653313 -0.03271734 -0.7799685 0.624963 -0.1164245 -0.859901 0.4970067 -0.204571 -0.8155612 0.5413046 -0.3818253 -0.8162158 0.4335912 -0.3150196 -0.8532832 0.4155363 -0.477657 -0.8382325 0.2630784 -0.4599784 -0.8564448 0.2343552 -0.5680022 -0.8172455 0.09738314 -0.51481 -0.8559813 0.04760915 -0.5763236 -0.8070429 -0.1285803 -0.5241016 -0.8391984 -0.1451328 -0.5191468 -0.8340311 -0.1867588 -0.3661954 -0.8824597 -0.2952389 -0.3877947 -0.8307253 -0.3993879 -0.2735471 -0.8319979 -0.4826505 -0.2729158 -0.8285982 -0.4888169 -0.07790297 -0.8332973 -0.5473087 -0.07873511 -0.8343591 -0.5455691 0.1001966 -0.8053938 -0.5842102 0.1361148 -0.8574327 -0.4962681 0.2783401 -0.8135688 -0.510522 0.3030222 -0.8752143 -0.3770646 0.4632934 -0.7938953 -0.393814 0.4185366 -0.8968701 -0.1430074 0.6005156 -0.7952054 -0.08384335 0.500347 -0.86458 0.0464152 0.5715656 -0.8054709 0.1566185 0.4547573 -0.8467468 0.2760721 0.4486043 -0.8577287 0.2511093 0.299371 -0.8808037 0.3668269 0.3044816 -0.864324 0.4002937 0.127703 -0.8194383 0.55876 0.001801311 -0.8264532 0.5630026 0.04753178 -0.8651158 0.4993149 -0.1878226 -0.8227045 0.5365445 -0.1965458 -0.8641702 0.4632275 -0.3871494 -0.8123276 0.4361642 -0.3874313 -0.8494141 0.3583194 -0.5154157 -0.7991431 0.3093816 -0.4742835 -0.8596613 0.189836 -0.5739561 -0.8095611 0.1232287 -0.5126679 -0.8584876 -0.01307225 -0.573115 -0.8158356 -0.07714653 -0.5159903 -0.8153454 -0.2626136 -0.492946 -0.8433785 -0.2138153 -0.3598412 -0.8620785 -0.3568404 -0.3692755 -0.8277753 -0.4224025 -0.272772 -0.8007234 -0.5333268 -0.1528164 -0.8654211 -0.4771724 -0.0674026 -0.8026731 -0.5925984 0.03998309 -0.8521555 -0.521759 0.1126934 -0.8128333 -0.5714913 0.2259221 -0.8654156 -0.4472303 0.2974234 -0.8249587 -0.4806063 0.4507123 -0.8014997 -0.3930099 0.3784035 -0.8913611 -0.2495721 0.524667 -0.8343529 -0.1690559 0.4562003 -0.8856337 -0.08680123 0.5414944 -0.8391402 0.05125868 0.4660747 -0.8805243 0.08632266 0.4806116 -0.8342327 0.2703119 0.447813 -0.8524492 0.2698035 0.3471314 -0.8322515 0.4322699 0.307372 -0.8570888 0.4134261 0.1469433 -0.795933 0.5872805 0.06183481 -0.8898172 0.4521082 -0.164619 -0.8239251 0.542262 -0.165894 -0.829508 0.5332877 -0.3110742 -0.8431183 0.4386165 -0.3029988 -0.8673149 0.3949135 -0.43136 -0.8583884 0.277665 -0.4038789 -0.8832138 0.2383598 -0.5770156 -0.8123834 0.08418077 -0.4979701 -0.8671436 -0.009375572 -0.5764929 -0.8115447 -0.09513908 -0.4797398 -0.8472255 -0.2281641 -0.4865344 -0.8399632 -0.2403041 -0.2935915 -0.8750945 -0.3847258 -0.2983194 -0.8488882 -0.436342 -0.1527937 -0.8567225 -0.4926265 -0.1355594 -0.8173931 -0.5599038 0.1016428 -0.8563676 -0.5062642 0.09717816 -0.8475672 -0.5217149 0.3213487 -0.8039189 -0.5004494 0.3140447 -0.8520289 -0.4188349 0.472083 -0.8101527 -0.347549 0.4433135 -0.8523703 -0.2773771 0.5726302 -0.8105981 -0.1225782 0.5366715 -0.8386895 -0.09264898 0.5702207 -0.8177078 0.07875519 0.4448303 -0.8891299 0.1075828 0.4566538 -0.8135092 0.3600972 0.3991319 -0.8473694 0.3502266 0.3049544 -0.8109958 0.4992882 0.2389233 -0.8516413 0.4665005 0.1272748 -0.8218406 0.5553191 0.0606442 -0.8575583 0.5107994 -0.01333504 -0.8189826 0.5736635 -0.1534356 -0.855896 0.493862 -0.1566639 -0.8540813 0.4959853 -0.3098396 -0.864732 0.3952698 -0.3016383 -0.8817436 0.3626884 -0.5160956 -0.8114428 0.2742372 -0.4784352 -0.8604185 0.1754416 -0.5805978 -0.8053216 0.1198469 -0.5134673 -0.8568983 -0.04557377 -0.4758754 -0.8794334 -0.01181966 -0.5071382 -0.8353874 -0.2119883 -0.3889723 -0.8920895 -0.2299499 -0.385602 -0.8224498 -0.4181954 -0.2905198 -0.8593714 -0.4208077 -0.2759541 -0.8000851 -0.5326473 -0.04896003 -0.8337482 -0.5499697 -0.02488666 -0.8632972 -0.504082 0.1755328 -0.7937569 -0.5823559 0.2281889 -0.8613919 -0.4537993 0.3416885 -0.8075135 -0.4808025 0.4064785 -0.8478788 -0.3404069 0.4023824 -0.8543696 -0.3288483 0.5488893 -0.8044849 -0.2269901 0.4925299 -0.8636861 -0.1070553 0.5871849 -0.8084484 -0.04031145 0.4993513 -0.8595309 0.1088808 0.540167 -0.8268269 0.1567702 0.4337533 -0.8243343 0.3637736 0.3699476 -0.8613013 0.3482803 0.3148347 -0.8060996 0.5010815 0.1860356 -0.8293645 0.5268257 0.2032043 -0.8462452 0.4925212 -0.01668518 -0.8545851 0.5190434 -0.01731604 -0.8540183 0.5199549 -0.2321873 -0.7799362 0.581196 -0.2976427 -0.8589673 0.4166341 -0.3061437 -0.8405455 0.4469445 -0.4922288 -0.8172488 0.2996922 -0.4630976 -0.8505026 0.2493711 -0.5616813 -0.8180754 0.1235588 -0.5093255 -0.8578426 0.06851094 -0.5738936 -0.8153379 -0.07661777 -0.4671047 -0.8777573 -0.1065629 -0.4150122 -0.867301 -0.274871 -0.4406912 -0.8354778 -0.3282806 -0.3181684 -0.826193 -0.4649453 -0.3163012 -0.8567364 -0.4073777 -0.2260523 -0.8161671 -0.5317628 -0.09366488 -0.8951261 -0.4358626 0.02828693 -0.8098452 -0.5859614 0.1229887 -0.8977532 -0.422981 0.2977546 -0.8025692 -0.5169382 0.3634365 -0.8586502 -0.361433 0.4049282 -0.8368232 -0.3684561 0.5615237 -0.7933163 -0.2352457 0.4524365 -0.8864206 -0.09777575 0.6056709 -0.795625 0.01199388 0.4211242 -0.8988552 0.1213006 0.4842588 -0.8253644 0.2902877 0.373852 -0.8818093 0.2874842 0.3214936 -0.8398945 0.4372861 0.2329959 -0.8881698 0.3960647 0.1218597 -0.8268737 0.5490265 0.01768308 -0.8677987 0.4966014 -0.0201134 -0.8321727 0.5541517 -0.2177224 -0.7859218 0.5787263 -0.2469656 -0.8690617 0.4286488 -0.3980768 -0.804771 0.4403165 -0.4112203 -0.8619147 0.2966495 -0.5316296 -0.8008418 0.2757217 -0.5583376 -0.8185711 0.1349095 -0.5023162 -0.8603376 0.08658969 -0.5851339 -0.805679 -0.09219485 -0.4936555 -0.8592011 -0.1344546 -0.5139803 -0.8134241 -0.2723335 -0.4079138 -0.8642325 -0.2944633 -0.3826453 -0.8073269 -0.4492282 -0.2698445 -0.8612602 -0.4305981 -0.2257542 -0.8208722 -0.5245988 -0.06643217 -0.8876067 -0.4557863 -0.02017205 -0.8445436 -0.5351068 0.1632078 -0.8838683 -0.4383378 0.2724722 -0.8069679 -0.5239865 0.400369 -0.8395637 -0.3672025 0.388894 -0.8575447 -0.3367178 0.5377019 -0.8122733 -0.2260286 0.4953089 -0.8535955 -0.1613813 0.6003119 -0.7996742 -0.01211601 0.5095195 -0.8590345 0.04949688 0.5556489 -0.8073948 0.1984137 0.4617183 -0.8572769 0.2277997 0.4486408 -0.8160835 0.3643203 0.3019889 -0.8948001 0.3288395 0.1813369 -0.8297101 0.5279188 0.1549198 -0.8517861 0.50046 -0.02693021 -0.8008558 0.5982516 -0.08674162 -0.8527008 0.5151478 -0.1267378 -0.8375412 0.5314718 -0.2571243 -0.8839241 0.3905962 -0.3603013 -0.8232085 0.4387608 -0.5113514 -0.8085173 0.2912381 -0.4489576 -0.8727166 0.1918408 -0.5779713 -0.8081359 0.1134268 -0.5128661 -0.8565746 -0.05699396 -0.4867438 -0.8711736 -0.06432145 -0.5308644 -0.7869665 -0.3144311 -0.318633 -0.9080277 -0.2719536 -0.2900039 -0.8104732 -0.508951 -0.1496775 -0.8931531 -0.4241158 -0.07166999 -0.8352338 -0.5452046 0.04262715 -0.8868389 -0.4601086 0.1499742 -0.828584 -0.5394037 0.2428192 -0.8415542 -0.4825199 0.2950328 -0.8104909 -0.5060241 0.4061889 -0.8518434 -0.3307169 0.4344406 -0.8365059 -0.333945 0.5783309 -0.780772 -0.2364921 0.4768005 -0.8780866 -0.04031533 0.4988632 -0.8651975 -0.05068588 0.5924106 -0.7842511 0.1843904 0.4297635 -0.8703391 0.2404438 0.4613966 -0.8211711 0.3358442 0.314919 -0.8299533 0.4604386 0.2585201 -0.8646567 0.4307392 0.1445648 -0.8057045 0.5744053 0.03610521 -0.8705958 0.4906723 -0.06902503 -0.7955525 0.6019402 -0.1993461 -0.8315606 0.5184286 -0.1986473 -0.8861784 0.4186013 -0.3668176 -0.8430317 0.3933733 -0.352668 -0.8864027 0.2998594 -0.507121 -0.8262768 0.2451426 -0.4261044 -0.8957075 0.127056 -0.5951095 -0.8032229 -0.02603411 -0.4899584 -0.868363 -0.07672399 -0.5518323 -0.7842361 -0.2836459 -0.3961158 -0.8639869 -0.3108358 -0.3981894 -0.8076267 -0.4349535 -0.2419934 -0.8655254 -0.4385262 -0.206758 -0.7942875 -0.571278 0.002218067 -0.9009156 -0.4339887 0.1328929 -0.8006402 -0.5842214 0.2103926 -0.8535717 -0.476603 0.3138848 -0.8086287 -0.4975901 0.3556696 -0.8631452 -0.3584404 0.4487668 -0.8229624 -0.3483409 0.4751355 -0.8576152 -0.1968313 0.5947027 -0.7855305 -0.1710866 0.4939472 -0.8666492 0.07025367 0.5621039 -0.8157373 0.1364254 0.4163021 -0.8666543 0.2749598 0.4550728 -0.8098168 0.3702777 0.3632618 -0.7844661 0.5026469 0.2004184 -0.880146 0.4303205 0.1238951 -0.7945169 0.5944686 -0.01484203 -0.849013 0.5281636 -0.02404445 -0.8653568 0.5005793 -0.2084011 -0.8601936 0.4654418 -0.2087527 -0.8749668 0.4368701 -0.3994579 -0.8373588 0.3731805 -0.4014206 -0.858485 0.319163 -0.5091072 -0.8068065 0.299789 -0.4916745 -0.8610543 0.1297757 -0.5678642 -0.8174409 0.09654337 -0.5693644 -0.8123334 -0.126249 -0.4623702 -0.8767395 -0.1324452 -0.3865212 -0.8570885 -0.340589 -0.3912699 -0.8503758 -0.351808 -0.2501479 -0.8073562 -0.5344175 -0.1560841 -0.8669012 -0.4734131 -0.05925124 -0.798897 -0.5985423 0.03963083 -0.8551893 -0.5167985 0.1420583 -0.808897 -0.5705305 0.2124462 -0.8676298 -0.4495389 0.3194112 -0.8252143 -0.4658305 0.3711223 -0.8536495 -0.365446 0.4822782 -0.7968738 -0.3638681 0.4022287 -0.899114 -0.1726448 0.6305623 -0.7748725 -0.04431664 0.4865459 -0.8714436 0.06212252 0.5490143 -0.820149 0.1610561 0.4730511 -0.8430973 0.2557535 0.3971058 -0.8831874 0.2495741 0.3306993 -0.8086569 0.4865306 0.2501508 -0.8606395 0.4435364 0.1483703 -0.8205309 0.5520102 0.04788357 -0.8806777 0.4712899 -0.08206462 -0.7908614 0.6064681 -0.2262179 -0.8279717 0.5131163 -0.2260774 -0.8540153 0.4685583 -0.3920878 -0.8173691 0.4221081 -0.3805218 -0.8597028 0.3407553 -0.5143686 -0.8159138 0.2640258 -0.4857541 -0.8544669 0.1841992 -0.5884163 -0.8035852 0.08953815 -0.5036924 -0.8638683 0.00507301 -0.5670721 -0.8128277 -0.1331931 -0.5047377 -0.8429014 -0.186433 -0.5349896 -0.7999519 -0.2717779 -0.3656221 -0.8626124 -0.3496003 -0.3645053 -0.8084459 -0.462116 -0.1895338 -0.8982757 -0.3964563 -0.08225792 -0.7695415 -0.6332769 0.04696869 -0.8718642 -0.4874904 0.1623526 -0.8083314 -0.5658993 0.2460601 -0.856991 -0.4527924 0.2788227 -0.842757 -0.460455 0.3645693 -0.8814232 -0.3003042 0.472175 -0.8250751 -0.3103255 0.5311708 -0.8222469 -0.2043716 0.4390103 -0.894994 -0.07909357 0.5408162 -0.8410522 -0.01220124 0.4592519 -0.8800327 0.1209564 0.5251247 -0.8196095 0.229095 0.4364542 -0.844191 0.3112065 0.4521129 -0.8105369 0.3723227 0.2914044 -0.8304998 0.4747143 0.2361443 -0.8671461 0.4385128 0.1067293 -0.8076407 0.5799357 0.01838803 -0.8493905 0.5274446 -0.05057293 -0.8077643 0.5873324 -0.1685847 -0.8537862 0.4925732 -0.2333354 -0.8198261 0.5229146 -0.3299063 -0.866571 0.3744549 -0.4032363 -0.8275663 0.3905566 -0.5395585 -0.8043637 0.2487485 -0.4375349 -0.8868445 0.1485602 -0.5446127 -0.8386293 0.009907603 -0.4710994 -0.8814919 -0.0322085 -0.4953765 -0.8336303 -0.2442594 -0.478208 -0.8435403 -0.2444522 -0.4051415 -0.8142405 -0.4157798 -0.2937601 -0.8748884 -0.3850656 -0.2303931 -0.7962686 -0.5593527 -0.09142112 -0.8506337 -0.5177497 -0.04511851 -0.8141134 -0.5789505 0.1084918 -0.8556866 -0.5059942 0.1570802 -0.8200724 -0.5502792 0.353843 -0.806494 -0.4736693 0.2965549 -0.8998575 -0.319862 0.5226718 -0.8312339 -0.1893796 0.5066826 -0.8446391 -0.1727938 0.5752413 -0.8179173 0.01043468 0.5273972 -0.8487495 0.03842872 0.5649117 -0.7932738 0.2271381 0.43747 -0.8645394 0.2473694 0.4267895 -0.8050265 0.4120476 0.2886233 -0.8777956 0.3823237 0.1973725 -0.7467339 0.6351635 0.03941565 -0.8783038 0.4764755 -0.03887712 -0.8281353 0.5591785 -0.2160495 -0.8393902 0.4987453 -0.217051 -0.8555803 0.4699695 -0.4296636 -0.803922 0.4112161 -0.4034612 -0.8560186 0.3231894 -0.5400826 -0.8079079 0.2357875 -0.4708545 -0.8721748 0.1326926 -0.6114769 -0.7912456 0.00514394 -0.4332509 -0.8954729 -0.1020886 -0.5007678 -0.8359199 -0.2246548 -0.379237 -0.8853821 -0.2688456 -0.3855485 -0.8370087 -0.3882898 -0.2400457 -0.8913285 -0.3845927 -0.2080441 -0.8150491 -0.5407519 -0.04092937 -0.8966436 -0.4408571 0.05740034 -0.8253317 -0.5617231 0.1383369 -0.8896715 -0.4351412 0.3345764 -0.7984846 -0.5004808 0.3379574 -0.8627776 -0.3760317 0.4653791 -0.8156703 -0.3436632 0.4508706 -0.8615828 -0.2332186 0.5648952 -0.8076804 -0.1689555 0.4929424 -0.8685696 -0.05093801 0.5952154 -0.7999284 0.07637637 0.4856361 -0.8621267 0.1445513 0.5386762 -0.790364 0.2918095 0.3834388 -0.8614333 0.3330276 0.371443 -0.7981714 0.4742916 0.2358815 -0.858623 0.4551118 0.1712158 -0.8017304 0.5726375 0.06798261 -0.8588018 0.5077775 -0.04823273 -0.806549 0.5891963 -0.1243278 -0.8593868 0.4959809 -0.2366698 -0.8037735 0.5458348 -0.3498667 -0.8457841 0.4027935 -0.3440312 -0.8564938 0.384787 -0.5518272 -0.782788 0.2876281 -0.4602102 -0.877254 0.1364995 -0.5904113 -0.8062584 0.036906 -0.4964375 -0.8651846 -0.07075077 -0.5580368 -0.8157134 -0.1523375 -0.5206795 -0.8017026 -0.2935404 -0.4128679 -0.8610005 -0.2970155 -0.3796005 -0.8054736 -0.4550999 -0.275778 -0.8539701 -0.4412274 -0.2186071 -0.8046774 -0.5520012 -0.1115065 -0.8548249 -0.5067946 -0.03264158 -0.8134186 -0.5807623 0.07358157 -0.868478 -0.4902364 0.174077 -0.81835 -0.5477232 0.2785392 -0.8585993 -0.4303757 0.34232 -0.8204382 -0.4579282 0.4245789 -0.8807128 -0.2099473 0.5522559 -0.8101994 -0.1964446 0.4671288 -0.8834376 -0.03645139 0.5176023 -0.855607 -0.004967212 0.5480446 -0.8036007 0.2321059 0.4128674 -0.8768495 0.2463242 0.4177493 -0.8510929 0.3180038 0.2437802 -0.8803503 0.406884 0.2474523 -0.8469159 0.470639 0.1049945 -0.7889314 0.6054448 -0.0953384 -0.8229356 0.5600783 -0.03271174 -0.8697664 0.4923782 -0.2676137 -0.8293755 0.4904276 -0.2700951 -0.8498521 0.4525485 -0.403657 -0.8091326 0.4270427 -0.4168806 -0.8573104 0.3020424 -0.5211471 -0.808929 0.2721024 -0.496361 -0.8574877 0.135427 -0.5848714 -0.8076157 0.07538259 -0.4987755 -0.8644581 -0.06273227 -0.5456472 -0.8302577 -0.1137605 -0.450297 -0.8344799 -0.31761 -0.4015422 -0.8616929 -0.3102408 -0.3370112 -0.8018025 -0.4934941 -0.2483191 -0.8678346 -0.4303496 -0.06836229 -0.8744751 -0.480229 -0.01672178 -0.8060188 -0.5916537 0.1455544 -0.8627756 -0.4841821 0.1981735 -0.8285397 -0.5236883 0.3384725 -0.8051183 -0.4870533 0.3416557 -0.8670141 -0.3627092 0.4989852 -0.8024607 -0.3272166 0.4678933 -0.8565992 -0.2175176 0.5786679 -0.8039257 -0.1372843 0.4556449 -0.8893176 -0.03875684 0.5406082 -0.818987 0.1923622 0.4921744 -0.8482928 0.1953553 0.4546851 -0.8212937 0.3445842 0.3031392 -0.8912075 0.3374255 0.2875461 -0.8391951 0.4615939 0.1510893 -0.8849492 0.4404963 0.08476966 -0.8259855 0.5572812 -0.01936751 -0.8391246 0.5435943 -0.04631197 -0.817644 0.5738584 -0.2119863 -0.8536967 0.4756722 -0.2420377 -0.8351649 0.4938801 -0.4058543 -0.7885131 0.4620925 -0.400525 -0.8733823 0.2770977 -0.5044568 -0.8189127 0.2736886 -0.5825764 -0.8106541 0.058694 -0.4946939 -0.8690567 0.004323482 -0.5823755 -0.8008046 -0.1398243 -0.4594056 -0.8533192 -0.2465624 -0.4397762 -0.8645388 -0.2432485 -0.3178557 -0.8601563 -0.3988721 -0.2854886 -0.8792658 -0.3812975 -0.1452797 -0.831014 -0.5369448 -0.05088102 -0.8669168 -0.4958492 -0.02674585 -0.8408629 -0.5405871 0.165392 -0.7979841 -0.5795403 0.3177673 -0.7870446 -0.5287578 0.2047688 -0.8373951 -0.5067932 0.4069499 -0.8240497 -0.3941244 0.4600042 -0.7950364 -0.3953647 0.4367363 -0.8879548 -0.1442137 0.5598822 -0.8197683 -0.1204658 0.5732178 -0.8144223 0.09020954 0.4847455 -0.8673067 0.1131418 0.5764458 -0.7727933 0.26552 0.4075105 -0.8376402 0.3637228 0.5139696 -0.7538776 0.4092723 0.4368562 -0.03327149 0.898916 0.1149067 -0.9022274 0.4156708 0.9665501 -0.112157 0.2306553 0.742305 0.5053085 0.4400529 -0.7709639 0.5257815 0.3594005 -0.7544476 -0.6448279 0.1224983 -0.7046566 0.7071 -0.05889624 -0.6678764 -0.700095 -0.2526029 -0.4977816 0.721746 -0.4809327 0.6777871 -0.5155735 -0.524203 0.7855632 0.5846277 -0.2027336 0.6401408 -0.7631406 -0.08852243 0.4928629 0.7285124 0.4757688 0.4513627 -0.62318 0.6386849 0.2243837 0.5672059 0.7924201 0.7385796 0.490057 -0.4629734 0.7580409 -0.6135286 -0.2212615 0.7489689 0.6619705 -0.02899467 0.834389 -0.5404219 0.108348 0.786924 0.5299255 0.3161167 0.6979975 -0.5939877 0.3999726 0.1677228 -0.5869263 0.7920775 -0.08489477 0.5462157 0.8333314 -0.2092629 -0.704101 0.6785652 -0.5052506 0.7316578 0.4576011 -0.6538265 -0.6465651 0.3930197 -0.6923768 0.7124042 0.1144323 -0.7858409 -0.3976036 -0.4736724 -0.4550356 0.6031779 -0.6550719 -0.1896167 -0.5754156 -0.7955769 0.1776152 0.3849183 -0.9056991 0.8430237 0.4746994 0.2529261 0.7306086 -0.363094 0.5782507 -0.3546629 0.6785289 0.6432829 -0.515898 -0.6005661 0.6108762 -0.6878105 0.6071165 0.3979026 -0.7064369 0.6767812 -0.2071571 -0.7757239 -0.5203584 -0.357043 -0.5954588 0.5195658 -0.6127645 -0.8789095 -0.444399 -0.1732856 -0.668907 0.5577211 -0.4914373 -0.2862153 -0.4616143 -0.8396387 0.03098601 0.5745205 -0.8179035 0.07400894 -0.4326747 -0.8985072 0.4938414 0.0910238 -0.8647748 0.7461726 -0.6648981 0.03372001 0.6943026 0.6410247 0.3271566 0.6688157 -0.6106816 0.4239737 0.576879 0.5332283 0.6187716 0.4571202 -0.5909071 0.664733 0.1800493 0.6987005 0.6923871 -0.2362675 0.3722239 -0.8975673 -0.006856799 -0.6238165 -0.7815409 0.1787773 0.7084957 -0.6826951 0.3222608 -0.719439 -0.6152687 0.5400702 0.5810589 0.6088471 0.2955541 -0.3662902 0.8823148 -0.3783183 0.535553 0.755022 -0.5202379 -0.5784544 0.6282859 -0.6746774 -0.6010605 -0.4284119 -0.478167 0.6161642 -0.625858 -0.3805204 -0.5985255 -0.7049622 -0.2472111 0.5005612 -0.8296537 -0.0809856 -0.5640773 -0.8217409 0.1483944 0.6997641 -0.6987913 -0.4404546 0.527257 0.7266361 -0.5857973 -0.5594897 0.5863556 -0.7068262 0.5709443 0.4176356 -0.7826195 -0.516606 0.3473109 -0.8117677 0.5696593 0.1285365 -0.7149454 -0.698351 -0.03404301 -0.25112 0.0203303 -0.9677425 0.2126385 0.2662137 -0.9401677 0.5680287 -0.8061107 -0.1659188 -0.1947955 0.5942463 0.7803372 -0.3679473 -0.5598362 0.7424273 -0.5060226 0.6719631 0.5407466 -0.7883099 -0.5770273 -0.213558 -0.6878615 0.5690973 -0.4505274 -0.5454146 -0.6708318 -0.5025014 0.5846145 -0.6946153 -0.4192082 0.7544819 0.6218653 -0.2098586 0.6929515 -0.7194156 -0.04753488 0.6851376 0.472055 0.5547528 0.4507511 -0.5931528 0.6670781 -0.5288165 0.1958577 -0.8258286 -0.103684 -0.5424833 -0.8336436 0.5544921 0.5628437 -0.6129809 0.6906086 -0.5637226 -0.4530748 0.7267478 0.6791284 -0.1030652 0.7994796 -0.6006678 0.005541205 0.7619441 0.5711265 0.3053778 -0.9191125 0.2646747 0.2918556 -0.8431802 -0.5374563 -0.01370799 -0.7906991 0.5912262 -0.1588914 -0.737897 -0.5661943 -0.367331 0.6654524 0.2734586 -0.6945456 0.9294932 0.1644604 -0.3301442 0.1739864 -0.8232996 0.5402837 -0.790566 -0.612012 -0.0211386 -0.8098974 0.5269761 -0.2576096 -0.767241 -0.5197858 -0.375718 -0.6804421 0.4972627 -0.5382642 -0.5725018 -0.5389048 -0.6179186 -0.3942473 0.5407767 -0.7430543 -0.270443 -0.5918346 -0.7593369 -0.0884509 0.6068159 -0.7899057 0.1099788 -0.5566229 -0.8234536 0.2562264 0.4753736 -0.841646 0.4479233 -0.5956138 -0.66679 0.4525726 -0.6898558 -0.5650461 0.6845202 0.5947289 -0.42158 0.7023131 -0.6675922 -0.2471376 0.7355251 0.6673704 0.1167026 0.6456009 -0.7125494 0.2747236 0.4836655 0.6533764 0.5823805 0.3855674 -0.5493322 0.7413313 -0.3883327 -0.6991137 -0.6003646 -0.2519895 0.5283623 -0.8107617 -0.01644986 -0.5251387 -0.8508577 0.8522474 -0.5003616 -0.1526852 0.8165056 0.5645253 0.1209545 0.6297327 -0.7432534 0.2258564 0.4602149 0.7040928 0.5407917 0.4136478 -0.561496 0.7166713 0.1581825 0.6028441 0.7820214 -0.6515716 0.550451 -0.5219752 -0.4758622 -0.5990674 -0.6439515 -0.2164853 0.7533943 -0.6209117 0.8037754 -0.1520246 -0.5751816 0.9776046 0.02464145 -0.2090022 0.04287713 0.3167832 0.9475284 -0.1522913 -0.3777734 0.9132878 -0.4129223 0.1040498 0.9048032 -0.2775499 -0.8635101 0.4210895 -0.4912053 -0.3591601 0.7935498 -0.2545897 -0.7540211 0.605505 -0.2238803 -0.7590982 0.6112673 -0.2118134 -0.7363361 0.6426073 -0.1013032 -0.7236099 0.6827345 -0.2318089 -0.1018104 0.967419 -0.009896397 -0.98978 0.1422598 0.0336939 -0.8742619 0.484284 -0.03288668 -0.471938 0.8810182 -0.03902786 -0.3138926 0.948656 0.1270412 -0.7524169 0.64632 0.09167981 -0.0613268 0.9938983 0.1441236 -0.7405835 0.6563265 0.1877865 -0.2837882 0.9403194 0.2024698 -0.7558298 0.6226776 0.2315036 -0.8349958 0.4991874 0.4108927 -0.1938698 0.8908321 0.4363835 -0.1436813 0.8882146 0.3406913 -0.7835587 0.5195819 0.5146591 -0.5114485 0.6881473 0.5327132 -0.2001068 0.822298 0.3500339 -0.8748052 0.3349511 0.6320815 0.2586096 0.7304753 0.4858812 -0.7866606 0.3809 0.6298474 -0.526954 0.5706241 0.7320848 -0.3259527 0.5981695 0.5558755 -0.7721095 0.3079766 0.670763 -0.6674357 0.3234295 0.3421097 -0.9321906 0.1182438 0.8563506 -0.2483589 0.452749 0.8958998 -0.1071349 0.4311445 0.7174882 -0.6904812 0.0919044 0.6650244 -0.7367139 0.1224548 0.9472193 -0.2693518 0.173854 0.2574574 -0.9653573 -0.04243993 0.9955165 0.0731405 0.05997759 0.6383078 -0.7696696 0.01311373 0.9774489 -0.2058178 -0.04725348 0.742595 -0.6661561 -0.06920087 0.4005951 -0.9060961 -0.1360647 0.7444986 -0.6524899 -0.1413466 0.8349928 -0.500454 -0.2287641 0.9241271 -0.3028104 -0.2330129 0.3976768 -0.8973844 -0.191192 0.7862661 -0.5021885 -0.3599894 0.2299162 -0.9585283 -0.1684105 0.65415 -0.6576489 -0.373612 0.911909 0.1773257 -0.370105 0.8823744 -0.171593 -0.4381455 0.6318668 -0.6317709 -0.4490099 0.4234673 -0.7883878 -0.4462289 0.7513016 -0.2740793 -0.6003553 0.4236651 -0.792163 -0.4393014 0.5648508 -0.4043534 -0.7193344 0.714484 -0.1165091 -0.6898828 0.2043516 -0.8666152 -0.4552128 0.491344 -0.3574304 -0.7942447 0.4742296 -0.2323896 -0.849177 0.2653974 -0.682702 -0.6807953 0.2347331 -0.7533403 -0.6143119 0.2634874 -0.3500958 -0.8988922 0.03466814 -0.9888377 -0.1449082 0.3185989 -0.2022467 -0.9260621 0.04074901 -0.7122265 -0.700766 0.06552255 -0.357146 -0.9317476 -0.0311132 -0.8740139 -0.4849039 0.03018301 -0.4201573 -0.9069493 -0.08341097 -0.8586899 -0.5056623 -0.08881264 -0.3804783 -0.9205154 -0.1721653 -0.7283757 -0.6631953 -0.2284755 -0.01882898 -0.9733676 -0.2496827 -0.6819353 -0.6874758 -0.07991695 -0.9826794 -0.1671965 -0.3575751 -0.3965919 -0.8454909 -0.2973878 -0.8022509 -0.5176429 -0.05142569 -0.9954509 -0.08020585 -0.3853251 -0.7503711 -0.537092 -0.4987628 -0.3104639 -0.8092267 -0.4199139 -0.7697832 -0.4807351 -0.2560542 -0.9373121 -0.2363944 -0.5518794 -0.1883089 -0.8123847 -0.561088 -0.6337224 -0.5325188 -0.6851619 -0.301816 -0.6629181 -0.664793 -0.6450323 -0.3768072 -0.7850091 -0.07606697 -0.6147964 -0.3371075 -0.9217686 -0.1915754 -0.2275642 -0.9705222 -0.07937973 -0.641211 -0.6899171 -0.3359508 -0.8203117 -0.293861 -0.490647 -0.3822171 -0.9203648 -0.08269697 -0.7321445 -0.6445526 -0.2202644 -0.6867989 -0.7052557 -0.1758456 -0.9401637 -0.08367902 -0.3302881 -0.9241571 -0.2866136 -0.2525596 -0.7679497 -0.6405047 -0.002674281 -0.9838702 -0.1602603 -0.07947474 -0.5028362 -0.8629711 0.04936379 -0.6619981 -0.7472534 0.05805987 -0.4305106 -0.9003829 0.06301885 -0.9656523 -0.2591572 -0.01879674 -0.7900763 -0.5807713 0.1961739 -0.9849525 -0.00642544 0.1727063 -0.4523212 -0.8748667 0.173245 -0.9675972 -0.1416611 0.2090164 -0.703377 -0.6425009 0.3040615 -0.690553 -0.6562726 0.3040441 -0.2390204 -0.9584891 0.15546 -0.8623198 -0.3004593 0.4075892 -0.6131505 -0.668443 0.4209873 -0.07287794 -0.9952318 0.0648269 -0.4245191 -0.8365219 0.3464316 -0.8522621 -0.09375393 0.514645 -0.7130987 -0.3687805 0.596231 -0.3941503 -0.7954695 0.4602977 -0.5996985 -0.4044147 0.6905147 -0.6609476 -0.3310216 0.6734783 0.001310646 -0.9999951 0.002833127 0.003787398 -0.9999903 0.002291381 0.001749396 -0.999998 -0.001104712 0.00305438 -0.9999945 0.001363813 0.001528322 -0.9999964 0.002258718 0.001769542 -0.9999981 -9.06313e-4 0.005145192 -0.9999816 0.003217995 -0.006331264 -0.9999189 0.01104992 0.003460168 -0.9999748 -0.006207108 0.632323 -0.4475958 -0.6323177 0.2600492 -0.9341272 -0.2445011 0.644014 -0.5530767 -0.5285379 0.6993374 -0.49026 -0.5201659 0.1911616 -0.9684522 -0.1598674 0.7192988 -0.5751256 -0.3896663 0.8346407 -0.3913521 -0.3875803 0.5035595 -0.8283415 -0.2455166 0.8683986 -0.4197511 -0.2639942 0.4399839 -0.8883424 -0.131385 0.6426635 -0.7544043 -0.1336337 0.508465 -0.8518501 -0.1257576 0.7319445 -0.6776031 -0.07149451 0.7523697 -0.6543493 0.0759415 0.1367264 -0.9905449 0.01126003 0.6687386 -0.7423046 0.0421037 0.829035 -0.5335935 0.1672698 0.2793111 -0.9593415 0.04061198 0.7973943 -0.5627157 0.2179756 0.8372405 -0.4623234 0.292037 0.4231123 -0.8944543 0.1446636 0.3926159 -0.9017801 0.1806808 0.6467174 -0.6687048 0.3668657 0.640268 -0.6831487 0.3512332 0.6698964 -0.5038722 0.5452997 0.5922079 -0.6705885 0.4467672 0.4371768 -0.8182652 0.3732541 0.1437145 -0.9853019 0.09233862 0.6249811 -0.3603981 0.6924681 0.3569198 -0.8284062 0.4316843 0.4434952 -0.6636964 0.6023446 0.386958 -0.7594091 0.5230309 0.4562792 -0.4297813 0.7791647 0.2386964 -0.8506128 0.468489 0.3637921 -0.497226 0.7876686 0.2791289 -0.6859247 0.6720077 0.06254607 -0.9831814 0.1715874 0.1513383 -0.6549177 0.7403916 0.1535972 -0.7061935 0.6911575 0.08245056 -0.8865285 0.4552682 0.08892029 -0.5014789 0.8605883 -0.001004397 -0.9212592 0.388948 -0.02610862 -0.6191551 0.7848347 -0.1209847 -0.315674 0.9411231 -0.03350806 -0.8568313 0.5145069 -0.2377508 -0.4532737 0.8590795 -0.3006622 -0.3057958 0.9033777 -0.119147 -0.8700098 0.4784213 -0.1906819 -0.7733518 0.6046218 -0.4034284 -0.4776399 0.7804522 -0.04556286 -0.9933165 0.1060489 -0.3820493 -0.6045587 0.6989615 -0.2780061 -0.7668007 0.578558 -0.1729766 -0.9392221 0.2965483 -0.4839043 -0.6170599 0.6205431 -0.478457 -0.6451113 0.5957435 -0.320068 -0.8669158 0.3821175 -0.2807998 -0.9189833 0.2768054 -0.6351903 -0.5518162 0.5404002 -0.5599384 -0.7209044 0.40837 -0.5774511 -0.727897 0.3697516 -0.7695004 -0.5034532 0.3929431 -0.8129588 -0.4927472 0.3103197 -0.3418952 -0.9274122 0.151705 -0.4804009 -0.863978 0.1508548 -0.7636617 -0.5956051 0.2491495 -0.9061226 -0.4011693 0.1341832 -0.8279966 -0.5576991 0.05825394 -0.4157949 -0.9070221 0.06652551 -0.5708316 -0.8201759 0.03824806 -0.9067148 -0.4213645 -0.01789927 -0.8172889 -0.5532789 -0.1610006 -0.8390192 -0.521442 -0.1553865 -0.5699078 -0.8132984 -0.1172648 -0.4474949 -0.8916326 -0.06884533 -0.8362139 -0.456825 -0.3034096 -0.04916357 -0.998655 -0.01646363 -0.6896339 -0.6545614 -0.3097652 -0.5701737 -0.7834876 -0.2470812 -0.7668517 -0.4654874 -0.4418824 -0.3560668 -0.9156976 -0.1863185 -0.6469367 -0.5459288 -0.532386 -0.559539 -0.6563123 -0.5061329 -0.4382752 -0.8106839 -0.3882094 -0.2677732 -0.9229263 -0.2765946 -0.5573827 -0.583943 -0.5901994 -0.4739554 -0.6223406 -0.6229435 -0.3266879 -0.7791309 -0.5350049 -0.275879 -0.8558145 -0.4375755 -0.3541019 -0.550016 -0.7563691 -0.3204258 -0.7192698 -0.6164239 -0.2811853 -0.4150276 -0.8652669 -0.1861278 -0.5910991 -0.7848302 -0.04743444 -0.991155 -0.1239429 -0.1407338 -0.8606015 -0.4894478 -0.09140408 -0.9230133 -0.3737536 -0.1174191 -0.539424 -0.8338074 -0.04618579 -0.6281449 -0.7767244 -0.02605384 -0.7445337 -0.6670764 0.004250109 -0.3826692 -0.9238757 -0.03756654 -0.8753268 -0.4820703 0.1677597 -0.3129161 -0.9348478 0.1779248 -0.4137792 -0.8928212 0.1022511 -0.8010699 -0.5897725 0.01994419 -0.9794725 -0.2005887 0.1345177 -0.7600868 -0.6357461 0.1946156 -0.8007113 -0.5665565 0.3322166 -0.4508747 -0.8284589 0.3087783 -0.6256753 -0.7163703 0.1251515 -0.9515586 -0.2808443 0.01603978 -0.9982036 -0.05772614 0.4179477 -0.6377703 -0.6469689 0.4050607 -0.712435 -0.5730292 0.356119 -0.7918162 -0.4961919 0.6818385 -0.005601167 -0.7314813 0.7940982 0.002907037 -0.6077826 0.806077 1.15027e-4 -0.5918107 0.8700842 0.004122912 -0.4928859 0.9209766 0.005957722 -0.3895725 0.8989694 -5.6749e-4 -0.4380112 0.9728404 -0.002800107 -0.2314597 0.9793125 0.001007139 -0.2023516 0.996352 -0.007289528 -0.08502757 0.9999036 -9.34452e-4 -0.01385807 0.9999021 -0.003412306 0.01356816 0.9867415 8.09451e-4 0.1622984 0.9856564 -2.18504e-4 0.1687642 0.9387189 5.44324e-6 0.3446837 0.9346462 -0.002242445 0.3555721 0.8692138 -0.001924037 0.4944329 0.8499085 0.002882301 0.5269225 0.8006258 -0.006437897 0.5991301 0.7100743 0.003855347 0.7041163 0.6554443 -0.004433035 0.7552307 0.5784953 0.003941416 0.8156763 0.5357168 -0.003294944 0.8443914 0.3868618 0.001207768 0.922137 0.3451994 -0.004574954 0.9385183 0.2496829 -0.001677036 0.9683262 0.2802813 9.18086e-4 0.9599176 0.1877334 0.00407356 0.9822117 0.1113771 -0.005514323 0.993763 -0.02597773 0.004559457 0.9996522 -0.1095245 -0.004975318 0.9939717 -0.1837326 0.004589736 0.9829656 -0.3692041 0.005536139 0.9293318 -0.3239937 -0.00182414 0.9460575 -0.4942964 -0.005650997 0.8692752 -0.5799307 0.002652227 0.8146616 -0.6191759 -0.003169119 0.7852461 -0.6668234 7.68337e-4 0.7452154 -0.7683401 -0.008309423 0.639988 -0.8067332 0.001933813 0.5909126 -0.8670092 -0.004008769 0.498276 -0.9014979 0.004238784 0.4327628 -0.9405203 -0.004374265 0.3397095 -0.963054 0.001589834 0.2693041 -0.9906328 0.001297354 0.1365472 -0.987148 -0.002971827 0.1597818 -0.9983718 1.66276e-4 -0.05704367 -0.9989151 0.002601206 -0.04649472 -0.9862411 -0.006211042 -0.1651967 -0.9572908 0.006241083 -0.2890596 -0.9306772 -0.004656195 -0.3658118 -0.8850094 -4.36019e-4 -0.465573 -0.8725518 -0.004026293 -0.4885051 -0.7794083 0.001823842 -0.6265137 -0.7692783 3.19681e-4 -0.6389138 -0.7412877 0.003418445 -0.6711787 -0.6635414 -0.004542171 -0.7481258 -0.5941134 2.83179e-4 -0.8043813 -0.565382 -0.00374943 -0.8248207 -0.4511533 0.002411365 -0.8924432 -0.4785485 -0.002618134 -0.8780573 -0.3079963 -0.004752874 -0.9513757 -0.2308199 0.006682097 -0.9729736 -0.1376569 -0.003979921 -0.990472 -0.01522701 8.85614e-4 -0.9998838 -0.02408641 -7.40237e-4 -0.9997097 0.1792465 -0.001096725 -0.9838036 0.1834773 -0.001815736 -0.9830223 0.2745794 0.004722237 -0.9615529 0.4311773 9.02058e-4 -0.9022669 0.4058011 -0.002729952 -0.9139573 0.5407838 -0.007464706 -0.8411286 0.6250161 0.004939079 -0.7805963 -0.007533729 -0.999563 -0.02858597 -0.01678967 -0.9998589 -5.79299e-4 -6.88564e-4 -0.9997665 0.0216009 -0.01289457 -0.9999082 -0.00415498 -0.01441329 -0.9998115 0.01300704 -0.004489481 -0.9997511 0.02185529 -0.01272076 -0.9999098 -0.004327833 -0.01445579 -0.9998913 0.002937197 0.008705258 -0.999902 -0.01096814 0.01156044 -0.9997879 0.01704615 8.58404e-5 -0.9999961 0.002780079 -6.66797e-4 -0.9999996 -7.38717e-4 -6.86475e-4 -0.9999957 0.002860546 -0.002259194 -0.9999955 0.00199598 -9.91263e-5 -1 -5.59984e-4 0.003455817 -0.9999927 0.001695632 0.001677513 -0.9999893 0.004322469 0.00159949 -0.9999975 -0.001611948 0.005577981 -0.9999808 0.002740085 -0.001278162 -0.9999817 -0.005925714 0.001187801 -0.9999722 0.007361888 0.0068928 -0.9999693 -0.003752768 0.002269089 -0.9998567 0.01677942 0.003796696 -0.9996529 -0.0260691 0.01776909 -0.9998065 -0.008436024 5.59349e-4 -0.9997805 0.02094548 0.01889717 -0.9998214 4.56383e-4 0.01794207 -0.9998381 -0.001400351 0.6054456 0.2620743 -0.7515003 0.3989084 0.6382245 -0.6584389 0.3838058 0.6499258 -0.6559647 0.3792766 0.4528145 -0.8069128 0.2406487 0.861703 -0.4467171 0.2734444 0.4940926 -0.8252882 0.1539568 0.9191592 -0.3625515 0.1900883 0.6403795 -0.7441644 0.1294522 0.8556556 -0.5010948 0.1136013 0.4515488 -0.884985 0.06772869 0.4835856 -0.8726729 0.03901535 0.9290311 -0.3679391 -0.001873016 0.3142732 -0.9493308 -0.001284241 0.8132805 -0.5818706 -0.1197681 0.5623433 -0.8181844 -0.07888621 0.762131 -0.6425989 -0.2112618 0.3461847 -0.9140704 -0.1143641 0.9161916 -0.3840751 -0.316572 0.6159167 -0.7214075 -0.2282184 0.8131873 -0.5353906 -0.3845875 0.5095502 -0.7697084 -0.462722 0.5920025 -0.6598647 -0.3447504 0.8217259 -0.4537774 -0.5455334 0.4491549 -0.7075685 -0.2662118 0.884386 -0.3833966 -0.6181283 0.4656391 -0.6333228 -0.4828659 0.775519 -0.4067072 -0.4869705 0.7513431 -0.4453575 -0.7661985 0.3810792 -0.5174154 -0.5861465 0.6832855 -0.4353771 -0.8428843 0.2831166 -0.4575929 -0.1551261 0.9820953 -0.1068874 -0.5111397 0.8245237 -0.242687 -0.779973 0.5273193 -0.3370113 -0.5233778 0.8143659 -0.2507665 -0.9124736 0.3067589 -0.2707231 -0.4436559 0.8842647 -0.1457578 -0.8366677 0.5290073 -0.1419101 -0.7020173 0.7037017 -0.1094334 -0.1703528 0.9849709 -0.02850145 -0.9560747 0.286525 -0.06184327 -0.5985111 0.7999528 -0.04312795 -0.06732928 0.9977231 -0.003943741 -0.8405784 0.5400912 0.04158651 -0.6555458 0.7550714 0.01126706 -0.8866274 0.4507678 0.1034415 -0.4330451 0.898101 0.07672423 -0.4821397 0.8691923 0.1097548 -0.737679 0.6473724 0.1916736 -0.8110821 0.5163048 0.2749099 -0.8023552 0.4788205 0.3563104 -0.3155688 0.938521 0.1399816 -0.6261661 0.6864624 0.3697102 -0.7546769 0.3012607 0.5828422 -0.6208717 0.6609014 0.4215777 -0.659247 0.3550486 0.6628228 -0.45023 0.799353 0.3979043 -0.5228669 0.6130014 0.5923172 -0.457846 0.7392479 0.4938519 -0.5071179 0.4150808 0.7553406 -0.04826056 0.9975578 0.05049097 -0.4236401 0.5166786 0.7440244 -0.2299819 0.9137647 0.3348765 -0.2679592 0.7993335 0.5378324 -0.3652762 0.248458 0.8971298 -0.2063156 0.821321 0.5318513 -0.2211402 0.5996192 0.7691254 -0.07707875 0.9588278 0.2733277 -0.1608019 0.5376782 0.8276745 -0.07728672 0.6288212 0.7736993 -0.01267838 0.2873914 0.9577293 -0.03091955 0.7803713 0.6245517 -0.01360791 0.8019055 0.5972959 0.1154552 0.4191859 0.9005295 0.01527577 0.9815604 0.190541 0.1130369 0.711553 0.6934804 0.1405062 0.761865 0.6323132 0.2699709 0.5997377 0.7532799 0.1753153 0.7526406 0.6346628 0.3610523 0.5129435 0.7788004 0.3737676 0.5274572 0.7629462 0.1248425 0.960325 0.2493801 0.5595393 0.1977505 0.8048668 0.3379333 0.7980427 0.4989277 0.3106739 0.8344767 0.4551159 0.5205138 0.5555275 0.6484246 0.652396 0.448527 0.6109035 0.2594296 0.9328342 0.2500334 0.6474149 0.5356861 0.5421202 0.5266523 0.7470972 0.4055652 0.8212794 0.2451031 0.5151939 0.7449119 0.5509552 0.3762377 0.5838766 0.7412466 0.3311219 0.04564934 0.9985575 0.0282731 0.8404227 0.446685 0.3068586 0.8170097 0.5167804 0.2557991 0.2722093 0.956858 0.1016122 0.934684 0.3216223 0.1514097 0.5476483 0.8290615 0.1128647 0.8761921 0.4729908 0.09256011 0.514152 0.8512793 0.1047447 0.8994762 0.4369697 -2.52543e-4 0.392121 0.9197664 0.01646 0.8232684 0.5657134 -0.04687821 0.2375634 0.9712755 -0.01370215 0.8136721 0.5591716 -0.1589494 0.8385536 0.5236618 -0.1503536 0.4244345 0.8999377 -0.09983742 0.414963 0.8978924 -0.146952 0.75568 0.5881606 -0.2881233 0.7214615 0.6299491 -0.2875024 0.6575894 0.630268 -0.4127209 0.2457011 0.9619759 -0.1193034 0.6355242 0.6501489 -0.4164317 0.7059409 0.426584 -0.5653969 0.4957274 0.7952588 -0.3490243 0.3853811 0.8459571 -0.3685625 0.5874709 0.548527 -0.5949758 0.4666858 0.7392759 -0.4854643 0.1825976 0.9618735 -0.2036117 -0.9925123 0.02098369 -0.1203296 -0.9918566 0.02545768 -0.1247894 -0.5945658 0.02557605 0.8036402 -0.5983475 0.02098137 0.800962 0.3919134 0.02111786 0.9197598 0.387736 0.0255776 0.9214156 0.05553758 -0.002032637 -0.9984546 0.1492003 0.00172168 -0.9888056 0.4931604 -7.98259e-4 -0.869938 0.5069988 -0.001558959 -0.8619454 0.7663381 0.002070307 -0.6424343 0.8661012 -0.003704667 -0.4998551 0.9612695 0.003902316 -0.2755827 0.9999083 -0.003532528 0.01307117 0.9662648 0.003693938 0.2575243 0.9124696 -0.002420246 0.4091373 0.6844226 0.002208113 0.7290822 0.6058418 -0.002797245 0.7955802 0.2840734 0.003201842 0.9587972 0.06084543 -0.004551887 0.9981369 -0.152055 0.003568947 0.9883657 -0.4946678 -0.002847611 0.8690775 -0.6259014 0.003490447 0.7798944 -0.8123776 -0.003659069 0.5831202 -0.9404481 0.003620445 0.3399182 -0.9935494 -0.003414869 0.1133495 -0.9962788 0.003001749 -0.08613669 -0.9268889 -0.003114223 -0.3753229 -0.8461771 0.002583563 -0.5328956 -0.6960453 -0.002290546 -0.7179943 -0.5815654 0.001924753 -0.8134974 -0.2598032 0.001380503 -0.9656606 -0.3394192 -0.00153613 -0.940634 0 1 1.64092e-5 0 1 -3.71021e-5 0 1 -3.26976e-6 0 1 2.65041e-6 0 1 -7.7321e-7 0 1 9.55927e-6 0 -1 -1.57473e-5 0 -1 -5.04406e-6 0 -1 7.1895e-6 0 -1 5.91628e-7 0 -1 -2.47352e-6 0 -1 3.72259e-6 0.1539158 -0.002482831 -0.9880809 0.2711869 0.002292394 -0.962524 0.5278753 -0.002112209 -0.8493194 0.7045252 0.002909779 -0.7096731 0.766007 -9.00141e-4 -0.6428317 0.9624199 -9.02228e-5 -0.2715657 0.9710115 0.001542031 -0.2390279 0.9972252 -0.001557707 0.07442784 0.984753 0.001557707 0.1739515 0.9011659 -0.001128435 0.4334732 0.8613864 0.001728951 0.5079473 0.6613929 -0.003205001 0.7500329 0.5263673 0.003531694 0.8502501 0.1683291 -0.002856016 0.9857268 0.1441739 -0.001573801 0.9895511 -0.1792504 0.002897679 0.9837993 -0.3908294 -0.004235863 0.9204535 -0.6258984 0.004336655 0.7798926 -0.7729765 -0.002944707 0.634428 -0.9404529 -7.32663e-4 0.3399233 -0.9540508 0.001908421 0.2996392 -0.9989085 0.001572668 -0.04668664 -0.980687 -0.003382682 -0.1955547 -0.9278644 0.002405583 -0.3729102 -0.7426685 -0.002041757 -0.6696562 -0.6758987 0.002289175 -0.736991 -0.3520348 -0.00329858 -0.9359812 -0.2038376 0.003485858 -0.9789985 0 1 -1.38298e-5 0 1 7.26102e-6 0 1 1.41397e-5 0 1 3.7319e-5 0 1 1.14533e-5 0 1 8.23145e-6 0 1 9.82109e-7 0 1 -9.51628e-6 0 1 -5.44178e-6 0 -1 -4.24625e-6 0 -1 4.04216e-6 0 -1 -4.26109e-6 0 -1 -1.28576e-5 0 -1 6.65772e-6 0 -1 -2.95785e-6 0 -1 -9.67712e-6 0 -1 4.55223e-6 0.07250249 -0.003439009 -0.9973623 0.2947839 0.003636956 -0.955557 0.5486222 -0.002421557 -0.8360669 0.6745142 0.00251919 -0.7382576 0.8311033 -0.003364264 -0.5561081 0.9367592 0.003213167 -0.3499599 0.9994674 -0.002845466 -0.03250944 0.9964713 5.64555e-5 -0.08393448 0.9557272 -3.49327e-4 0.2942543 0.9478281 5.97966e-4 0.3187815 0.8121054 -5.98094e-4 0.5835107 0.7967973 3.49318e-4 0.6042466 0.511155 -5.95208e-5 0.8594886 0.5451223 0.002232551 0.8383536 0.2195352 -0.002973198 0.9756001 -0.03606897 0.004319965 0.99934 -0.1518534 -8.88319e-4 0.9884026 -0.4955592 -0.001958489 0.8685721 -0.5808731 0.002789616 0.8139894 -0.8771474 0.001939713 0.4802173 -0.8337615 -0.001481533 0.5521228 -0.9884907 -0.003498494 0.1512414 -0.9999093 0.003273308 -0.01306647 -0.9089674 -0.002421081 -0.4168602 -0.9248657 2.09629e-4 -0.3802937 -0.6388881 -7.54043e-4 -0.7692993 -0.5952526 0.001833021 -0.8035366 -0.321024 -0.001790106 -0.9470695 -0.1706399 0.002740919 -0.9853296 0 1 -2.27715e-5 0 1 5.37808e-6 0 1 2.92002e-5 0 1 -1.40653e-6 0 1 9.67097e-6 0 1 -3.74801e-6 0 1 -1.21364e-5 0 -1 5.10045e-5 0 -1 -3.52637e-5 0 -1 -4.26267e-6 0 -1 6.50421e-6 0 -1 -5.75569e-6 0 -1 -5.38508e-6 0 -1 3.04639e-6 0 -1 3.48636e-6 0 -1 -2.51581e-5 0.1760176 0.002311527 -0.9843843 0.2515646 -5.46183e-4 -0.9678404 0.5282316 -2.73479e-6 -0.8491004 0.5429471 6.89071e-4 -0.8397666 0.8404561 0.002158761 -0.5418754 0.8019285 -7.22043e-4 -0.5974197 0.9710119 -0.003033995 -0.2390123 0.9987324 0.002924501 -0.05025213 0.9817113 -0.00296545 0.1903528 0.9451128 0.001850068 0.3267392 0.7917329 5.51293e-4 0.6108673 0.7503002 -0.002369105 0.6610931 0.4825904 0.002292335 0.8758432 0.3987149 -0.00171554 0.9170733 -0.02226465 8.13583e-4 0.9997518 -0.02183622 7.88585e-4 0.9997613 -0.4435915 -9.02053e-4 0.8962287 -0.4973478 0.001703619 0.8675497 -0.7294526 -0.001760363 0.6840292 -0.808749 0.001758098 0.5881513 -0.9248644 -0.001722753 0.3802933 -0.9635596 0.002099215 0.2674856 -0.9981105 -0.003065049 -0.06136757 -0.9754842 0.003969967 -0.2200338 -0.8295074 -0.003986239 -0.5584815 -0.7164154 0.003197729 -0.6976667 -0.4831732 -0.002232849 -0.8755219 -0.3286197 0.002882182 -0.9444579 -0.1212764 -0.002933263 -0.9926145 0 1 4.56263e-6 0 1 -5.27307e-6 0 1 -5.07344e-6 0 1 4.80422e-6 0 1 -3.2963e-5 0 1 8.9987e-6 0 -1 1.32617e-5 0 -1 -2.69954e-5 0 -1 -4.00485e-5 0 -1 7.11349e-6 0 -1 5.01503e-6 0 -1 -7.2965e-6 0 -1 3.498e-6 0 -1 -3.35969e-5 0 -1 3.86531e-6 0 -1 -6.08829e-6 0.9849503 0.02856236 -0.1704617 0.9551417 -0.02669686 -0.2949435 0.8739317 0.02895534 -0.4851857 0.821007 -0.01948034 -0.5705857 0.6358403 -5.52431e-4 -0.7718205 0.6174103 0.01517373 -0.7864951 0.3724355 -0.007855415 -0.9280249 0.3187195 0.01897877 -0.9476592 0.1233431 -0.02720201 -0.9919912 -0.04935389 0.03653436 -0.998113 -0.2388529 -0.03670334 -0.970362 -0.3721051 0.0218361 -0.9279338 -0.6013283 -0.01252108 -0.798904 -0.5772438 0.01028609 -0.8165072 -0.7769643 -0.02136635 -0.6291821 -0.8470893 0.02518427 -0.5308538 -0.9149942 -0.02038156 -0.4029519 -0.9631403 0.02029508 -0.268233 -0.9951683 -0.017403 -0.09662955 -0.9996847 0.01254534 -0.02175474 -0.981122 -0.01641327 0.1926921 -0.9661019 0.0146386 0.2577461 -0.8755202 -0.009674787 0.4830849 -0.8646953 0.001322448 0.5022951 -0.6900381 -0.01541692 0.7236089 -0.7118791 0.001321017 0.7023009 -0.4534298 0.02818012 0.8908464 -0.3679116 -0.0281797 0.9294337 -0.08016395 0.01628714 0.9966487 -0.06161767 0.005444467 0.998085 0.1894728 -0.01225912 0.9818094 0.2233132 0.00610584 0.9747277 0.449602 0.01338112 0.8931288 0.506434 -0.02019506 0.8620422 0.7366222 -0.006778895 0.6762705 0.7121003 0.01394617 0.7019393 0.9225172 -0.01458132 0.3856804 0.9055994 0.008446216 0.4240502 0.9870099 0.01701611 0.1597558 0.9974664 -0.02695572 0.06583464 0 1 -2.66362e-5 0 1 5.56991e-5 0 1 1.9239e-6 0 1 1.76758e-6 0 1 -6.42789e-6 0 1 9.19111e-6 0 1 1.78608e-6 0 1 -1.30701e-6 0 1 -1.36192e-6 0 1 1.85408e-5 0 1 9.89667e-6 0 1 -6.52965e-6 0.9991185 -0.01087605 0.04054814 0.9945485 0.005813419 0.1041128 0.9724594 0.002427279 0.2330597 0.9628663 -0.009610831 0.2698079 0.917553 0.007582068 0.3975414 0.8906124 -0.00636053 0.4547185 0.8433858 0.005387365 0.5372815 0.8030637 -0.006899535 0.5958532 0.7477399 0.008415222 0.6639385 0.6685888 -0.01122117 0.7435476 0.6074891 0.01025128 0.7942619 0.4867926 -0.007582187 0.8734848 0.4453923 0.005026698 0.8953214 0.3197456 -0.005709707 0.9474863 0.2909986 0.00390619 0.9567155 0.1033784 -8.01984e-4 0.9946418 0.1028652 -0.00102359 0.9946948 -0.09489434 -0.001849949 0.9954857 -0.09697574 -0.001024246 0.9952862 -0.241805 0.004181802 0.9703159 -0.305212 -0.008837699 0.9522435 -0.3479552 0.002321302 0.9375084 -0.4686493 0.002868294 0.8833798 -0.5048821 -0.007112801 0.8631591 -0.5672814 0.004317402 0.8235127 -0.6461365 -0.004745125 0.7632072 -0.6771379 0.004236936 0.735844 -0.7790733 0.003572762 0.6269227 -0.7581664 -0.004792273 0.6520437 -0.8627085 -0.00172007 0.5056986 -0.8605244 -0.00300765 0.5094005 -0.9163824 0.003517031 0.4002887 -0.931769 -0.004811763 0.3630197 -0.9654165 0.004864752 0.2606671 -0.9757061 -0.005489706 0.2190151 -0.9961252 0.006497621 0.08770591 -0.9989215 -0.004026532 0.04625719 -0.9967915 0.003148674 -0.07998096 -0.9961856 0.001021623 -0.08725357 -0.9719981 -0.003823757 -0.2349579 -0.9652165 0.004395067 -0.261415 -0.9130753 9.36394e-4 -0.4077903 -0.9196857 -0.002943813 -0.3926445 -0.8545091 0.002161324 -0.5194321 -0.8605639 -0.001057147 -0.5093413 -0.7456957 0.004384517 -0.6662723 -0.7596253 -0.002366483 -0.6503568 -0.6106691 0.004340291 -0.7918741 -0.6352651 -0.00589317 -0.7722718 -0.4736226 0.001358807 -0.8807269 -0.4533026 -0.006056249 -0.8913362 -0.3286752 0.005654871 -0.9444261 -0.2993093 -0.002144515 -0.9541537 -0.1698509 -0.001700758 -0.9854683 -0.1575921 0.002524256 -0.9875011 0.005268454 0.001967906 -0.9999843 0.02866655 -0.005255341 -0.9995753 0.163041 0.00473982 -0.986608 0.2077029 -0.007282614 -0.9781649 0.3258914 0.008417725 -0.9453698 0.4451311 -0.003087103 -0.8954601 0.4271026 -0.009661257 -0.9041516 0.5559923 0.007051587 -0.8311577 0.6527842 -0.002890646 -0.7575384 0.6370055 -0.009661495 -0.7707987 0.7477841 0.006673038 -0.6639085 0.8198859 -2.55189e-4 -0.572527 0.8026899 -0.008286774 -0.5963391 0.8966162 0.003219783 -0.4427969 0.9052262 -0.003214538 -0.4249181 0.9591447 2.87534e-4 -0.2829162 0.964497 0.005826711 -0.2640296 0.9882646 -0.007029056 -0.1525904 0.9975084 0.009412169 -0.06991928 0 -1 -2.08356e-5 0 -1 -6.28644e-6 0 -1 -2.62171e-5 0 -1 8.82605e-6 0 -1 -1.59227e-6 0 -1 2.04755e-6 0 -1 -3.06365e-6 0 -1 1.28583e-6 0 -1 -2.57941e-6 0 -1 -1.33824e-6 0 -1 7.10779e-7 0 -1 -8.31774e-7 0 -1 5.50657e-7 0 -1 -1.19322e-5 0 -1 -3.75699e-7 0 -1 1.15115e-5 0 -1 2.37678e-6 0 -1 -8.01982e-6 0.6549028 -0.7538375 0.05321002 0.7659667 -0.6281056 0.1370342 0.6276221 -0.7595145 0.1709632 0.7034292 -0.6570117 0.2711516 0.6238896 -0.7305806 0.2775138 0.5884339 -0.7251337 0.3576685 0.6253087 -0.6909357 0.3627628 0.5800323 -0.6746913 0.4564585 0.4934857 -0.7504974 0.4395743 0.5210592 -0.6779209 0.5185757 0.4087188 -0.7271251 0.5515779 0.4456673 -0.6812714 0.5807323 0.3204584 -0.7378154 0.5940832 0.3275249 -0.6665431 0.6696625 0.2217198 -0.7411898 0.6336229 0.2160732 -0.6747729 0.7056869 0.1098034 -0.7061898 0.6994564 0.1012596 -0.7248223 0.6814537 -0.003003597 -0.6910654 0.722786 -0.007445991 -0.7070308 0.7071436 -0.1093037 -0.7357971 0.6683229 -0.1328886 -0.6908385 0.7106918 -0.2206673 -0.6887307 0.69062 -0.2241691 -0.7307116 0.6448325 -0.3210017 -0.6897431 0.6490089 -0.3210619 -0.6893526 0.6493939 -0.3790824 -0.7338855 0.5636565 -0.4480621 -0.6635934 0.5990694 -0.4410684 -0.7366024 0.5127142 -0.5307936 -0.671118 0.517551 -0.5102298 -0.7310678 0.4529963 -0.5661179 -0.7233328 0.3953484 -0.5813402 -0.6917843 0.4283435 -0.6384923 -0.6779582 0.3642805 -0.5933586 -0.7497012 0.2930422 -0.7057309 -0.6521537 0.2768385 -0.633499 -0.7540579 0.1734232 -0.7168356 -0.6781526 0.1620366 -0.673033 -0.7381069 0.04716962 -0.6938652 -0.7178841 0.05651175 -0.7432867 -0.6684663 -0.02603107 -0.6672598 -0.7415408 -0.06986814 -0.7196925 -0.6834719 -0.1221021 -0.6603163 -0.7341298 -0.1582276 -0.7104704 -0.6724412 -0.2074962 -0.6229742 -0.7341965 -0.2699236 -0.6411083 -0.7115944 -0.2874261 -0.6255813 -0.6880799 -0.3676876 -0.5693319 -0.7377722 -0.362703 -0.5803728 -0.6717154 -0.4603974 -0.497025 -0.7480386 -0.4397777 -0.5166887 -0.6394612 -0.5693173 -0.3889117 -0.7660737 -0.5117409 -0.4018957 -0.6494973 -0.6454712 -0.2976377 -0.747243 -0.5941715 -0.2931389 -0.6648392 -0.6870651 -0.1930584 -0.7427685 -0.641111 -0.1828375 -0.671374 -0.7182114 -0.07052969 -0.7389094 -0.6701034 -0.06938219 -0.7335382 -0.6760976 0.01537984 -0.6543823 -0.7560076 0.06275248 -0.756854 -0.6505644 0.1413742 -0.656982 -0.7405323 0.1636009 -0.7277675 -0.666025 0.2479835 -0.6887701 -0.6812489 0.2485035 -0.7027301 -0.6666457 0.3377315 -0.7107271 -0.6170936 0.3423025 -0.6844951 -0.643658 0.3854022 -0.7314366 -0.5625528 0.4636167 -0.6529471 -0.5989322 0.4464487 -0.7536231 -0.482427 0.5601707 -0.6635075 -0.4959503 0.5278171 -0.7355687 -0.4246738 0.6230706 -0.6717376 -0.400689 0.5898716 -0.7288144 -0.3476797 0.6543559 -0.693942 -0.3004381 0.6343829 -0.7223057 -0.2753778 0.6992238 -0.6810793 -0.2172951 0.6493956 -0.7394903 -0.1773122 0.737578 -0.6672664 -0.1036059 0.6679734 -0.7418798 -0.05853158 0.7500508 -0.6613783 -0.001672506 0.9999876 0.002630352 -0.00424844 0.9903565 -0.02042025 -0.1370301 0.9785789 0.03052848 -0.2035959 0.9541564 -0.01887416 -0.2987129 0.9291551 0.01513761 -0.3693805 0.9089595 -0.01189434 -0.4167149 0.862802 0.01420789 -0.5053423 0.8416898 -0.01323544 -0.5397992 0.783638 0.01135152 -0.6211141 0.7471011 -0.01851767 -0.6644525 0.7061139 0.01560515 -0.7079263 0.6130151 -0.0120908 -0.7899787 0.5935412 0.009599685 -0.8047465 0.4800354 -0.01327621 -0.8771488 0.4452927 0.01689863 -0.8952257 0.2989063 0.01670378 -0.9541363 0.3432481 -0.01502668 -0.9391247 0.1866046 -0.01839375 -0.9822629 0.1360299 0.02176731 -0.9904657 0.02035748 -0.01979041 -0.9995969 -0.04624599 0.01718789 -0.9987822 -0.1037675 -0.01152181 -0.9945349 -0.187639 0.01302534 -0.9821517 -0.2445724 -0.01574856 -0.9695031 -0.3067086 0.01538079 -0.9516792 -0.392439 -0.01596015 -0.9196397 -0.4394374 0.01593202 -0.898132 -0.5302912 -0.01781404 -0.8476284 -0.5608405 0.008596956 -0.8278793 -0.658253 0.003074586 -0.7527906 -0.6710819 -0.01341754 -0.7412618 -0.7801557 0.01152998 -0.6254792 -0.7841076 0.004642903 -0.6206076 -0.8608868 -0.01452386 -0.5085893 -0.8879359 0.0194711 -0.4595549 -0.9134026 -0.01154279 -0.4068938 -0.9469091 0.01146894 -0.3212968 -0.9595036 -0.01027065 -0.2815092 -0.9778437 0.01038146 -0.209079 -0.9858571 -0.01174443 -0.1671764 -0.9969072 0.01180154 -0.07769691 -0.9993345 -0.01000618 -0.03507924 -0.9987897 0.01282167 0.0474866 -0.9966402 -0.01021331 0.08126538 -0.9753838 0.003779947 0.2204821 -0.9752908 0.004208922 0.2208848 -0.9313665 -0.003626406 0.3640651 -0.9292812 0.001576483 0.3693699 -0.8672624 0.003121972 0.4978416 -0.8679226 0.004359602 0.4966804 -0.8041503 -0.0106936 0.59433 -0.7789876 0.01569133 0.6268431 -0.7165277 -0.01603394 0.6973745 -0.682308 0.01152169 0.730974 -0.5856496 0.004800498 0.8105502 -0.5988849 -0.009969234 0.8007731 -0.4353868 0.004209101 0.9002338 -0.4433816 -0.005042672 0.8963188 -0.3044441 -0.003168225 0.9525249 -0.2976098 0.002101898 0.9546853 -0.1836695 -0.002231657 0.9829856 -0.1759581 0.004802644 0.984386 -0.001667559 0.004208505 0.9999898 -0.01057368 -0.005045354 0.9999314 0.1552047 0.003795921 0.9878751 0.1469814 -0.003588795 0.9891328 0.300716 0.003797233 0.9537062 0.2927728 -0.003588438 0.9561753 0.4311618 -0.01350474 0.9021736 0.4393883 -0.004018723 0.8982883 0.5330327 0.0180481 0.8459022 0.5952091 -0.02148121 0.8032838 0.6474626 0.01681649 0.7619118 0.7086744 -0.01365995 0.7054035 0.7595052 0.01796931 0.6502532 0.7858632 -0.01021289 0.6183161 0.8649781 0.003777742 0.5017955 0.8651839 0.004208207 0.5014371 0.9330847 -0.004017233 0.3596341 0.9362398 0.005249857 0.3513227 0.9841541 -0.005454599 0.1772317 0.9845119 -0.003127932 0.1752899 0.999925 0.01167035 0.003746688 1.67213e-6 1 -6.77713e-6 1.58363e-6 1 -7.3619e-7 7.8782e-6 1 4.58331e-6 3.07396e-6 1 -1.47551e-6 4.23976e-6 1 7.9032e-6 -2.58572e-7 1 -8.86848e-6 6.68036e-7 1 0 -1.52326e-6 1 -2.94422e-6 -1.4063e-6 1 -1.42033e-5 0 1 -7.9217e-6 2.51749e-6 1 1.15598e-5 7.98839e-6 1 0 0 1 -2.88906e-7 -7.98553e-6 1 -8.45084e-7 2.43144e-6 1 7.76914e-6 2.42753e-6 1 -1.83486e-6 -4.59663e-7 1 -1.97259e-6 7.35979e-6 1 -2.50962e-6 1.06252e-6 1 9.82659e-6 -1.57701e-5 1 5.19453e-6 4.42796e-6 1 7.90644e-6 7.15185e-6 1 -9.85506e-6 -2.4501e-6 1 -7.29635e-6 4.51163e-6 1 -8.50796e-6 1.88675e-6 1 0 6.17855e-6 1 -6.75496e-6 -1.79264e-6 1 -1.87625e-6 -1.81724e-6 1 0 -5.28249e-6 1 6.69266e-6 1.39812e-6 1 0 -7.11334e-6 1 2.63033e-6 1.15566e-6 1 2.95095e-6 -4.46065e-6 1 4.323e-7 5.78698e-7 1 2.22297e-6 7.02836e-7 1 2.94139e-6 -3.87605e-6 1 0 -4.2437e-6 1 -9.03637e-7 8.30429e-6 1 0 -4.73447e-6 1 0 -3.10041e-6 1 1.59384e-6 -1.49541e-7 1 0 2.8326e-6 1 3.92032e-6 -6.14893e-6 1 -1.75805e-5 -5.78597e-7 1 0 -1.03386e-5 1 -1.67941e-6 -1.131e-6 1 3.23362e-6 1.3085e-6 1 1.35123e-5 7.74305e-6 1 9.75763e-6 -5.61612e-6 1 -1.004e-5 -4.98268e-7 1 4.85756e-6 -3.8745e-7 1 3.98289e-6 -3.93605e-7 1 0 -4.60077e-7 1 0 0.685522 0.7277355 0.02146214 0.6842955 0.7288669 0.02219659 0.7218852 0.6808032 0.1240519 0.6501954 0.7360888 0.1882005 0.6807574 0.6954677 0.2299874 0.6000695 0.7214398 0.3456029 0.6180185 0.706633 0.344562 0.5710295 0.6913495 0.4426753 0.511306 0.7273789 0.4576966 0.5106898 0.6929121 0.5089881 0.4074789 0.724616 0.5557813 0.4089342 0.7038004 0.5808939 0.3176763 0.6910372 0.6492683 0.2726007 0.7276688 0.629434 0.2130586 0.6869053 0.6948146 0.1590577 0.7285 0.6663246 0.0887227 0.686316 0.7218717 0.03556257 0.7233173 0.6895995 -0.002135753 0.6963281 0.7177205 -0.07939034 0.7205601 0.6888327 -0.09734493 0.7026239 0.7048714 -0.1830326 0.6967726 0.6935467 -0.2061292 0.7297836 0.6518641 -0.2824531 0.6866735 0.6698506 -0.3324136 0.7274299 0.6002892 -0.3790258 0.691073 0.6154329 -0.4476751 0.7231805 0.5259248 -0.4800556 0.6965919 0.5332038 -0.5528994 0.7079579 0.4394292 -0.5470309 0.7227135 0.4224243 -0.6446132 0.6833522 0.3427881 -0.6189063 0.7338451 0.2800471 -0.6900148 0.6845685 0.2350438 -0.6734851 0.7213654 0.1613998 -0.7094716 0.693277 0.1265595 -0.6870402 0.7232025 0.07038432 -0.727889 0.685409 0.01980865 -0.6838291 0.7274819 -0.05610626 -0.7124569 0.6961978 -0.08782863 -0.6772001 0.7100028 -0.1931223 -0.6623092 0.7227129 -0.1975666 -0.6546061 0.683353 -0.3232949 -0.5886698 0.7338429 -0.3390316 -0.5933754 0.6900814 -0.4143589 -0.5272892 0.7119593 -0.4637674 -0.5218658 0.7162358 -0.4633168 -0.4376873 0.7205569 -0.5377988 -0.4644684 0.7020319 -0.5398336 -0.4007395 0.6863499 -0.6069034 -0.3203517 0.734461 -0.5982824 -0.2951433 0.6884143 -0.6625528 -0.2037177 0.7162367 -0.667461 -0.1998887 0.7199342 -0.6646348 -0.1071399 0.6873049 -0.718424 -0.07111853 0.7242635 -0.685846 0.0339244 0.6978535 -0.7154367 0.03417116 0.6974887 -0.7157806 0.139998 0.7161193 -0.6837936 0.1608992 0.6973423 -0.6984448 0.2431843 0.7142144 -0.6563224 0.252281 0.7059317 -0.661827 0.3637974 0.7120504 -0.6005295 0.3626966 0.7006514 -0.6144419 0.4523884 0.7154968 -0.5323618 0.4501397 0.7021722 -0.5516598 0.5159683 0.6953419 -0.5002764 0.5212387 0.722481 -0.4542372 0.584887 0.6901962 -0.426071 0.5827069 0.7265716 -0.3640693 0.6520826 0.681132 -0.3329377 0.6356098 0.7301787 -0.250678 0.703987 0.6804499 -0.203446 0.6660403 0.7334935 -0.1355642 0.7312916 0.678415 -0.07046914 0.9951708 0.01795542 -0.09650319 0.9879892 -0.0173797 -0.1535426 0.9595754 0.01153647 -0.2812153 0.9606608 0.007537245 -0.2776223 0.8930479 -0.007515907 -0.449899 0.8906335 -0.001772582 -0.4547185 0.8082449 0.008764386 -0.5887812 0.7860586 -0.02024149 -0.6178205 0.7178468 0.01647746 -0.6960061 0.6541481 -0.01446956 -0.7562281 0.6321897 0.004383504 -0.7748013 0.53311 -0.004376649 -0.8460347 0.5094233 0.01378643 -0.8604057 0.4311378 -0.01655274 -0.9021343 0.3539847 0.01415753 -0.9351441 0.3006925 -0.01296144 -0.9536331 0.2265807 0.01616597 -0.9738583 0.1626024 -0.01620084 -0.9865587 0.03904342 0.01272845 -0.9991565 0.04517334 0.00611478 -0.9989604 -0.1341811 -0.005671977 -0.9909407 -0.1460256 0.005588591 -0.9892651 -0.2887908 -0.004916667 -0.9573796 -0.2919014 -0.002351403 -0.9564455 -0.4084427 0.007880687 -0.9127501 -0.4214622 -0.003091156 -0.9068407 -0.5239633 -0.007863521 -0.8517046 -0.5490751 0.01193255 -0.8356878 -0.6379751 -0.00862962 -0.7700086 -0.6527764 0.00442934 -0.7575377 -0.7468655 -0.005048036 -0.664956 -0.7477976 -0.003894567 -0.6639155 -0.8198466 0.009860873 -0.5724985 -0.8423083 -0.01482731 -0.5387921 -0.8964946 0.01681888 -0.4427355 -0.9165457 -0.01755839 -0.3995444 -0.9704566 -0.008728444 -0.2411182 -0.9618384 0.01552313 -0.2731777 -0.9921724 0.006542623 -0.1247051 -0.9944074 -0.00764203 -0.1053361 -0.9995114 0.01040333 0.02947479 -0.9984129 -0.008728444 0.05563962 -0.9848506 0.006542801 0.1732817 -0.981277 -0.00764203 0.1924503 -0.9461867 0.01049816 0.3234511 -0.9324476 -0.01945161 0.3607814 -0.8826922 0.02283793 0.4693962 -0.8519239 -0.01786822 0.5233607 -0.7799306 0.009807169 0.6257892 -0.7828626 0.00548911 0.6221703 -0.684729 -0.004915297 0.7287812 -0.6690449 0.01184105 0.7431277 -0.5683887 -0.0163871 0.822597 -0.5234554 0.01797372 0.8518636 -0.4394558 -0.01432639 0.89815 -0.3893901 0.01443862 0.9209599 -0.3006747 -0.01493847 0.9536098 -0.2561363 0.01056224 0.966583 -0.1614472 -0.007455527 0.9868532 -0.1360534 0.007108569 0.9906761 -0.03072643 -0.01184338 0.9994577 -0.002985298 0.007057487 0.9999707 0.1300966 -0.003462374 0.9914953 0.1220139 0.003878235 0.9925208 0.2589046 -0.008809149 0.9658628 0.2931151 0.01656991 0.9559336 0.4001296 -0.01617002 0.9163159 0.4394586 0.0133413 0.8981637 0.5592952 -0.01149559 0.828889 0.5756487 0.006891131 0.8176682 0.7052882 -0.006872594 0.7088873 0.7082635 -0.002993583 0.7059419 0.8038136 -0.007212579 0.5948376 0.7903149 0.007217526 0.6126583 0.8675131 0.002353549 0.4974091 0.8733771 0.01184213 0.4869008 0.9261046 -0.01499998 0.3769686 0.9472501 0.01738727 0.3200236 0.9658769 -0.01248544 0.2587006 0.9856536 0.01410019 0.1681913 0.9918262 -0.008707344 0.1272984 0.9994137 0.005771219 0.03374874 0.9999352 -0.01042753 0.004571557 0 -1 -1.1702e-5 0 -1 1.38791e-5 0 -1 3.67647e-6 0 -1 6.40949e-6 0 -1 5.67972e-6 0 -1 1.11031e-5 0 -1 -1.14642e-5 0 -1 1.30384e-5 0 -1 4.46605e-6 0 -1 5.03711e-6 0 -1 1.47773e-6 0 -1 3.32862e-6 0 -1 2.46194e-6 0 -1 -2.84235e-6 0 -1 -5.87307e-6 0 -1 2.47901e-6 0 -1 2.57378e-6 0 -1 -2.9557e-6 0 -1 -3.40801e-6 0 -1 7.07922e-6 0 -1 -4.69598e-6 0 -1 1.08645e-5 0 -1 -1.35268e-5 0 -1 6.70916e-6 0 -1 8.86659e-6 0 -1 -3.54318e-6 0 -1 3.32478e-6 0 -1 -3.42022e-6 0 -1 5.35704e-6 0 -1 -9.98275e-6 0 -1 3.55621e-6 0 -1 8.87935e-7 0 -1 2.10372e-6 0 -1 1.18733e-5 0 -1 -6.73224e-6 0 -1 -6.13594e-6 0 -1 2.46104e-6 0 -1 1.1462e-5 0 -1 -5.91954e-6 0 -1 1.01708e-5 0 -1 -2.62301e-6 0 -1 7.12644e-6 0 -1 -2.52704e-6 + + + + + + + + + + + + + +

4151 4150 4153 4152

+
+ + + +

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

+
+ + + +

2181 3587 2144 3587 2145 3587 2182 3588 2144 3588 2181 3588 2145 3589 2144 3589 2146 3589 2144 3590 2147 3590 2146 3590 2147 3591 2148 3591 2146 3591 2146 3592 2148 3592 2149 3592 2148 3593 2150 3593 2149 3593 2149 3594 2150 3594 2151 3594 2150 3595 2152 3595 2151 3595 2151 3596 2152 3596 2153 3596 2152 3597 2154 3597 2153 3597 2153 3598 2154 3598 2155 3598 2154 3599 2156 3599 2155 3599 2155 3600 2156 3600 2157 3600 2156 3601 2158 3601 2157 3601 2157 3602 2158 3602 2159 3602 2159 3603 2158 3603 2160 3603 2158 3604 2161 3604 2160 3604 2160 3605 2161 3605 2162 3605 2161 3606 2163 3606 2162 3606 2163 3607 2164 3607 2162 3607 2162 3608 2164 3608 2165 3608 2164 3609 2166 3609 2165 3609 2165 3610 2166 3610 2167 3610 2167 3611 2166 3611 2168 3611 2166 3612 2169 3612 2168 3612 2168 3613 2169 3613 2170 3613 2169 3614 2171 3614 2170 3614 2170 3615 2171 3615 2172 3615 2171 3616 2173 3616 2172 3616 2172 3617 2173 3617 2174 3617 2174 3618 2175 3618 2176 3618 2173 3619 2175 3619 2174 3619 2176 3620 2177 3620 2178 3620 2175 3621 2177 3621 2176 3621 2177 3622 2179 3622 2178 3622 2178 3623 2179 3623 2180 3623 2180 3624 2179 3624 2181 3624 2179 3625 2182 3625 2181 3625 2183 3626 2184 3626 2185 3626 2186 3627 2183 3627 2185 3627 2183 3628 2187 3628 2184 3628 2183 3629 2188 3629 2187 3629 2183 10 2189 10 2188 10 2183 3630 2186 3630 2190 3630 2183 3631 2190 3631 2189 3631 2191 3632 2192 3632 2193 3632 2193 10 2192 10 2194 10 2194 10 2192 10 2195 10 2207 10 2196 10 2197 10 2198 3633 2185 3633 2199 3633 2200 10 2185 10 2198 10 2200 3634 2186 3634 2185 3634 2201 10 2186 10 2200 10 2201 3635 2202 3635 2186 3635 2202 10 2203 10 2186 10 2203 3636 2190 3636 2186 3636 2203 3637 2204 3637 2190 3637 2190 3638 2205 3638 2206 3638 2204 3639 2205 3639 2190 3639 2208 3640 2198 3640 2199 3640 2192 3641 2196 3641 2195 3641 2195 10 2196 10 2207 10 2199 3642 2192 3642 2191 3642 2199 3643 2191 3643 2208 3643 2211 3644 2209 3644 2210 3644 2212 10 2210 10 2209 10 2213 3645 2211 3645 2210 3645 2214 10 2210 10 2212 10 2217 10 2216 10 2215 10 2217 3646 2218 3646 2216 3646 2215 10 2216 10 2219 10 2217 3647 2214 3647 2218 3647 2220 3648 2214 3648 2217 3648 2221 3649 2215 3649 2219 3649 2221 10 2219 10 2222 10 2220 3650 2223 3650 2214 3650 2221 10 2222 10 2224 10 2225 3651 2221 3651 2224 3651 2225 10 2224 10 2226 10 2227 10 2223 10 2220 10 2227 3652 2228 3652 2223 3652 2225 3653 2226 3653 2229 3653 2230 3654 2228 3654 2227 3654 2231 10 2228 10 2230 10 2229 3655 2232 3655 2225 3655 2233 3656 2232 3656 2229 3656 2231 3657 2230 3657 2234 3657 2235 10 2231 10 2234 10 2236 10 2232 10 2233 10 2235 10 2234 10 2237 10 2236 3658 2238 3658 2232 3658 2239 10 2235 10 2237 10 2240 10 2238 10 2236 10 2240 3659 2241 3659 2238 3659 2242 10 2239 10 2237 10 2242 10 2237 10 2243 10 2244 10 2241 10 2240 10 2244 3660 2243 3660 2241 3660 2244 3661 2242 3661 2243 3661 2210 10 2245 10 2213 10 2246 3662 2210 3662 2223 3662 2223 3663 2210 3663 2214 3663 2272 3664 2247 3664 2248 3664 2247 3665 2249 3665 2248 3665 2248 3666 2249 3666 2250 3666 2249 3667 2251 3667 2250 3667 2250 3668 2251 3668 2252 3668 2251 3669 2253 3669 2252 3669 2252 3670 2253 3670 2254 3670 2253 3671 2255 3671 2254 3671 2254 3672 2255 3672 2256 3672 2255 3673 2257 3673 2256 3673 2256 3674 2257 3674 2258 3674 2257 3675 2259 3675 2258 3675 2258 3676 2259 3676 2260 3676 2259 3677 2261 3677 2260 3677 2260 3678 2261 3678 2262 3678 2261 3679 2263 3679 2262 3679 2262 3680 2263 3680 2264 3680 2264 3681 2263 3681 2265 3681 2263 3682 2266 3682 2265 3682 2266 3683 2267 3683 2265 3683 2265 3684 2267 3684 2268 3684 2267 3685 2269 3685 2268 3685 2268 3686 2269 3686 2270 3686 2269 3687 2271 3687 2270 3687 2270 3688 2271 3688 2272 3688 2271 3689 2247 3689 2272 3689 2266 3690 2269 3690 2267 3690 2257 3691 2255 3691 2259 3691 2255 3692 2253 3692 2259 3692 2259 3693 2253 3693 2261 3693 2271 3694 2249 3694 2247 3694 2266 3695 2249 3695 2269 3695 2261 10 2249 10 2263 10 2269 3696 2249 3696 2271 3696 2263 10 2249 10 2266 10 2253 3697 2249 3697 2261 3697 2251 3698 2249 3698 2253 3698 2296 3699 2273 3699 2274 3699 2273 3700 2275 3700 2274 3700 2274 3701 2275 3701 2276 3701 2275 3702 2277 3702 2276 3702 2276 3703 2277 3703 2278 3703 2277 3704 2279 3704 2278 3704 2278 3705 2279 3705 2280 3705 2279 3706 2281 3706 2280 3706 2280 3707 2281 3707 2282 3707 2281 3708 2283 3708 2282 3708 2282 3709 2283 3709 2284 3709 2283 3710 2285 3710 2284 3710 2284 3711 2285 3711 2286 3711 2285 3712 2287 3712 2286 3712 2287 3713 2288 3713 2286 3713 2286 3714 2288 3714 2289 3714 2288 3715 2290 3715 2289 3715 2289 3716 2290 3716 2291 3716 2291 3717 2290 3717 2292 3717 2290 3718 2293 3718 2292 3718 2292 3719 2293 3719 2294 3719 2293 3720 2295 3720 2294 3720 2294 3721 2295 3721 2296 3721 2295 3722 2273 3722 2296 3722 2283 10 2281 10 2285 10 2285 3723 2279 3723 2287 3723 2281 10 2279 10 2285 10 2287 10 2279 10 2288 10 2295 3724 2275 3724 2273 3724 2290 3725 2275 3725 2293 3725 2293 3726 2275 3726 2295 3726 2288 10 2275 10 2290 10 2279 10 2277 10 2288 10 2288 10 2277 10 2275 10 2322 3727 2298 3727 2297 3727 2297 3728 2298 3728 2299 3728 2298 3729 2300 3729 2299 3729 2299 3730 2300 3730 2301 3730 2300 3731 2302 3731 2301 3731 2301 3732 2302 3732 2303 3732 2303 3733 2304 3733 2305 3733 2302 3734 2304 3734 2303 3734 2305 3735 2304 3735 2306 3735 2304 3736 2307 3736 2306 3736 2307 3737 2308 3737 2306 3737 2306 3738 2308 3738 2309 3738 2309 3739 2308 3739 2310 3739 2308 3740 2311 3740 2310 3740 2310 3741 2311 3741 2312 3741 2311 3742 2313 3742 2312 3742 2312 3743 2313 3743 2314 3743 2313 3744 2315 3744 2314 3744 2315 3745 2316 3745 2314 3745 2314 3746 2316 3746 2317 3746 2316 3747 2318 3747 2317 3747 2317 3748 2318 3748 2319 3748 2318 3749 2320 3749 2319 3749 2319 3750 2320 3750 2321 3750 2320 3751 2322 3751 2321 3751 2321 3752 2322 3752 2297 3752 2308 3753 2307 3753 2311 3753 2311 3754 2307 3754 2313 3754 2318 10 2322 10 2320 10 2313 10 2302 10 2315 10 2307 10 2302 10 2313 10 2304 10 2302 10 2307 10 2315 3755 2302 3755 2316 3755 2302 10 2300 10 2316 10 2316 10 2300 10 2318 10 2322 3756 2300 3756 2298 3756 2318 10 2300 10 2322 10 2323 3757 2324 3757 2325 3757 2324 3758 2326 3758 2325 3758 2325 3759 2326 3759 2327 3759 2326 3760 2328 3760 2327 3760 2327 3761 2328 3761 2329 3761 2328 3762 2330 3762 2329 3762 2330 3763 2331 3763 2329 3763 2329 3764 2331 3764 2332 3764 2331 3765 2333 3765 2332 3765 2332 3766 2333 3766 2334 3766 2333 3767 2335 3767 2334 3767 2334 3768 2335 3768 2336 3768 2335 3769 2337 3769 2336 3769 2336 3770 2337 3770 2338 3770 2337 3771 2339 3771 2338 3771 2338 3772 2339 3772 2340 3772 2340 3773 2339 3773 2341 3773 2339 3774 2342 3774 2341 3774 2341 3775 2342 3775 2343 3775 2342 3776 2344 3776 2343 3776 2343 3777 2344 3777 2345 3777 2344 3778 2346 3778 2345 3778 2345 3779 2347 3779 2348 3779 2346 3780 2347 3780 2345 3780 2348 3781 2347 3781 2323 3781 2347 3782 2324 3782 2323 3782 2335 10 2333 10 2337 10 2337 3783 2333 3783 2339 3783 2339 3784 2331 3784 2342 3784 2333 10 2331 10 2339 10 2342 10 2331 10 2344 10 2331 3785 2330 3785 2344 3785 2330 10 2328 10 2344 10 2344 3786 2328 3786 2346 3786 2324 10 2328 10 2326 10 2346 10 2328 10 2347 10 2347 10 2328 10 2324 10 2349 3787 2350 3787 2352 3787 2353 3788 2349 3788 2352 3788 2353 3789 2352 3789 2354 3789 2355 3790 2353 3790 2354 3790 2355 3791 2354 3791 2356 3791 2357 3792 2355 3792 2356 3792 2357 3793 2356 3793 2358 3793 2359 3794 2357 3794 2358 3794 2360 3795 2359 3795 2358 3795 2360 3796 2358 3796 2361 3796 2362 3797 2360 3797 2361 3797 2363 3798 2362 3798 2361 3798 2363 3799 2361 3799 2364 3799 2365 3800 2363 3800 2364 3800 2365 3801 2364 3801 2366 3801 2367 3802 2365 3802 2366 3802 2367 3803 2366 3803 2368 3803 2369 3804 2367 3804 2368 3804 2369 3805 2368 3805 2370 3805 2371 3806 2369 3806 2370 3806 2371 3807 2370 3807 2372 3807 2373 3808 2371 3808 2372 3808 2374 3809 2373 3809 2372 3809 2374 3810 2372 3810 2375 3810 2376 3811 2374 3811 2375 3811 2376 3812 2375 3812 2377 3812 2378 3813 2376 3813 2377 3813 2378 3814 2377 3814 2379 3814 2380 3815 2378 3815 2379 3815 2380 3816 2379 3816 2381 3816 2382 3817 2380 3817 2381 3817 2382 3818 2381 3818 2383 3818 2384 3819 2382 3819 2383 3819 2384 3820 2383 3820 2385 3820 2384 3821 2385 3821 2350 3821 2386 3822 2384 3822 2350 3822 2292 3823 2366 3823 2364 3823 2294 10 2366 10 2292 10 2294 3824 2368 3824 2366 3824 2292 10 2364 10 2361 10 2296 10 2368 10 2294 10 2291 3825 2292 3825 2361 3825 2296 3826 2370 3826 2368 3826 2291 10 2361 10 2358 10 2274 10 2370 10 2296 10 2289 10 2291 10 2358 10 2274 3827 2372 3827 2370 3827 2276 10 2372 10 2274 10 2289 3828 2358 3828 2356 3828 2286 10 2289 10 2356 10 2375 3829 2372 3829 2276 3829 2354 3830 2286 3830 2356 3830 2375 3831 2276 3831 2278 3831 2377 10 2375 10 2278 10 2352 10 2286 10 2354 10 2352 3832 2284 3832 2286 3832 2350 3833 2284 3833 2352 3833 2377 10 2278 10 2280 10 2379 10 2377 10 2280 10 2385 10 2284 10 2350 10 2383 10 2284 10 2385 10 2381 3834 2379 3834 2280 3834 2383 3835 2282 3835 2284 3835 2381 3836 2280 3836 2282 3836 2381 3837 2282 3837 2383 3837 2387 3838 2350 3838 2388 3838 2386 3839 2387 3839 2388 3839 2389 3840 2386 3840 2388 3840 2390 3841 2389 3841 2388 3841 2390 3842 2388 3842 2391 3842 2390 3843 2391 3843 2392 3843 2393 3844 2390 3844 2392 3844 2393 3845 2392 3845 2394 3845 2395 3846 2393 3846 2394 3846 2395 3847 2394 3847 2396 3847 2397 3848 2395 3848 2396 3848 2397 3849 2396 3849 2398 3849 2399 3850 2397 3850 2398 3850 2399 3851 2398 3851 2400 3851 2401 3852 2399 3852 2400 3852 2401 3853 2400 3853 2402 3853 2403 3854 2401 3854 2402 3854 2403 3855 2402 3855 2404 3855 2405 3856 2403 3856 2404 3856 2405 3857 2404 3857 2406 3857 2407 3858 2405 3858 2406 3858 2407 3859 2406 3859 2408 3859 2409 3860 2407 3860 2408 3860 2409 3861 2408 3861 2410 3861 2411 3862 2409 3862 2410 3862 2411 3863 2410 3863 2412 3863 2413 3864 2411 3864 2412 3864 2413 3865 2412 3865 2414 3865 2415 3866 2413 3866 2414 3866 2416 3867 2415 3867 2414 3867 2416 3868 2414 3868 2417 3868 2418 3869 2416 3869 2417 3869 2418 3870 2417 3870 2419 3870 2418 3871 2419 3871 2420 3871 2421 3872 2418 3872 2420 3872 2349 3873 2421 3873 2420 3873 2351 3874 2349 3874 2420 3874 2351 3875 2420 3875 2350 3875 2270 10 2419 10 2417 10 2268 10 2270 10 2417 10 2270 10 2420 10 2419 10 2268 10 2417 10 2414 10 2265 3876 2268 3876 2414 3876 2272 10 2420 10 2270 10 2265 10 2414 10 2412 10 2272 3877 2350 3877 2420 3877 2272 3878 2388 3878 2350 3878 2264 10 2265 10 2412 10 2248 3879 2388 3879 2272 3879 2248 3880 2391 3880 2388 3880 2262 3881 2264 3881 2412 3881 2262 10 2412 10 2410 10 2250 10 2392 10 2391 10 2250 3882 2391 3882 2248 3882 2408 3883 2262 3883 2410 3883 2408 3884 2260 3884 2262 3884 2394 10 2392 10 2250 10 2406 10 2260 10 2408 10 2394 3885 2250 3885 2252 3885 2406 3886 2258 3886 2260 3886 2396 10 2394 10 2252 10 2404 3887 2258 3887 2406 3887 2396 10 2252 10 2254 10 2404 3888 2256 3888 2258 3888 2398 3889 2396 3889 2254 3889 2402 10 2256 10 2404 10 2400 10 2398 10 2254 10 2400 10 2256 10 2402 10 2400 10 2254 10 2256 10 2423 3890 2367 3890 2369 3890 2422 3891 2405 3891 2424 3891 2405 3892 2407 3892 2424 3892 2423 3893 2425 3893 2367 3893 2424 3894 2407 3894 2426 3894 2407 3895 2409 3895 2426 3895 2425 3896 2427 3896 2365 3896 2426 3897 2409 3897 2428 3897 2355 3898 2357 3898 2416 3898 2409 3899 2411 3899 2428 3899 2427 3900 2429 3900 2363 3900 2411 3901 2413 3901 2428 3901 2362 3902 2429 3902 2360 3902 2428 3903 2413 3903 2430 3903 2415 3904 2359 3904 2413 3904 2359 3905 2360 3905 2413 3905 2429 3906 2431 3906 2360 3906 2360 3907 2431 3907 2413 3907 2413 3908 2431 3908 2430 3908 2430 3909 2431 3909 2432 3909 2431 3910 2433 3910 2432 3910 2416 3911 2418 3911 2355 3911 2418 3912 2421 3912 2353 3912 2349 3913 2353 3913 2421 3913 2353 3914 2355 3914 2418 3914 2416 3915 2357 3915 2415 3915 2357 3916 2359 3916 2415 3916 2362 3917 2363 3917 2429 3917 2363 3918 2365 3918 2427 3918 2365 3919 2367 3919 2425 3919 2434 3920 2435 3920 2436 3920 2438 3921 2434 3921 2436 3921 2439 3922 2438 3922 2436 3922 2439 3923 2436 3923 2440 3923 2439 3924 2440 3924 2441 3924 2442 3925 2439 3925 2441 3925 2442 3926 2441 3926 2443 3926 2444 3927 2442 3927 2443 3927 2444 3928 2443 3928 2445 3928 2446 3929 2444 3929 2445 3929 2446 3930 2445 3930 2447 3930 2448 3931 2446 3931 2447 3931 2449 3932 2448 3932 2447 3932 2449 3933 2447 3933 2450 3933 2451 3934 2449 3934 2450 3934 2451 3935 2450 3935 2452 3935 2453 3936 2451 3936 2452 3936 2453 3937 2452 3937 2454 3937 2455 3938 2453 3938 2454 3938 2455 3939 2454 3939 2456 3939 2457 3940 2455 3940 2456 3940 2458 3941 2457 3941 2456 3941 2458 3942 2456 3942 2459 3942 2460 3943 2458 3943 2459 3943 2460 3944 2459 3944 2461 3944 2460 3945 2461 3945 2462 3945 2463 3946 2460 3946 2462 3946 2464 3947 2463 3947 2462 3947 2464 3948 2462 3948 2465 3948 2466 3949 2464 3949 2465 3949 2466 3950 2465 3950 2467 3950 2468 3951 2466 3951 2467 3951 2469 3952 2468 3952 2467 3952 2469 3953 2467 3953 2470 3953 2471 3954 2469 3954 2470 3954 2472 3955 2470 3955 2435 3955 2472 3956 2471 3956 2470 3956 2437 3957 2472 3957 2435 3957 2319 3958 2321 3958 2450 3958 2319 10 2450 10 2447 10 2321 10 2452 10 2450 10 2317 3959 2319 3959 2447 3959 2297 10 2452 10 2321 10 2317 10 2447 10 2445 10 2297 3960 2454 3960 2452 3960 2314 3961 2317 3961 2445 3961 2314 3962 2445 3962 2443 3962 2299 10 2454 10 2297 10 2299 3963 2456 3963 2454 3963 2314 3964 2443 3964 2441 3964 2299 10 2459 10 2456 10 2312 3965 2314 3965 2441 3965 2461 10 2459 10 2299 10 2461 10 2299 10 2301 10 2440 10 2312 10 2441 10 2436 3966 2312 3966 2440 3966 2436 3967 2310 3967 2312 3967 2461 3968 2301 3968 2303 3968 2462 10 2461 10 2303 10 2435 3969 2310 3969 2436 3969 2462 10 2303 10 2305 10 2435 3970 2309 3970 2310 3970 2470 10 2309 10 2435 10 2465 3971 2462 3971 2305 3971 2470 10 2306 10 2309 10 2467 10 2465 10 2305 10 2467 10 2305 10 2306 10 2467 10 2306 10 2470 10 2473 3972 2455 3972 2474 3972 2473 3973 2453 3973 2455 3973 2475 10 2453 10 2473 10 2475 3974 2451 3974 2453 3974 2476 3975 2451 3975 2475 3975 2476 3976 2449 3976 2451 3976 2476 3977 2448 3977 2449 3977 2490 3978 2448 3978 2476 3978 2434 3979 2477 3979 2437 3979 2434 3980 2438 3980 2477 3980 2439 10 2478 10 2438 10 2442 3981 2478 3981 2439 3981 2442 3982 2479 3982 2478 3982 2444 3983 2479 3983 2442 3983 2444 10 2480 10 2479 10 2481 3984 2168 3984 2482 3984 2483 10 2167 10 2481 10 2481 10 2167 10 2168 10 2168 3985 2170 3985 2482 3985 2483 3986 2165 3986 2167 3986 2484 10 2165 10 2483 10 2170 3987 2172 3987 2482 3987 2484 3988 2162 3988 2165 3988 2485 3989 2162 3989 2484 3989 2172 3990 2174 3990 2482 3990 2486 3991 2162 3991 2485 3991 2486 3992 2160 3992 2162 3992 2486 3993 2159 3993 2160 3993 2480 3994 2159 3994 2486 3994 2446 3995 2159 3995 2444 3995 2444 3996 2159 3996 2480 3996 2487 3997 2488 3997 2489 3997 2489 3998 2488 3998 2490 3998 2488 10 2491 10 2490 10 2492 10 2374 10 2491 10 2493 10 2373 10 2492 10 2492 3999 2373 3999 2374 3999 2374 4000 2376 4000 2491 4000 2490 4001 2376 4001 2448 4001 2491 10 2376 10 2490 10 2493 4002 2371 4002 2373 4002 2448 10 2376 10 2446 10 2494 10 2371 10 2493 10 2376 4003 2378 4003 2446 4003 2494 4004 2369 4004 2371 4004 2446 4005 2378 4005 2159 4005 2159 4006 2378 4006 2157 4006 2423 4007 2369 4007 2494 4007 2382 4008 2390 4008 2393 4008 2382 10 2393 10 2380 10 2384 10 2390 10 2382 10 2176 4009 2495 4009 2174 4009 2178 4010 2495 4010 2176 4010 2180 4011 2495 4011 2178 4011 2174 4012 2495 4012 2482 4012 2393 10 2395 10 2380 10 2384 10 2389 10 2390 10 2181 4013 2495 4013 2180 4013 2380 10 2395 10 2378 10 2384 4014 2386 4014 2389 4014 2378 4015 2395 4015 2157 4015 2181 4016 2496 4016 2495 4016 2386 4017 2351 4017 2387 4017 2395 10 2397 10 2157 10 2157 10 2397 10 2155 10 2145 10 2496 10 2181 10 2155 10 2397 10 2153 10 2145 4018 2497 4018 2496 4018 2397 10 2399 10 2153 10 2146 10 2497 10 2145 10 2153 10 2399 10 2151 10 2399 10 2401 10 2151 10 2146 4019 2498 4019 2497 4019 2149 10 2498 10 2146 10 2151 10 2499 10 2149 10 2499 10 2500 10 2149 10 2149 4020 2500 4020 2498 4020 2401 4021 2501 4021 2151 4021 2151 4022 2501 4022 2499 4022 2403 10 2502 10 2401 10 2401 4023 2502 4023 2501 4023 2498 10 2500 10 2503 10 2500 4024 2504 4024 2503 4024 2405 4025 2502 4025 2403 4025 2405 4026 2422 4026 2502 4026 2503 4027 2504 4027 2505 4027 2471 4028 2472 4028 2506 4028 2437 4029 2507 4029 2472 4029 2507 4030 2435 4030 2508 4030 2472 4031 2507 4031 2508 4031 2506 4032 2472 4032 2508 4032 2506 4033 2508 4033 2509 4033 2510 4034 2506 4034 2509 4034 2510 4035 2509 4035 2511 4035 2512 4036 2511 4036 2513 4036 2512 4037 2510 4037 2511 4037 2514 4038 2512 4038 2513 4038 2514 4039 2513 4039 2515 4039 2516 4040 2514 4040 2515 4040 2516 4041 2515 4041 2517 4041 2518 4042 2516 4042 2517 4042 2518 4043 2517 4043 2519 4043 2520 4044 2518 4044 2519 4044 2520 4045 2519 4045 2521 4045 2522 4046 2520 4046 2521 4046 2482 4047 2522 4047 2521 4047 2482 4048 2521 4048 2523 4048 2481 4049 2482 4049 2523 4049 2481 4050 2523 4050 2524 4050 2483 4051 2481 4051 2524 4051 2483 4052 2524 4052 2525 4052 2484 4053 2483 4053 2525 4053 2484 4054 2525 4054 2526 4054 2485 4055 2484 4055 2526 4055 2485 4056 2526 4056 2527 4056 2486 4057 2485 4057 2527 4057 2486 4058 2527 4058 2528 4058 2480 4059 2486 4059 2528 4059 2480 4060 2528 4060 2529 4060 2479 4061 2480 4061 2529 4061 2479 4062 2529 4062 2530 4062 2478 4063 2479 4063 2530 4063 2478 4064 2530 4064 2531 4064 2438 4065 2478 4065 2531 4065 2477 4066 2438 4066 2531 4066 2477 4067 2531 4067 2435 4067 2348 4068 2529 4068 2345 4068 2348 4069 2530 4069 2529 4069 2345 4070 2529 4070 2528 4070 2323 10 2530 10 2348 10 2343 4071 2345 4071 2528 4071 2323 4072 2531 4072 2530 4072 2343 4073 2528 4073 2527 4073 2323 4074 2435 4074 2531 4074 2323 4075 2508 4075 2435 4075 2325 10 2508 10 2323 10 2341 10 2343 10 2527 10 2325 4076 2509 4076 2508 4076 2341 4077 2527 4077 2526 4077 2327 10 2511 10 2509 10 2327 10 2509 10 2325 10 2341 4078 2526 4078 2525 4078 2525 4079 2340 4079 2341 4079 2513 10 2511 10 2327 10 2524 10 2340 10 2525 10 2513 4080 2327 4080 2329 4080 2524 10 2338 10 2340 10 2515 10 2513 10 2329 10 2523 10 2338 10 2524 10 2523 4081 2336 4081 2338 4081 2515 4082 2329 4082 2332 4082 2521 10 2336 10 2523 10 2517 10 2515 10 2332 10 2519 4083 2517 4083 2332 4083 2521 10 2334 10 2336 10 2519 10 2332 10 2334 10 2519 10 2334 10 2521 10 2489 4084 2532 4084 2487 4084 2487 4085 2532 4085 2533 4085 2532 4086 2534 4086 2533 4086 2533 4087 2534 4087 2535 4087 2534 4088 2536 4088 2535 4088 2535 4089 2536 4089 2537 4089 2536 4090 2538 4090 2537 4090 2537 4091 2538 4091 2539 4091 2538 4092 2540 4092 2539 4092 2539 4093 2540 4093 2541 4093 2540 4094 2543 4094 2541 4094 2688 4095 2803 4095 2543 4095 2541 4096 2543 4096 2542 4096 2542 4097 2543 4097 2825 4097 2543 4098 2803 4098 2825 4098 2803 4099 2544 4099 2825 4099 2825 4100 2544 4100 2824 4100 2548 4101 2547 4101 2549 4101 2548 4102 2546 4102 2547 4102 2206 4103 2544 4103 2190 4103 2550 4104 2544 4104 2206 4104 2551 4105 2550 4105 2206 4105 2824 4106 2550 4106 2552 4106 2545 4107 2824 4107 2552 4107 2546 4108 2552 4108 2547 4108 2546 4109 2545 4109 2552 4109 2553 4110 2824 4110 2545 4110 2824 4111 2544 4111 2550 4111 2551 4112 2206 4112 2205 4112 2554 4113 2551 4113 2205 4113 2656 4114 2205 4114 2204 4114 2656 4115 2554 4115 2205 4115 2656 4116 2749 4116 2554 4116 2554 4117 2749 4117 2549 4117 2749 4118 2548 4118 2549 4118 2749 4119 2555 4119 2548 4119 2581 4120 2582 4120 2556 4120 2582 4121 2557 4121 2556 4121 2556 4122 2557 4122 2558 4122 2557 4123 2559 4123 2558 4123 2558 4124 2559 4124 2560 4124 2559 4125 2561 4125 2560 4125 2560 4126 2561 4126 2562 4126 2561 4127 2563 4127 2562 4127 2562 4128 2563 4128 2564 4128 2563 4129 2565 4129 2564 4129 2564 4130 2565 4130 2566 4130 2565 4131 2567 4131 2566 4131 2566 4132 2567 4132 2568 4132 2567 4133 2569 4133 2568 4133 2568 4134 2569 4134 2570 4134 2569 4135 2571 4135 2570 4135 2570 4136 2571 4136 2572 4136 2571 4137 2573 4137 2572 4137 2572 4138 2573 4138 2574 4138 2573 4139 2575 4139 2574 4139 2574 4140 2575 4140 2576 4140 2575 4141 2577 4141 2576 4141 2577 4142 2578 4142 2576 4142 2576 4143 2578 4143 2579 4143 2578 4144 2580 4144 2579 4144 2579 4145 2580 4145 2581 4145 2580 4146 2582 4146 2581 4146 2558 4147 2560 4147 2556 4147 2556 10 2560 10 2581 10 2579 4148 2560 4148 2576 4148 2581 4149 2560 4149 2579 4149 2560 4150 2562 4150 2576 4150 2576 10 2562 10 2574 10 2574 10 2562 10 2572 10 2570 4151 2566 4151 2568 4151 2562 4152 2564 4152 2572 4152 2570 4153 2564 4153 2566 4153 2572 4154 2564 4154 2570 4154 2606 4155 2583 4155 2607 4155 2607 4156 2583 4156 2584 4156 2584 4157 2583 4157 2585 4157 2583 4158 2586 4158 2585 4158 2586 4159 2587 4159 2585 4159 2585 4160 2587 4160 2588 4160 2587 4161 2589 4161 2588 4161 2589 4162 2590 4162 2588 4162 2588 4163 2590 4163 2591 4163 2590 4164 2592 4164 2591 4164 2591 4165 2592 4165 2593 4165 2592 4166 2594 4166 2593 4166 2593 4167 2594 4167 2595 4167 2594 4168 2596 4168 2595 4168 2595 4169 2596 4169 2597 4169 2596 4170 2598 4170 2597 4170 2597 4171 2598 4171 2599 4171 2599 4172 2598 4172 2600 4172 2598 4173 2601 4173 2600 4173 2600 4174 2601 4174 2602 4174 2601 4175 2603 4175 2602 4175 2603 4176 2604 4176 2602 4176 2602 4177 2604 4177 2605 4177 2604 4178 2606 4178 2605 4178 2605 4179 2606 4179 2607 4179 2607 10 2584 10 2605 10 2605 10 2584 10 2602 10 2600 10 2597 10 2599 10 2597 4180 2593 4180 2595 4180 2584 4181 2591 4181 2602 4181 2602 10 2591 10 2600 10 2585 10 2591 10 2584 10 2588 10 2591 10 2585 10 2597 4182 2591 4182 2593 4182 2600 10 2591 10 2597 10 2221 4183 2225 4183 2608 4183 2608 4184 2225 4184 2609 4184 2609 4185 2225 4185 2610 4185 2225 4186 2232 4186 2610 4186 2610 4187 2232 4187 2611 4187 2232 4188 2238 4188 2611 4188 2611 4189 2238 4189 2612 4189 2238 4190 2241 4190 2612 4190 2241 4191 2243 4191 2612 4191 2612 4192 2243 4192 2613 4192 2613 4193 2243 4193 2614 4193 2243 4194 2237 4194 2614 4194 2237 4195 2234 4195 2614 4195 2614 4196 2234 4196 2615 4196 2234 4197 2230 4197 2615 4197 2615 4198 2230 4198 2616 4198 2616 4199 2227 4199 2617 4199 2230 4200 2227 4200 2616 4200 2227 4201 2220 4201 2617 4201 2617 4202 2220 4202 2618 4202 2220 4203 2217 4203 2618 4203 2618 4204 2217 4204 2619 4204 2217 4205 2215 4205 2619 4205 2619 4206 2215 4206 2620 4206 2215 4207 2221 4207 2620 4207 2620 4208 2221 4208 2608 4208 2608 10 2609 10 2620 10 2620 10 2609 10 2619 10 2617 4209 2615 4209 2616 4209 2618 10 2615 10 2617 10 2615 10 2613 10 2614 10 2609 10 2612 10 2619 10 2610 10 2612 10 2609 10 2619 10 2612 10 2618 10 2611 4210 2612 4210 2610 4210 2612 4211 2613 4211 2618 4211 2618 10 2613 10 2615 10 2646 4212 2622 4212 2621 4212 2621 4213 2622 4213 2623 4213 2623 4214 2622 4214 2624 4214 2622 4215 2625 4215 2624 4215 2625 4216 2626 4216 2624 4216 2624 4217 2626 4217 2627 4217 2627 4218 2626 4218 2628 4218 2626 4219 2629 4219 2628 4219 2628 4220 2629 4220 2630 4220 2629 4221 2631 4221 2630 4221 2631 4222 2632 4222 2630 4222 2630 4223 2632 4223 2633 4223 2632 4224 2634 4224 2633 4224 2633 4225 2634 4225 2635 4225 2634 4226 2636 4226 2635 4226 2635 4227 2636 4227 2637 4227 2636 4228 2638 4228 2637 4228 2637 4229 2638 4229 2639 4229 2638 4230 2640 4230 2639 4230 2639 4231 2640 4231 2641 4231 2640 4232 2642 4232 2641 4232 2641 4233 2642 4233 2643 4233 2643 4234 2644 4234 2645 4234 2642 4235 2644 4235 2643 4235 2644 4236 2646 4236 2645 4236 2645 4237 2646 4237 2621 4237 2621 10 2624 10 2645 10 2623 10 2624 10 2621 10 2643 4238 2624 4238 2641 4238 2645 10 2624 10 2643 10 2627 10 2628 10 2624 10 2624 4239 2628 4239 2641 4239 2641 4240 2628 4240 2639 4240 2639 10 2628 10 2637 10 2635 10 2630 10 2633 10 2628 10 2630 10 2637 10 2637 10 2630 10 2635 10 2648 4241 2647 4241 2762 4241 2648 4242 2762 4242 2763 4242 2649 4243 2648 4243 2763 4243 2649 4244 2763 4244 2761 4244 2650 4245 2649 4245 2761 4245 2650 4246 2761 4246 2760 4246 2651 4247 2650 4247 2760 4247 2651 4248 2760 4248 2758 4248 2652 4249 2651 4249 2758 4249 2652 4250 2758 4250 2756 4250 2653 4251 2652 4251 2756 4251 2653 4252 2756 4252 2752 4252 2654 4253 2752 4253 2754 4253 2654 4254 2653 4254 2752 4254 2655 4255 2754 4255 2746 4255 2655 4256 2654 4256 2754 4256 2656 4257 2655 4257 2746 4257 2656 4258 2746 4258 2749 4258 2657 4259 2543 4259 2540 4259 2658 4260 2657 4260 2540 4260 2658 4261 2540 4261 2538 4261 2659 4262 2658 4262 2538 4262 2659 4263 2538 4263 2536 4263 2660 4264 2659 4264 2536 4264 2660 4265 2536 4265 2534 4265 2661 4266 2660 4266 2534 4266 2661 4267 2534 4267 2532 4267 2662 4268 2661 4268 2532 4268 2662 4269 2532 4269 2489 4269 2663 4270 2662 4270 2489 4270 2663 4271 2489 4271 2490 4271 2664 4272 2663 4272 2490 4272 2665 4273 2664 4273 2490 4273 2665 4274 2490 4274 2476 4274 2666 4275 2665 4275 2476 4275 2666 4276 2476 4276 2475 4276 2667 4277 2666 4277 2475 4277 2667 4278 2475 4278 2473 4278 2668 4279 2667 4279 2473 4279 2669 4280 2668 4280 2473 4280 2669 4281 2473 4281 2474 4281 2669 4282 2474 4282 2670 4282 2671 4283 2669 4283 2670 4283 2672 4284 2670 4284 2673 4284 2672 4285 2671 4285 2670 4285 2672 4286 2673 4286 2674 4286 2675 4287 2672 4287 2674 4287 2675 4288 2674 4288 2676 4288 2675 4289 2676 4289 2679 4289 2677 4290 2675 4290 2679 4290 2678 4291 2677 4291 2679 4291 2678 4292 2679 4292 2680 4292 2678 4293 2680 4293 2681 4293 2682 4294 2678 4294 2681 4294 2682 4295 2681 4295 2683 4295 2684 4296 2682 4296 2683 4296 2684 4297 2683 4297 2685 4297 2684 4298 2685 4298 2686 4298 2687 4299 2684 4299 2686 4299 2687 4300 2686 4300 2688 4300 2687 4301 2688 4301 2543 4301 2657 4302 2687 4302 2543 4302 2689 4303 2433 4303 2431 4303 2690 4304 2689 4304 2431 4304 2690 4305 2431 4305 2429 4305 2690 4306 2429 4306 2427 4306 2691 4307 2690 4307 2427 4307 2691 4308 2427 4308 2425 4308 2691 4309 2425 4309 2423 4309 2692 4310 2691 4310 2423 4310 2692 4311 2423 4311 2494 4311 2692 4312 2494 4312 2493 4312 2693 4313 2692 4313 2493 4313 2693 4314 2493 4314 2492 4314 2694 4315 2693 4315 2492 4315 2694 4316 2492 4316 2491 4316 2695 4317 2694 4317 2491 4317 2695 4318 2491 4318 2488 4318 2696 4319 2695 4319 2488 4319 2697 4320 2696 4320 2488 4320 2697 4321 2488 4321 2487 4321 2697 4322 2487 4322 2533 4322 2698 4323 2697 4323 2533 4323 2698 4324 2533 4324 2535 4324 2698 4325 2535 4325 2537 4325 2699 4326 2698 4326 2537 4326 2699 4327 2537 4327 2539 4327 2699 4328 2539 4328 2541 4328 2700 4329 2699 4329 2541 4329 2701 4330 2700 4330 2541 4330 2701 4331 2541 4331 2542 4331 2701 4332 2542 4332 2702 4332 2703 4333 2701 4333 2702 4333 2703 4334 2702 4334 2704 4334 2705 4335 2703 4335 2704 4335 2705 4336 2704 4336 2706 4336 2705 4337 2706 4337 2707 4337 2708 4338 2705 4338 2707 4338 2708 4339 2707 4339 2709 4339 2712 4340 2710 4340 2711 4340 2716 4341 2713 4341 2714 4341 2716 4342 2714 4342 2715 4342 2717 4343 2712 4343 2711 4343 2717 4344 2711 4344 2713 4344 2719 4345 2717 4345 2713 4345 2718 4346 2712 4346 2717 4346 2719 4347 2713 4347 2716 4347 2721 4348 2716 4348 2715 4348 2721 4349 2715 4349 2720 4349 2723 4350 2717 4350 2719 4350 2724 4351 2721 4351 2720 4351 2725 4352 2719 4352 2716 4352 2725 4353 2716 4353 2721 4353 2722 4354 2718 4354 2717 4354 2725 4355 2721 4355 2726 4355 2722 4356 2717 4356 2723 4356 2726 4357 2721 4357 2724 4357 2728 4358 2723 4358 2719 4358 2728 4359 2719 4359 2725 4359 2724 4360 2720 4360 2727 4360 2730 4361 2724 4361 2727 4361 2732 4362 2725 4362 2726 4362 2733 4363 2722 4363 2723 4363 2733 4364 2723 4364 2728 4364 2733 4365 2729 4365 2722 4365 2731 4366 2730 4366 2727 4366 2732 4367 2728 4367 2725 4367 2735 4368 2732 4368 2726 4368 2736 4369 2733 4369 2728 4369 2737 4370 2726 4370 2724 4370 2735 4371 2726 4371 2737 4371 2736 4372 2728 4372 2732 4372 2737 4373 2724 4373 2730 4373 2739 4374 2732 4374 2735 4374 2734 4375 2729 4375 2733 4375 2740 4376 2730 4376 2731 4376 2742 4377 2736 4377 2732 4377 2742 4378 2732 4378 2739 4378 2743 4379 2734 4379 2733 4379 2740 4380 2737 4380 2730 4380 2743 4381 2733 4381 2736 4381 2740 4382 2731 4382 2738 4382 2744 4383 2735 4383 2737 4383 2745 4384 2737 4384 2740 4384 2746 4385 2740 4385 2738 4385 2747 4386 2743 4386 2736 4386 2747 4387 2736 4387 2742 4387 2741 4388 2734 4388 2743 4388 2745 4389 2744 4389 2737 4389 2745 4390 2740 4390 2746 4390 2744 4391 2739 4391 2735 4391 2751 4392 2742 4392 2739 4392 2750 4393 2743 4393 2747 4393 2751 4394 2739 4394 2744 4394 2746 4395 2738 4395 2749 4395 2750 4396 2741 4396 2743 4396 2752 4397 2744 4397 2745 4397 2753 4398 2742 4398 2751 4398 2752 4399 2751 4399 2744 4399 2747 4400 2742 4400 2753 4400 2754 4401 2752 4401 2745 4401 2754 4402 2745 4402 2746 4402 2755 4403 2748 4403 2741 4403 2755 4404 2741 4404 2750 4404 2755 4405 2750 4405 2747 4405 2756 4406 2751 4406 2752 4406 2757 4407 2747 4407 2753 4407 2757 4408 2755 4408 2747 4408 2758 4409 2751 4409 2756 4409 2758 4410 2753 4410 2751 4410 2759 4411 2748 4411 2755 4411 2760 4412 2757 4412 2753 4412 2761 4413 2755 4413 2757 4413 2760 4414 2753 4414 2758 4414 2761 4415 2757 4415 2760 4415 2763 4416 2759 4416 2755 4416 2763 4417 2755 4417 2761 4417 2762 4418 2759 4418 2763 4418 2765 4419 2653 4419 2654 4419 2766 4420 2654 4420 2655 4420 2764 4421 2655 4421 2656 4421 2765 4422 2654 4422 2766 4422 2766 4423 2655 4423 2764 4423 2652 4424 2653 4424 2765 4424 2767 4425 2765 4425 2766 4425 2768 4426 2766 4426 2764 4426 2770 4427 2651 4427 2652 4427 2770 4428 2652 4428 2765 4428 2767 4429 2766 4429 2769 4429 2769 4430 2766 4430 2768 4430 2770 4431 2765 4431 2767 4431 2771 4432 2651 4432 2770 4432 2771 4433 2650 4433 2651 4433 2772 4434 2771 4434 2770 4434 2773 4435 2649 4435 2650 4435 2774 4436 2769 4436 2768 4436 2775 4437 2767 4437 2769 4437 2773 4438 2650 4438 2771 4438 2775 4439 2770 4439 2767 4439 2775 4440 2769 4440 2776 4440 2648 4441 2649 4441 2773 4441 2776 4442 2769 4442 2774 4442 2777 4443 2772 4443 2770 4443 2777 4444 2770 4444 2775 4444 2778 4445 2773 4445 2771 4445 2772 4446 2778 4446 2771 4446 2780 4447 2647 4447 2648 4447 2780 4448 2648 4448 2773 4448 2781 4449 2772 4449 2777 4449 2782 4450 2776 4450 2774 4450 2783 4451 2777 4451 2775 4451 2782 4452 2775 4452 2776 4452 2784 4453 2773 4453 2778 4453 2782 4454 2774 4454 2779 4454 2781 4455 2778 4455 2772 4455 2784 4456 2780 4456 2773 4456 2785 4457 2781 4457 2777 4457 2785 4458 2777 4458 2783 4458 2783 4459 2775 4459 2782 4459 2786 4460 2782 4460 2779 4460 2787 4461 2778 4461 2781 4461 2788 4462 2780 4462 2784 4462 2787 4463 2784 4463 2778 4463 2785 4464 2787 4464 2781 4464 2789 4465 2784 4465 2787 4465 2791 4466 2782 4466 2786 4466 2791 4467 2783 4467 2782 4467 2792 4468 2787 4468 2785 4468 2788 4469 2784 4469 2789 4469 2790 4470 2786 4470 2779 4470 2793 4471 2785 4471 2783 4471 2791 4472 2786 4472 2790 4472 2792 4473 2785 4473 2793 4473 2793 4474 2783 4474 2791 4474 2794 4475 2789 4475 2787 4475 2794 4476 2787 4476 2792 4476 2795 4477 2791 4477 2790 4477 2796 4478 2793 4478 2791 4478 2796 4479 2791 4479 2795 4479 2794 4480 2792 4480 2793 4480 2797 4481 2793 4481 2796 4481 2797 4482 2794 4482 2793 4482 2799 4483 2796 4483 2795 4483 2798 4484 2794 4484 2797 4484 2800 4485 2796 4485 2799 4485 2800 4486 2797 4486 2796 4486 2802 4487 2797 4487 2800 4487 2801 4488 2800 4488 2799 4488 2802 4489 2798 4489 2797 4489 2688 4490 2804 4490 2803 4490 2688 4491 2686 4491 2804 4491 2803 4492 2804 4492 2544 4492 2804 4493 2805 4493 2544 4493 2686 4494 2806 4494 2804 4494 2685 4495 2806 4495 2686 4495 2804 4496 2806 4496 2805 4496 2806 4497 2807 4497 2805 4497 2685 4498 2808 4498 2806 4498 2806 4499 2808 4499 2807 4499 2685 4500 2683 4500 2808 4500 2808 4501 2809 4501 2807 4501 2683 4502 2810 4502 2808 4502 2808 4503 2810 4503 2809 4503 2681 4504 2810 4504 2683 4504 2810 4505 2811 4505 2809 4505 2810 4506 2812 4506 2811 4506 2681 4507 2812 4507 2810 4507 2812 4508 2813 4508 2811 4508 2681 4509 2680 4509 2812 4509 2812 4510 2814 4510 2813 4510 2680 4511 2814 4511 2812 4511 2813 4512 2814 4512 2815 4512 2644 4513 2671 4513 2672 4513 2642 10 2671 10 2644 10 2642 4514 2669 4514 2671 4514 2644 10 2672 10 2675 10 2640 4515 2669 4515 2642 4515 2646 4516 2644 4516 2675 4516 2640 4517 2668 4517 2669 4517 2646 10 2675 10 2677 10 2646 4518 2677 4518 2678 4518 2640 4519 2667 4519 2668 4519 2638 4520 2667 4520 2640 4520 2622 4521 2646 4521 2678 4521 2638 10 2666 10 2667 10 2622 10 2678 10 2682 10 2622 10 2682 10 2684 10 2636 10 2666 10 2638 10 2625 10 2622 10 2684 10 2665 10 2666 10 2636 10 2687 4522 2625 4522 2684 4522 2687 4523 2626 4523 2625 4523 2664 10 2665 10 2636 10 2664 4524 2636 4524 2634 4524 2663 10 2664 10 2634 10 2657 10 2626 10 2687 10 2663 10 2634 10 2632 10 2662 4525 2663 4525 2632 4525 2657 4526 2629 4526 2626 4526 2658 4527 2629 4527 2657 4527 2661 4528 2662 4528 2632 4528 2659 4529 2629 4529 2658 4529 2661 4530 2632 4530 2631 4530 2660 10 2661 10 2631 10 2659 4531 2631 4531 2629 4531 2660 10 2631 10 2659 10 2707 4532 2816 4532 2709 4532 2816 4533 2707 4533 2817 4533 2817 4534 2819 4534 2818 4534 2817 4535 2707 4535 2819 4535 2706 4536 2819 4536 2707 4536 2819 4537 2820 4537 2818 4537 2706 4538 2704 4538 2819 4538 2819 4539 2704 4539 2820 4539 2818 4540 2820 4540 2821 4540 2820 4541 2704 4541 2821 4541 2704 4542 2822 4542 2821 4542 2702 4543 2822 4543 2704 4543 2822 4544 2823 4544 2821 4544 2822 4545 2702 4545 2823 4545 2823 4546 2825 4546 2824 4546 2702 4547 2825 4547 2823 4547 2542 4548 2825 4548 2702 4548 2824 4549 2553 4549 2823 4549 2553 4550 2826 4550 2823 4550 2823 4551 2826 4551 2821 4551 2826 4552 2827 4552 2821 4552 2821 4553 2827 4553 2818 4553 2818 4554 2828 4554 2817 4554 2827 4555 2828 4555 2818 4555 2817 4556 2828 4556 2816 4556 2816 4557 2708 4557 2709 4557 2828 4558 2708 4558 2816 4558 2555 4559 2749 4559 2738 4559 2829 4560 2555 4560 2738 4560 2829 4561 2738 4561 2731 4561 2829 4562 2731 4562 2727 4562 2830 4563 2829 4563 2727 4563 2830 4564 2727 4564 2720 4564 2831 4565 2830 4565 2720 4565 2831 4566 2720 4566 2715 4566 2831 4567 2715 4567 2714 4567 2832 4568 2714 4568 2713 4568 2832 4569 2831 4569 2714 4569 2832 4570 2713 4570 2711 4570 2833 4571 2711 4571 2710 4571 2833 4572 2832 4572 2711 4572 2546 3584 2548 3584 2834 3584 2198 4573 2801 4573 2799 4573 2198 4574 2799 4574 2795 4574 2200 4575 2198 4575 2795 4575 2200 4576 2795 4576 2790 4576 2201 4577 2200 4577 2790 4577 2201 4578 2790 4578 2779 4578 2202 4579 2201 4579 2779 4579 2202 4580 2779 4580 2774 4580 2202 4581 2774 4581 2768 4581 2203 4582 2202 4582 2768 4582 2203 4583 2768 4583 2764 4583 2204 4584 2203 4584 2764 4584 2204 4585 2764 4585 2656 4585 2185 4586 2184 4586 2815 4586 2815 4587 2184 4587 2813 4587 2184 4588 2187 4588 2813 4588 2813 4589 2187 4589 2811 4589 2811 4590 2187 4590 2809 4590 2187 4591 2188 4591 2809 4591 2809 4592 2188 4592 2807 4592 2807 4593 2189 4593 2805 4593 2188 4594 2189 4594 2807 4594 2805 4595 2189 4595 2544 4595 2189 4596 2190 4596 2544 4596 2546 4597 2834 4597 2835 4597 2546 4598 2835 4598 2836 4598 2545 4599 2546 4599 2836 4599 2550 4600 2547 4600 2552 4600 2550 4601 2551 4601 2547 4601 2554 4602 2547 4602 2551 4602 2554 4603 2549 4603 2547 4603 2198 4604 2208 4604 2801 4604 2208 4605 2885 4605 2801 4605 2199 4606 2245 4606 2210 4606 2199 4607 2210 4607 2192 4607 2245 4608 2199 4608 2185 4608 2815 4609 2245 4609 2185 4609 2837 4610 2213 4610 2245 4610 2837 4611 2245 4611 2815 4611 2482 4612 2495 4612 2522 4612 2495 4613 2838 4613 2522 4613 2455 4614 2457 4614 2474 4614 2474 4615 2457 4615 2670 4615 2457 4616 2458 4616 2670 4616 2838 4617 2839 4617 2522 4617 2522 4618 2839 4618 2520 4618 2458 4619 2460 4619 2670 4619 2839 4620 2840 4620 2520 4620 2520 4621 2840 4621 2518 4621 2670 4622 2460 4622 2673 4622 2512 4623 2514 4623 2466 4623 2460 4624 2463 4624 2673 4624 2840 4625 2841 4625 2518 4625 2673 4626 2463 4626 2674 4626 2514 4627 2516 4627 2464 4627 2464 4628 2516 4628 2463 4628 2463 4629 2516 4629 2674 4629 2518 4630 2841 4630 2516 4630 2516 4631 2841 4631 2674 4631 2674 4632 2841 4632 2676 4632 2841 4633 2842 4633 2676 4633 2679 4634 2814 4634 2680 4634 2676 4635 2842 4635 2679 4635 2842 4636 2843 4636 2679 4636 2679 4637 2972 4637 2814 4637 2843 4638 2972 4638 2679 4638 2814 4639 2972 4639 2815 4639 2972 4640 2837 4640 2815 4640 2506 4641 2510 4641 2469 4641 2510 4642 2512 4642 2468 4642 2464 4643 2466 4643 2514 4643 2466 4644 2468 4644 2512 4644 2468 4645 2469 4645 2510 4645 2469 4646 2471 4646 2506 4646 2845 4647 2844 4647 2647 4647 2845 4648 2647 4648 2780 4648 3015 4649 2845 4649 2780 4649 3015 4650 2780 4650 2788 4650 2846 4651 3015 4651 2788 4651 2846 4652 2788 4652 2789 4652 2995 4653 2846 4653 2789 4653 2995 4654 2789 4654 2794 4654 2995 4655 2794 4655 2798 4655 2990 4656 2995 4656 2798 4656 2985 4657 2798 4657 2802 4657 2985 4658 2990 4658 2798 4658 2984 4659 2985 4659 2802 4659 2984 4660 2802 4660 2800 4660 2885 4661 2984 4661 2800 4661 2885 4662 2800 4662 2801 4662 2166 4663 2647 4663 2169 4663 2171 4664 2169 4664 2647 4664 2164 4665 2647 4665 2166 4665 2173 4666 2171 4666 2647 4666 2163 4667 2647 4667 2164 4667 2161 4668 2647 4668 2163 4668 2158 4669 2647 4669 2161 4669 2762 4670 2647 4670 2158 4670 2762 4671 2158 4671 2156 4671 2762 4672 2156 4672 2154 4672 2844 4673 2182 4673 2179 4673 2844 4674 2179 4674 2177 4674 2844 4675 2148 4675 2147 4675 2844 4676 2147 4676 2144 4676 2844 4677 2177 4677 2175 4677 2844 4678 2175 4678 2173 4678 2844 4679 2144 4679 2182 4679 2962 4680 2152 4680 2150 4680 2962 4681 2150 4681 2148 4681 2962 4682 2762 4682 2154 4682 2962 4683 2148 4683 2844 4683 2962 4684 2154 4684 2152 4684 2647 4685 2844 4685 2173 4685 2847 10 2833 10 2848 10 2548 4686 2555 4686 2834 4686 2835 10 2831 10 2832 10 2829 10 2830 10 2835 10 2830 4687 2831 4687 2835 4687 2835 10 2834 10 2829 10 2829 10 2834 10 2555 10 2847 4688 2835 4688 2832 4688 2847 4689 2832 4689 2833 4689 2849 10 2850 10 2851 10 2849 10 2852 10 2850 10 2853 4690 2854 4690 2855 4690 2854 4691 2856 4691 2857 4691 2857 10 2856 10 2858 10 2858 4692 2856 4692 2859 4692 2853 10 2856 10 2854 10 2856 10 2860 10 2859 10 2856 10 2861 10 2860 10 2856 4693 2862 4693 2861 4693 2862 10 2863 10 2861 10 2835 4694 2847 4694 2864 4694 2836 4695 2835 4695 2864 4695 2864 2687 2865 2687 2866 2687 2848 2687 2865 2687 2864 2687 2847 2687 2848 2687 2864 2687 2867 4696 2862 4696 2856 4696 2867 4697 2856 4697 2868 4697 2869 4698 2868 4698 2856 4698 2853 4699 2869 4699 2856 4699 2710 4700 2865 4700 2833 4700 2865 4701 2848 4701 2833 4701 2865 4702 2950 4702 2870 4702 2870 4703 2861 4703 2863 4703 2950 4704 2861 4704 2870 4704 2710 4705 2950 4705 2865 4705 2869 3584 2871 3584 2872 3584 2855 3584 2871 3584 2869 3584 2853 3584 2855 3584 2869 3584 2873 4706 2849 4706 2851 4706 2875 4707 2874 4707 2873 4707 2875 4708 2873 4708 2851 4708 2850 2687 2876 2687 2851 2687 2851 2687 2876 2687 2875 2687 2855 4709 2854 4709 2871 4709 2871 4710 2877 4710 2876 4710 2854 4711 2877 4711 2871 4711 2877 4712 2875 4712 2876 4712 2207 4713 2878 4713 2879 4713 2207 4714 2879 4714 2996 4714 2195 4715 2207 4715 2996 4715 2195 4716 2996 4716 2880 4716 2194 4717 2195 4717 2880 4717 2194 4718 2880 4718 2881 4718 2193 4719 2194 4719 2881 4719 2193 4720 2881 4720 2882 4720 2193 4721 2882 4721 2883 4721 2191 4722 2193 4722 2883 4722 2191 4723 2883 4723 2884 4723 2208 4724 2191 4724 2884 4724 2208 4725 2884 4725 2885 4725 2888 4726 2889 4726 2887 4726 2887 4727 2890 4727 2886 4727 2889 4728 2890 4728 2887 4728 2891 4729 2889 4729 2888 4729 2891 4730 2888 4730 2887 4730 2891 4731 2887 4731 2886 4731 2890 4732 2891 4732 2886 4732 2866 10 2865 10 2870 10 2866 10 2870 10 2892 10 2867 2581 2892 2581 2870 2581 2863 4733 2862 4733 2867 4733 2863 2581 2867 2581 2870 2581 2604 10 2894 10 2893 10 2606 4734 2893 4734 2895 4734 2606 4735 2604 4735 2893 4735 2603 4736 2894 4736 2604 4736 2603 4737 2896 4737 2894 4737 2606 4738 2895 4738 2897 4738 2601 4739 2896 4739 2603 4739 2606 10 2897 10 2898 10 2601 4740 2890 4740 2896 4740 2583 10 2606 10 2898 10 2583 10 2898 10 2899 10 2598 4741 2890 4741 2601 4741 2586 10 2583 10 2899 10 2598 4742 2891 4742 2890 4742 2868 10 2896 10 2890 10 2900 10 2586 10 2899 10 2889 10 2868 10 2890 10 2587 10 2586 10 2900 10 2889 4743 2891 4743 2598 4743 2589 10 2587 10 2900 10 2889 4744 2598 4744 2596 4744 2901 10 2889 10 2596 10 2901 4745 2596 4745 2594 4745 2901 10 2594 10 2592 10 2902 4746 2901 4746 2592 4746 2902 10 2589 10 2900 10 2902 4747 2592 4747 2590 4747 2902 4748 2590 4748 2589 4748 2867 10 2868 10 2901 10 2901 4749 2868 4749 2889 4749 2868 10 2869 10 2896 10 2906 10 2904 10 2903 10 2906 10 2905 10 2904 10 2907 10 2906 10 2903 10 2900 4750 2907 4750 2903 4750 2902 4751 2900 4751 2903 4751 2866 4752 2433 4752 2689 4752 2864 4753 2866 4753 2689 4753 2892 4754 2432 4754 2866 4754 2901 4755 2892 4755 2867 4755 2901 4756 2432 4756 2892 4756 2432 4757 2433 4757 2866 4757 2578 10 2694 10 2695 10 2578 4758 2693 4758 2694 4758 2580 4759 2578 4759 2695 4759 2577 4760 2693 4760 2578 4760 2582 10 2695 10 2696 10 2582 10 2580 10 2695 10 2577 10 2692 10 2693 10 2575 10 2692 10 2577 10 2582 10 2696 10 2697 10 2575 4761 2691 4761 2692 4761 2573 10 2691 10 2575 10 2557 10 2697 10 2698 10 2557 4762 2582 4762 2697 4762 2573 4763 2690 4763 2691 4763 2571 10 2690 10 2573 10 2559 10 2557 10 2698 10 2699 10 2559 10 2698 10 2690 4764 2571 4764 2569 4764 2689 10 2690 10 2569 10 2699 4765 2561 4765 2559 4765 2689 4766 2569 4766 2567 4766 2700 10 2561 10 2699 10 2701 10 2561 10 2700 10 2701 4767 2563 4767 2561 4767 2708 10 2689 10 2567 10 2703 10 2563 10 2701 10 2705 10 2708 10 2567 10 2703 10 2565 10 2563 10 2705 10 2567 10 2565 10 2705 10 2565 10 2703 10 2836 10 2826 10 2553 10 2836 4768 2827 4768 2826 4768 2836 4769 2828 4769 2827 4769 2836 4770 2708 4770 2828 4770 2545 10 2836 10 2553 10 2836 10 2864 10 2689 10 2836 10 2689 10 2708 10 2861 4771 2950 4771 2908 4771 2861 4772 2908 4772 2909 4772 2860 4773 2861 4773 2909 4773 2860 4774 2909 4774 2910 4774 2859 4775 2860 4775 2910 4775 2859 4776 2910 4776 2911 4776 2858 4777 2859 4777 2911 4777 2858 4778 2911 4778 2912 4778 2857 4779 2858 4779 2912 4779 2857 4780 2912 4780 2913 4780 2854 4781 2913 4781 2914 4781 2854 4782 2857 4782 2913 4782 2854 4783 2914 4783 2877 4783 2872 10 2871 10 2876 10 2872 10 2876 10 2915 10 2916 4784 2915 4784 2876 4784 2850 4785 2852 4785 2916 4785 2850 4786 2916 4786 2876 4786 2873 4787 2916 4787 2852 4787 2849 4788 2873 4788 2852 4788 2915 4789 2916 4789 2873 4789 2915 4790 2873 4790 2874 4790 2896 4791 2869 4791 2872 4791 2917 4792 2872 4792 2915 4792 2917 4793 2896 4793 2872 4793 2874 4794 2917 4794 2915 4794 2894 4795 2917 4795 2918 4795 2894 4796 2896 4796 2917 4796 2893 4797 2894 4797 2918 4797 2893 4798 2918 4798 2919 4798 2893 4799 2919 4799 2920 4799 2895 4800 2893 4800 2920 4800 2895 4801 2920 4801 2921 4801 2897 4802 2895 4802 2921 4802 2897 4803 2921 4803 2504 4803 2898 4804 2897 4804 2504 4804 2898 4805 2504 4805 2500 4805 2899 4806 2898 4806 2500 4806 2899 4807 2500 4807 2499 4807 2900 4808 2899 4808 2499 4808 2900 4809 2499 4809 2907 4809 2907 4810 2499 4810 2501 4810 2906 4811 2907 4811 2501 4811 2906 4812 2501 4812 2502 4812 2905 4813 2906 4813 2502 4813 2905 4814 2502 4814 2422 4814 2904 4815 2905 4815 2422 4815 2904 4816 2422 4816 2424 4816 2904 4817 2424 4817 2426 4817 2903 4818 2904 4818 2426 4818 2903 4819 2426 4819 2428 4819 2902 4820 2903 4820 2428 4820 2901 4821 2902 4821 2428 4821 2901 4822 2428 4822 2430 4822 2901 4823 2430 4823 2432 4823 2759 4824 2962 4824 2963 4824 2759 4825 2762 4825 2962 4825 2748 4826 2963 4826 2922 4826 2748 4827 2759 4827 2963 4827 2741 4828 2748 4828 2922 4828 2741 4829 2922 4829 2961 4829 2734 4830 2961 4830 2960 4830 2734 4831 2741 4831 2961 4831 2729 4832 2960 4832 2957 4832 2729 4833 2734 4833 2960 4833 2722 4834 2957 4834 2954 4834 2722 4835 2729 4835 2957 4835 2718 4836 2954 4836 2952 4836 2718 4837 2722 4837 2954 4837 2712 4838 2952 4838 2949 4838 2712 4839 2718 4839 2952 4839 2712 4840 2949 4840 2950 4840 2710 4841 2712 4841 2950 4841 2924 4842 2914 4842 2913 4842 2914 4843 2923 4843 2877 4843 2925 4844 2923 4844 2914 4844 2926 4845 2914 4845 2924 4845 2924 4846 2913 4846 2912 4846 2926 4847 2925 4847 2914 4847 2927 4848 2912 4848 2911 4848 2928 4849 2926 4849 2924 4849 2929 4850 2924 4850 2912 4850 2928 4851 2924 4851 2929 4851 2930 4852 2925 4852 2926 4852 2931 4853 2929 4853 2912 4853 2931 4854 2912 4854 2927 4854 2927 4855 2911 4855 2910 4855 2932 4856 2926 4856 2928 4856 2930 4857 2926 4857 2932 4857 2931 4858 2927 4858 2910 4858 2932 4859 2928 4859 2929 4859 2934 4860 2931 4860 2910 4860 2935 4861 2929 4861 2931 4861 2935 4862 2932 4862 2929 4862 2934 4863 2910 4863 2909 4863 2933 4864 2930 4864 2932 4864 2937 4865 2935 4865 2931 4865 2936 4866 2933 4866 2932 4866 2937 4867 2931 4867 2934 4867 2938 4868 2936 4868 2932 4868 2938 4869 2932 4869 2935 4869 2939 4870 2933 4870 2936 4870 2941 4871 2934 4871 2909 4871 2940 4872 2937 4872 2934 4872 2940 4873 2934 4873 2941 4873 2942 4874 2938 4874 2935 4874 2941 4875 2909 4875 2908 4875 2945 4876 2935 4876 2937 4876 2946 4877 2939 4877 2936 4877 2944 4878 2937 4878 2940 4878 2942 4879 2935 4879 2945 4879 2947 4880 2940 4880 2941 4880 2945 4881 2937 4881 2944 4881 2946 4882 2936 4882 2938 4882 2943 4883 2939 4883 2946 4883 2948 4884 2946 4884 2938 4884 2949 4885 2941 4885 2908 4885 2944 4886 2940 4886 2947 4886 2949 4887 2947 4887 2941 4887 2942 4888 2948 4888 2938 4888 2949 4889 2908 4889 2950 4889 2951 4890 2942 4890 2945 4890 2948 4891 2943 4891 2946 4891 2952 4892 2947 4892 2949 4892 2953 4893 2945 4893 2944 4893 2954 4894 2944 4894 2947 4894 2951 4895 2945 4895 2953 4895 2954 4896 2953 4896 2944 4896 2955 4897 2942 4897 2951 4897 2954 4898 2947 4898 2952 4898 2955 4899 2948 4899 2942 4899 2956 4900 2943 4900 2948 4900 2957 4901 2953 4901 2954 4901 2958 4902 2948 4902 2955 4902 2959 4903 2948 4903 2958 4903 2959 4904 2956 4904 2948 4904 2957 4905 2951 4905 2953 4905 2960 4906 2951 4906 2957 4906 2960 4907 2955 4907 2951 4907 2961 4908 2955 4908 2960 4908 2961 4909 2958 4909 2955 4909 2962 4910 2956 4910 2959 4910 2959 4911 2958 4911 2961 4911 2922 4912 2959 4912 2961 4912 2963 4913 2962 4913 2959 4913 2963 4914 2959 4914 2922 4914 2504 4915 2921 4915 2505 4915 2505 4916 2921 4916 2964 4916 2921 4917 2920 4917 2964 4917 2964 4918 2920 4918 2965 4918 2920 4919 2919 4919 2965 4919 2965 4920 2919 4920 2966 4920 2919 4921 2918 4921 2966 4921 2966 4922 2918 4922 2967 4922 2918 4923 2917 4923 2967 4923 2967 4924 2917 4924 2968 4924 2968 4925 2874 4925 2969 4925 2968 4926 2917 4926 2874 4926 2837 4927 2972 4927 2970 4927 2970 4928 2972 4928 2973 4928 2975 4929 2972 4929 2843 4929 2970 4930 2973 4930 2971 4930 2972 4931 2975 4931 2973 4931 2971 4932 2973 4932 2974 4932 2973 4933 2975 4933 2977 4933 2973 4934 2977 4934 2974 4934 2974 4935 2977 4935 2976 4935 2977 4936 2980 4936 2976 4936 2976 4937 2980 4937 2978 4937 2978 4938 2980 4938 2979 4938 2980 4939 2981 4939 2979 4939 2982 4940 2979 4940 2981 4940 2984 4941 2885 4941 2884 4941 2983 4942 2884 4942 2883 4942 2984 4943 2884 4943 2983 4943 2983 4944 2883 4944 2882 4944 2986 4945 2984 4945 2983 4945 2987 4946 2983 4946 2882 4946 2985 4947 2984 4947 2986 4947 2988 4948 2882 4948 2881 4948 2987 4949 2882 4949 2988 4949 2989 4950 2983 4950 2987 4950 2991 4951 2985 4951 2986 4951 2989 4952 2986 4952 2983 4952 2990 4953 2985 4953 2991 4953 2992 4954 2987 4954 2988 4954 2992 4955 2989 4955 2987 4955 2880 4956 2988 4956 2881 4956 2993 4957 2992 4957 2988 4957 2989 4958 2991 4958 2986 4958 2994 4959 2988 4959 2880 4959 2993 4960 2988 4960 2994 4960 2995 4961 2990 4961 2991 4961 2997 4962 2991 4962 2989 4962 2998 4963 2989 4963 2992 4963 2996 4964 2994 4964 2880 4964 2999 4965 2995 4965 2991 4965 2997 4966 2989 4966 2998 4966 3000 4967 2992 4967 2993 4967 2999 4968 2991 4968 2997 4968 3000 4969 2998 4969 2992 4969 3000 4970 2993 4970 2994 4970 3001 4971 2994 4971 2996 4971 3002 4972 2995 4972 2999 4972 3003 4973 3000 4973 2994 4973 3004 4974 2997 4974 2998 4974 3005 4975 2999 4975 2997 4975 3006 4976 2996 4976 2879 4976 3003 4977 2994 4977 3001 4977 2846 4978 2995 4978 3002 4978 3004 4979 2998 4979 3000 4979 3001 4980 2996 4980 3006 4980 3005 4981 3002 4981 2999 4981 3005 4982 2997 4982 3004 4982 3007 4983 3000 4983 3003 4983 2878 4984 3006 4984 2879 4984 3008 4985 3001 4985 3006 4985 3007 4986 3004 4986 3000 4986 3009 4987 2846 4987 3002 4987 3008 4988 3003 4988 3001 4988 3010 4989 3002 4989 3005 4989 3011 4990 3005 4990 3004 4990 3012 4991 3004 4991 3007 4991 3013 4992 3008 4992 3006 4992 3013 4993 3006 4993 2878 4993 3009 4994 3015 4994 2846 4994 3012 4995 3011 4995 3004 4995 3009 4996 3002 4996 3010 4996 3010 4997 3005 4997 3011 4997 3008 4998 3007 4998 3003 4998 3016 4999 3007 4999 3008 4999 3016 5000 3008 5000 3013 5000 3012 5001 3007 5001 3014 5001 3017 5002 3009 5002 3010 5002 3014 5003 3007 5003 3016 5003 3018 5004 3010 5004 3011 5004 3018 5005 3011 5005 3012 5005 3018 5006 3017 5006 3010 5006 3017 5007 3015 5007 3009 5007 3019 5008 3012 5008 3014 5008 3019 5009 3018 5009 3012 5009 2845 5010 3015 5010 3017 5010 3020 5011 3018 5011 3019 5011 3021 5012 2845 5012 3017 5012 3017 5013 3018 5013 3020 5013 3022 5014 3017 5014 3020 5014 2844 5015 2845 5015 3021 5015 3021 5016 3017 5016 3022 5016 2962 5017 2844 5017 3021 5017 2956 5018 2962 5018 3021 5018 2956 5019 3021 5019 3022 5019 2943 5020 2956 5020 3022 5020 2943 5021 3022 5021 3020 5021 2939 5022 3020 5022 3019 5022 2939 5023 2943 5023 3020 5023 2933 5024 3019 5024 3014 5024 2933 5025 2939 5025 3019 5025 2930 5026 3014 5026 3016 5026 2930 5027 2933 5027 3014 5027 2925 5028 2930 5028 3016 5028 2925 5029 3016 5029 3013 5029 2923 5030 2925 5030 3013 5030 2923 5031 3013 5031 2878 5031 2877 5032 2923 5032 2878 5032 2875 5033 2878 5033 3023 5033 2877 5034 2878 5034 2875 5034 3023 10 2969 10 2874 10 3023 10 2874 10 2875 10 2982 5035 2214 5035 2979 5035 2214 5036 2212 5036 2979 5036 2979 5037 2212 5037 2978 5037 2212 5038 2209 5038 2978 5038 2978 5039 2209 5039 2976 5039 2976 5040 2209 5040 2974 5040 2209 5041 2211 5041 2974 5041 2974 5042 2211 5042 2971 5042 2971 5043 2211 5043 2970 5043 2211 5044 2213 5044 2970 5044 2970 5045 2213 5045 2837 5045 2969 5046 2246 5046 2223 5046 2969 5047 2223 5047 2968 5047 2218 5048 2214 5048 2982 5048 2218 5049 2982 5049 2981 5049 2218 5050 2981 5050 2980 5050 2216 5051 2218 5051 2980 5051 2216 5052 2980 5052 2977 5052 2219 5053 2216 5053 2977 5053 2219 5054 2977 5054 2975 5054 2222 5055 2975 5055 2843 5055 2222 5056 2219 5056 2975 5056 2224 5057 2843 5057 2842 5057 2224 5058 2222 5058 2843 5058 2224 5059 2842 5059 2841 5059 2226 5060 2224 5060 2841 5060 2229 5061 2226 5061 2841 5061 2229 5062 2841 5062 2840 5062 2229 5063 2840 5063 2839 5063 2233 5064 2229 5064 2839 5064 2233 5065 2839 5065 2838 5065 2233 5066 2838 5066 2495 5066 2236 5067 2233 5067 2495 5067 2236 5068 2495 5068 2496 5068 2240 5069 2236 5069 2496 5069 2240 5070 2496 5070 2497 5070 2244 5071 2240 5071 2497 5071 2244 5072 2497 5072 2498 5072 2242 5073 2244 5073 2498 5073 2242 5074 2498 5074 2503 5074 2239 5075 2242 5075 2503 5075 2235 5076 2239 5076 2503 5076 2235 5077 2503 5077 2505 5077 2235 5078 2505 5078 2964 5078 2231 5079 2235 5079 2964 5079 2231 5080 2964 5080 2965 5080 2231 5081 2965 5081 2966 5081 2228 5082 2231 5082 2966 5082 2228 5083 2966 5083 2967 5083 2223 5084 2228 5084 2967 5084 2223 5085 2967 5085 2968 5085 2207 5086 3023 5086 2878 5086 2197 5087 3023 5087 2207 5087 2246 5088 2197 5088 2196 5088 3023 5089 2197 5089 2246 5089 2969 5090 3023 5090 2246 5090 2192 5091 2210 5091 2246 5091 2192 5092 2246 5092 2196 5092

+
+ + + +

3026 5093 3024 5093 3025 5093 3026 5094 3025 5094 3027 5094 3026 5095 3027 5095 3028 5095 3029 5096 3026 5096 3028 5096 3029 5097 3028 5097 3030 5097 3031 5098 3029 5098 3030 5098 3031 5099 3030 5099 3032 5099 3033 5100 3031 5100 3032 5100 3033 5101 3032 5101 3034 5101 3025 5102 3044 5102 3035 5102 3025 5103 3024 5103 3044 5103 3037 5104 3038 5104 3036 5104 3036 272 3039 272 3037 272 3040 272 3041 272 3037 272 3037 5105 3041 5105 3038 5105 3042 5106 3041 5106 3040 5106 3037 5107 3039 5107 3576 5107 3039 5108 3043 5108 3576 5108 3044 5109 3041 5109 3042 5109 3044 5110 3045 5110 3041 5110 3043 5111 3046 5111 3576 5111 3024 272 3045 272 3044 272 3024 5112 3047 5112 3045 5112 3026 272 3047 272 3024 272 3046 5113 3048 5113 3576 5113 3029 272 3049 272 3026 272 3026 5114 3049 5114 3047 5114 3048 5115 3050 5115 3576 5115 3029 5116 3051 5116 3049 5116 3050 5117 3052 5117 3576 5117 3029 272 3031 272 3051 272 3052 5118 3053 5118 3576 5118 3031 5119 3033 5119 3051 5119 3051 272 3033 272 3054 272 3033 272 3055 272 3054 272 3054 272 3055 272 3056 272 3055 272 3057 272 3056 272 3056 272 3057 272 3058 272 3058 5120 3057 5120 3059 5120 3057 272 3060 272 3059 272 3059 272 3060 272 3061 272 3060 5121 3080 5121 3061 5121 3062 5122 3063 5122 3064 5122 3062 5123 3065 5123 3063 5123 3066 5124 3065 5124 3062 5124 3063 5125 3067 5125 3064 5125 3064 272 3067 272 3068 272 3069 272 3065 272 3066 272 3069 5126 3070 5126 3065 5126 3071 272 3070 272 3069 272 3068 272 3067 272 3072 272 3067 5127 3073 5127 3072 5127 3076 272 3070 272 3071 272 3072 272 3073 272 3074 272 3076 5128 3075 5128 3070 5128 3073 272 3077 272 3074 272 3078 5129 3075 5129 3076 5129 3079 272 3075 272 3078 272 3074 272 3077 272 3080 272 3079 272 3081 272 3075 272 3077 5130 3082 5130 3080 5130 3083 272 3081 272 3079 272 3083 5131 3084 5131 3081 5131 3082 272 3085 272 3080 272 3083 272 3086 272 3084 272 3084 5132 3086 5132 3087 5132 3085 5133 3088 5133 3080 5133 3080 5134 3088 5134 3061 5134 3086 5135 3089 5135 3087 5135 3087 272 3090 272 3091 272 3089 272 3090 272 3087 272 3090 5136 3092 5136 3091 5136 3094 272 3092 272 3093 272 3091 5137 3092 5137 3094 5137 3092 5138 3270 5138 3093 5138 3096 5139 3270 5139 3095 5139 3097 5140 3270 5140 3096 5140 3098 5141 3270 5141 3097 5141 3093 5142 3270 5142 3098 5142 3270 5143 3576 5143 3099 5143 3270 5144 3099 5144 3061 5144 3270 5145 3061 5145 3095 5145 3099 5146 3576 5146 3053 5146 3095 5147 3061 5147 3088 5147 3100 5148 3071 5148 3069 5148 3101 5149 3100 5149 3069 5149 3101 5150 3069 5150 3066 5150 3102 5151 3101 5151 3066 5151 3102 5152 3066 5152 3062 5152 3103 5153 3102 5153 3062 5153 3103 5154 3062 5154 3064 5154 3104 5155 3103 5155 3064 5155 3108 5156 3104 5156 3064 5156 3108 5157 3064 5157 3068 5157 3105 5158 3106 5158 3080 5158 3080 5159 3106 5159 3074 5159 3106 5160 3107 5160 3074 5160 3074 5161 3107 5161 3072 5161 3107 5162 3108 5162 3072 5162 3072 5163 3108 5163 3068 5163 3033 5164 3109 5164 3055 5164 3034 5165 3109 5165 3033 5165 3109 5166 3110 5166 3055 5166 3055 5167 3110 5167 3057 5167 3110 5168 3111 5168 3057 5168 3111 5169 3112 5169 3057 5169 3057 5170 3112 5170 3060 5170 3060 5171 3112 5171 3105 5171 3060 5172 3105 5172 3080 5172 3114 5173 3115 5173 3113 5173 3113 5174 3116 5174 3114 5174 3114 5175 3117 5175 3115 5175 3116 5176 3118 5176 3114 5176 3119 5177 3117 5177 3114 5177 3119 5178 3120 5178 3117 5178 3118 5179 3121 5179 3114 5179 3119 10 3122 10 3120 10 3123 5180 3122 5180 3119 5180 3123 5181 3124 5181 3122 5181 3125 5182 3124 5182 3123 5182 3125 5183 3126 5183 3124 5183 3127 10 3126 10 3125 10 3127 10 3128 10 3126 10 3128 5184 3129 5184 3126 5184 3128 10 3130 10 3129 10 3129 10 3130 10 3131 10 3130 10 3132 10 3131 10 3132 10 3133 10 3131 10 3131 10 3133 10 3134 10 3134 10 3133 10 3135 10 3135 10 3100 10 3136 10 3133 10 3100 10 3135 10 3136 10 3100 10 3137 10 3100 10 3101 10 3137 10 3137 10 3101 10 3138 10 3101 10 3102 10 3138 10 3108 10 3107 10 3139 10 3140 10 3108 10 3139 10 3139 5185 3107 5185 3141 5185 3102 10 3103 10 3138 10 3142 10 3104 10 3140 10 3140 5186 3104 5186 3108 5186 3138 5187 3103 5187 3142 5187 3103 5188 3104 5188 3142 5188 3107 5189 3106 5189 3141 5189 3141 5190 3106 5190 3143 5190 3143 10 3106 10 3144 10 3106 10 3105 10 3144 10 3144 10 3105 10 3146 10 3146 10 3105 10 3145 10 3105 10 3112 10 3145 10 3112 5191 3147 5191 3145 5191 3145 5192 3147 5192 3148 5192 3112 10 3149 10 3147 10 3147 5193 3150 5193 3148 5193 3148 10 3150 10 3151 10 3112 5194 3152 5194 3149 5194 3150 10 3153 10 3151 10 3111 10 3154 10 3112 10 3112 10 3154 10 3152 10 3151 5195 3153 5195 3155 5195 3153 5196 3156 5196 3155 5196 3111 10 3157 10 3154 10 3155 5197 3156 5197 3121 5197 3110 10 3157 10 3111 10 3109 5198 3157 5198 3110 5198 3109 10 3158 10 3157 10 3034 10 3158 10 3109 10 3034 10 3159 10 3158 10 3032 5199 3159 5199 3034 5199 3030 5200 3160 5200 3032 5200 3032 10 3160 10 3159 10 3030 10 3028 10 3160 10 3160 5201 3028 5201 3161 5201 3028 10 3027 10 3161 10 3161 10 3025 10 3162 10 3027 5202 3025 5202 3161 5202 3162 5203 3025 5203 3163 5203 3025 5204 3035 5204 3163 5204 3163 10 3035 10 3164 10 3035 10 3165 10 3164 10 3164 10 3165 10 3166 10 3167 5205 3575 5205 3156 5205 3168 5206 3575 5206 3167 5206 3169 5207 3575 5207 3168 5207 3170 5208 3575 5208 3169 5208 3171 5209 3575 5209 3170 5209 3172 5210 3575 5210 3171 5210 3173 5211 3575 5211 3172 5211 3174 5212 3575 5212 3173 5212 3175 5213 3575 5213 3174 5213 3165 10 3176 10 3166 10 3166 10 3176 10 3177 10 3176 10 3178 10 3177 10 3175 5214 3178 5214 3575 5214 3179 10 3178 10 3175 10 3177 10 3178 10 3179 10 3575 5215 3114 5215 3156 5215 3156 5216 3114 5216 3121 5216 3121 5217 3118 5217 3180 5217 3180 5218 3118 5218 3181 5218 3181 5219 3118 5219 3182 5219 3118 5220 3116 5220 3182 5220 3182 5221 3116 5221 3183 5221 3116 5222 3113 5222 3183 5222 3183 5223 3113 5223 3184 5223 3113 5224 3115 5224 3184 5224 3184 5225 3115 5225 3185 5225 3115 5226 3117 5226 3185 5226 3185 5227 3117 5227 3186 5227 3117 5228 3120 5228 3186 5228 3186 5229 3120 5229 3187 5229 3120 5230 3122 5230 3187 5230 3187 5231 3122 5231 3188 5231 3122 5232 3124 5232 3188 5232 3188 5233 3124 5233 3189 5233 3124 5234 3126 5234 3189 5234 3189 5235 3126 5235 3190 5235 3126 5236 3129 5236 3190 5236 3190 5237 3129 5237 3191 5237 3129 5238 3131 5238 3191 5238 3191 5239 3131 5239 3192 5239 3131 5240 3134 5240 3192 5240 3134 5241 3135 5241 3192 5241 3192 5242 3135 5242 3193 5242 3135 5243 3136 5243 3193 5243 3136 5244 3137 5244 3193 5244 3193 5245 3137 5245 3194 5245 3194 5246 3138 5246 3195 5246 3137 5247 3138 5247 3194 5247 3195 5248 3138 5248 3196 5248 3138 5249 3142 5249 3196 5249 3196 5250 3142 5250 3197 5250 3197 5251 3140 5251 3198 5251 3142 5252 3140 5252 3197 5252 3140 5253 3139 5253 3198 5253 3198 5254 3139 5254 3199 5254 3199 5255 3139 5255 3200 5255 3139 5256 3141 5256 3200 5256 3200 5257 3141 5257 3201 5257 3141 5258 3143 5258 3201 5258 3201 5259 3143 5259 3202 5259 3143 5260 3144 5260 3202 5260 3202 5261 3144 5261 3203 5261 3144 5262 3146 5262 3203 5262 3203 5263 3146 5263 3204 5263 3146 5264 3145 5264 3204 5264 3145 5265 3148 5265 3204 5265 3204 5266 3148 5266 3205 5266 3205 5267 3148 5267 3206 5267 3148 5268 3151 5268 3206 5268 3206 5269 3151 5269 3207 5269 3151 5270 3155 5270 3207 5270 3207 5271 3155 5271 3208 5271 3155 5272 3121 5272 3208 5272 3208 5273 3121 5273 3180 5273 3204 5274 3210 5274 3209 5274 3205 10 3210 10 3204 10 3204 10 3209 10 3203 10 3206 5275 3210 5275 3205 5275 3209 10 3211 10 3203 10 3206 5276 3212 5276 3210 5276 3207 10 3212 10 3206 10 3203 10 3211 10 3202 10 3211 10 3213 10 3202 10 3208 5277 3212 5277 3207 5277 3202 10 3213 10 3201 10 3208 5278 3214 5278 3212 5278 3180 10 3214 10 3208 10 3201 10 3213 10 3200 10 3180 5279 3215 5279 3214 5279 3200 10 3216 10 3199 10 3213 10 3216 10 3200 10 3181 5280 3215 5280 3180 5280 3181 5281 3217 5281 3215 5281 3199 10 3216 10 3198 10 3182 10 3217 10 3181 10 3198 10 3218 10 3197 10 3216 5282 3218 5282 3198 5282 3183 10 3217 10 3182 10 3197 10 3218 10 3196 10 3183 5283 3219 5283 3217 5283 3220 10 3196 10 3218 10 3183 5284 3184 5284 3219 5284 3219 5285 3184 5285 3221 5285 3220 5286 3195 5286 3196 5286 3222 10 3195 10 3220 10 3184 10 3185 10 3221 10 3222 5287 3194 5287 3195 5287 3221 10 3185 10 3223 10 3185 5288 3186 5288 3223 5288 3224 10 3194 10 3222 10 3224 5289 3193 5289 3194 5289 3186 5290 3187 5290 3223 5290 3225 10 3193 10 3224 10 3223 10 3187 10 3226 10 3225 5291 3192 5291 3193 5291 3227 10 3192 10 3225 10 3187 10 3188 10 3226 10 3226 10 3188 10 3228 10 3227 5292 3191 5292 3192 5292 3229 10 3191 10 3227 10 3188 5293 3189 5293 3228 5293 3228 10 3189 10 3230 10 3229 10 3190 10 3191 10 3189 10 3190 10 3230 10 3230 5294 3190 5294 3229 5294 3213 5295 3073 5295 3216 5295 3073 5296 3067 5296 3216 5296 3067 5297 3063 5297 3216 5297 3216 5298 3063 5298 3218 5298 3218 5299 3063 5299 3220 5299 3063 5300 3065 5300 3220 5300 3220 5301 3065 5301 3222 5301 3065 5302 3070 5302 3222 5302 3222 5303 3070 5303 3224 5303 3224 5304 3070 5304 3225 5304 3070 5305 3075 5305 3225 5305 3225 5306 3075 5306 3227 5306 3075 5307 3081 5307 3227 5307 3227 5308 3081 5308 3229 5308 3081 5309 3084 5309 3229 5309 3229 5310 3084 5310 3230 5310 3084 5311 3087 5311 3230 5311 3230 5312 3087 5312 3228 5312 3087 5313 3091 5313 3228 5313 3228 5314 3091 5314 3226 5314 3226 5315 3091 5315 3223 5315 3091 5316 3094 5316 3223 5316 3094 5317 3093 5317 3223 5317 3223 5318 3093 5318 3221 5318 3093 5319 3098 5319 3221 5319 3221 5320 3098 5320 3219 5320 3098 5321 3097 5321 3219 5321 3219 5322 3097 5322 3217 5322 3097 5323 3096 5323 3217 5323 3217 5324 3096 5324 3215 5324 3096 5325 3095 5325 3215 5325 3215 5326 3095 5326 3214 5326 3214 5327 3095 5327 3212 5327 3095 5328 3088 5328 3212 5328 3212 5329 3088 5329 3210 5329 3088 5330 3085 5330 3210 5330 3210 5331 3085 5331 3209 5331 3085 5332 3082 5332 3209 5332 3082 5333 3077 5333 3209 5333 3209 5334 3077 5334 3211 5334 3211 5335 3077 5335 3213 5335 3077 5336 3073 5336 3213 5336 3231 5337 3156 5337 3232 5337 3156 5338 3153 5338 3232 5338 3232 5339 3153 5339 3233 5339 3153 5340 3150 5340 3233 5340 3233 5341 3150 5341 3234 5341 3234 5342 3150 5342 3235 5342 3150 5343 3147 5343 3235 5343 3147 5344 3149 5344 3235 5344 3235 5345 3149 5345 3236 5345 3149 5346 3152 5346 3236 5346 3236 5347 3154 5347 3237 5347 3152 5348 3154 5348 3236 5348 3154 5349 3157 5349 3237 5349 3237 5350 3157 5350 3238 5350 3238 5351 3157 5351 3239 5351 3157 5352 3158 5352 3239 5352 3239 5353 3158 5353 3240 5353 3158 5354 3159 5354 3240 5354 3240 5355 3159 5355 3241 5355 3159 5356 3160 5356 3241 5356 3241 5357 3160 5357 3242 5357 3160 5358 3161 5358 3242 5358 3242 5359 3161 5359 3243 5359 3161 5360 3162 5360 3243 5360 3243 5361 3162 5361 3244 5361 3162 5362 3163 5362 3244 5362 3244 5363 3163 5363 3245 5363 3163 5364 3164 5364 3245 5364 3245 5365 3164 5365 3246 5365 3164 5366 3166 5366 3246 5366 3246 5367 3166 5367 3247 5367 3247 5368 3177 5368 3248 5368 3166 5369 3177 5369 3247 5369 3248 5370 3179 5370 3249 5370 3177 5371 3179 5371 3248 5371 3249 5372 3179 5372 3250 5372 3179 5373 3175 5373 3250 5373 3250 5374 3175 5374 3251 5374 3175 5375 3174 5375 3251 5375 3174 5376 3173 5376 3251 5376 3251 5377 3173 5377 3252 5377 3173 5378 3172 5378 3252 5378 3252 5379 3172 5379 3253 5379 3172 5380 3171 5380 3253 5380 3253 5381 3170 5381 3254 5381 3171 5382 3170 5382 3253 5382 3254 5383 3170 5383 3255 5383 3170 5384 3169 5384 3255 5384 3255 5385 3169 5385 3256 5385 3169 5386 3168 5386 3256 5386 3256 5387 3168 5387 3257 5387 3168 5388 3167 5388 3257 5388 3257 5389 3167 5389 3258 5389 3258 5390 3167 5390 3231 5390 3167 5391 3156 5391 3231 5391 3270 5392 3092 5392 3119 5392 3259 1402 3260 1402 3261 1402 3262 1402 3263 1402 3260 1402 3262 1402 3260 1402 3259 1402 3264 5393 3259 5393 3261 5393 3265 1402 3263 1402 3262 1402 3264 1402 3261 1402 3266 1402 3265 1402 3267 1402 3263 1402 3268 5394 3264 5394 3266 5394 3114 5395 3270 5395 3119 5395 3114 5396 3269 5396 3270 5396 3268 1402 3266 1402 3271 1402 3272 1402 3267 1402 3265 1402 3273 1402 3269 1402 3114 1402 3273 5397 3271 5397 3269 5397 3274 1402 3268 1402 3271 1402 3273 1402 3274 1402 3271 1402 3272 5398 3275 5398 3267 5398 3276 5399 3275 5399 3272 5399 3277 5400 3275 5400 3276 5400 3277 5401 3278 5401 3275 5401 3277 5402 3279 5402 3278 5402 3280 1402 3279 1402 3277 1402 3280 5403 3281 5403 3279 5403 3282 1402 3281 1402 3280 1402 3282 5404 3283 5404 3281 5404 3284 5405 3283 5405 3282 5405 3285 1402 3283 1402 3284 1402 3285 1402 3284 1402 3286 1402 3287 1402 3285 1402 3286 1402 3287 1402 3286 1402 3288 1402 3289 1402 3287 1402 3288 1402 3290 1402 3289 1402 3288 1402 3290 1402 3288 1402 3291 1402 3292 1402 3290 1402 3291 1402 3293 1402 3290 1402 3292 1402 3294 1402 3290 1402 3293 1402 3294 5406 3296 5406 3290 5406 3294 5407 3295 5407 3296 5407 3311 5408 3297 5408 3295 5408 3311 5409 3295 5409 3294 5409 3298 5410 3299 5410 3300 5410 3298 10 3301 10 3299 10 3302 10 3301 10 3298 10 3299 10 3303 10 3300 10 3300 10 3303 10 3304 10 3302 10 3305 10 3301 10 3306 10 3305 10 3302 10 3303 10 3307 10 3304 10 3306 10 3308 10 3305 10 3307 10 3309 10 3304 10 3304 5411 3309 5411 3310 5411 3311 10 3308 10 3306 10 3311 10 3312 10 3308 10 3309 10 3313 10 3310 10 3310 10 3313 10 3314 10 3311 10 3315 10 3312 10 3314 5412 3313 5412 3316 5412 3313 5413 3317 5413 3316 5413 3317 10 3318 10 3316 10 3311 5414 3294 5414 3315 5414 3319 5415 3294 5415 3320 5415 3315 5416 3294 5416 3319 5416 3316 5417 3318 5417 3321 5417 3318 10 3322 10 3321 10 3322 5418 3323 5418 3321 5418 3294 5419 3324 5419 3320 5419 3322 5420 3325 5420 3323 5420 3294 5421 3326 5421 3324 5421 3325 5422 3327 5422 3323 5422 3294 5423 3328 5423 3326 5423 3325 10 3329 10 3327 10 3330 5424 3329 5424 3325 5424 3331 10 3329 10 3330 10 3331 10 3332 10 3329 10 3333 10 3332 10 3331 10 3333 5425 3334 5425 3332 5425 3335 10 3334 10 3333 10 3335 5426 3336 5426 3334 5426 3337 5427 3336 5427 3335 5427 3338 5428 3336 5428 3337 5428 3339 5429 3336 5429 3338 5429 3340 10 3341 10 3342 10 3345 10 3343 10 3340 10 3340 5430 3343 5430 3341 5430 3341 5431 3344 5431 3342 5431 3346 10 3343 10 3345 10 3346 10 3347 10 3343 10 3344 5432 3348 5432 3342 5432 3342 10 3348 10 3349 10 3350 10 3347 10 3346 10 3349 10 3348 10 3351 10 3350 10 3352 10 3347 10 3348 10 3353 10 3351 10 3354 10 3352 10 3350 10 3351 10 3353 10 3355 10 3354 5433 3356 5433 3352 5433 3353 10 3357 10 3355 10 3358 5434 3356 5434 3354 5434 3355 10 3357 10 3359 10 3358 5435 3360 5435 3356 5435 3361 10 3360 10 3358 10 3361 10 3362 10 3360 10 3357 10 3363 10 3359 10 3359 10 3363 10 3364 10 3361 5436 3365 5436 3362 5436 3363 5437 3366 5437 3364 5437 3336 10 3367 10 3361 10 3361 5438 3367 5438 3365 5438 3339 10 3367 10 3336 10 3366 5439 3368 5439 3364 5439 3369 5440 3367 5440 3339 5440 3369 10 3370 10 3367 10 3368 10 3371 10 3364 10 3372 5441 3373 5441 3371 5441 3374 5442 3373 5442 3372 5442 3375 5443 3373 5443 3374 5443 3376 5444 3373 5444 3375 5444 3377 5445 3373 5445 3376 5445 3378 5446 3373 5446 3377 5446 3379 5447 3373 5447 3378 5447 3380 5448 3373 5448 3379 5448 3371 5449 3373 5449 3364 5449 3469 5450 3381 5450 3369 5450 3369 5451 3381 5451 3370 5451 3351 5452 3382 5452 3383 5452 3349 5453 3351 5453 3383 5453 3349 5454 3383 5454 3384 5454 3342 5455 3349 5455 3384 5455 3342 5456 3384 5456 3385 5456 3340 5457 3342 5457 3385 5457 3340 5458 3385 5458 3386 5458 3345 5459 3340 5459 3386 5459 3345 5460 3386 5460 3387 5460 3346 5461 3345 5461 3387 5461 3382 5462 3351 5462 3355 5462 3388 5463 3314 5463 3316 5463 3389 5464 3388 5464 3316 5464 3389 5465 3316 5465 3321 5465 3390 5466 3389 5466 3321 5466 3390 5467 3321 5467 3323 5467 3391 5468 3390 5468 3323 5468 3391 5469 3323 5469 3327 5469 3391 5470 3327 5470 3329 5470 3392 5471 3391 5471 3329 5471 3392 5472 3329 5472 3393 5472 3329 5473 3332 5473 3393 5473 3393 5474 3332 5474 3394 5474 3332 5475 3334 5475 3394 5475 3394 5476 3334 5476 3395 5476 3334 5477 3336 5477 3395 5477 3361 5478 3358 5478 3396 5478 3396 5479 3358 5479 3397 5479 3358 5480 3354 5480 3397 5480 3397 5481 3354 5481 3398 5481 3354 5482 3350 5482 3398 5482 3350 5483 3346 5483 3398 5483 3398 5484 3346 5484 3387 5484 3399 5485 3401 5485 3400 5485 3400 5486 3402 5486 3399 5486 3401 5487 3403 5487 3400 5487 3400 5488 3448 5488 3402 5488 3403 5489 3404 5489 3400 5489 3404 5490 3405 5490 3400 5490 3407 272 3406 272 3405 272 3408 272 3406 272 3407 272 3409 272 3406 272 3408 272 3405 5491 3406 5491 3400 5491 3409 272 3410 272 3406 272 3409 5492 3411 5492 3410 5492 3412 272 3411 272 3409 272 3412 5493 3382 5493 3411 5493 3413 272 3382 272 3412 272 3413 5494 3383 5494 3382 5494 3414 5495 3383 5495 3413 5495 3414 5496 3384 5496 3383 5496 3416 272 3398 272 3415 272 3398 5497 3387 5497 3415 5497 3415 5498 3387 5498 3417 5498 3414 272 3385 272 3384 272 3418 272 3385 272 3414 272 3416 5499 3397 5499 3398 5499 3419 5500 3397 5500 3416 5500 3417 5501 3387 5501 3418 5501 3387 272 3386 272 3418 272 3418 272 3386 272 3385 272 3419 272 3396 272 3397 272 3420 272 3396 272 3419 272 3421 5502 3396 5502 3420 5502 3422 272 3423 272 3395 272 3395 5503 3424 5503 3422 5503 3395 272 3423 272 3394 272 3421 272 3424 272 3396 272 3396 272 3424 272 3395 272 3423 272 3425 272 3394 272 3394 272 3425 272 3393 272 3425 5504 3426 5504 3393 5504 3393 272 3426 272 3392 272 3426 272 3427 272 3392 272 3392 272 3427 272 3391 272 3427 5505 3428 5505 3391 5505 3428 5506 3390 5506 3391 5506 3429 5507 3390 5507 3428 5507 3429 272 3389 272 3390 272 3430 5508 3295 5508 3436 5508 3431 5509 3295 5509 3430 5509 3432 5510 3295 5510 3431 5510 3433 5511 3295 5511 3432 5511 3434 272 3389 272 3429 272 3434 5512 3388 5512 3389 5512 3435 272 3388 272 3434 272 3436 272 3297 272 3437 272 3295 5513 3297 5513 3436 5513 3439 272 3438 272 3435 272 3435 5514 3438 5514 3388 5514 3437 5515 3297 5515 3440 5515 3297 272 3441 272 3440 272 3442 5516 3438 5516 3439 5516 3442 5517 3443 5517 3438 5517 3441 272 3444 272 3440 272 3442 5518 3445 5518 3443 5518 3440 5519 3444 5519 3446 5519 3442 5520 3447 5520 3445 5520 3444 272 3447 272 3446 272 3446 5521 3447 5521 3442 5521 3400 5522 3295 5522 3448 5522 3448 5523 3295 5523 3449 5523 3449 5524 3295 5524 3421 5524 3421 5525 3295 5525 3450 5525 3421 272 3450 272 3424 272 3450 5526 3295 5526 3433 5526 3395 5527 3336 5527 3361 5527 3395 5528 3361 5528 3396 5528 3484 5529 3313 5529 3451 5529 3313 5530 3309 5530 3451 5530 3451 5531 3309 5531 3452 5531 3309 5532 3307 5532 3452 5532 3452 5533 3307 5533 3453 5533 3307 5534 3303 5534 3453 5534 3453 5535 3303 5535 3454 5535 3303 5536 3299 5536 3454 5536 3454 5537 3299 5537 3455 5537 3299 5538 3301 5538 3455 5538 3455 5539 3301 5539 3456 5539 3301 5540 3305 5540 3456 5540 3456 5541 3305 5541 3457 5541 3305 5542 3308 5542 3457 5542 3457 5543 3308 5543 3458 5543 3308 5544 3312 5544 3458 5544 3458 5545 3312 5545 3459 5545 3312 5546 3315 5546 3459 5546 3459 5547 3315 5547 3460 5547 3315 5548 3319 5548 3460 5548 3460 5549 3319 5549 3461 5549 3319 5550 3320 5550 3461 5550 3461 5551 3320 5551 3462 5551 3320 5552 3324 5552 3462 5552 3462 5553 3324 5553 3463 5553 3324 5554 3326 5554 3463 5554 3463 5555 3326 5555 3464 5555 3326 5556 3328 5556 3464 5556 3464 5557 3328 5557 3465 5557 3328 5558 3466 5558 3465 5558 3466 5559 3467 5559 3465 5559 3465 5560 3467 5560 3468 5560 3468 5561 3469 5561 3470 5561 3467 5562 3469 5562 3468 5562 3470 5563 3469 5563 3471 5563 3469 5564 3369 5564 3471 5564 3471 5565 3369 5565 3472 5565 3369 5566 3339 5566 3472 5566 3472 5567 3339 5567 3473 5567 3339 5568 3338 5568 3473 5568 3473 5569 3338 5569 3474 5569 3338 5570 3337 5570 3474 5570 3474 5571 3337 5571 3475 5571 3337 5572 3335 5572 3475 5572 3475 5573 3335 5573 3476 5573 3335 5574 3333 5574 3476 5574 3476 5575 3333 5575 3477 5575 3333 5576 3331 5576 3477 5576 3477 5577 3331 5577 3478 5577 3331 5578 3330 5578 3478 5578 3478 5579 3330 5579 3479 5579 3330 5580 3325 5580 3479 5580 3479 5581 3325 5581 3480 5581 3325 5582 3322 5582 3480 5582 3480 5583 3322 5583 3481 5583 3322 5584 3318 5584 3481 5584 3481 5585 3318 5585 3482 5585 3318 5586 3317 5586 3482 5586 3482 5587 3317 5587 3483 5587 3317 5588 3313 5588 3483 5588 3483 5589 3313 5589 3484 5589 3481 5590 3485 5590 3480 5590 3485 5591 3486 5591 3480 5591 3480 10 3486 10 3479 10 3482 5592 3487 5592 3481 5592 3481 10 3487 10 3485 10 3486 10 3488 10 3479 10 3479 5593 3488 5593 3478 5593 3483 10 3487 10 3482 10 3483 5594 3489 5594 3487 5594 3478 5595 3490 5595 3477 5595 3488 10 3490 10 3478 10 3484 10 3489 10 3483 10 3484 5596 3491 5596 3489 5596 3477 5597 3492 5597 3476 5597 3490 10 3492 10 3477 10 3451 10 3491 10 3484 10 3451 5598 3493 5598 3491 5598 3476 10 3492 10 3475 10 3452 10 3493 10 3451 10 3492 5599 3494 5599 3475 5599 3475 5600 3494 5600 3474 5600 3453 10 3495 10 3452 10 3452 5601 3495 5601 3493 5601 3474 5602 3494 5602 3473 5602 3454 10 3495 10 3453 10 3494 5603 3496 5603 3473 5603 3454 5604 3497 5604 3495 5604 3496 10 3472 10 3473 10 3454 5605 3455 5605 3497 5605 3497 10 3455 10 3498 10 3499 10 3471 10 3496 10 3496 10 3471 10 3472 10 3455 10 3456 10 3498 10 3498 10 3456 10 3500 10 3499 5606 3470 5606 3471 5606 3456 5607 3457 5607 3500 5607 3499 5608 3468 5608 3470 5608 3501 10 3468 10 3499 10 3457 5609 3458 5609 3500 5609 3501 5610 3465 5610 3468 5610 3500 10 3458 10 3502 10 3458 10 3459 10 3502 10 3503 5611 3465 5611 3501 5611 3502 5612 3459 5612 3504 5612 3459 5613 3460 5613 3504 5613 3503 5614 3464 5614 3465 5614 3505 10 3464 10 3503 10 3460 10 3461 10 3504 10 3504 10 3461 10 3506 10 3505 5615 3463 5615 3464 5615 3461 10 3462 10 3506 10 3506 10 3463 10 3505 10 3506 5616 3462 5616 3463 5616 3293 5617 3328 5617 3294 5617 3507 5618 3381 5618 3469 5618 3467 5619 3466 5619 3293 5619 3507 5620 3469 5620 3467 5620 3507 5621 3467 5621 3293 5621 3373 5622 3508 5622 3507 5622 3509 5623 3373 5623 3507 5623 3509 5624 3507 5624 3293 5624 3509 5625 3293 5625 3292 5625 3510 5626 3509 5626 3292 5626 3510 5627 3292 5627 3291 5627 3511 5628 3510 5628 3291 5628 3466 5629 3328 5629 3293 5629 3380 5630 3508 5630 3373 5630 3426 5631 3425 5631 3492 5631 3492 5632 3423 5632 3494 5632 3425 5633 3423 5633 3492 5633 3494 5634 3422 5634 3496 5634 3423 5635 3422 5635 3494 5635 3422 5636 3424 5636 3496 5636 3496 5637 3424 5637 3499 5637 3424 5638 3450 5638 3499 5638 3499 5639 3450 5639 3501 5639 3450 5640 3433 5640 3501 5640 3501 5641 3433 5641 3503 5641 3433 5642 3432 5642 3503 5642 3503 5643 3432 5643 3505 5643 3432 5644 3431 5644 3505 5644 3505 5645 3431 5645 3506 5645 3431 5646 3430 5646 3506 5646 3506 5647 3430 5647 3504 5647 3430 5648 3436 5648 3504 5648 3504 5649 3436 5649 3502 5649 3502 5650 3436 5650 3500 5650 3436 5651 3437 5651 3500 5651 3437 5652 3440 5652 3500 5652 3500 5653 3440 5653 3498 5653 3440 5654 3446 5654 3498 5654 3498 5655 3446 5655 3497 5655 3497 5656 3442 5656 3495 5656 3446 5657 3442 5657 3497 5657 3495 5658 3442 5658 3493 5658 3442 5659 3439 5659 3493 5659 3493 5660 3439 5660 3491 5660 3439 5661 3435 5661 3491 5661 3491 5662 3434 5662 3489 5662 3435 5663 3434 5663 3491 5663 3489 5664 3434 5664 3487 5664 3434 5665 3429 5665 3487 5665 3487 5666 3428 5666 3485 5666 3429 5667 3428 5667 3487 5667 3428 5668 3427 5668 3485 5668 3485 5669 3427 5669 3486 5669 3486 5670 3427 5670 3488 5670 3427 5671 3426 5671 3488 5671 3488 5672 3426 5672 3490 5672 3490 5673 3426 5673 3492 5673 3295 5674 3400 5674 3296 5674 3400 5675 3512 5675 3296 5675 3296 5676 3512 5676 3290 5676 3290 5677 3512 5677 3289 5677 3512 5678 3513 5678 3289 5678 3287 5679 3513 5679 3514 5679 3287 5680 3289 5680 3513 5680 3285 5681 3287 5681 3514 5681 3285 5682 3514 5682 3515 5682 3283 5683 3285 5683 3515 5683 3283 5684 3515 5684 3516 5684 3281 5685 3283 5685 3516 5685 3281 5686 3516 5686 3517 5686 3279 5687 3281 5687 3517 5687 3279 5688 3517 5688 3518 5688 3279 5689 3518 5689 3519 5689 3278 5690 3279 5690 3519 5690 3278 5691 3519 5691 3520 5691 3551 5692 3353 5692 3521 5692 3521 5693 3353 5693 3522 5693 3353 5694 3348 5694 3522 5694 3522 5695 3348 5695 3523 5695 3348 5696 3344 5696 3523 5696 3523 5697 3344 5697 3524 5697 3344 5698 3341 5698 3524 5698 3524 5699 3341 5699 3525 5699 3341 5700 3343 5700 3525 5700 3525 5701 3343 5701 3526 5701 3343 5702 3347 5702 3526 5702 3526 5703 3347 5703 3527 5703 3347 5704 3352 5704 3527 5704 3527 5705 3352 5705 3528 5705 3352 5706 3356 5706 3528 5706 3528 5707 3356 5707 3529 5707 3356 5708 3360 5708 3529 5708 3529 5709 3360 5709 3530 5709 3360 5710 3362 5710 3530 5710 3530 5711 3362 5711 3531 5711 3362 5712 3365 5712 3531 5712 3531 5713 3365 5713 3532 5713 3365 5714 3367 5714 3532 5714 3532 5715 3367 5715 3533 5715 3367 5716 3370 5716 3533 5716 3533 5717 3370 5717 3534 5717 3370 5718 3381 5718 3534 5718 3534 5719 3381 5719 3535 5719 3381 5720 3507 5720 3535 5720 3535 5721 3507 5721 3536 5721 3507 5722 3508 5722 3536 5722 3536 5723 3508 5723 3537 5723 3508 5724 3380 5724 3537 5724 3537 5725 3380 5725 3538 5725 3538 5726 3380 5726 3539 5726 3380 5727 3379 5727 3539 5727 3539 5728 3379 5728 3540 5728 3379 5729 3378 5729 3540 5729 3540 5730 3378 5730 3541 5730 3378 5731 3377 5731 3541 5731 3541 5732 3377 5732 3542 5732 3377 5733 3376 5733 3542 5733 3542 5734 3376 5734 3543 5734 3376 5735 3375 5735 3543 5735 3543 5736 3375 5736 3544 5736 3375 5737 3374 5737 3544 5737 3544 5738 3374 5738 3545 5738 3374 5739 3372 5739 3545 5739 3545 5740 3372 5740 3546 5740 3372 5741 3371 5741 3546 5741 3546 5742 3371 5742 3547 5742 3371 5743 3368 5743 3547 5743 3547 5744 3368 5744 3548 5744 3368 5745 3366 5745 3548 5745 3548 5746 3366 5746 3549 5746 3366 5747 3363 5747 3549 5747 3549 5748 3363 5748 3550 5748 3363 5749 3357 5749 3550 5749 3550 5750 3357 5750 3551 5750 3357 5751 3353 5751 3551 5751 3304 5752 3438 5752 3443 5752 3304 5753 3310 5753 3438 5753 3304 5754 3443 5754 3445 5754 3300 5755 3304 5755 3445 5755 3300 5756 3445 5756 3447 5756 3298 5757 3300 5757 3447 5757 3298 5758 3447 5758 3444 5758 3302 5759 3298 5759 3444 5759 3306 5760 3444 5760 3441 5760 3306 5761 3302 5761 3444 5761 3306 5762 3441 5762 3297 5762 3311 5763 3306 5763 3297 5763 3438 5764 3314 5764 3388 5764 3438 5765 3310 5765 3314 5765 3411 5766 3355 5766 3359 5766 3411 5767 3382 5767 3355 5767 3410 5768 3411 5768 3359 5768 3410 5769 3359 5769 3364 5769 3406 5770 3410 5770 3364 5770 3552 5771 3519 5771 3518 5771 3553 5772 3552 5772 3518 5772 3553 5773 3518 5773 3517 5773 3554 5774 3553 5774 3517 5774 3554 5775 3517 5775 3516 5775 3555 5776 3554 5776 3516 5776 3555 5777 3516 5777 3515 5777 3556 5778 3555 5778 3515 5778 3556 5779 3515 5779 3514 5779 3557 5780 3556 5780 3514 5780 3513 5781 3557 5781 3514 5781 3513 5782 3511 5782 3557 5782 3510 5783 3511 5783 3513 5783 3510 5784 3513 5784 3512 5784 3509 5785 3510 5785 3512 5785 3373 5786 3509 5786 3512 5786 3373 5787 3512 5787 3400 5787 3364 5788 3373 5788 3400 5788 3364 5789 3400 5789 3406 5789 3076 5790 3133 5790 3132 5790 3078 5791 3076 5791 3132 5791 3079 5792 3078 5792 3132 5792 3079 5793 3132 5793 3130 5793 3079 5794 3130 5794 3128 5794 3083 5795 3079 5795 3128 5795 3083 5796 3128 5796 3127 5796 3086 5797 3083 5797 3127 5797 3086 5798 3127 5798 3125 5798 3089 5799 3086 5799 3125 5799 3089 5800 3125 5800 3123 5800 3090 5801 3089 5801 3123 5801 3090 5802 3123 5802 3119 5802 3092 5803 3090 5803 3119 5803 3133 5804 3076 5804 3100 5804 3100 5805 3076 5805 3071 5805 3035 5806 3044 5806 3042 5806 3165 5807 3035 5807 3042 5807 3165 5808 3042 5808 3040 5808 3176 5809 3165 5809 3040 5809 3176 5810 3040 5810 3037 5810 3178 5811 3176 5811 3037 5811 3559 5812 3560 5812 3558 5812 3558 5813 3560 5813 3561 5813 3560 5814 3562 5814 3561 5814 3561 5815 3562 5815 3563 5815 3562 5816 3564 5816 3563 5816 3563 5817 3564 5817 3565 5817 3564 5818 3566 5818 3565 5818 3566 5819 3567 5819 3565 5819 3567 5820 3568 5820 3565 5820 3569 5821 3570 5821 3567 5821 3567 5822 3570 5822 3568 5822 3571 5823 3570 5823 3569 5823 3571 5824 3572 5824 3570 5824 3572 5825 3573 5825 3570 5825 3570 5826 3573 5826 3574 5826 3573 5827 3575 5827 3574 5827 3574 5828 3575 5828 3576 5828 3576 5829 3178 5829 3037 5829 3575 5830 3178 5830 3576 5830 3249 10 3577 10 3248 10 3249 10 3578 10 3577 10 3577 5831 3579 5831 3248 5831 3250 10 3578 10 3249 10 3248 10 3579 10 3247 10 3251 10 3578 10 3250 10 3251 10 3580 10 3578 10 3579 10 3581 10 3247 10 3247 5832 3581 5832 3246 5832 3252 10 3580 10 3251 10 3246 10 3581 10 3245 10 3252 10 3582 10 3580 10 3581 10 3583 10 3245 10 3245 10 3583 10 3244 10 3252 10 3584 10 3582 10 3253 5833 3584 5833 3252 5833 3583 10 3585 10 3244 10 3253 10 3586 10 3584 10 3244 10 3585 10 3243 10 3254 5834 3586 5834 3253 5834 3585 10 3587 10 3243 10 3254 5835 3588 5835 3586 5835 3243 5836 3587 5836 3242 5836 3255 5837 3588 5837 3254 5837 3587 10 3589 10 3242 10 3255 10 3256 10 3588 10 3588 10 3256 10 3590 10 3589 5838 3241 5838 3242 5838 3591 5839 3240 5839 3589 5839 3589 5840 3240 5840 3241 5840 3256 5841 3257 5841 3590 5841 3590 10 3257 10 3592 10 3593 5842 3239 5842 3591 5842 3591 5843 3239 5843 3240 5843 3257 10 3258 10 3592 10 3592 10 3258 10 3594 10 3258 10 3231 10 3594 10 3595 10 3238 10 3593 10 3593 10 3238 10 3239 10 3231 5844 3232 5844 3594 5844 3595 10 3237 10 3238 10 3594 10 3232 10 3596 10 3232 10 3233 10 3596 10 3595 10 3236 10 3237 10 3597 10 3236 10 3595 10 3596 10 3233 10 3598 10 3233 5845 3234 5845 3598 5845 3597 5846 3235 5846 3236 5846 3234 5847 3235 5847 3598 5847 3598 10 3235 10 3597 10 3540 10 3599 10 3539 10 3540 5848 3600 5848 3599 5848 3541 10 3600 10 3540 10 3539 10 3601 10 3538 10 3599 5849 3601 5849 3539 5849 3542 10 3600 10 3541 10 3538 10 3601 10 3537 10 3542 10 3602 10 3600 10 3601 10 3603 10 3537 10 3537 10 3603 10 3536 10 3543 5850 3602 5850 3542 5850 3543 10 3604 10 3602 10 3536 5851 3603 5851 3535 5851 3544 5852 3604 5852 3543 5852 3603 5853 3605 5853 3535 5853 3544 10 3606 10 3604 10 3545 5854 3606 5854 3544 5854 3535 5855 3605 5855 3534 5855 3605 10 3607 10 3534 10 3545 10 3608 10 3606 10 3546 5856 3608 5856 3545 5856 3534 5857 3607 5857 3533 5857 3547 5858 3608 5858 3546 5858 3547 10 3609 10 3608 10 3607 10 3610 10 3533 10 3533 10 3610 10 3532 10 3547 10 3548 10 3609 10 3611 10 3532 10 3610 10 3611 5859 3531 5859 3532 5859 3609 10 3548 10 3612 10 3548 5860 3549 5860 3612 5860 3613 10 3531 10 3611 10 3613 10 3530 10 3531 10 3612 10 3550 10 3614 10 3549 10 3550 10 3612 10 3613 10 3529 10 3530 10 3550 10 3551 10 3614 10 3615 5861 3529 5861 3613 5861 3615 10 3528 10 3529 10 3614 5862 3521 5862 3616 5862 3551 10 3521 10 3614 10 3617 5863 3528 5863 3615 5863 3617 10 3527 10 3528 10 3521 5864 3522 5864 3616 5864 3618 5865 3527 5865 3617 5865 3616 10 3522 10 3619 10 3618 10 3526 10 3527 10 3522 10 3523 10 3619 10 3618 10 3525 10 3526 10 3523 5866 3524 5866 3619 5866 3619 5867 3524 5867 3620 5867 3620 5868 3525 5868 3618 5868 3620 5869 3524 5869 3525 5869 3056 5870 3593 5870 3054 5870 3595 5871 3593 5871 3056 5871 3593 5872 3591 5872 3054 5872 3054 5873 3591 5873 3051 5873 3591 5874 3589 5874 3051 5874 3589 5875 3587 5875 3051 5875 3051 5876 3587 5876 3049 5876 3049 5877 3587 5877 3047 5877 3587 5878 3585 5878 3047 5878 3047 5879 3583 5879 3045 5879 3585 5880 3583 5880 3047 5880 3045 5881 3581 5881 3041 5881 3583 5882 3581 5882 3045 5882 3581 5883 3579 5883 3041 5883 3041 5884 3579 5884 3038 5884 3579 5885 3577 5885 3038 5885 3038 5886 3577 5886 3036 5886 3577 5887 3578 5887 3036 5887 3036 5888 3578 5888 3039 5888 3578 5889 3580 5889 3039 5889 3039 5890 3582 5890 3043 5890 3580 5891 3582 5891 3039 5891 3043 5892 3582 5892 3046 5892 3582 5893 3584 5893 3046 5893 3584 5894 3586 5894 3046 5894 3046 5895 3586 5895 3048 5895 3586 5896 3588 5896 3048 5896 3048 5897 3588 5897 3050 5897 3588 5898 3590 5898 3050 5898 3050 5899 3590 5899 3052 5899 3590 5900 3592 5900 3052 5900 3052 5901 3592 5901 3053 5901 3592 5902 3594 5902 3053 5902 3053 5903 3594 5903 3099 5903 3099 5904 3596 5904 3061 5904 3594 5905 3596 5905 3099 5905 3596 5906 3598 5906 3061 5906 3061 5907 3598 5907 3059 5907 3598 5908 3597 5908 3059 5908 3059 5909 3597 5909 3058 5909 3597 5910 3595 5910 3058 5910 3058 5911 3595 5911 3056 5911 3615 5912 3613 5912 3416 5912 3416 5913 3613 5913 3419 5913 3613 5914 3611 5914 3419 5914 3419 5915 3611 5915 3420 5915 3611 5916 3610 5916 3420 5916 3420 5917 3610 5917 3421 5917 3610 5918 3607 5918 3421 5918 3421 5919 3605 5919 3449 5919 3607 5920 3605 5920 3421 5920 3449 5921 3605 5921 3448 5921 3605 5922 3603 5922 3448 5922 3448 5923 3603 5923 3402 5923 3603 5924 3601 5924 3402 5924 3402 5925 3601 5925 3399 5925 3601 5926 3599 5926 3399 5926 3599 5927 3600 5927 3399 5927 3399 5928 3600 5928 3401 5928 3600 5929 3602 5929 3401 5929 3401 5930 3602 5930 3403 5930 3403 5931 3604 5931 3404 5931 3602 5932 3604 5932 3403 5932 3604 5933 3606 5933 3404 5933 3404 5934 3606 5934 3405 5934 3606 5935 3608 5935 3405 5935 3405 5936 3608 5936 3407 5936 3407 5937 3609 5937 3408 5937 3608 5938 3609 5938 3407 5938 3408 5939 3612 5939 3409 5939 3609 5940 3612 5940 3408 5940 3612 5941 3614 5941 3409 5941 3409 5942 3614 5942 3412 5942 3412 5943 3614 5943 3413 5943 3614 5944 3616 5944 3413 5944 3413 5945 3619 5945 3414 5945 3616 5946 3619 5946 3413 5946 3414 5947 3619 5947 3418 5947 3619 5948 3620 5948 3418 5948 3620 5949 3618 5949 3418 5949 3418 5950 3618 5950 3417 5950 3417 5951 3618 5951 3415 5951 3618 5952 3617 5952 3415 5952 3617 5953 3615 5953 3415 5953 3415 5954 3615 5954 3416 5954 3114 5955 3575 5955 3573 5955 3273 5956 3114 5956 3573 5956 3273 5957 3573 5957 3572 5957 3274 5958 3273 5958 3572 5958 3274 5959 3572 5959 3571 5959 3268 5960 3274 5960 3571 5960 3270 5961 3269 5961 3576 5961 3576 5962 3269 5962 3574 5962 3269 5963 3271 5963 3574 5963 3574 5964 3271 5964 3570 5964 3271 5965 3266 5965 3570 5965 3570 5966 3266 5966 3261 5966 3568 5967 3570 5967 3261 5967 3565 5968 3261 5968 3260 5968 3565 5969 3568 5969 3261 5969 3563 5970 3565 5970 3260 5970 3563 5971 3260 5971 3263 5971 3561 5972 3263 5972 3267 5972 3561 5973 3563 5973 3263 5973 3558 5974 3561 5974 3267 5974 3558 5975 3267 5975 3275 5975 3621 5976 3558 5976 3275 5976 3622 5977 3621 5977 3275 5977 3623 5978 3278 5978 3520 5978 3624 5979 3623 5979 3520 5979 3625 5980 3278 5980 3623 5980 3626 5981 3624 5981 3520 5981 3627 5982 3278 5982 3625 5982 3628 5983 3626 5983 3520 5983 3629 5984 3628 5984 3520 5984 3629 5985 3520 5985 3630 5985 3631 5986 3629 5986 3630 5986 3642 272 3631 272 3630 272 3634 272 3633 272 3632 272 3632 5987 3633 5987 3635 5987 3634 5988 3636 5988 3633 5988 3637 272 3636 272 3634 272 3638 272 3632 272 3635 272 3638 5989 3635 5989 3639 5989 3637 5990 3640 5990 3636 5990 3637 5991 3643 5991 3640 5991 3638 5992 3639 5992 3631 5992 3638 5993 3642 5993 3641 5993 3638 5994 3631 5994 3642 5994 3637 5995 3661 5995 3643 5995 3645 5996 3644 5996 3826 5996 3646 5997 3645 5997 3826 5997 3647 5998 3826 5998 3644 5998 3648 5999 3649 5999 3826 5999 3648 6000 3826 6000 3647 6000 3650 6001 3641 6001 3649 6001 3650 6002 3638 6002 3641 6002 3650 6003 3649 6003 3648 6003 3650 6004 3648 6004 3651 6004 3652 6005 3650 6005 3651 6005 3653 6006 3646 6006 3826 6006 3653 6007 3654 6007 3646 6007 3652 6008 3651 6008 3655 6008 3653 6009 3657 6009 3654 6009 3656 6010 3657 6010 3653 6010 3658 6011 3661 6011 3637 6011 3659 272 3652 272 3655 272 3656 272 3664 272 3657 272 3662 272 3660 272 3661 272 3662 6012 3661 6012 3658 6012 3660 6013 3627 6013 3661 6013 3663 6014 3664 6014 3656 6014 3660 6015 3275 6015 3278 6015 3660 6016 3278 6016 3627 6016 3665 6017 3275 6017 3660 6017 3666 6018 3662 6018 3658 6018 3663 6019 3671 6019 3664 6019 3667 6020 3275 6020 3665 6020 3666 6021 3658 6021 3668 6021 3669 6022 3666 6022 3668 6022 3670 6023 3671 6023 3663 6023 3669 6024 3668 6024 3672 6024 3673 6025 3275 6025 3667 6025 3674 272 3669 272 3672 272 3670 272 3675 272 3671 272 3676 6026 3275 6026 3673 6026 3677 6027 3674 6027 3672 6027 3670 6028 3678 6028 3675 6028 3679 6029 3677 6029 3672 6029 3679 6030 3680 6030 3677 6030 3681 6031 3680 6031 3679 6031 3682 6032 3683 6032 3678 6032 3682 6033 3678 6033 3670 6033 3681 6034 3691 6034 3680 6034 3682 6035 3655 6035 3683 6035 3682 272 3659 272 3655 272 3682 272 3684 272 3685 272 3682 6036 3685 6036 3659 6036 3696 6037 3684 6037 3682 6037 3622 6038 3676 6038 3686 6038 3622 6039 3686 6039 3687 6039 3622 6040 3687 6040 3688 6040 3622 6041 3688 6041 3689 6041 3622 6042 3275 6042 3676 6042 3690 6043 3622 6043 3689 6043 3690 6044 3689 6044 3691 6044 3692 6045 3690 6045 3691 6045 3692 6046 3691 6046 3681 6046 3693 272 3692 272 3681 272 3693 6047 3681 6047 3699 6047 3694 272 3696 272 3682 272 3694 6048 3697 6048 3695 6048 3694 6049 3695 6049 3696 6049 3700 272 3698 272 3699 272 3700 6050 3699 6050 3701 6050 3702 272 3699 272 3698 272 3702 6051 3693 6051 3699 6051 3702 6052 3703 6052 3693 6052 3704 6053 3701 6053 3697 6053 3704 272 3700 272 3701 272 3704 6054 3697 6054 3694 6054 3705 6055 3703 6055 3702 6055 3706 272 3704 272 3694 272 3707 6056 3703 6056 3705 6056 3706 6057 3710 6057 3704 6057 3708 6058 3703 6058 3707 6058 3709 272 3710 272 3706 272 3709 6059 3711 6059 3710 6059 3709 6060 3713 6060 3711 6060 3712 272 3713 272 3709 272 3712 6061 3714 6061 3713 6061 3715 272 3714 272 3712 272 3715 6062 3716 6062 3714 6062 3715 6063 3718 6063 3716 6063 3717 6064 3718 6064 3715 6064 3717 6065 3703 6065 3708 6065 3717 6066 3708 6066 3718 6066 3571 6067 3569 6067 3268 6067 3268 6068 3569 6068 3264 6068 3569 6069 3567 6069 3264 6069 3264 6070 3567 6070 3259 6070 3567 6071 3566 6071 3259 6071 3566 6072 3564 6072 3259 6072 3259 6073 3564 6073 3262 6073 3564 6074 3562 6074 3262 6074 3262 6075 3562 6075 3265 6075 3562 6076 3560 6076 3265 6076 3265 6077 3560 6077 3272 6077 3560 6078 3559 6078 3272 6078 3272 6079 3559 6079 3276 6079 3559 6080 3719 6080 3276 6080 3719 6081 3720 6081 3276 6081 3511 6082 3291 6082 3557 6082 3291 6083 3288 6083 3557 6083 3557 6084 3288 6084 3556 6084 3288 6085 3286 6085 3556 6085 3556 6086 3286 6086 3555 6086 3286 6087 3284 6087 3555 6087 3555 6088 3284 6088 3554 6088 3284 6089 3282 6089 3554 6089 3554 6090 3282 6090 3553 6090 3282 6091 3280 6091 3553 6091 3553 6092 3280 6092 3552 6092 3552 6093 3277 6093 3721 6093 3280 6094 3277 6094 3552 6094 3721 6095 3723 6095 3722 6095 3721 6096 3277 6096 3723 6096 3276 6097 3723 6097 3277 6097 3724 6098 3725 6098 3722 6098 3722 6099 3726 6099 3724 6099 3722 6100 3725 6100 3721 6100 3725 6101 3727 6101 3721 6101 3722 6102 3728 6102 3726 6102 3729 6103 3728 6103 3722 6103 3723 6104 3728 6104 3729 6104 3723 6105 3730 6105 3728 6105 3727 6106 3731 6106 3721 6106 3721 6107 3732 6107 3733 6107 3731 6108 3732 6108 3721 6108 3733 6109 3732 6109 3734 6109 3732 10 3735 10 3734 10 3735 6110 3745 6110 3734 6110 3745 6111 3736 6111 3734 6111 3740 6112 3739 6112 3737 6112 3737 6113 3739 6113 3738 6113 3738 10 3741 10 3737 10 3737 10 3741 10 3742 10 3740 6114 3743 6114 3739 6114 3741 10 3744 10 3742 10 3742 10 3744 10 3745 10 3746 10 3743 10 3740 10 3736 10 3744 10 3747 10 3745 10 3744 10 3736 10 3768 10 3743 10 3746 10 3749 6115 3750 6115 3748 6115 3748 6116 3751 6116 3749 6116 3750 6117 3752 6117 3748 6117 3753 6118 3754 6118 3748 6118 3748 6119 3754 6119 3751 6119 3747 6120 3755 6120 3753 6120 3754 10 3755 10 3756 10 3744 10 3755 10 3747 10 3753 6121 3755 6121 3754 6121 3756 6122 3757 6122 3758 6122 3755 6123 3757 6123 3756 6123 3752 6124 3759 6124 3748 6124 3760 6125 3759 6125 3752 6125 3760 6126 3761 6126 3759 6126 3762 10 3761 10 3760 10 3758 10 3757 10 3787 10 3757 10 3763 10 3787 10 3768 10 3764 10 3743 10 3765 6127 3761 6127 3762 6127 3767 10 3766 10 3765 10 3765 10 3766 10 3761 10 3730 10 3769 10 3768 10 3769 10 3770 10 3768 10 3723 6128 3769 6128 3730 6128 3768 6129 3770 6129 3764 6129 3723 6130 3771 6130 3769 6130 3276 6131 3771 6131 3723 6131 3770 6132 3772 6132 3764 6132 3773 10 3766 10 3767 10 3276 6133 3774 6133 3771 6133 3764 6134 3772 6134 3775 6134 3772 10 3776 10 3775 10 3276 6135 3777 6135 3774 6135 3775 6136 3776 6136 3778 6136 3779 10 3780 10 3773 10 3773 10 3780 10 3766 10 3776 10 3781 10 3778 10 3276 6137 3795 6137 3777 6137 3782 6138 3780 6138 3779 6138 3781 6139 3783 6139 3778 6139 3784 6140 3783 6140 3781 6140 3782 10 3785 10 3780 10 3784 6141 3786 6141 3783 6141 3787 10 3785 10 3782 10 3797 10 3786 10 3784 10 3763 10 3788 10 3787 10 3787 6142 3788 6142 3785 6142 3789 10 3788 10 3763 10 3790 10 3788 10 3789 10 3790 6143 3791 6143 3788 6143 3793 6144 3720 6144 3792 6144 3794 6145 3720 6145 3793 6145 3795 6146 3720 6146 3794 6146 3276 6147 3720 6147 3795 6147 3720 6148 3796 6148 3792 6148 3792 6149 3796 6149 3797 6149 3796 10 3798 10 3797 10 3797 10 3798 10 3786 10 3798 6150 3799 6150 3786 6150 3786 6151 3800 6151 3803 6151 3799 6152 3800 6152 3786 6152 3791 10 3801 10 3788 10 3802 10 3801 10 3791 10 3803 10 3804 10 3805 10 3803 6153 3806 6153 3804 6153 3804 6154 3807 6154 3805 6154 3800 6155 3806 6155 3803 6155 3901 6156 3806 6156 3800 6156 3805 10 3807 10 3802 10 3802 6157 3807 6157 3801 6157 3901 6158 3808 6158 3806 6158 3807 6159 3809 6159 3801 6159 3809 10 3810 10 3801 10 3901 6160 3811 6160 3808 6160 3812 10 3810 10 3809 10 3901 6161 3813 6161 3811 6161 3901 6162 3821 6162 3813 6162 3814 10 3810 10 3812 10 3814 10 3815 10 3810 10 3816 6163 3815 6163 3814 6163 3817 6164 3815 6164 3816 6164 3818 6165 3815 6165 3817 6165 3818 6166 3819 6166 3815 6166 3820 10 3819 10 3818 10 3821 10 3819 10 3820 10 3821 6167 3822 6167 3819 6167 3901 6168 3822 6168 3821 6168 3839 6169 3840 6169 3823 6169 3840 6170 3824 6170 3823 6170 3823 6171 3824 6171 3825 6171 3824 6172 3826 6172 3825 6172 3825 6173 3826 6173 3748 6173 3826 6174 3649 6174 3748 6174 3748 6175 3649 6175 3753 6175 3753 6176 3641 6176 3747 6176 3649 6177 3641 6177 3753 6177 3747 6178 3641 6178 3736 6178 3641 6179 3642 6179 3736 6179 3736 6180 3642 6180 3734 6180 3642 6181 3630 6181 3734 6181 3734 6182 3630 6182 3733 6182 3630 6183 3520 6183 3733 6183 3733 6184 3520 6184 3721 6184 3520 6185 3519 6185 3721 6185 3721 6186 3519 6186 3552 6186 3837 6187 3849 6187 3850 6187 3827 6188 3828 6188 3829 6188 3830 6189 3827 6189 3829 6189 3830 6190 3829 6190 3831 6190 3832 6191 3828 6191 3827 6191 3832 6192 3833 6192 3828 6192 3834 6193 3849 6193 3837 6193 3834 6194 3835 6194 3836 6194 3834 6195 3837 6195 3835 6195 3832 6196 3838 6196 3833 6196 3839 6197 3830 6197 3831 6197 3839 6198 3831 6198 3840 6198 3841 6199 3834 6199 3836 6199 3842 6200 3838 6200 3832 6200 3842 6201 3836 6201 3838 6201 3842 6202 3841 6202 3836 6202 3845 6203 3843 6203 3844 6203 3845 6204 3844 6204 3846 6204 3845 6205 3846 6205 3847 6205 3848 6206 3845 6206 3847 6206 3849 6207 3848 6207 3847 6207 3849 6208 3847 6208 3850 6208 3852 6209 3853 6209 3851 6209 3851 6210 3854 6210 3852 6210 3851 6211 3853 6211 3855 6211 3853 272 3856 272 3855 272 3851 6212 3857 6212 3854 6212 3856 272 3858 272 3855 272 3858 272 3859 272 3855 272 3855 272 3859 272 3860 272 3859 6213 3861 6213 3860 6213 3860 6214 3861 6214 3862 6214 3862 272 3861 272 3863 272 3861 6215 3864 6215 3863 6215 3863 272 3864 272 3865 272 3864 272 3866 272 3865 272 3866 6216 3867 6216 3865 6216 3868 6217 3867 6217 3866 6217 3868 6218 3869 6218 3867 6218 3870 272 3869 272 3868 272 3871 6219 3837 6219 3879 6219 3872 6220 3837 6220 3871 6220 3873 6221 3837 6221 3872 6221 3874 6222 3837 6222 3873 6222 3880 6223 3837 6223 3874 6223 3870 6224 3844 6224 3869 6224 3875 272 3844 272 3870 272 3875 6225 3846 6225 3844 6225 3876 272 3846 272 3875 272 3876 6226 3847 6226 3846 6226 3878 6227 3850 6227 3877 6227 3879 6228 3850 6228 3878 6228 3837 6229 3850 6229 3879 6229 3877 272 3850 272 3876 272 3876 6230 3850 6230 3847 6230 3851 6231 3837 6231 3880 6231 3851 6232 3880 6232 3857 6232 3844 6233 3843 6233 3869 6233 3869 6234 3843 6234 3881 6234 3838 6235 4048 6235 3882 6235 3833 6236 3838 6236 3882 6236 3828 6237 3882 6237 3883 6237 3828 6238 3833 6238 3882 6238 3828 6239 3883 6239 3884 6239 3829 6240 3828 6240 3884 6240 3831 6241 3829 6241 3884 6241 3831 6242 3884 6242 3885 6242 3840 6243 3885 6243 3886 6243 3840 6244 3831 6244 3885 6244 3840 6245 3886 6245 3887 6245 3824 6246 3840 6246 3887 6246 3824 6247 3887 6247 3888 6247 3826 6248 3824 6248 3888 6248 3826 6249 3888 6249 3653 6249 3842 6250 3832 6250 4043 6250 4043 6251 3832 6251 3889 6251 3889 6252 3832 6252 3890 6252 3832 6253 3827 6253 3890 6253 3890 6254 3827 6254 3891 6254 3827 6255 3830 6255 3891 6255 3891 6256 3830 6256 3892 6256 3892 6257 3830 6257 3893 6257 3830 6258 3839 6258 3893 6258 3893 6259 3839 6259 3894 6259 3894 6260 3823 6260 3895 6260 3839 6261 3823 6261 3894 6261 3823 6262 3825 6262 3895 6262 3825 6263 3748 6263 3895 6263 3895 6264 3748 6264 3759 6264 3897 6265 3896 6265 3898 6265 3896 6266 3899 6266 3898 6266 3898 6267 3899 6267 3900 6267 3899 6268 3901 6268 3900 6268 3900 6269 3901 6269 3703 6269 3901 6270 3800 6270 3703 6270 3703 6271 3800 6271 3693 6271 3693 6272 3799 6272 3692 6272 3800 6273 3799 6273 3693 6273 3799 6274 3798 6274 3692 6274 3692 6275 3798 6275 3690 6275 3798 6276 3796 6276 3690 6276 3690 6277 3796 6277 3622 6277 3796 6278 3720 6278 3622 6278 3720 6279 3719 6279 3622 6279 3622 6280 3719 6280 3621 6280 3719 6281 3559 6281 3621 6281 3621 6282 3559 6282 3558 6282 3923 6283 3902 6283 3924 6283 3905 6284 3904 6284 3903 6284 3905 6285 3906 6285 3904 6285 3904 6286 3907 6286 3903 6286 3903 6287 3907 6287 3908 6287 3923 6288 3909 6288 3902 6288 3902 6289 3909 6289 3910 6289 3913 6290 3906 6290 3905 6290 3907 6291 3911 6291 3908 6291 3908 6292 3911 6292 3912 6292 3909 6293 3914 6293 3910 6293 3913 6294 3915 6294 3906 6294 3914 6295 3916 6295 3910 6295 3910 6296 3916 6296 3913 6296 3913 6297 3916 6297 3915 6297 3912 6298 3896 6298 3897 6298 3911 6299 3896 6299 3912 6299 3917 6300 3918 6300 3919 6300 3920 6301 3917 6301 3919 6301 3920 6302 3919 6302 3921 6302 3922 6303 3920 6303 3921 6303 3922 6304 3921 6304 3923 6304 3924 6305 3922 6305 3923 6305 3909 6306 3926 6306 3925 6306 3909 6307 3927 6307 3926 6307 3925 6308 3928 6308 3909 6308 3909 6309 3929 6309 3927 6309 3928 6310 3930 6310 3909 6310 3909 6311 3931 6311 3929 6311 3909 6312 3923 6312 3931 6312 3933 6313 3923 6313 3932 6313 3931 6314 3923 6314 3933 6314 3936 6315 3935 6315 3934 6315 3937 6316 3935 6316 3936 6316 3934 6317 3935 6317 3930 6317 3923 10 3921 10 3932 10 3921 10 3938 10 3932 10 3937 6318 3939 6318 3935 6318 3940 6319 3939 6319 3937 6319 3921 6320 3919 6320 3938 6320 3938 6321 3919 6321 3941 6321 3942 6322 3939 6322 3940 6322 3941 6323 3919 6323 3943 6323 3919 10 3918 10 3943 10 3942 10 3944 10 3939 10 3943 10 3918 10 3945 10 3946 6324 3944 6324 3942 6324 3918 10 3947 10 3945 10 3945 10 3947 10 3948 10 3946 10 3949 10 3944 10 3950 6325 3949 6325 3946 6325 3948 10 3947 10 3951 10 3950 6326 3952 6326 3949 6326 3947 10 3953 10 3951 10 3954 6327 3952 6327 3950 6327 3954 10 3955 10 3952 10 3951 10 3953 10 3956 10 3953 6328 3957 6328 3956 6328 3956 10 3957 10 3954 10 3954 6329 3957 6329 3955 6329 3935 6330 3909 6330 3930 6330 3918 6331 3917 6331 3947 6331 3947 6332 3917 6332 3977 6332 4051 6333 3958 6333 3915 6333 3915 6334 3958 6334 3906 6334 3958 6335 3959 6335 3906 6335 3906 6336 3959 6336 3904 6336 3904 6337 3959 6337 3907 6337 3959 6338 3960 6338 3907 6338 3907 6339 3960 6339 3911 6339 3960 6340 3961 6340 3911 6340 3961 6341 3962 6341 3911 6341 3911 6342 3962 6342 3896 6342 3896 6343 3962 6343 3899 6343 3962 6344 3963 6344 3899 6344 3899 6345 3963 6345 3901 6345 3963 6346 3822 6346 3901 6346 3964 6347 3913 6347 3905 6347 3964 6348 4045 6348 3913 6348 3965 6349 3964 6349 3905 6349 3965 6350 3905 6350 3903 6350 3966 6351 3965 6351 3903 6351 3966 6352 3903 6352 3908 6352 3967 6353 3966 6353 3908 6353 3967 6354 3908 6354 3912 6354 3968 6355 3912 6355 3897 6355 3968 6356 3967 6356 3912 6356 3969 6357 3897 6357 3898 6357 3969 6358 3968 6358 3897 6358 3969 6359 3898 6359 3900 6359 3717 6360 3900 6360 3703 6360 3717 6361 3969 6361 3900 6361 3970 6362 3971 6362 3972 6362 3971 6363 3973 6363 3972 6363 3975 272 3971 272 3970 272 3972 6364 3973 6364 3974 6364 3973 6365 3976 6365 3974 6365 3977 272 3978 272 3975 272 3975 6366 3978 6366 3971 6366 3974 6367 3976 6367 3979 6367 3979 6368 3980 6368 3981 6368 3976 6369 3980 6369 3979 6369 3977 6370 3982 6370 3978 6370 3917 272 3982 272 3977 272 3981 272 3983 272 3984 272 3980 272 3983 272 3981 272 3917 6371 3985 6371 3982 6371 3983 6372 3986 6372 3984 6372 3920 6373 3985 6373 3917 6373 3920 272 3987 272 3985 272 3986 6374 3988 6374 3984 6374 3922 6375 3987 6375 3920 6375 3984 6376 3988 6376 3989 6376 3988 6377 3990 6377 3989 6377 3922 6378 3991 6378 3987 6378 3922 6379 3924 6379 3991 6379 3990 6380 3992 6380 3989 6380 3991 272 3924 272 3993 272 3924 6381 3994 6381 3993 6381 3992 6382 3995 6382 3989 6382 3997 6383 3902 6383 3996 6383 3998 6384 3902 6384 3997 6384 3999 6385 3902 6385 3998 6385 4000 6386 3902 6386 3999 6386 3994 6387 3902 6387 4000 6387 3924 6388 3902 6388 3994 6388 3902 6389 3989 6389 3995 6389 3902 6390 3995 6390 3996 6390 4001 10 4002 10 3849 10 3849 10 4002 10 3848 10 3849 10 4003 10 4001 10 4002 10 4004 10 3848 10 3848 10 4004 10 3845 10 3849 6391 4005 6391 4003 6391 4004 10 4006 10 3845 10 3845 10 4006 10 3843 10 3849 6392 4007 6392 4005 6392 3849 6393 3834 6393 4007 6393 4006 10 4008 10 3843 10 3834 6394 4009 6394 4007 6394 3843 10 4008 10 3881 10 4008 10 4010 10 3881 10 3834 6395 4011 6395 4009 6395 3881 10 4012 10 4013 10 4010 10 4012 10 3881 10 3834 6396 4014 6396 4011 6396 4013 10 4012 10 4015 10 4012 10 4016 10 4015 10 3834 6397 4017 6397 4014 6397 4016 10 4018 10 4015 10 4018 10 4019 10 4015 10 3834 6398 4020 6398 4017 6398 4018 10 4021 10 4019 10 4021 10 4022 10 4019 10 3834 6399 4023 6399 4020 6399 4024 6400 4022 6400 4021 6400 4024 6401 4025 6401 4022 6401 4026 6402 4025 6402 4024 6402 4026 10 4027 10 4025 10 4028 6403 4027 6403 4026 6403 4028 6404 4029 6404 4027 6404 4030 6405 4029 6405 4028 6405 4031 10 4029 10 4030 10 4031 10 4032 10 4029 10 4033 6406 4032 6406 4031 6406 4034 10 4032 10 4033 10 4034 6407 4035 6407 4032 6407 4036 6408 4035 6408 4034 6408 4037 6409 4035 6409 4036 6409 3834 6410 4038 6410 4023 6410 4035 6411 4037 6411 4039 6411 4040 6412 4038 6412 3834 6412 4035 6413 4039 6413 4040 6413 4041 6414 4035 6414 4040 6414 4041 6415 4040 6415 3834 6415 4041 6416 3834 6416 3841 6416 4042 6417 4041 6417 3841 6417 4043 6418 3841 6418 3842 6418 4043 6419 4042 6419 3841 6419 3902 6420 3910 6420 3989 6420 3989 6421 3910 6421 4044 6421 3910 6422 3913 6422 4044 6422 4044 6423 3913 6423 4045 6423 3767 6424 3671 6424 3773 6424 3671 6425 3675 6425 3773 6425 3773 6426 3675 6426 3779 6426 3675 6427 3678 6427 3779 6427 3779 6428 3678 6428 3782 6428 3678 6429 3683 6429 3782 6429 3782 6430 3683 6430 3787 6430 3683 6431 3655 6431 3787 6431 3787 6432 3655 6432 3758 6432 3655 6433 3651 6433 3758 6433 3758 6434 3651 6434 3756 6434 3756 6435 3648 6435 3754 6435 3651 6436 3648 6436 3756 6436 3754 6437 3647 6437 3751 6437 3648 6438 3647 6438 3754 6438 3647 6439 3644 6439 3751 6439 3751 6440 3644 6440 3749 6440 3644 6441 3645 6441 3749 6441 3749 6442 3645 6442 3750 6442 3645 6443 3646 6443 3750 6443 3750 6444 3646 6444 3752 6444 3646 6445 3654 6445 3752 6445 3752 6446 3654 6446 3760 6446 3760 6447 3657 6447 3762 6447 3654 6448 3657 6448 3760 6448 3762 6449 3657 6449 3765 6449 3657 6450 3664 6450 3765 6450 3765 6451 3664 6451 3767 6451 3664 6452 3671 6452 3767 6452 3745 6453 3639 6453 3742 6453 3639 6454 3635 6454 3742 6454 3742 6455 3635 6455 3737 6455 3635 6456 3633 6456 3737 6456 3633 6457 3636 6457 3737 6457 3737 6458 3636 6458 3740 6458 3636 6459 3640 6459 3740 6459 3740 6460 3640 6460 3746 6460 3640 6461 3643 6461 3746 6461 3643 6462 3661 6462 3746 6462 3746 6463 3661 6463 3768 6463 3768 6464 3661 6464 3730 6464 3661 6465 3627 6465 3730 6465 3730 6466 3627 6466 3728 6466 3627 6467 3625 6467 3728 6467 3728 6468 3625 6468 3726 6468 3625 6469 3623 6469 3726 6469 3726 6470 3623 6470 3724 6470 3623 6471 3624 6471 3724 6471 3724 6472 3624 6472 3725 6472 3624 6473 3626 6473 3725 6473 3725 6474 3626 6474 3727 6474 3626 6475 3628 6475 3727 6475 3727 6476 3628 6476 3731 6476 3628 6477 3629 6477 3731 6477 3731 6478 3629 6478 3732 6478 3629 6479 3631 6479 3732 6479 3732 6480 3631 6480 3735 6480 3735 6481 3631 6481 3745 6481 3631 6482 3639 6482 3745 6482 3784 6483 3691 6483 3797 6483 3797 6484 3689 6484 3792 6484 3691 6485 3689 6485 3797 6485 3689 6486 3688 6486 3792 6486 3792 6487 3688 6487 3793 6487 3688 6488 3687 6488 3793 6488 3793 6489 3687 6489 3794 6489 3687 6490 3686 6490 3794 6490 3794 6491 3686 6491 3795 6491 3686 6492 3676 6492 3795 6492 3676 6493 3673 6493 3795 6493 3795 6494 3673 6494 3777 6494 3673 6495 3667 6495 3777 6495 3777 6496 3667 6496 3774 6496 3774 6497 3667 6497 3771 6497 3667 6498 3665 6498 3771 6498 3665 6499 3660 6499 3771 6499 3771 6500 3660 6500 3769 6500 3660 6501 3662 6501 3769 6501 3769 6502 3662 6502 3770 6502 3662 6503 3666 6503 3770 6503 3770 6504 3666 6504 3772 6504 3666 6505 3669 6505 3772 6505 3772 6506 3669 6506 3776 6506 3669 6507 3674 6507 3776 6507 3776 6508 3674 6508 3781 6508 3674 6509 3677 6509 3781 6509 3781 6510 3680 6510 3784 6510 3677 6511 3680 6511 3781 6511 3680 6512 3691 6512 3784 6512 3816 6513 3713 6513 3817 6513 3713 6514 3714 6514 3817 6514 3817 6515 3714 6515 3818 6515 3714 6516 3716 6516 3818 6516 3818 6517 3716 6517 3820 6517 3716 6518 3718 6518 3820 6518 3820 6519 3718 6519 3821 6519 3718 6520 3708 6520 3821 6520 3821 6521 3708 6521 3813 6521 3708 6522 3707 6522 3813 6522 3813 6523 3707 6523 3811 6523 3811 6524 3705 6524 3808 6524 3707 6525 3705 6525 3811 6525 3705 6526 3702 6526 3808 6526 3808 6527 3702 6527 3806 6527 3702 6528 3698 6528 3806 6528 3806 6529 3698 6529 3804 6529 3698 6530 3700 6530 3804 6530 3804 6531 3700 6531 3807 6531 3700 6532 3704 6532 3807 6532 3807 6533 3704 6533 3809 6533 3704 6534 3710 6534 3809 6534 3809 6535 3710 6535 3812 6535 3710 6536 3711 6536 3812 6536 3812 6537 3711 6537 3814 6537 3814 6538 3713 6538 3816 6538 3711 6539 3713 6539 3814 6539 3791 6540 3695 6540 3802 6540 3696 6541 3695 6541 3791 6541 3695 6542 3697 6542 3802 6542 3802 6543 3697 6543 3805 6543 3697 6544 3701 6544 3805 6544 3805 6545 3701 6545 3803 6545 3701 6546 3699 6546 3803 6546 3681 6547 3803 6547 3699 6547 3786 6548 3803 6548 3681 6548 3658 6549 3764 6549 3668 6549 3764 6550 3775 6550 3668 6550 3668 6551 3778 6551 3672 6551 3775 6552 3778 6552 3668 6552 3672 6553 3783 6553 3679 6553 3778 6554 3783 6554 3672 6554 3679 6555 3783 6555 3681 6555 3783 6556 3786 6556 3681 6556 3743 6557 3764 6557 3658 6557 3743 6558 3658 6558 3637 6558 3684 6559 3790 6559 3685 6559 3790 6560 3789 6560 3685 6560 3685 6561 3763 6561 3659 6561 3789 6562 3763 6562 3685 6562 3659 6563 3763 6563 3652 6563 3763 6564 3757 6564 3652 6564 3652 6565 3757 6565 3650 6565 3757 6566 3755 6566 3650 6566 3791 6567 3790 6567 3696 6567 3696 6568 3790 6568 3684 6568 3743 6569 3637 6569 3739 6569 3637 6570 3634 6570 3739 6570 3739 6571 3634 6571 3738 6571 3634 6572 3632 6572 3738 6572 3738 6573 3632 6573 3741 6573 3632 6574 3638 6574 3741 6574 3741 6575 3638 6575 3744 6575 3650 6576 3744 6576 3638 6576 3755 6577 3744 6577 3650 6577 3851 6578 4046 6578 3837 6578 3837 6579 4046 6579 3835 6579 3835 6580 4046 6580 3836 6580 4046 6581 4047 6581 3836 6581 3836 6582 4047 6582 3838 6582 4047 6583 4048 6583 3838 6583 3914 6584 3935 6584 4049 6584 3914 6585 3909 6585 3935 6585 3916 6586 3914 6586 4049 6586 3916 6587 4049 6587 4050 6587 3915 6588 4050 6588 4051 6588 3915 6589 3916 6589 4050 6589 3894 6590 3887 6590 3886 6590 3893 6591 3894 6591 3886 6591 3893 6592 3886 6592 3885 6592 3892 6593 3893 6593 3885 6593 3892 6594 3885 6594 3884 6594 3891 6595 3892 6595 3884 6595 3890 6596 3891 6596 3884 6596 3889 6597 3884 6597 3883 6597 3889 6598 3890 6598 3884 6598 4043 6599 3889 6599 3883 6599 4042 6600 4043 6600 3883 6600 4042 6601 3883 6601 3882 6601 4041 6602 4042 6602 3882 6602 4035 6603 3882 6603 4048 6603 4035 6604 4041 6604 3882 6604 4035 6605 4048 6605 4047 6605 4032 6606 4047 6606 4046 6606 4032 6607 4035 6607 4047 6607 4032 6608 4046 6608 3851 6608 4032 6609 3851 6609 3855 6609 4029 6610 4032 6610 3855 6610 3968 6611 3962 6611 3961 6611 3967 6612 3968 6612 3961 6612 3967 6613 3961 6613 3960 6613 3967 6614 3960 6614 3959 6614 3966 6615 3967 6615 3959 6615 3966 6616 3959 6616 3958 6616 3965 6617 3966 6617 3958 6617 3965 6618 3958 6618 4051 6618 3965 6619 4051 6619 4050 6619 3964 6620 4050 6620 4049 6620 3964 6621 3965 6621 4050 6621 3964 6622 4049 6622 3935 6622 4045 6623 3964 6623 3935 6623 4044 6624 4045 6624 3935 6624 4044 6625 3935 6625 3939 6625 3989 6626 4044 6626 3939 6626 3984 6627 3989 6627 3939 6627 3944 6628 3984 6628 3939 6628 3895 6629 3759 6629 3653 6629 3895 6630 3653 6630 3888 6630 3895 6631 3888 6631 3887 6631 3894 6632 3895 6632 3887 6632 3759 6633 3761 6633 3653 6633 3653 6634 3761 6634 3656 6634 3656 6635 3766 6635 3663 6635 3761 6636 3766 6636 3656 6636 3663 6637 3766 6637 3670 6637 3766 6638 3780 6638 3670 6638 3670 6639 3785 6639 3682 6639 3780 6640 3785 6640 3670 6640 3785 6641 3788 6641 3682 6641 3984 6642 3949 6642 3981 6642 3944 6643 3949 6643 3984 6643 3962 6644 3968 6644 3969 6644 3963 6645 3962 6645 3969 6645 3822 6646 3963 6646 3969 6646 3822 6647 3969 6647 3717 6647 3822 6648 3717 6648 3819 6648 3717 6649 3715 6649 3819 6649 3819 6650 3715 6650 3815 6650 3715 6651 3712 6651 3815 6651 3712 6652 3709 6652 3815 6652 3815 6653 3709 6653 3810 6653 3709 6654 3706 6654 3810 6654 3810 6655 3694 6655 3801 6655 3706 6656 3694 6656 3810 6656 4027 6657 4029 6657 3860 6657 3860 6658 4029 6658 3855 6658 3682 6659 3788 6659 3801 6659 3682 6660 3801 6660 3694 6660 4009 6661 4081 6661 4007 6661 4081 6662 4052 6662 4007 6662 4007 6663 4052 6663 4005 6663 4005 6664 4053 6664 4003 6664 4052 6665 4053 6665 4005 6665 4053 6666 4054 6666 4003 6666 4003 6667 4054 6667 4001 6667 4054 6668 4055 6668 4001 6668 4001 6669 4055 6669 4002 6669 4055 6670 4056 6670 4002 6670 4002 6671 4056 6671 4004 6671 4056 6672 4057 6672 4004 6672 4004 6673 4057 6673 4006 6673 4057 6674 4058 6674 4006 6674 4006 6675 4058 6675 4008 6675 4008 6676 4059 6676 4010 6676 4058 6677 4059 6677 4008 6677 4059 6678 4060 6678 4010 6678 4010 6679 4060 6679 4012 6679 4060 6680 4061 6680 4012 6680 4012 6681 4061 6681 4016 6681 4061 6682 4062 6682 4016 6682 4016 6683 4062 6683 4018 6683 4062 6684 4063 6684 4018 6684 4018 6685 4063 6685 4021 6685 4021 6686 4064 6686 4024 6686 4063 6687 4064 6687 4021 6687 4024 6688 4065 6688 4026 6688 4064 6689 4065 6689 4024 6689 4026 6690 4066 6690 4028 6690 4065 6691 4066 6691 4026 6691 4028 6692 4067 6692 4030 6692 4066 6693 4067 6693 4028 6693 4030 6694 4068 6694 4031 6694 4067 6695 4068 6695 4030 6695 4031 6696 4069 6696 4033 6696 4068 6697 4069 6697 4031 6697 4033 6698 4070 6698 4034 6698 4069 6699 4070 6699 4033 6699 4034 6700 4071 6700 4036 6700 4070 6701 4071 6701 4034 6701 4036 6702 4072 6702 4037 6702 4071 6703 4072 6703 4036 6703 4072 6704 4073 6704 4037 6704 4037 6705 4073 6705 4039 6705 4073 6706 4074 6706 4039 6706 4039 6707 4074 6707 4040 6707 4074 6708 4075 6708 4040 6708 4040 6709 4075 6709 4038 6709 4038 6710 4076 6710 4023 6710 4075 6711 4076 6711 4038 6711 4023 6712 4077 6712 4020 6712 4076 6713 4077 6713 4023 6713 4077 6714 4078 6714 4020 6714 4020 6715 4078 6715 4017 6715 4017 6716 4079 6716 4014 6716 4078 6717 4079 6717 4017 6717 4014 6718 4080 6718 4011 6718 4079 6719 4080 6719 4014 6719 4011 6720 4081 6720 4009 6720 4080 6721 4081 6721 4011 6721 4070 10 4082 10 4071 10 4070 10 4083 10 4082 10 4082 6722 4084 6722 4071 6722 4069 10 4083 10 4070 10 4071 10 4084 10 4072 10 4069 10 4085 10 4083 10 4068 10 4085 10 4069 10 4072 6723 4084 6723 4073 6723 4084 6724 4086 6724 4073 6724 4067 10 4087 10 4068 10 4068 10 4087 10 4085 10 4073 10 4086 10 4074 10 4086 10 4088 10 4074 10 4066 6725 4087 6725 4067 6725 4066 10 4089 10 4087 10 4074 10 4088 10 4075 10 4065 6726 4089 6726 4066 6726 4088 10 4090 10 4075 10 4065 6727 4091 6727 4089 6727 4064 6728 4091 6728 4065 6728 4075 10 4090 10 4076 10 4090 10 4092 10 4076 10 4063 10 4091 10 4064 10 4076 10 4092 10 4077 10 4063 10 4093 10 4091 10 4092 10 4094 10 4077 10 4063 10 4062 10 4093 10 4094 6729 4078 6729 4077 6729 4093 10 4062 10 4095 10 4096 6730 4078 6730 4094 6730 4062 10 4061 10 4095 10 4096 6731 4079 6731 4078 6731 4095 10 4061 10 4097 10 4061 10 4060 10 4097 10 4096 10 4080 10 4079 10 4097 6732 4060 6732 4098 6732 4099 10 4080 10 4096 10 4060 10 4059 10 4098 10 4099 6733 4081 6733 4080 6733 4059 10 4058 10 4098 10 4100 10 4052 10 4099 10 4099 10 4052 10 4081 10 4098 10 4058 10 4101 10 4058 10 4057 10 4101 10 4102 6734 4052 6734 4100 6734 4102 6735 4053 6735 4052 6735 4057 6736 4056 6736 4101 6736 4101 10 4056 10 4103 10 4104 6737 4053 6737 4102 6737 4104 6738 4054 6738 4053 6738 4056 6739 4055 6739 4103 6739 4103 10 4055 10 4104 10 4104 6740 4055 6740 4054 6740 4105 6741 4106 6741 3929 6741 3929 6742 4106 6742 3927 6742 4106 6743 4107 6743 3927 6743 3927 6744 4107 6744 3926 6744 3926 6745 4107 6745 3925 6745 4107 6746 4108 6746 3925 6746 4108 6747 4109 6747 3925 6747 3925 6748 4109 6748 3928 6748 4109 6749 4110 6749 3928 6749 3928 6750 4110 6750 3930 6750 4110 6751 4111 6751 3930 6751 3930 6752 4111 6752 3934 6752 4111 6753 4112 6753 3934 6753 3934 6754 4112 6754 3936 6754 4112 6755 4113 6755 3936 6755 3936 6756 4113 6756 3937 6756 4113 6757 4114 6757 3937 6757 3937 6758 4115 6758 3940 6758 4114 6759 4115 6759 3937 6759 3940 6760 4116 6760 3942 6760 4115 6761 4116 6761 3940 6761 3942 6762 4117 6762 3946 6762 4116 6763 4117 6763 3942 6763 4117 6764 4118 6764 3946 6764 3946 6765 4118 6765 3950 6765 4118 6766 4119 6766 3950 6766 3950 6767 4119 6767 3954 6767 4119 6768 4120 6768 3954 6768 3954 6769 4120 6769 3956 6769 4120 6770 4121 6770 3956 6770 3956 6771 4121 6771 3951 6771 4121 6772 4122 6772 3951 6772 3951 6773 4122 6773 3948 6773 4122 6774 4123 6774 3948 6774 3948 6775 4123 6775 3945 6775 4123 6776 4124 6776 3945 6776 3945 6777 4124 6777 3943 6777 3943 6778 4125 6778 3941 6778 4124 6779 4125 6779 3943 6779 3941 6780 4126 6780 3938 6780 4125 6781 4126 6781 3941 6781 3938 6782 4127 6782 3932 6782 4126 6783 4127 6783 3938 6783 3932 6784 4128 6784 3933 6784 4127 6785 4128 6785 3932 6785 3933 6786 4128 6786 3931 6786 4128 6787 4105 6787 3931 6787 3931 6788 4105 6788 3929 6788 4120 10 4129 10 4121 10 4119 10 4129 10 4120 10 4129 6789 4130 6789 4121 6789 4119 6790 4131 6790 4129 6790 4121 10 4130 10 4122 10 4130 10 4132 10 4122 10 4118 10 4131 10 4119 10 4118 6791 4133 6791 4131 6791 4117 6792 4133 6792 4118 6792 4122 10 4132 10 4123 10 4132 10 4134 10 4123 10 4117 10 4135 10 4133 10 4123 10 4134 10 4124 10 4116 10 4135 10 4117 10 4134 10 4136 10 4124 10 4124 6793 4136 6793 4125 6793 4116 6794 4137 6794 4135 6794 4115 6795 4137 6795 4116 6795 4136 10 4138 10 4125 10 4125 6796 4138 6796 4126 6796 4115 6797 4139 6797 4137 6797 4114 6798 4139 6798 4115 6798 4138 6799 4140 6799 4126 6799 4140 6800 4127 6800 4126 6800 4114 10 4113 10 4139 10 4139 6801 4113 6801 4141 6801 4113 10 4112 10 4141 10 4140 10 4128 10 4127 10 4142 6802 4128 6802 4140 6802 4141 10 4112 10 4143 10 4144 6803 4128 6803 4142 6803 4112 10 4111 10 4143 10 4144 10 4105 10 4128 10 4143 6804 4111 6804 4145 6804 4111 10 4110 10 4145 10 4146 6805 4105 6805 4144 6805 4146 10 4106 10 4105 10 4145 6806 4110 6806 4147 6806 4148 10 4106 10 4146 10 4110 10 4109 10 4147 10 4148 10 4107 10 4106 10 4149 10 4107 10 4148 10 4147 10 4108 10 4149 10 4109 10 4108 10 4147 10 4149 10 4108 10 4107 10 3880 6807 4086 6807 3857 6807 4088 6808 4086 6808 3880 6808 3857 6809 4084 6809 3854 6809 4086 6810 4084 6810 3857 6810 4084 6811 4082 6811 3854 6811 3854 6812 4082 6812 3852 6812 4082 6813 4083 6813 3852 6813 3852 6814 4083 6814 3853 6814 3853 6815 4085 6815 3856 6815 4083 6816 4085 6816 3853 6816 3856 6817 4087 6817 3858 6817 4085 6818 4087 6818 3856 6818 3858 6819 4089 6819 3859 6819 4087 6820 4089 6820 3858 6820 3859 6821 4089 6821 3861 6821 4089 6822 4091 6822 3861 6822 3861 6823 4091 6823 3864 6823 4091 6824 4093 6824 3864 6824 3864 6825 4093 6825 3866 6825 4093 6826 4095 6826 3866 6826 3866 6827 4095 6827 3868 6827 4095 6828 4097 6828 3868 6828 4097 6829 4098 6829 3868 6829 3868 6830 4098 6830 3870 6830 3870 6831 4098 6831 3875 6831 4098 6832 4101 6832 3875 6832 3875 6833 4101 6833 3876 6833 4101 6834 4103 6834 3876 6834 4103 6835 4104 6835 3876 6835 3876 6836 4104 6836 3877 6836 3877 6837 4102 6837 3878 6837 4104 6838 4102 6838 3877 6838 4102 6839 4100 6839 3878 6839 3878 6840 4100 6840 3879 6840 4100 6841 4099 6841 3879 6841 3879 6842 4096 6842 3871 6842 4099 6843 4096 6843 3879 6843 3871 6844 4096 6844 3872 6844 4096 6845 4094 6845 3872 6845 3872 6846 4094 6846 3873 6846 4094 6847 4092 6847 3873 6847 4092 6848 4090 6848 3873 6848 3873 6849 4090 6849 3874 6849 4090 6850 4088 6850 3874 6850 3874 6851 4088 6851 3880 6851 4134 6852 4132 6852 3982 6852 3982 6853 4132 6853 3978 6853 4132 6854 4130 6854 3978 6854 3978 6855 4130 6855 3971 6855 4130 6856 4129 6856 3971 6856 3971 6857 4129 6857 3973 6857 4129 6858 4131 6858 3973 6858 3973 6859 4131 6859 3976 6859 3976 6860 4133 6860 3980 6860 4131 6861 4133 6861 3976 6861 3980 6819 4135 6819 3983 6819 4133 6862 4135 6862 3980 6862 3983 6821 4135 6821 3986 6821 4135 6863 4137 6863 3986 6863 3986 6864 4137 6864 3988 6864 4137 6865 4139 6865 3988 6865 3988 6866 4139 6866 3990 6866 4139 6867 4141 6867 3990 6867 3990 6868 4141 6868 3992 6868 4141 6869 4143 6869 3992 6869 3992 6870 4143 6870 3995 6870 4143 6871 4145 6871 3995 6871 3995 6872 4145 6872 3996 6872 4145 6873 4147 6873 3996 6873 3996 6874 4147 6874 3997 6874 4147 6875 4149 6875 3997 6875 3997 6876 4149 6876 3998 6876 4149 6877 4148 6877 3998 6877 3998 6878 4148 6878 3999 6878 4148 6879 4146 6879 3999 6879 3999 6880 4146 6880 4000 6880 4000 6881 4144 6881 3994 6881 4146 6882 4144 6882 4000 6882 3994 6883 4142 6883 3993 6883 4144 6884 4142 6884 3994 6884 4142 6885 4140 6885 3993 6885 3993 6886 4140 6886 3991 6886 3991 6887 4140 6887 3987 6887 4140 6888 4138 6888 3987 6888 4138 6889 4136 6889 3987 6889 3987 6890 4136 6890 3985 6890 4136 6891 4134 6891 3985 6891 3985 6892 4134 6892 3982 6892 3979 6893 3981 6893 3949 6893 3979 6894 3949 6894 3952 6894 3974 6895 3979 6895 3952 6895 3974 6896 3952 6896 3955 6896 3972 6897 3974 6897 3955 6897 3972 6898 3955 6898 3957 6898 3970 6899 3972 6899 3957 6899 3970 6900 3957 6900 3953 6900 3975 6901 3970 6901 3953 6901 3975 6902 3953 6902 3947 6902 3977 6903 3975 6903 3947 6903 4025 6904 4027 6904 3860 6904 4025 6905 3860 6905 3862 6905 4022 6906 4025 6906 3862 6906 4022 6907 3862 6907 3863 6907 4022 6908 3863 6908 3865 6908 4019 6909 4022 6909 3865 6909 4019 6910 3865 6910 3867 6910 4015 6911 4019 6911 3867 6911 4013 6912 3867 6912 3869 6912 4013 6913 4015 6913 3867 6913 3881 6914 4013 6914 3869 6914

+
+ + + +

4154 6915 4155 6915 4156 6915 4154 6916 4156 6916 4157 6916 4158 6917 4154 6917 4157 6917 4158 6918 4157 6918 4159 6918 4158 6919 4159 6919 4160 6919 4161 6920 4158 6920 4160 6920 4161 6921 4160 6921 4162 6921 4163 6922 4161 6922 4162 6922 4163 6923 4162 6923 4164 6923 4163 6924 4164 6924 4165 6924 4166 6925 4163 6925 4165 6925 4166 6926 4165 6926 4694 6926 4166 6927 4694 6927 4167 6927 4169 6928 4168 6928 4170 6928 4168 6929 4171 6929 4170 6929 4170 6930 4171 6930 4172 6930 4171 6931 4173 6931 4172 6931 4172 6932 4173 6932 4174 6932 4173 6933 4175 6933 4174 6933 4174 6934 4175 6934 4176 6934 4175 6935 4177 6935 4176 6935 4176 6936 4177 6936 4178 6936 4177 6937 4179 6937 4178 6937 4178 6938 4179 6938 4180 6938 4179 6939 4181 6939 4180 6939 4181 6940 4182 6940 4180 6940 4180 6941 4182 6941 4183 6941 4182 6942 4184 6942 4183 6942 4183 6943 4184 6943 4185 6943 4184 6944 4186 6944 4185 6944 4185 6945 4186 6945 4187 6945 4186 6946 4188 6946 4187 6946 4187 6947 4188 6947 4189 6947 4188 6948 4190 6948 4189 6948 4189 6949 4190 6949 4191 6949 4190 6950 4192 6950 4191 6950 4191 6951 4192 6951 4193 6951 4192 6952 4194 6952 4193 6952 4193 6953 4194 6953 4195 6953 4194 6954 4196 6954 4195 6954 4195 6955 4196 6955 4197 6955 4196 6956 4198 6956 4197 6956 4197 6957 4198 6957 4199 6957 4198 6958 4200 6958 4199 6958 4199 6959 4200 6959 4201 6959 4200 6960 4202 6960 4201 6960 4201 6961 4202 6961 4203 6961 4202 6962 4204 6962 4203 6962 4203 6963 4204 6963 4205 6963 4204 6964 4206 6964 4205 6964 4205 6965 4206 6965 4169 6965 4206 6966 4168 6966 4169 6966 4247 6967 4208 6967 4207 6967 4207 6968 4208 6968 4209 6968 4208 6969 4210 6969 4209 6969 4209 6970 4210 6970 4211 6970 4210 6971 4212 6971 4211 6971 4211 6972 4212 6972 4213 6972 4212 6973 4214 6973 4213 6973 4213 6974 4214 6974 4215 6974 4214 6975 4216 6975 4215 6975 4215 6976 4217 6976 4218 6976 4216 6977 4217 6977 4215 6977 4218 6978 4217 6978 4219 6978 4217 6979 4220 6979 4219 6979 4219 6980 4220 6980 4221 6980 4220 6981 4222 6981 4221 6981 4221 6982 4222 6982 4223 6982 4222 6983 4224 6983 4223 6983 4223 6984 4224 6984 4225 6984 4225 6985 4224 6985 4226 6985 4224 6986 4227 6986 4226 6986 4227 6987 4228 6987 4226 6987 4226 6988 4228 6988 4229 6988 4229 6989 4228 6989 4230 6989 4228 6990 4231 6990 4230 6990 4231 6991 4232 6991 4230 6991 4230 6992 4232 6992 4233 6992 4233 6993 4232 6993 4234 6993 4232 6994 4235 6994 4234 6994 4234 6995 4235 6995 4236 6995 4235 6996 4237 6996 4236 6996 4236 6997 4237 6997 4238 6997 4237 6998 4239 6998 4238 6998 4238 6999 4239 6999 4240 6999 4239 7000 4241 7000 4240 7000 4240 7001 4241 7001 4242 7001 4241 7002 4243 7002 4242 7002 4242 7003 4243 7003 4244 7003 4243 7004 4245 7004 4244 7004 4244 7005 4245 7005 4246 7005 4245 7006 4247 7006 4246 7006 4246 7007 4247 7007 4207 7007 4248 7008 4249 7008 4250 7008 4286 7009 4249 7009 4248 7009 4249 7010 4251 7010 4250 7010 4250 7011 4251 7011 4252 7011 4251 7012 4253 7012 4252 7012 4252 7013 4253 7013 4254 7013 4253 7014 4255 7014 4254 7014 4254 7015 4255 7015 4256 7015 4256 7016 4257 7016 4258 7016 4255 7017 4257 7017 4256 7017 4257 7018 4259 7018 4258 7018 4258 7019 4259 7019 4260 7019 4259 7020 4261 7020 4260 7020 4260 7021 4261 7021 4262 7021 4262 7022 4261 7022 4263 7022 4261 7023 4264 7023 4263 7023 4263 7024 4264 7024 4265 7024 4264 7025 4266 7025 4265 7025 4265 7026 4266 7026 4267 7026 4266 7027 4268 7027 4267 7027 4267 7028 4268 7028 4269 7028 4268 7029 4270 7029 4269 7029 4269 7030 4270 7030 4271 7030 4270 7031 4272 7031 4271 7031 4271 7032 4272 7032 4273 7032 4272 7033 4274 7033 4273 7033 4273 7034 4274 7034 4275 7034 4274 7035 4276 7035 4275 7035 4275 7036 4276 7036 4277 7036 4277 7037 4278 7037 4279 7037 4276 7038 4278 7038 4277 7038 4279 7039 4278 7039 4280 7039 4278 7040 4281 7040 4280 7040 4280 7041 4281 7041 4282 7041 4281 7042 4283 7042 4282 7042 4283 7043 4284 7043 4282 7043 4282 7044 4284 7044 4285 7044 4284 7045 4286 7045 4285 7045 4285 7046 4286 7046 4248 7046 4327 7047 4288 7047 4287 7047 4287 7048 4288 7048 4289 7048 4289 7049 4290 7049 4291 7049 4288 7050 4290 7050 4289 7050 4291 7051 4290 7051 4292 7051 4290 7052 4293 7052 4292 7052 4292 7053 4293 7053 4294 7053 4293 7054 4295 7054 4294 7054 4294 7055 4295 7055 4296 7055 4295 7056 4297 7056 4296 7056 4296 7057 4297 7057 4298 7057 4297 7058 4299 7058 4298 7058 4298 7059 4299 7059 4300 7059 4299 7060 4301 7060 4300 7060 4300 7061 4301 7061 4302 7061 4301 7062 4303 7062 4302 7062 4302 7063 4303 7063 4304 7063 4304 7064 4303 7064 4305 7064 4303 7065 4306 7065 4305 7065 4305 7066 4306 7066 4307 7066 4306 7067 4308 7067 4307 7067 4307 7068 4308 7068 4309 7068 4308 7069 4310 7069 4309 7069 4309 7070 4310 7070 4311 7070 4310 7071 4312 7071 4311 7071 4311 7072 4312 7072 4313 7072 4313 7073 4314 7073 4315 7073 4312 7074 4314 7074 4313 7074 4314 7075 4316 7075 4315 7075 4315 7076 4316 7076 4317 7076 4317 7077 4316 7077 4318 7077 4316 7078 4319 7078 4318 7078 4318 7079 4319 7079 4320 7079 4319 7080 4321 7080 4320 7080 4320 7081 4321 7081 4322 7081 4321 7082 4323 7082 4322 7082 4322 7083 4323 7083 4324 7083 4323 7084 4325 7084 4324 7084 4324 7085 4325 7085 4326 7085 4325 7086 4327 7086 4326 7086 4326 7087 4327 7087 4287 7087 4328 7088 4329 7088 5159 7088 5159 7089 4329 7089 5158 7089 4330 7090 4331 7090 4332 7090 4333 7091 4330 7091 4332 7091 4334 7092 4332 7092 4335 7092 4334 7093 4333 7093 4332 7093 4336 7094 4334 7094 4335 7094 4336 7095 4335 7095 4337 7095 4338 7096 4336 7096 4337 7096 4338 7097 4337 7097 4339 7097 4338 7098 4339 7098 4340 7098 4341 7099 4338 7099 4340 7099 4341 7100 4340 7100 4342 7100 4343 7101 4341 7101 4342 7101 4344 7102 4330 7102 4345 7102 4344 7103 4331 7103 4330 7103 4346 7104 4329 7104 4328 7104 4346 7105 4328 7105 4347 7105 4348 7106 4346 7106 4347 7106 4348 7107 4347 7107 4349 7107 4350 7108 4348 7108 4349 7108 4350 7109 4349 7109 4351 7109 4352 7110 4350 7110 4351 7110 4352 7111 4351 7111 4353 7111 4354 7112 4353 7112 4355 7112 4354 7113 4352 7113 4353 7113 4354 7114 4355 7114 4356 7114 4357 7115 4354 7115 4356 7115 4356 7116 4358 7116 4359 7116 4356 7117 4359 7117 4357 7117 4360 272 4323 272 4361 272 4360 7118 4325 7118 4323 7118 4362 272 4325 272 4360 272 4323 272 4321 272 4361 272 4361 7119 4321 7119 4363 7119 4364 272 4325 272 4362 272 4363 7120 4321 7120 4365 7120 4364 7121 4327 7121 4325 7121 4321 272 4319 272 4365 272 4366 272 4327 272 4364 272 4365 272 4319 272 4367 272 4368 272 4327 272 4366 272 4319 7122 4316 7122 4367 7122 4368 7123 4288 7123 4327 7123 4370 7124 4288 7124 4368 7124 4367 7125 4316 7125 4369 7125 4369 272 4316 272 4371 272 4370 7126 4290 7126 4288 7126 4373 272 4290 272 4370 272 4316 272 4314 272 4371 272 4371 272 4314 272 4372 272 4314 7127 4312 7127 4372 7127 4290 272 4374 272 4293 272 4373 272 4374 272 4290 272 4312 7128 4375 7128 4372 7128 4293 272 4374 272 4295 272 4374 272 4376 272 4295 272 4310 272 4375 272 4312 272 4310 7129 4377 7129 4375 7129 4295 272 4378 272 4297 272 4376 7130 4378 7130 4295 7130 4310 7131 4379 7131 4377 7131 4308 272 4379 272 4310 272 4378 7132 4380 7132 4297 7132 4306 272 4381 272 4308 272 4308 7133 4381 7133 4379 7133 4380 272 4382 272 4297 272 4297 7134 4382 7134 4299 7134 4306 7135 4383 7135 4381 7135 4382 272 4384 272 4299 272 4303 7136 4383 7136 4306 7136 4303 7137 4385 7137 4383 7137 4299 272 4384 272 4301 272 4384 7138 4386 7138 4301 7138 4303 272 4386 272 4385 272 4301 272 4386 272 4303 272 4379 7139 4381 7139 4387 7139 4387 7140 4381 7140 4388 7140 4381 7141 4383 7141 4388 7141 4388 7142 4383 7142 4389 7142 4383 7143 4385 7143 4389 7143 4389 7144 4385 7144 4390 7144 4385 7145 4386 7145 4390 7145 4390 7146 4386 7146 4391 7146 4391 7147 4384 7147 4392 7147 4386 7148 4384 7148 4391 7148 4392 7149 4382 7149 4393 7149 4384 7150 4382 7150 4392 7150 4393 7151 4380 7151 4394 7151 4382 7152 4380 7152 4393 7152 4380 7153 4378 7153 4394 7153 4394 7154 4378 7154 4395 7154 4378 7155 4376 7155 4395 7155 4395 7156 4376 7156 4396 7156 4376 7157 4374 7157 4396 7157 4396 7158 4374 7158 4397 7158 4374 7159 4373 7159 4397 7159 4397 7160 4373 7160 4398 7160 4373 7161 4370 7161 4398 7161 4398 7162 4370 7162 4399 7162 4370 7163 4368 7163 4399 7163 4368 7164 4366 7164 4399 7164 4399 7165 4366 7165 4400 7165 4366 7166 4364 7166 4400 7166 4400 7167 4364 7167 4401 7167 4364 7168 4362 7168 4401 7168 4401 7169 4362 7169 4402 7169 4402 7170 4362 7170 4403 7170 4362 7171 4360 7171 4403 7171 4360 7172 4361 7172 4403 7172 4403 7173 4361 7173 4404 7173 4404 7174 4363 7174 4405 7174 4361 7175 4363 7175 4404 7175 4363 7176 4365 7176 4405 7176 4405 7177 4365 7177 4406 7177 4406 7178 4365 7178 4407 7178 4365 7179 4367 7179 4407 7179 4407 7180 4367 7180 4408 7180 4367 7181 4369 7181 4408 7181 4369 7182 4371 7182 4408 7182 4408 7183 4371 7183 4409 7183 4409 7184 4372 7184 4410 7184 4371 7185 4372 7185 4409 7185 4410 7186 4375 7186 4411 7186 4372 7187 4375 7187 4410 7187 4411 7188 4377 7188 4412 7188 4375 7189 4377 7189 4411 7189 4412 7190 4379 7190 4413 7190 4377 7191 4379 7191 4412 7191 4413 7192 4379 7192 4387 7192 4414 272 4243 272 4415 272 4416 272 4243 272 4414 272 4243 7193 4241 7193 4415 7193 4415 7194 4241 7194 4417 7194 4416 7195 4245 7195 4243 7195 4418 272 4245 272 4416 272 4417 7196 4241 7196 4419 7196 4241 272 4239 272 4419 272 4420 7197 4247 7197 4418 7197 4418 7198 4247 7198 4245 7198 4419 7199 4239 7199 4421 7199 4422 272 4247 272 4420 272 4239 272 4237 272 4421 272 4421 272 4237 272 4423 272 4424 272 4247 272 4422 272 4424 7200 4208 7200 4247 7200 4237 7201 4235 7201 4423 7201 4423 7202 4235 7202 4425 7202 4426 272 4208 272 4424 272 4426 7203 4210 7203 4208 7203 4425 7204 4235 7204 4427 7204 4235 7205 4232 7205 4427 7205 4428 7206 4210 7206 4426 7206 4427 7207 4232 7207 4429 7207 4428 7208 4430 7208 4210 7208 4210 272 4430 272 4212 272 4232 272 4431 272 4429 272 4231 272 4431 272 4232 272 4212 7209 4430 7209 4214 7209 4231 7210 4432 7210 4431 7210 4430 7211 4433 7211 4214 7211 4228 272 4432 272 4231 272 4433 7212 4434 7212 4214 7212 4228 7213 4435 7213 4432 7213 4227 272 4435 272 4228 272 4214 272 4434 272 4216 272 4434 7214 4436 7214 4216 7214 4227 7215 4437 7215 4435 7215 4436 7216 4438 7216 4216 7216 4224 7217 4437 7217 4227 7217 4216 7218 4438 7218 4217 7218 4224 7219 4439 7219 4437 7219 4438 272 4440 272 4217 272 4224 272 4441 272 4439 272 4222 272 4441 272 4224 272 4217 7220 4440 7220 4220 7220 4440 7221 4442 7221 4220 7221 4220 7222 4441 7222 4222 7222 4220 272 4442 272 4441 272 4435 7223 4437 7223 4443 7223 4443 7224 4439 7224 4444 7224 4437 7225 4439 7225 4443 7225 4444 7226 4441 7226 4445 7226 4439 7227 4441 7227 4444 7227 4445 7228 4441 7228 4446 7228 4441 7229 4442 7229 4446 7229 4446 7230 4442 7230 4447 7230 4447 7231 4440 7231 4448 7231 4442 7232 4440 7232 4447 7232 4448 7233 4438 7233 4449 7233 4440 7234 4438 7234 4448 7234 4449 7235 4436 7235 4450 7235 4438 7236 4436 7236 4449 7236 4436 7237 4434 7237 4450 7237 4450 7238 4434 7238 4451 7238 4434 7239 4433 7239 4451 7239 4451 7240 4433 7240 4452 7240 4433 7241 4430 7241 4452 7241 4430 7242 4428 7242 4452 7242 4452 7243 4428 7243 4453 7243 4453 7244 4426 7244 4454 7244 4428 7245 4426 7245 4453 7245 4454 7246 4424 7246 4455 7246 4426 7247 4424 7247 4454 7247 4455 7248 4422 7248 4456 7248 4424 7249 4422 7249 4455 7249 4422 7250 4420 7250 4456 7250 4456 7251 4420 7251 4457 7251 4420 7252 4418 7252 4457 7252 4457 7253 4418 7253 4458 7253 4418 7254 4416 7254 4458 7254 4458 7255 4416 7255 4459 7255 4416 7256 4414 7256 4459 7256 4414 7257 4415 7257 4459 7257 4459 7258 4415 7258 4460 7258 4460 7259 4415 7259 4461 7259 4415 7260 4417 7260 4461 7260 4461 7261 4417 7261 4462 7261 4417 7262 4419 7262 4462 7262 4462 7263 4419 7263 4463 7263 4419 7264 4421 7264 4463 7264 4463 7265 4421 7265 4464 7265 4421 7266 4423 7266 4464 7266 4464 7267 4423 7267 4465 7267 4423 7268 4425 7268 4465 7268 4465 7269 4425 7269 4466 7269 4466 7270 4427 7270 4467 7270 4425 7271 4427 7271 4466 7271 4467 7272 4429 7272 4468 7272 4427 7273 4429 7273 4467 7273 4429 7274 4431 7274 4468 7274 4468 7275 4431 7275 4469 7275 4469 7276 4432 7276 4470 7276 4431 7277 4432 7277 4469 7277 4470 7278 4432 7278 4471 7278 4432 7279 4435 7279 4471 7279 4471 7280 4435 7280 4443 7280 4472 7281 4283 7281 4473 7281 4283 7282 4281 7282 4473 7282 4474 7283 4283 7283 4472 7283 4473 7284 4281 7284 4475 7284 4474 7285 4284 7285 4283 7285 4476 272 4284 272 4474 272 4281 272 4278 272 4475 272 4475 7286 4278 7286 4477 7286 4478 272 4286 272 4476 272 4476 7287 4286 7287 4284 7287 4477 272 4278 272 4479 272 4278 272 4276 272 4479 272 4480 272 4286 272 4478 272 4479 272 4276 272 4481 272 4482 272 4249 272 4480 272 4480 7288 4249 7288 4286 7288 4276 272 4274 272 4481 272 4481 7289 4274 7289 4483 7289 4482 7290 4251 7290 4249 7290 4484 272 4251 272 4482 272 4274 272 4272 272 4483 272 4486 7291 4251 7291 4484 7291 4483 7292 4272 7292 4485 7292 4486 272 4487 272 4251 272 4251 272 4487 272 4253 272 4272 272 4488 272 4485 272 4270 272 4488 272 4272 272 4487 7293 4489 7293 4253 7293 4253 272 4489 272 4255 272 4270 7294 4490 7294 4488 7294 4268 272 4490 272 4270 272 4489 272 4491 272 4255 272 4268 7295 4492 7295 4490 7295 4255 7296 4493 7296 4257 7296 4491 272 4493 272 4255 272 4266 272 4492 272 4268 272 4266 7297 4494 7297 4492 7297 4257 7298 4495 7298 4259 7298 4493 272 4495 272 4257 272 4266 7299 4496 7299 4494 7299 4495 272 4497 272 4259 272 4264 7300 4496 7300 4266 7300 4259 7301 4497 7301 4261 7301 4264 7302 4498 7302 4496 7302 4497 272 4499 272 4261 272 4261 7303 4498 7303 4264 7303 4261 7304 4499 7304 4498 7304 4492 7305 4494 7305 4500 7305 4500 7306 4494 7306 4501 7306 4494 7307 4496 7307 4501 7307 4501 7308 4496 7308 4502 7308 4496 7309 4498 7309 4502 7309 4502 7310 4498 7310 4503 7310 4498 7311 4499 7311 4503 7311 4503 7312 4499 7312 4504 7312 4499 7313 4497 7313 4504 7313 4504 7314 4497 7314 4505 7314 4505 7315 4495 7315 4506 7315 4497 7316 4495 7316 4505 7316 4506 7317 4493 7317 4507 7317 4495 7318 4493 7318 4506 7318 4507 7319 4491 7319 4508 7319 4493 7320 4491 7320 4507 7320 4491 7321 4489 7321 4508 7321 4508 7322 4489 7322 4509 7322 4489 7323 4487 7323 4509 7323 4509 7324 4486 7324 4510 7324 4487 7325 4486 7325 4509 7325 4510 7326 4484 7326 4511 7326 4486 7327 4484 7327 4510 7327 4484 7328 4482 7328 4511 7328 4511 7329 4482 7329 4512 7329 4482 7330 4480 7330 4512 7330 4512 7331 4480 7331 4513 7331 4480 7332 4478 7332 4513 7332 4513 7333 4478 7333 4514 7333 4478 7334 4476 7334 4514 7334 4514 7335 4476 7335 4515 7335 4476 7336 4474 7336 4515 7336 4515 7337 4474 7337 4516 7337 4474 7338 4472 7338 4516 7338 4472 7339 4473 7339 4516 7339 4516 7340 4473 7340 4517 7340 4517 7341 4475 7341 4518 7341 4473 7342 4475 7342 4517 7342 4475 7343 4477 7343 4518 7343 4518 7344 4477 7344 4519 7344 4477 7345 4479 7345 4519 7345 4519 7346 4479 7346 4520 7346 4479 7347 4481 7347 4520 7347 4520 7348 4481 7348 4521 7348 4521 7349 4483 7349 4522 7349 4481 7350 4483 7350 4521 7350 4522 7351 4485 7351 4523 7351 4483 7352 4485 7352 4522 7352 4523 7353 4488 7353 4524 7353 4485 7354 4488 7354 4523 7354 4524 7355 4490 7355 4525 7355 4488 7356 4490 7356 4524 7356 4525 7357 4492 7357 4526 7357 4490 7358 4492 7358 4525 7358 4526 7359 4492 7359 4500 7359 4204 272 4202 272 4527 272 4528 272 4204 272 4527 272 4527 272 4202 272 4529 272 4202 272 4200 272 4529 272 4529 272 4200 272 4530 272 4528 7360 4206 7360 4204 7360 4531 272 4206 272 4528 272 4532 7361 4206 7361 4531 7361 4530 7362 4200 7362 4533 7362 4532 7363 4168 7363 4206 7363 4200 7364 4198 7364 4533 7364 4535 272 4168 272 4532 272 4533 7365 4198 7365 4534 7365 4534 272 4198 272 4536 272 4537 272 4168 272 4535 272 4198 7366 4196 7366 4536 7366 4537 272 4171 272 4168 272 4536 272 4196 272 4538 272 4539 272 4171 272 4537 272 4196 7367 4194 7367 4538 7367 4539 272 4173 272 4171 272 4538 272 4194 272 4540 272 4539 7368 4541 7368 4173 7368 4541 272 4175 272 4173 272 4194 272 4542 272 4540 272 4192 272 4542 272 4194 272 4541 7369 4543 7369 4175 7369 4192 7370 4544 7370 4542 7370 4543 7371 4545 7371 4175 7371 4192 7372 4546 7372 4544 7372 4190 272 4546 272 4192 272 4175 7373 4545 7373 4177 7373 4545 7374 4547 7374 4177 7374 4190 7375 4548 7375 4546 7375 4177 272 4547 272 4179 272 4188 272 4548 272 4190 272 4188 7376 4549 7376 4548 7376 4547 272 4550 272 4179 272 4550 272 4551 272 4179 272 4179 272 4551 272 4181 272 4188 7377 4552 7377 4549 7377 4186 7378 4552 7378 4188 7378 4181 7379 4551 7379 4182 7379 4186 7380 4553 7380 4552 7380 4551 272 4554 272 4182 272 4184 7381 4553 7381 4186 7381 4182 7382 4554 7382 4184 7382 4184 7383 4554 7383 4553 7383 4548 7384 4549 7384 4555 7384 4555 7385 4549 7385 4556 7385 4549 7386 4552 7386 4556 7386 4556 7387 4553 7387 4557 7387 4552 7388 4553 7388 4556 7388 4557 7389 4554 7389 4558 7389 4553 7390 4554 7390 4557 7390 4558 7391 4554 7391 4559 7391 4554 7392 4551 7392 4559 7392 4559 7393 4551 7393 4560 7393 4560 7394 4550 7394 4561 7394 4551 7395 4550 7395 4560 7395 4561 7396 4547 7396 4562 7396 4550 7397 4547 7397 4561 7397 4562 7398 4545 7398 4563 7398 4547 7399 4545 7399 4562 7399 4545 7400 4543 7400 4563 7400 4563 7401 4543 7401 4564 7401 4543 7402 4541 7402 4564 7402 4564 7403 4541 7403 4565 7403 4541 7404 4539 7404 4565 7404 4565 7405 4539 7405 4566 7405 4566 7406 4537 7406 4567 7406 4539 7407 4537 7407 4566 7407 4567 7408 4535 7408 4568 7408 4537 7409 4535 7409 4567 7409 4535 7410 4532 7410 4568 7410 4568 7411 4532 7411 4569 7411 4532 7412 4531 7412 4569 7412 4569 7413 4531 7413 4570 7413 4531 7414 4528 7414 4570 7414 4570 7415 4528 7415 4571 7415 4528 7416 4527 7416 4571 7416 4571 7417 4527 7417 4572 7417 4527 7418 4529 7418 4572 7418 4572 7419 4529 7419 4573 7419 4529 7420 4530 7420 4573 7420 4573 7421 4530 7421 4574 7421 4530 7422 4533 7422 4574 7422 4574 7423 4533 7423 4575 7423 4533 7424 4534 7424 4575 7424 4534 7425 4536 7425 4575 7425 4575 7426 4536 7426 4576 7426 4576 7427 4538 7427 4577 7427 4536 7428 4538 7428 4576 7428 4577 7429 4538 7429 4578 7429 4538 7430 4540 7430 4578 7430 4578 7431 4542 7431 4579 7431 4540 7432 4542 7432 4578 7432 4542 7433 4544 7433 4579 7433 4579 7434 4544 7434 4580 7434 4544 7435 4546 7435 4580 7435 4580 7436 4546 7436 4581 7436 4546 7437 4548 7437 4581 7437 4581 7438 4548 7438 4555 7438 4359 7439 4358 7439 4582 7439 4583 7440 4359 7440 4582 7440 4583 7441 4582 7441 4584 7441 4585 7442 4583 7442 4584 7442 4586 7443 4585 7443 4584 7443 4586 7444 4584 7444 4587 7444 4588 7445 4586 7445 4587 7445 4588 7446 4587 7446 4589 7446 4590 7447 4588 7447 4589 7447 4590 7448 4589 7448 4591 7448 4590 7449 4591 7449 4592 7449 4593 7450 4590 7450 4592 7450 4593 7451 4592 7451 4594 7451 4595 7452 4593 7452 4594 7452 4344 7453 4345 7453 4596 7453 4597 7454 4344 7454 4596 7454 4597 7455 4596 7455 4598 7455 4599 7456 4597 7456 4598 7456 4599 7457 4598 7457 4600 7457 4601 7458 4599 7458 4600 7458 4601 7459 4600 7459 4602 7459 4603 7460 4601 7460 4602 7460 4603 7461 4602 7461 4604 7461 4605 7462 4603 7462 4604 7462 4606 7463 4605 7463 4604 7463 4606 7464 4604 7464 4607 7464 4608 7465 4606 7465 4607 7465 4608 7466 4607 7466 4609 7466 4610 7467 5106 7467 4611 7467 4610 7468 4611 7468 4612 7468 4613 7469 4608 7469 4609 7469 4613 7470 4609 7470 4614 7470 4615 7471 4613 7471 4614 7471 4615 7472 4614 7472 4616 7472 4617 7473 4615 7473 4616 7473 4617 7474 4616 7474 4618 7474 4619 7475 4617 7475 4618 7475 4619 7476 4618 7476 4620 7476 4626 7477 4619 7477 4620 7477 4626 7478 4620 7478 4625 7478 4623 7479 4621 7479 4622 7479 4623 7480 4622 7480 4624 7480 4625 7481 4623 7481 4624 7481 4625 7482 4624 7482 4626 7482 4627 7483 4595 7483 4594 7483 4627 7484 4594 7484 4628 7484 4629 7485 4627 7485 4628 7485 4630 7486 4628 7486 4631 7486 4630 7487 4629 7487 4628 7487 4630 7488 4631 7488 4632 7488 4633 7489 4630 7489 4632 7489 4633 7490 4632 7490 4634 7490 4635 7491 4633 7491 4634 7491 4635 7492 4634 7492 4636 7492 4612 7493 4611 7493 4637 7493 4638 7494 4637 7494 4639 7494 4638 7495 4612 7495 4637 7495 4636 7496 4639 7496 4635 7496 4636 7497 4638 7497 4639 7497 4642 7498 4640 7498 4641 7498 4642 7499 4641 7499 4643 7499 4644 7500 4642 7500 4643 7500 4644 7501 4643 7501 4645 7501 4644 7502 4645 7502 4646 7502 4647 7503 4646 7503 4648 7503 4647 7504 4644 7504 4646 7504 4647 7505 4648 7505 4649 7505 4650 7506 4647 7506 4649 7506 4650 7507 4649 7507 5257 7507 4650 7508 5257 7508 4651 7508 4652 7509 4650 7509 4651 7509 4652 7510 4651 7510 4653 7510 4652 7511 4653 7511 4654 7511 5041 7512 4656 7512 5042 7512 4655 7513 4656 7513 5041 7513 5042 7514 4657 7514 5051 7514 4656 7515 4657 7515 5042 7515 5051 7516 4657 7516 4658 7516 4657 7517 4659 7517 4658 7517 4658 7518 4659 7518 5050 7518 4659 7519 4660 7519 5050 7519 5050 7520 4660 7520 4661 7520 4660 7521 4750 7521 4661 7521 4661 7522 4750 7522 4662 7522 4662 7523 4663 7523 4664 7523 4750 7524 4663 7524 4662 7524 4664 7525 4663 7525 4665 7525 4663 7526 4666 7526 4665 7526 4665 7527 4666 7527 4668 7527 4666 7528 4667 7528 4668 7528 4670 7529 4672 7529 4669 7529 4671 7530 4673 7530 4670 7530 4670 7531 4673 7531 4672 7531 4672 7532 4674 7532 4675 7532 4673 7533 4674 7533 4672 7533 4675 7534 4676 7534 4677 7534 4674 7535 4676 7535 4675 7535 4676 7536 4678 7536 4677 7536 4677 7537 4678 7537 4167 7537 4680 7538 4681 7538 4682 7538 4680 7539 4682 7539 4679 7539 4683 7540 4680 7540 4679 7540 4683 7541 4679 7541 4684 7541 4685 7542 4162 7542 4160 7542 4687 7543 4688 7543 4681 7543 4686 7544 4706 7544 4689 7544 4164 7545 4162 7545 4686 7545 4690 7546 4680 7546 4683 7546 4690 7547 4681 7547 4680 7547 4690 7548 4687 7548 4681 7548 4691 7549 4686 7549 4689 7549 4692 7550 4164 7550 4686 7550 4690 7551 4693 7551 4687 7551 4694 7552 4165 7552 4164 7552 4696 7553 4683 7553 4684 7553 4696 7554 4690 7554 4683 7554 4695 7555 4691 7555 4689 7555 4696 7556 4693 7556 4690 7556 4697 7557 4694 7557 4164 7557 4697 7558 4164 7558 4692 7558 4693 7559 4695 7559 4689 7559 4696 7560 4684 7560 4698 7560 4697 7561 4692 7561 4691 7561 4699 7562 4695 7562 4693 7562 4699 7563 4693 7563 4696 7563 4695 7564 4697 7564 4691 7564 4698 7565 4699 7565 4696 7565 4157 7566 4156 7566 4711 7566 4700 7567 4702 7567 4159 7567 4700 7568 4159 7568 4157 7568 4700 7569 4157 7569 4711 7569 4703 7570 4704 7570 4702 7570 4688 7571 4713 7571 4681 7571 4688 7572 4704 7572 4713 7572 4705 7573 4702 7573 4704 7573 4685 7574 4702 7574 4705 7574 4706 7575 4685 7575 4705 7575 4686 7576 4685 7576 4706 7576 4686 7577 4162 7577 4685 7577 4689 7578 4706 7578 4687 7578 4691 7579 4692 7579 4686 7579 4709 7580 4708 7580 4695 7580 4709 7581 4695 7581 4699 7581 4698 7582 4709 7582 4699 7582 4698 7583 4710 7583 4709 7583 4669 7584 4672 7584 4708 7584 4669 7585 4709 7585 4710 7585 4669 7586 4708 7586 4709 7586 4711 7587 4701 7587 4700 7587 4701 7588 4703 7588 4700 7588 4712 7589 4703 7589 4701 7589 4700 7590 4703 7590 4702 7590 4703 7591 4713 7591 4704 7591 4160 7592 4159 7592 4702 7592 4160 7593 4702 7593 4685 7593 4706 7594 4705 7594 4704 7594 4706 7595 4688 7595 4687 7595 4706 7596 4704 7596 4688 7596 4689 7597 4687 7597 4693 7597 4697 7598 4707 7598 4694 7598 4156 7599 4155 7599 4711 7599 4713 7600 4703 7600 4712 7600 4707 7601 4167 7601 4694 7601 4707 7602 4677 7602 4167 7602 4708 7603 4707 7603 4697 7603 4708 7604 4697 7604 4695 7604 4675 7605 4708 7605 4672 7605 4675 7606 4677 7606 4707 7606 4675 7607 4707 7607 4708 7607 4714 7608 4682 7608 4681 7608 4713 7609 4714 7609 4681 7609 5227 7610 4679 7610 5274 7610 5274 7611 4679 7611 4715 7611 4679 7612 4682 7612 4715 7612 4715 7613 4682 7613 4716 7613 4682 7614 4714 7614 4716 7614 4716 7615 4714 7615 4717 7615 4714 7616 4713 7616 4717 7616 4717 7617 4713 7617 4718 7617 4713 7618 4712 7618 4718 7618 4718 7619 4701 7619 4719 7619 4712 7620 4701 7620 4718 7620 4719 7621 4701 7621 4720 7621 4701 7622 4711 7622 4720 7622 4720 7623 4155 7623 4654 7623 4711 7624 4155 7624 4720 7624 4725 7625 4726 7625 4667 7625 4727 7626 4726 7626 4725 7626 4727 7627 4725 7627 4728 7627 4733 7628 4734 7628 4735 7628 4730 7629 4721 7629 4732 7629 4730 7630 4731 7630 4736 7630 4733 7631 4751 7631 4734 7631 4721 7632 4730 7632 4736 7632 4721 7633 4736 7633 4722 7633 4741 7634 4742 7634 4657 7634 4741 7635 4657 7635 4656 7635 4743 7636 4744 7636 4739 7636 4743 7637 4739 7637 4738 7637 4743 7638 4738 7638 4740 7638 4741 7639 4745 7639 4742 7639 4746 7640 4723 7640 4747 7640 4746 7641 4745 7641 4741 7641 4746 7642 4724 7642 4723 7642 4666 7643 4725 7643 4667 7643 4748 7644 4725 7644 4666 7644 4748 7645 4728 7645 4725 7645 4748 7646 4737 7646 4728 7646 4728 7647 4737 7647 4733 7647 4729 7648 4730 7648 4732 7648 4737 7649 4749 7649 4733 7649 4728 7650 4733 7650 4735 7650 4735 7651 4729 7651 4728 7651 4735 7652 4731 7652 4730 7652 4735 7653 4730 7653 4729 7653 4738 7654 4749 7654 4750 7654 4740 7655 4660 7655 4659 7655 4751 7656 4738 7656 4739 7656 4751 7657 4733 7657 4749 7657 4751 7658 4749 7658 4738 7658 4743 7659 4742 7659 4745 7659 4743 7660 4740 7660 4742 7660 4724 7661 4656 7661 4655 7661 4724 7662 4741 7662 4656 7662 4724 7663 4746 7663 4741 7663 4747 7664 4745 7664 4746 7664 4747 7665 4744 7665 4743 7665 4747 7666 4743 7666 4745 7666 4663 7667 4748 7667 4666 7667 4748 7668 4663 7668 4749 7668 4748 7669 4749 7669 4737 7669 4729 7670 4727 7670 4728 7670 4729 7671 4726 7671 4727 7671 4740 7672 4738 7672 4750 7672 4740 7673 4750 7673 4660 7673 4742 7674 4740 7674 4659 7674 4742 7675 4659 7675 4657 7675 4750 7676 4749 7676 4663 7676 4722 7677 4752 7677 4721 7677 4754 7678 4752 7678 4722 7678 4754 7679 4722 7679 4755 7679 4754 7680 4755 7680 4756 7680 4758 7681 4757 7681 4754 7681 4758 7682 4754 7682 4756 7682 4758 7683 4759 7683 4757 7683 4759 7684 4756 7684 4760 7684 4759 7685 4758 7685 4756 7685 4760 7686 4753 7686 4759 7686 4762 7687 4648 7687 4646 7687 4763 7688 4641 7688 4761 7688 4763 7689 4761 7689 4764 7689 4763 7690 4643 7690 4641 7690 4765 7691 4643 7691 4763 7691 4765 7692 4763 7692 4764 7692 4765 7693 4645 7693 4643 7693 4765 7694 4764 7694 4766 7694 4645 7695 4765 7695 4766 7695 4645 7696 4766 7696 4762 7696 4645 7697 4762 7697 4646 7697 4769 272 4768 272 4767 272 4769 7698 4770 7698 4768 7698 4767 272 4768 272 4771 272 4769 272 4772 272 4770 272 4767 7699 4771 7699 4773 7699 4774 7700 4767 7700 4773 7700 4775 272 4772 272 4769 272 4775 7701 4776 7701 4772 7701 4774 7702 4773 7702 4777 7702 4775 7703 4778 7703 4776 7703 4779 7704 4774 7704 4777 7704 4779 272 4777 272 4780 272 4781 272 4778 272 4775 272 4782 272 4779 272 4780 272 4781 7705 4783 7705 4778 7705 4784 272 4782 272 4780 272 4784 7706 4785 7706 4782 7706 4786 272 4783 272 4781 272 4786 272 4781 272 4787 272 4788 272 4785 272 4784 272 4789 272 4787 272 4790 272 4789 7707 4786 7707 4787 7707 4791 7708 4785 7708 4788 7708 4791 7709 4792 7709 4785 7709 4793 272 4792 272 4791 272 4794 7710 4789 7710 4790 7710 4793 7711 4795 7711 4792 7711 4794 272 4790 272 4795 272 4796 272 4795 272 4793 272 4796 7712 4794 7712 4795 7712 4807 7713 4797 7713 4775 7713 4775 7714 4797 7714 4781 7714 4797 7715 4798 7715 4781 7715 4781 7716 4799 7716 4787 7716 4798 7717 4799 7717 4781 7717 4787 7718 4799 7718 4790 7718 4799 7719 4800 7719 4790 7719 4790 7720 4800 7720 4795 7720 4800 7721 4801 7721 4795 7721 4795 7722 4801 7722 4792 7722 4801 7723 4802 7723 4792 7723 4792 7724 4802 7724 4785 7724 4802 7725 4803 7725 4785 7725 4785 7726 4803 7726 4782 7726 4782 7727 4804 7727 4779 7727 4803 7728 4804 7728 4782 7728 4779 7729 4804 7729 4774 7729 4804 7730 4805 7730 4774 7730 4774 7731 4805 7731 4767 7731 4805 7732 4806 7732 4767 7732 4767 7733 4806 7733 4769 7733 4806 7734 4807 7734 4769 7734 4769 7735 4807 7735 4775 7735 4796 7736 4808 7736 4809 7736 4794 7737 4809 7737 4810 7737 4794 7738 4796 7738 4809 7738 4789 7739 4810 7739 4811 7739 4789 7740 4794 7740 4810 7740 4789 7741 4811 7741 4812 7741 4786 7742 4789 7742 4812 7742 4786 7743 4812 7743 4813 7743 4783 7744 4786 7744 4813 7744 4783 7745 4813 7745 4814 7745 4778 7746 4783 7746 4814 7746 4778 7747 4814 7747 4815 7747 4776 7748 4778 7748 4815 7748 4776 7749 4815 7749 4816 7749 4772 7750 4776 7750 4816 7750 4772 7751 4816 7751 4817 7751 4770 7752 4772 7752 4817 7752 4768 7753 4770 7753 4817 7753 4768 7754 4817 7754 4818 7754 4771 7755 4768 7755 4818 7755 4771 7756 4818 7756 4819 7756 4771 7757 4819 7757 4820 7757 4773 7758 4771 7758 4820 7758 4773 7759 4820 7759 4821 7759 4777 7760 4773 7760 4821 7760 4777 7761 4821 7761 4822 7761 4780 7762 4777 7762 4822 7762 4780 7763 4822 7763 4823 7763 4784 7764 4780 7764 4823 7764 4784 7765 4823 7765 4824 7765 4788 7766 4784 7766 4824 7766 4788 7767 4824 7767 4825 7767 4791 7768 4788 7768 4825 7768 4793 7769 4825 7769 4826 7769 4793 7770 4791 7770 4825 7770 4793 7771 4826 7771 4827 7771 4808 7772 4793 7772 4827 7772 4796 7773 4793 7773 4808 7773 4828 7774 4829 7774 4830 7774 4831 7775 4829 7775 4828 7775 4827 7776 4723 7776 4724 7776 4808 7777 4827 7777 4724 7777 4827 7778 4829 7778 4831 7778 4827 7779 4831 7779 4723 7779 4832 272 4833 272 4834 272 4834 272 4833 272 4835 272 4832 7780 4836 7780 4833 7780 4837 7781 4834 7781 4835 7781 4838 272 4836 272 4832 272 4837 7782 4835 7782 4839 7782 4838 7783 4840 7783 4836 7783 4841 272 4837 272 4839 272 4842 272 4840 272 4838 272 4841 272 4839 272 4843 272 4842 7784 4844 7784 4840 7784 4845 272 4844 272 4842 272 4846 272 4843 272 4847 272 4846 272 4841 272 4843 272 4845 272 4848 272 4844 272 4847 7785 4849 7785 4846 7785 4848 7786 4845 7786 4850 7786 4851 272 4848 272 4850 272 4852 7787 4849 7787 4847 7787 4853 272 4849 272 4852 272 4853 7788 4854 7788 4849 7788 4855 272 4851 272 4850 272 4855 272 4850 272 4856 272 4857 272 4854 272 4853 272 4858 272 4855 272 4856 272 4857 7789 4859 7789 4854 7789 4858 7790 4856 7790 4859 7790 4860 272 4859 272 4857 272 4860 272 4858 272 4859 272 4838 7791 4871 7791 4842 7791 4871 7792 4861 7792 4842 7792 4842 7793 4861 7793 4845 7793 4861 7794 4862 7794 4845 7794 4845 7795 4862 7795 4850 7795 4862 7796 4863 7796 4850 7796 4850 7797 4863 7797 4856 7797 4863 7798 4864 7798 4856 7798 4856 7799 4864 7799 4859 7799 4864 7800 4865 7800 4859 7800 4859 7801 4865 7801 4854 7801 4865 7802 4866 7802 4854 7802 4854 7803 4866 7803 4849 7803 4866 7804 4867 7804 4849 7804 4849 7805 4867 7805 4846 7805 4867 7806 4868 7806 4846 7806 4846 7807 4868 7807 4841 7807 4868 7808 4869 7808 4841 7808 4841 7809 4869 7809 4837 7809 4837 7810 4869 7810 4834 7810 4869 7811 4870 7811 4834 7811 4834 7812 4870 7812 4832 7812 4870 7813 4871 7813 4832 7813 4832 7814 4871 7814 4838 7814 4873 7815 4847 7815 4872 7815 4852 7816 4847 7816 4873 7816 4874 7817 4852 7817 4873 7817 4853 7818 4852 7818 4874 7818 4875 7819 4853 7819 4874 7819 4857 7820 4853 7820 4875 7820 4876 7821 4857 7821 4875 7821 4860 7822 4857 7822 4876 7822 4877 7823 4860 7823 4876 7823 4858 7824 4860 7824 4877 7824 4878 7825 4858 7825 4877 7825 4855 7826 4858 7826 4878 7826 4879 7827 4855 7827 4878 7827 4851 7828 4855 7828 4879 7828 4880 7829 4851 7829 4879 7829 4848 7830 4851 7830 4880 7830 4881 7831 4848 7831 4880 7831 4830 7832 4848 7832 4881 7832 4844 7833 4830 7833 4829 7833 4844 7834 4848 7834 4830 7834 4844 7835 4829 7835 4882 7835 4840 7836 4882 7836 4883 7836 4840 7837 4844 7837 4882 7837 4836 7838 4840 7838 4883 7838 4836 7839 4883 7839 4884 7839 4833 7840 4836 7840 4884 7840 4833 7841 4884 7841 4885 7841 4835 7842 4833 7842 4885 7842 4835 7843 4885 7843 4886 7843 4839 7844 4835 7844 4886 7844 4839 7845 4886 7845 4887 7845 4843 7846 4839 7846 4887 7846 4843 7847 4887 7847 4888 7847 4843 7848 4888 7848 4889 7848 4872 7849 4843 7849 4889 7849 4847 7850 4843 7850 4872 7850 4889 7851 4890 7851 4891 7851 4872 7852 4889 7852 4891 7852 4892 272 4894 272 4893 272 4895 272 4892 272 4893 272 4892 272 4896 272 4894 272 4897 272 4896 272 4892 272 4895 272 4893 272 4898 272 4899 7853 4895 7853 4898 7853 4897 7854 4900 7854 4896 7854 4899 272 4898 272 4901 272 4897 7855 4902 7855 4900 7855 4903 272 4902 272 4897 272 4904 7856 4899 7856 4901 7856 4904 7857 4901 7857 4905 7857 4903 7858 4906 7858 4902 7858 4907 272 4904 272 4905 272 4908 7859 4906 7859 4903 7859 4907 272 4905 272 4909 272 4910 272 4906 272 4908 272 4909 7860 4911 7860 4907 7860 4912 272 4911 272 4909 272 4913 272 4910 272 4908 272 4913 272 4908 272 4914 272 4915 272 4911 272 4912 272 4915 7861 4916 7861 4911 7861 4917 7862 4913 7862 4914 7862 4917 7863 4914 7863 4918 7863 4919 272 4916 272 4915 272 4919 7864 4920 7864 4916 7864 4921 7865 4917 7865 4918 7865 4921 7866 4918 7866 4920 7866 4921 272 4920 272 4919 272 4897 7867 4933 7867 4903 7867 4933 7868 4922 7868 4903 7868 4922 7869 4923 7869 4903 7869 4903 7870 4923 7870 4908 7870 4923 7871 4924 7871 4908 7871 4908 7872 4924 7872 4914 7872 4924 7873 4925 7873 4914 7873 4914 7874 4925 7874 4918 7874 4918 7875 4925 7875 4920 7875 4925 7876 4926 7876 4920 7876 4920 7877 4926 7877 4916 7877 4926 7878 4927 7878 4916 7878 4916 7879 4927 7879 4911 7879 4927 7880 4928 7880 4911 7880 4911 7881 4928 7881 4907 7881 4907 7882 4928 7882 4904 7882 4928 7883 4929 7883 4904 7883 4904 7884 4929 7884 4899 7884 4929 7885 4930 7885 4899 7885 4899 7886 4930 7886 4895 7886 4930 7887 4931 7887 4895 7887 4895 7888 4931 7888 4892 7888 4931 7889 4932 7889 4892 7889 4892 7890 4932 7890 4897 7890 4932 7891 4933 7891 4897 7891 4917 7892 4921 7892 4891 7892 4917 7893 4891 7893 4890 7893 4917 7894 4890 7894 4934 7894 4917 7895 4934 7895 4935 7895 4913 7896 4917 7896 4935 7896 4913 7897 4935 7897 4936 7897 4910 7898 4913 7898 4936 7898 4910 7899 4936 7899 4937 7899 4906 7900 4910 7900 4937 7900 4906 7901 4937 7901 4938 7901 4902 7902 4906 7902 4938 7902 4902 7903 4938 7903 4939 7903 4900 7904 4902 7904 4939 7904 4896 7905 4939 7905 4940 7905 4896 7906 4900 7906 4939 7906 4941 7907 4896 7907 4940 7907 4894 7908 4896 7908 4941 7908 4942 7909 4894 7909 4941 7909 4893 7910 4894 7910 4942 7910 4943 7911 4893 7911 4942 7911 4898 7912 4893 7912 4943 7912 4944 7913 4898 7913 4943 7913 4945 7914 4898 7914 4944 7914 4901 7915 4898 7915 4945 7915 4905 7916 4901 7916 4945 7916 4946 7917 4905 7917 4945 7917 4947 7918 4905 7918 4946 7918 4909 7919 4905 7919 4947 7919 4909 7920 4947 7920 4948 7920 4912 7921 4909 7921 4948 7921 4912 7922 4948 7922 4949 7922 4915 7923 4912 7923 4949 7923 4915 7924 4949 7924 4950 7924 4919 7925 4915 7925 4950 7925 4919 7926 4950 7926 4951 7926 4921 7927 4919 7927 4951 7927 4921 7928 4951 7928 4891 7928 4890 272 4889 272 4934 272 4889 7929 4888 7929 4934 7929 4939 7930 4953 7930 4940 7930 4940 7931 4953 7931 4952 7931 4888 272 4887 272 4934 272 4934 7932 4887 7932 4935 7932 4938 7933 4953 7933 4939 7933 4938 7934 4954 7934 4953 7934 4887 272 4886 272 4935 272 4935 272 4886 272 4936 272 4937 7935 4955 7935 4938 7935 4938 7936 4955 7936 4954 7936 4886 7937 4885 7937 4936 7937 4936 7938 4885 7938 4937 7938 4955 272 4823 272 4956 272 4885 7939 4823 7939 4937 7939 4937 7940 4823 7940 4955 7940 4885 7941 4824 7941 4823 7941 4884 272 4824 272 4885 272 4823 272 4822 272 4956 272 4956 272 4822 272 4957 272 4883 7942 4825 7942 4884 7942 4884 7943 4825 7943 4824 7943 4822 7944 4821 7944 4957 7944 4957 272 4821 272 4958 272 4882 7945 4826 7945 4883 7945 4883 7946 4826 7946 4825 7946 4821 7947 4820 7947 4958 7947 4829 272 4827 272 4882 272 4882 7948 4827 7948 4826 7948 4820 272 4819 272 4958 272 4958 7949 4819 7949 4959 7949 4818 7950 4960 7950 4959 7950 4819 7951 4818 7951 4959 7951 5001 7952 4941 7952 4940 7952 4952 7953 5001 7953 4940 7953 4963 7954 4962 7954 4961 7954 4961 272 4962 272 4964 272 4963 272 4965 272 4962 272 4961 272 4964 272 4966 272 4967 7955 4961 7955 4966 7955 4968 272 4965 272 4963 272 4968 7956 4969 7956 4965 7956 4967 7957 4966 7957 4970 7957 4971 272 4969 272 4968 272 4972 272 4967 272 4970 272 4972 272 4970 272 4973 272 4971 7958 4974 7958 4969 7958 4971 272 4975 272 4974 272 4976 7959 4973 7959 4977 7959 4976 272 4972 272 4973 272 4978 272 4975 272 4971 272 4979 272 4975 272 4978 272 4977 7960 4980 7960 4976 7960 4981 7961 4980 7961 4977 7961 4979 272 4978 272 4982 272 4983 7962 4979 7962 4982 7962 4984 7963 4980 7963 4981 7963 4985 7964 4983 7964 4982 7964 4984 7965 4986 7965 4980 7965 4987 272 4986 272 4984 272 4985 272 4982 272 4988 272 4989 7966 4985 7966 4988 7966 4987 7967 4990 7967 4986 7967 4991 7968 4990 7968 4987 7968 4991 7969 4988 7969 4990 7969 4991 272 4989 272 4988 272 4981 7970 5001 7970 4952 7970 4981 7971 4977 7971 5001 7971 4981 7972 4952 7972 4953 7972 4984 7973 4981 7973 4953 7973 4984 7974 4953 7974 4954 7974 4987 7975 4984 7975 4954 7975 4987 7976 4954 7976 4955 7976 4991 7977 4987 7977 4955 7977 4991 7978 4955 7978 4956 7978 4989 7979 4991 7979 4956 7979 4989 7980 4956 7980 4957 7980 4985 7981 4989 7981 4957 7981 4985 7982 4957 7982 4958 7982 4983 7983 4985 7983 4958 7983 4979 7984 4983 7984 4958 7984 4979 7985 4958 7985 4959 7985 4960 7986 4979 7986 4959 7986 4975 7987 4979 7987 4960 7987 4992 7988 4975 7988 4960 7988 4974 7989 4975 7989 4992 7989 4993 7990 4974 7990 4992 7990 4969 7991 4974 7991 4993 7991 4994 7992 4969 7992 4993 7992 4965 7993 4969 7993 4994 7993 4995 7994 4965 7994 4994 7994 4962 7995 4965 7995 4995 7995 4996 7996 4962 7996 4995 7996 4964 7997 4962 7997 4996 7997 4997 7998 4964 7998 4996 7998 4966 7999 4964 7999 4997 7999 4998 8000 4966 8000 4997 8000 4999 8001 4966 8001 4998 8001 4970 8002 4966 8002 4999 8002 5000 8003 4970 8003 4999 8003 4973 8004 4970 8004 5000 8004 4977 8005 4973 8005 5000 8005 5001 8006 4977 8006 5000 8006 5013 8007 5002 8007 4968 8007 4968 8008 5002 8008 4971 8008 5002 8009 5003 8009 4971 8009 4971 8010 5003 8010 4978 8010 4978 8011 5004 8011 4982 8011 5003 8012 5004 8012 4978 8012 5004 8013 5005 8013 4982 8013 4982 8014 5005 8014 4988 8014 4988 8015 5005 8015 4990 8015 5005 8016 5006 8016 4990 8016 4990 8017 5006 8017 4986 8017 5006 8018 5007 8018 4986 8018 4986 8019 5007 8019 4980 8019 5007 8020 5008 8020 4980 8020 4980 8021 5008 8021 4976 8021 4976 8022 5008 8022 4972 8022 5008 8023 5009 8023 4972 8023 4972 8024 5009 8024 4967 8024 5009 8025 5010 8025 4967 8025 4967 8026 5010 8026 4961 8026 5010 8027 5011 8027 4961 8027 4961 8028 5011 8028 4963 8028 5011 8029 5012 8029 4963 8029 5012 8030 5013 8030 4963 8030 4963 8031 5013 8031 4968 8031 5014 8032 5015 8032 4622 8032 5014 8033 4622 8033 4621 8033 4676 8034 5016 8034 4678 8034 5018 8035 5016 8035 4676 8035 5018 8036 5017 8036 5016 8036 4674 8037 5018 8037 4676 8037 5019 8038 4674 8038 4673 8038 5020 8039 5021 8039 5017 8039 5018 8040 5020 8040 5017 8040 5022 8041 4674 8041 5019 8041 5022 8042 5018 8042 4674 8042 4671 8043 5019 8043 4673 8043 5024 8044 4671 8044 5023 8044 5024 8045 5019 8045 4671 8045 5022 8046 5019 8046 5024 8046 5025 8047 5021 8047 5020 8047 5024 8048 5023 8048 5027 8048 5025 8049 5020 8049 5018 8049 5025 8050 5026 8050 5021 8050 5029 8051 5018 8051 5022 8051 5029 8052 5025 8052 5018 8052 5030 8053 5026 8053 5025 8053 5031 8054 5028 8054 5026 8054 5032 8055 5025 8055 5029 8055 5033 8056 5022 8056 5024 8056 5033 8057 5029 8057 5022 8057 5034 8058 5030 8058 5025 8058 5030 8059 5031 8059 5026 8059 5035 8060 5032 8060 5029 8060 5027 8061 5033 8061 5024 8061 5033 8062 5035 8062 5029 8062 5037 8063 5031 8063 5030 8063 5033 8064 5027 8064 5036 8064 5038 8065 5037 8065 5030 8065 5038 8066 5030 8066 5034 8066 5039 8067 5032 8067 5035 8067 5040 8068 5034 8068 5032 8068 5040 8069 5038 8069 5034 8069 5039 8070 5040 8070 5032 8070 5036 8071 5035 8071 5033 8071 5047 8072 5039 8072 5035 8072 5036 8073 5047 8073 5035 8073 5025 8074 5032 8074 5034 8074 5043 8075 5028 8075 5031 8075 5044 8076 5043 8076 5031 8076 5044 8077 5031 8077 5037 8077 4664 8078 5044 8078 5046 8078 4662 8079 4664 8079 5046 8079 5042 8080 5036 8080 5041 8080 5043 8081 5044 8081 5045 8081 5046 8082 5044 8082 5037 8082 4665 8083 5044 8083 4664 8083 4665 8084 5045 8084 5044 8084 5048 8085 5040 8085 5049 8085 5047 8086 5036 8086 5042 8086 5047 8087 5049 8087 5039 8087 4661 8088 4662 8088 5046 8088 4661 8089 5046 8089 5048 8089 5050 8090 5048 8090 5049 8090 5050 8091 4661 8091 5048 8091 5045 8092 4665 8092 4668 8092 5038 8093 5040 8093 5048 8093 5038 8094 5046 8094 5037 8094 5046 8095 5038 8095 5048 8095 5040 8096 5039 8096 5049 8096 4658 8097 5050 8097 5049 8097 5051 8098 5049 8098 5047 8098 5051 8099 4658 8099 5049 8099 5051 8100 5047 8100 5042 8100 5015 8101 5014 8101 5052 8101 5014 8102 5053 8102 5052 8102 5052 8103 5053 8103 5054 8103 5053 8104 5055 8104 5054 8104 5054 8105 5055 8105 5056 8105 5055 8106 5057 8106 5056 8106 5056 8107 5057 8107 5058 8107 5057 8108 5059 8108 5058 8108 5058 8109 5059 8109 5060 8109 5059 8110 5061 8110 5060 8110 5060 8111 5061 8111 5062 8111 5061 8112 5063 8112 5062 8112 5062 8113 5063 8113 5064 8113 5063 8114 5065 8114 5064 8114 5064 8115 5065 8115 5066 8115 5065 8116 5067 8116 5066 8116 5066 8117 5067 8117 5068 8117 5067 8118 5069 8118 5068 8118 5068 8119 5069 8119 5070 8119 5069 8120 5071 8120 5070 8120 5070 8121 5071 8121 5072 8121 5071 8122 5073 8122 5072 8122 5072 8123 5073 8123 5074 8123 5073 8124 5075 8124 5074 8124 5074 8125 5075 8125 5076 8125 5075 8126 5023 8126 5076 8126 5076 8127 5023 8127 5077 8127 5023 8128 4671 8128 5077 8128 4671 8129 4670 8129 5077 8129 5077 8130 4670 8130 5078 8130 5078 8131 4670 8131 5079 8131 5079 8132 4669 8132 5080 8132 4670 8133 4669 8133 5079 8133 4669 8134 4710 8134 5080 8134 5080 8135 4710 8135 5081 8135 4710 8136 5082 8136 5081 8136 5081 8137 5082 8137 5083 8137 5082 8138 5084 8138 5083 8138 5083 8139 5084 8139 5085 8139 5084 8140 5086 8140 5085 8140 5085 8141 5086 8141 5087 8141 5086 8142 5088 8142 5087 8142 5087 8143 5088 8143 5089 8143 5088 8144 5090 8144 5089 8144 5089 8145 5090 8145 5091 8145 5090 8146 5092 8146 5091 8146 5091 8147 5092 8147 5093 8147 5092 8148 5094 8148 5093 8148 5093 8149 5094 8149 5095 8149 5094 8150 5096 8150 5095 8150 5095 8151 5096 8151 5097 8151 5096 8152 5098 8152 5097 8152 5097 8153 5098 8153 5099 8153 5098 8154 5100 8154 5099 8154 5099 8155 5100 8155 5101 8155 5100 8156 5102 8156 5101 8156 5101 8157 5102 8157 5103 8157 5102 8158 5104 8158 5103 8158 5103 8159 5104 8159 5105 8159 5104 8160 5106 8160 5105 8160 5105 8161 5106 8161 4610 8161 4155 8162 4154 8162 4654 8162 4654 8163 4154 8163 4652 8163 4641 8164 5107 8164 5111 8164 4641 8165 4640 8165 5107 8165 5108 8166 5109 8166 4760 8166 4760 8167 5109 8167 4753 8167 5110 8168 4761 8168 5111 8168 4761 8169 4641 8169 5111 8169 5108 8170 5112 8170 5109 8170 5109 8171 5112 8171 5113 8171 5112 8172 5114 8172 5113 8172 5113 8173 5114 8173 5115 8173 5114 8174 5116 8174 5115 8174 5115 8175 5116 8175 5117 8175 5117 8176 5116 8176 5118 8176 5118 8177 5119 8177 5117 8177 5116 8178 5120 8178 5118 8178 5117 8179 5119 8179 5121 8179 5119 8180 5122 8180 5121 8180 5122 8181 5123 8181 5121 8181 5122 8182 5124 8182 5123 8182 5124 8183 5125 8183 5123 8183 5125 8184 5126 8184 5123 8184 5123 8185 5126 8185 5127 8185 5126 8186 5128 8186 5127 8186 5127 8187 5128 8187 5107 8187 5128 8188 5111 8188 5107 8188 5111 8189 5128 8189 5110 8189 5142 8190 5129 8190 5130 8190 5142 8191 5130 8191 5131 8191 5134 2687 5133 2687 5132 2687 5134 2687 5130 2687 5133 2687 5135 2687 5130 2687 5134 2687 5131 8192 5136 8192 5125 8192 5124 8193 5131 8193 5125 8193 5137 8194 5124 8194 5138 8194 5137 8195 5131 8195 5124 8195 5131 2687 5130 2687 5136 2687 5136 2687 5130 2687 5139 2687 5139 2687 5130 2687 5135 2687 5124 8196 5122 8196 5138 8196 5118 8197 5140 8197 5119 8197 5122 8198 5119 8198 5138 8198 5119 8199 5140 8199 5138 8199 5138 8200 5140 8200 5137 8200 5140 8201 5141 8201 5137 8201 5137 8202 5141 8202 5131 8202 5141 8203 5142 8203 5131 8203 5143 8204 5144 8204 5132 8204 5143 8205 5132 8205 5133 8205 5141 8206 5140 8206 5118 8206 5142 2581 5141 2581 5118 2581 5120 8207 5142 8207 5118 8207 5145 8208 5142 8208 5120 8208 5143 8209 5146 8209 5144 8209 5129 8210 5147 8210 5146 8210 5129 8211 5146 8211 5143 8211 5129 8212 5142 8212 5145 8212 5129 8213 5145 8213 5147 8213 5148 8214 5149 8214 5150 8214 5151 8215 5148 8215 5150 8215 5151 8216 5150 8216 5152 8216 5153 8217 5151 8217 5152 8217 5154 8218 5155 8218 5156 8218 5155 8219 5157 8219 5156 8219 5156 8220 5157 8220 5158 8220 5157 8221 5159 8221 5158 8221 5155 8222 5154 8222 5160 8222 5154 8223 5161 8223 5160 8223 5160 8224 5161 8224 5162 8224 5161 8225 5163 8225 5162 8225 5162 8226 5163 8226 5164 8226 5163 8227 5165 8227 5164 8227 5164 8228 5165 8228 5166 8228 5165 8229 5167 8229 5166 8229 5166 8230 5167 8230 5168 8230 5167 8231 5169 8231 5168 8231 5168 8232 5169 8232 5170 8232 5169 8233 5171 8233 5170 8233 5170 8234 5171 8234 5172 8234 5171 8235 5173 8235 5172 8235 5172 8236 5174 8236 5175 8236 5173 8237 5174 8237 5172 8237 5175 8238 5174 8238 5176 8238 5174 8239 5177 8239 5176 8239 5176 8240 5177 8240 5178 8240 5177 8241 5179 8241 5178 8241 5178 8242 5179 8242 5180 8242 5179 8243 5181 8243 5180 8243 5180 8244 5181 8244 5182 8244 5181 8245 5183 8245 5182 8245 5182 8246 5183 8246 5184 8246 5184 8247 5153 8247 5152 8247 5183 8248 5153 8248 5184 8248 5185 3584 5186 3584 5187 3584 5185 3584 5188 3584 5186 3584 5189 2687 5185 2687 5190 2687 5188 2687 5185 2687 5189 2687 5189 1402 5190 1402 5191 1402 5189 1402 5191 1402 5192 1402 5191 2581 5186 2581 5192 2581 5187 2581 5186 2581 5191 2581 5193 3584 5194 3584 5195 3584 5193 3584 5196 3584 5194 3584 5197 2687 5193 2687 5198 2687 5196 2687 5193 2687 5197 2687 5197 1402 5198 1402 5199 1402 5197 1402 5199 1402 5200 1402 5199 2581 5194 2581 5200 2581 5195 2581 5194 2581 5199 2581 5203 8249 4996 8249 5201 8249 5201 272 4996 272 5202 272 5202 272 4996 272 5204 272 5205 8250 4996 8250 5203 8250 4996 8251 4995 8251 5204 8251 5205 272 4997 272 4996 272 5205 8252 4998 8252 4997 8252 4995 8253 4994 8253 5204 8253 5205 272 4999 272 4998 272 4994 272 4993 272 5204 272 5205 8254 5000 8254 4999 8254 4338 8255 4452 8255 4336 8255 4336 272 4452 272 4453 272 4336 272 4453 272 4334 272 4453 8256 4454 8256 4334 8256 4454 8257 4455 8257 4334 8257 4334 272 4455 272 4333 272 4338 272 4451 272 4452 272 4341 272 4451 272 4338 272 4333 272 4455 272 4330 272 4455 272 4456 272 4330 272 4341 8258 4450 8258 4451 8258 4343 272 4450 272 4341 272 4992 272 5206 272 4993 272 4960 272 5206 272 4992 272 4993 8259 5206 8259 5204 8259 4456 272 4457 272 4330 272 4343 272 4449 272 4450 272 5207 272 4449 272 4343 272 5207 272 4448 272 4449 272 4457 272 4458 272 4330 272 5207 272 4447 272 4448 272 5208 8260 4447 8260 5207 8260 5208 8261 4446 8261 4447 8261 5209 8262 4445 8262 5208 8262 5208 8263 4445 8263 4446 8263 5000 272 5210 272 5001 272 5205 272 5210 272 5000 272 4818 8264 4817 8264 5211 8264 5210 272 4942 272 5001 272 5212 8265 4818 8265 5211 8265 4942 272 4941 272 5001 272 5210 8266 4943 8266 4942 8266 5206 8267 4818 8267 5212 8267 5209 272 4444 272 4445 272 4817 8268 4816 8268 5211 8268 5211 272 4816 272 5213 272 5210 272 4944 272 4943 272 5210 272 4945 272 4944 272 5214 8269 4444 8269 5209 8269 4816 272 4815 272 5213 272 5215 272 4945 272 5210 272 5215 8270 4946 8270 4945 8270 5213 272 4815 272 5216 272 4815 272 4814 272 5216 272 5214 8271 4443 8271 4444 8271 5215 272 4947 272 4946 272 4814 272 4813 272 5216 272 5216 8272 4813 8272 5217 8272 5218 8273 4947 8273 5215 8273 5218 272 4948 272 4947 272 5217 272 4813 272 5214 272 5214 8274 4813 8274 4443 8274 4813 8275 4812 8275 4443 8275 5218 8276 5219 8276 4948 8276 4948 8277 5219 8277 4949 8277 5219 272 5220 272 4949 272 4949 8278 5220 8278 4950 8278 5220 272 5221 272 4950 272 4724 8279 4655 8279 4808 8279 4808 8280 4655 8280 4809 8280 5221 272 5222 272 4950 272 4809 8281 4655 8281 4810 8281 4950 272 5222 272 4951 272 4810 8282 4655 8282 4811 8282 5222 272 5223 272 4951 272 4951 272 5223 272 4891 272 4811 8283 5041 8283 4812 8283 4655 8284 5041 8284 4811 8284 4812 8285 5041 8285 4443 8285 4443 8286 5041 8286 4471 8286 4891 272 5193 272 5195 272 5224 272 5193 272 5223 272 5223 8287 5193 8287 4891 8287 5224 272 5225 272 5193 272 5225 272 5187 272 5193 272 5226 8288 5187 8288 5225 8288 5226 8289 5185 8289 5187 8289 4468 8290 5067 8290 5065 8290 4469 8291 5067 8291 4468 8291 4468 8292 5065 8292 4467 8292 4470 272 5067 272 4469 272 5065 8293 5063 8293 4467 8293 4470 8294 5069 8294 5067 8294 4471 272 5069 272 4470 272 4467 272 5063 272 4466 272 5041 8295 5069 8295 4471 8295 4466 272 5061 272 4465 272 5063 272 5061 272 4466 272 5193 272 5191 272 5198 272 5187 272 5191 272 5193 272 5041 8296 5071 8296 5069 8296 5036 8297 5071 8297 5041 8297 5061 8298 5059 8298 4465 8298 5036 8299 5073 8299 5071 8299 4465 272 5059 272 4464 272 5059 272 5057 272 4464 272 4464 272 5057 272 4463 272 5027 8300 5075 8300 5036 8300 5036 8301 5075 8301 5073 8301 5198 8302 5183 8302 5181 8302 5198 272 5179 272 5199 272 5181 272 5179 272 5198 272 5191 272 5183 272 5198 272 5179 8303 5177 8303 5199 8303 5185 272 5148 272 5190 272 5226 272 5148 272 5185 272 5057 272 5055 272 4463 272 5190 272 5153 272 5191 272 5191 8304 5153 8304 5183 8304 5148 8305 5151 8305 5190 8305 5027 8306 5023 8306 5075 8306 5177 8307 5174 8307 5199 8307 5151 8308 5153 8308 5190 8308 4463 8309 5055 8309 4462 8309 5055 272 5053 272 4462 272 4828 8310 4830 8310 5227 8310 5173 8311 4872 8311 5174 8311 5174 8312 4872 8312 5199 8312 4830 8313 4881 8313 5227 8313 4881 8314 4880 8314 5227 8314 5173 272 5171 272 4872 272 4872 272 5171 272 4873 272 4460 272 4565 272 4459 272 4461 272 4564 272 4460 272 4460 8315 4564 8315 4565 8315 4565 272 4566 272 4459 272 4880 8316 4879 8316 5227 8316 4459 8317 4566 8317 4458 8317 4462 8318 4563 8318 4461 8318 4461 8319 4563 8319 4564 8319 5053 8320 4563 8320 4462 8320 5014 272 4563 272 5053 272 5171 272 5169 272 4873 272 5014 8321 4562 8321 4563 8321 4458 8322 4345 8322 4330 8322 4567 8323 4345 8323 4566 8323 4568 272 4345 272 4567 272 4566 272 4345 272 4458 272 4873 272 5169 272 4874 272 5014 8324 4561 8324 4562 8324 4568 272 4569 272 4345 272 4874 272 5169 272 4875 272 4345 8325 4569 8325 4596 8325 4878 8326 4679 8326 4879 8326 4879 8327 4679 8327 5227 8327 5169 272 5167 272 4875 272 5014 8328 4560 8328 4561 8328 4569 272 4570 272 4596 272 4596 272 4570 272 4598 272 5014 8329 4559 8329 4560 8329 4875 272 5167 272 4876 272 4570 8330 4571 8330 4598 8330 4598 8331 4571 8331 4600 8331 5167 272 5165 272 4876 272 5014 8332 4558 8332 4559 8332 4876 272 5165 272 4877 272 4571 272 4602 272 4600 272 4571 272 4572 272 4602 272 4698 8333 5082 8333 4710 8333 5014 8334 4557 8334 4558 8334 5165 272 5163 272 4877 272 4573 8335 4602 8335 4572 8335 4573 272 4604 272 4602 272 4877 272 5163 272 4878 272 4698 8336 5084 8336 5082 8336 4574 272 4604 272 4573 272 4574 272 4607 272 4604 272 4684 8337 5084 8337 4698 8337 4575 8338 4607 8338 4574 8338 4575 8339 4609 8339 4607 8339 4684 8340 5086 8340 5084 8340 4576 8341 4609 8341 4575 8341 4557 272 4621 272 4556 272 5014 272 4621 272 4557 272 4556 272 4621 272 4555 272 4576 272 4614 272 4609 272 4577 272 4614 272 4576 272 4555 272 4621 272 4581 272 4621 272 4623 272 4581 272 4577 272 4616 272 4614 272 4578 272 4616 272 4577 272 4623 8342 4625 8342 4581 8342 4581 272 4625 272 4580 272 4684 8343 5088 8343 5086 8343 4579 272 4618 272 4578 272 4578 272 4618 272 4616 272 4580 8344 4620 8344 4579 8344 4625 8345 4620 8345 4580 8345 4579 8346 4620 8346 4618 8346 5156 272 4397 272 5154 272 5156 272 4396 272 4397 272 4397 8347 4398 8347 5154 8347 5158 272 4396 272 5156 272 5154 272 4398 272 5161 272 5158 272 4395 272 4396 272 4398 272 4399 272 5161 272 5163 272 4399 272 4878 272 5161 272 4399 272 5163 272 5158 272 4394 272 4395 272 4878 8348 4399 8348 4679 8348 4329 8349 4394 8349 5158 8349 4399 8350 4400 8350 4679 8350 4329 272 4393 272 4394 272 4679 8351 4400 8351 4684 8351 4346 272 4393 272 4329 272 4684 8352 4400 8352 5088 8352 4400 272 4401 272 5088 272 5088 272 4401 272 5090 272 4346 272 4392 272 4393 272 4348 8353 4392 8353 4346 8353 4401 272 4402 272 5090 272 5090 272 4402 272 5092 272 4348 8354 4391 8354 4392 8354 4402 272 4403 272 5092 272 4350 8355 4391 8355 4348 8355 5092 272 4403 272 5094 272 4403 8356 4404 8356 5094 8356 4350 272 4390 272 4391 272 4350 272 4352 272 4390 272 4352 8357 4389 8357 4390 8357 4404 272 4405 272 5094 272 4405 8358 5096 8358 5094 8358 4352 272 4354 272 4389 272 4389 8359 4354 8359 4388 8359 4354 272 4357 272 4388 272 4388 8360 4357 8360 4387 8360 4357 8361 4413 8361 4387 8361 4406 8362 5098 8362 4405 8362 4405 8363 5098 8363 5096 8363 4357 8364 4412 8364 4413 8364 4407 8365 5098 8365 4406 8365 4407 8366 5100 8366 5098 8366 4408 8367 5102 8367 4407 8367 4407 8368 5102 8368 5100 8368 4408 8369 5104 8369 5102 8369 4409 272 5104 272 4408 272 4509 8370 4510 8370 5106 8370 5106 272 4510 272 4611 272 4510 272 4511 272 4611 272 5106 8371 4508 8371 4509 8371 4511 272 4512 272 4611 272 5106 8372 4507 8372 4508 8372 4512 272 4513 272 4611 272 4611 272 4513 272 4637 272 5106 8373 4506 8373 4507 8373 4637 272 4514 272 4639 272 4513 272 4514 272 4637 272 5106 8374 4505 8374 4506 8374 4639 8375 4514 8375 4635 8375 4514 272 4515 272 4635 272 5106 8376 4504 8376 4505 8376 4409 272 4504 272 5104 272 5104 272 4504 272 5106 272 4515 8377 4516 8377 4635 8377 4635 8378 4516 8378 4633 8378 4409 272 4503 272 4504 272 4410 272 4503 272 4409 272 4516 272 4517 272 4633 272 4411 8379 4503 8379 4410 8379 4517 8380 4630 8380 4633 8380 4411 272 4502 272 4503 272 4518 8381 4630 8381 4517 8381 4518 272 4629 272 4630 272 4519 8382 4629 8382 4518 8382 4519 272 4627 272 4629 272 4520 272 4627 272 4519 272 4520 272 4595 272 4627 272 4412 8383 4359 8383 4411 8383 4357 8384 4359 8384 4412 8384 4501 272 4359 272 4500 272 4502 272 4359 272 4501 272 4411 272 4359 272 4502 272 4500 272 4359 272 4526 272 4520 8385 4593 8385 4595 8385 4521 8386 4593 8386 4520 8386 4526 272 4359 272 4525 272 4359 272 4583 272 4525 272 4521 8387 4590 8387 4593 8387 4522 272 4590 272 4521 272 4583 8388 4585 8388 4525 8388 4525 272 4585 272 4524 272 4585 272 4586 272 4524 272 4522 272 4588 272 4590 272 4523 272 4588 272 4522 272 4524 272 4586 272 4523 272 4586 272 4588 272 4523 272 4960 8389 4818 8389 5206 8389 4872 272 4891 272 5195 272 4872 272 5195 272 5199 272 5228 8390 4343 8390 4342 8390 5149 8391 5148 8391 5240 8391 5240 8392 5148 8392 5226 8392 5215 8393 5229 8393 5230 8393 5215 8394 5210 8394 5229 8394 5218 8395 5215 8395 5230 8395 5218 8396 5230 8396 5231 8396 5219 8397 5218 8397 5231 8397 5219 8398 5231 8398 5232 8398 5220 8399 5219 8399 5232 8399 5220 8400 5232 8400 5233 8400 5221 8401 5220 8401 5233 8401 5221 8402 5233 8402 5234 8402 5222 8403 5221 8403 5234 8403 5222 8404 5234 8404 5235 8404 5222 8405 5235 8405 5236 8405 5223 8406 5222 8406 5236 8406 5223 8407 5236 8407 5237 8407 5224 8408 5237 8408 5238 8408 5224 8409 5223 8409 5237 8409 5225 8410 5238 8410 5239 8410 5225 8411 5224 8411 5238 8411 5226 8412 5239 8412 5240 8412 5226 8413 5225 8413 5239 8413 5205 8414 5254 8414 5210 8414 5210 8415 5254 8415 5229 8415 4603 10 4203 10 4601 10 4601 10 4203 10 4599 10 4603 8416 4201 8416 4203 8416 4605 8417 4201 8417 4603 8417 4203 10 4205 10 4599 10 4599 10 4205 10 4597 10 4606 10 4201 10 4605 10 4597 8418 4205 8418 4344 8418 4606 10 4199 10 4201 10 4205 10 4169 10 4344 10 4608 10 4199 10 4606 10 4608 8419 4197 8419 4199 8419 4613 8420 4197 8420 4608 8420 4169 10 4170 10 4344 10 4615 8421 4197 8421 4613 8421 4615 8422 4195 8422 4197 8422 4170 10 4172 10 4344 10 4617 10 4195 10 4615 10 4617 8423 4193 8423 4195 8423 4172 10 4174 10 4344 10 4617 10 4619 10 4193 10 4193 10 4619 10 4191 10 4619 10 4626 10 4191 10 4191 8424 4626 8424 4189 8424 4626 10 4624 10 4189 10 4624 8425 4622 8425 4189 8425 4189 8426 4622 8426 4187 8426 4185 10 4622 10 4183 10 4187 10 4622 10 4185 10 4622 10 5015 10 4183 10 4178 10 5015 10 4176 10 4180 8427 5015 8427 4178 8427 4183 8428 5015 8428 4180 8428 5015 10 5052 10 4176 10 4176 10 5052 10 4174 10 4242 10 4244 10 4331 10 4344 10 4242 10 4331 10 4174 10 4242 10 4344 10 5054 10 4242 10 5052 10 5052 8429 4242 8429 4174 8429 5054 10 4240 10 4242 10 5056 10 4240 10 5054 10 4244 10 4246 10 4331 10 5058 10 4238 10 5056 10 5056 8430 4238 8430 4240 8430 4246 10 4207 10 4331 10 5060 10 4238 10 5058 10 4331 10 4207 10 4332 10 5060 8431 4236 8431 4238 8431 5062 10 4236 10 5060 10 4207 10 4209 10 4332 10 4332 10 4209 10 4335 10 5062 8432 4234 8432 4236 8432 5064 8433 4234 8433 5062 8433 4209 8434 4211 8434 4335 8434 4211 8435 4337 8435 4335 8435 5064 8436 4233 8436 4234 8436 4211 8437 4339 8437 4337 8437 4213 10 4339 10 4211 10 4233 8438 5066 8438 4230 8438 5064 8439 5066 8439 4233 8439 4213 10 4340 10 4339 10 4215 8440 4340 8440 4213 8440 4215 10 4342 10 4340 10 4230 8441 5068 8441 4229 8441 5066 8442 5068 8442 4230 8442 4215 10 5228 10 4342 10 4218 10 5228 10 4215 10 4219 10 5228 10 4218 10 4221 10 5241 10 4219 10 4219 10 5241 10 5228 10 4229 10 5070 10 4226 10 5068 10 5070 10 4229 10 4223 10 5241 10 4221 10 4223 10 5242 10 5241 10 4225 10 5242 10 4223 10 4225 10 5243 10 5242 10 4226 10 5243 10 4225 10 4226 10 5244 10 5243 10 4631 10 4282 10 4632 10 4631 8443 4280 8443 4282 8443 4632 10 4282 10 4634 10 4628 10 4280 10 4631 10 4282 8444 4285 8444 4634 8444 4628 10 4279 10 4280 10 5070 10 5244 10 4226 10 4634 8445 4285 8445 4636 8445 4636 10 4285 10 4638 10 4594 10 4279 10 4628 10 4285 10 4248 10 4638 10 4638 10 4248 10 4612 10 4594 10 4277 10 4279 10 4592 8446 4277 8446 4594 8446 4248 10 4250 10 4612 10 4592 10 4275 10 4277 10 4591 8447 4275 8447 4592 8447 4589 10 4275 10 4591 10 4589 8448 4273 8448 4275 8448 4250 10 4252 10 4612 10 4587 10 4273 10 4589 10 4587 10 4271 10 4273 10 4252 10 4254 10 4612 10 4587 10 4584 10 4271 10 4271 10 4584 10 4269 10 4584 10 4582 10 4269 10 4582 10 4358 10 4269 10 4269 10 4358 10 4267 10 4263 10 4358 10 4262 10 4265 10 4358 10 4263 10 4267 10 4358 10 4265 10 4256 10 4610 10 4254 10 4258 10 4610 10 4256 10 4260 8449 4610 8449 4258 8449 4254 8450 4610 8450 4612 8450 4798 10 4797 10 5245 10 5246 10 4798 10 5245 10 5246 8451 4799 8451 4798 8451 5245 10 4797 10 5247 10 5244 10 4799 10 5246 10 5070 8452 4799 8452 5244 8452 5072 8453 4799 8453 5070 8453 4797 10 4807 10 5247 10 5072 10 4800 10 4799 10 5074 8454 4800 8454 5072 8454 5247 8455 4807 8455 5248 8455 4807 10 4806 10 5248 10 4262 10 5105 10 4260 10 4260 8456 5105 8456 4610 8456 5248 10 4806 10 5249 10 4806 10 4805 10 5249 10 4805 10 5250 10 5249 10 4804 10 5250 10 4805 10 4803 10 5250 10 4804 10 5074 10 5129 10 4800 10 5076 8457 5129 8457 5074 8457 5077 10 5129 10 5076 10 5078 10 5129 10 5077 10 4800 8458 5129 8458 4801 8458 5079 8459 5130 8459 5078 8459 5080 8460 5130 8460 5079 8460 5081 8461 5130 8461 5080 8461 5083 10 5130 10 5081 10 5078 10 5130 10 5129 10 4803 10 5143 10 5250 10 5129 10 5143 10 4801 10 4802 10 5143 10 4803 10 4801 10 5143 10 4802 10 5130 10 4862 10 5133 10 5250 10 5003 10 5251 10 4862 8462 4861 8462 5133 8462 5003 8463 5002 8463 5251 8463 5083 8464 4863 8464 5130 8464 5130 8465 4863 8465 4862 8465 5250 8466 5004 8466 5003 8466 5085 10 4863 10 5083 10 4861 8467 4871 8467 5133 8467 5002 10 5013 10 5251 10 5085 8468 4864 8468 4863 8468 5087 10 4864 10 5085 10 5013 8469 5012 8469 5251 8469 5250 8470 5005 8470 5004 8470 4871 8471 4870 8471 5133 8471 5012 10 5011 10 5251 10 5251 8472 5011 8472 5252 8472 5011 8473 5253 8473 5252 8473 4322 10 4324 10 5093 10 5093 10 4324 10 5091 10 5095 10 4322 10 5093 10 4324 10 4326 10 5091 10 5095 8474 4320 8474 4322 8474 5091 10 4326 10 5089 10 5097 10 4320 10 5095 10 5011 8475 5254 8475 5253 8475 5097 8476 4318 8476 4320 8476 5089 10 4326 10 5087 10 5099 10 4318 10 5097 10 5010 8477 5254 8477 5011 8477 5009 8478 5254 8478 5010 8478 5008 8479 5254 8479 5009 8479 4326 8480 4287 8480 5087 8480 5101 10 4318 10 5099 10 5101 8481 4317 8481 4318 8481 5103 10 4317 10 5101 10 5103 8482 4315 8482 4317 8482 4262 10 4315 10 5105 10 5105 10 4315 10 5103 10 4358 8483 4315 8483 4262 8483 5162 10 5164 10 4864 10 4864 10 5164 10 4865 10 5087 10 5162 10 4864 10 4287 10 5160 10 5087 10 5087 8484 5160 8484 5162 8484 5164 8485 5166 8485 4865 8485 4865 10 5166 10 4866 10 4289 8486 5160 8486 4287 8486 5166 10 5168 10 4866 10 4289 10 5155 10 5160 10 4291 10 5155 10 4289 10 4866 8487 5168 8487 4867 8487 5168 8488 5170 8488 4867 8488 4292 10 5157 10 4291 10 4291 8489 5157 8489 5155 8489 4294 10 5157 10 4292 10 4867 8490 5170 8490 4868 8490 4294 8491 5159 8491 5157 8491 4296 10 5159 10 4294 10 5170 8492 5172 8492 4868 8492 4868 8493 5172 8493 4869 8493 4296 10 4328 10 5159 10 4298 8494 4328 8494 4296 8494 4309 10 4356 10 4307 10 4311 10 4356 10 4309 10 4358 10 4356 10 4315 10 4313 8495 4356 8495 4311 8495 4315 10 4356 10 4313 10 5172 8496 5175 8496 4869 8496 4307 10 4356 10 4305 10 4298 10 4347 10 4328 10 4356 10 4355 10 4305 10 4305 10 4355 10 4304 10 4300 10 4347 10 4298 10 4355 10 4353 10 4304 10 4300 10 4349 10 4347 10 4353 10 4351 10 4304 10 4302 10 4351 10 4300 10 4300 8497 4351 8497 4349 8497 4304 10 4351 10 4302 10 4869 10 5200 10 4870 10 5005 10 5200 10 5006 10 5133 10 5200 10 5143 10 5250 8498 5200 8498 5005 8498 5143 10 5200 10 5250 10 4870 10 5200 10 5133 10 5178 10 5200 10 5176 10 5176 8499 5200 8499 5175 8499 5175 8500 5200 8500 4869 8500 5178 8501 5197 8501 5200 8501 5182 10 5197 10 5180 10 5180 8502 5197 8502 5178 8502 5200 10 5194 10 5006 10 5182 10 5192 10 5197 10 5184 10 5192 10 5182 10 5184 8503 5189 8503 5192 8503 5150 8504 5189 8504 5152 8504 5152 8505 5189 8505 5184 8505 5150 8506 5149 8506 5189 8506 5197 10 5186 10 5196 10 5192 10 5186 10 5197 10 5194 10 4923 10 5006 10 4923 8507 4922 8507 5006 8507 5194 8508 4924 8508 4923 8508 5149 10 5188 10 5189 10 4922 10 4933 10 5006 10 5006 10 4933 10 5007 10 4933 8509 4932 8509 5007 8509 5194 10 4925 10 4924 10 5196 10 4925 10 5194 10 5188 10 5240 10 5186 10 5149 10 5240 10 5188 10 5008 10 5229 10 5254 10 4932 10 5229 10 5007 10 4931 10 5229 10 4932 10 4930 10 5229 10 4931 10 5007 8510 5229 8510 5008 8510 4929 8511 5229 8511 4930 8511 4928 10 5230 10 4929 10 4929 10 5230 10 5229 10 5240 10 5239 10 5186 10 5186 8512 5239 8512 5196 8512 4927 10 5230 10 4928 10 5239 8513 5238 8513 5196 8513 4927 8514 5231 8514 5230 8514 5238 10 5237 10 5196 10 4926 10 5231 10 4927 10 4926 10 5232 10 5231 10 5237 10 5236 10 5196 10 4926 10 5233 10 5232 10 5236 10 5235 10 5196 10 5196 8515 5235 8515 4925 8515 4925 10 5235 10 4926 10 4926 8516 5234 8516 5233 8516 5235 8517 5234 8517 4926 8517 5202 8518 5204 8518 5251 8518 5202 8519 5251 8519 5252 8519 5201 8520 5202 8520 5252 8520 5201 8521 5252 8521 5253 8521 5203 8522 5201 8522 5253 8522 5205 8523 5253 8523 5254 8523 5205 8524 5203 8524 5253 8524 5250 8525 5251 8525 5204 8525 5250 8526 5204 8526 5206 8526 5250 8527 5212 8527 5249 8527 5206 8528 5212 8528 5250 8528 5212 8529 5211 8529 5249 8529 5249 8530 5211 8530 5248 8530 5211 8531 5213 8531 5248 8531 5248 8532 5213 8532 5247 8532 5247 8533 5213 8533 5245 8533 5213 8534 5216 8534 5245 8534 5216 8535 5217 8535 5245 8535 5245 8536 5217 8536 5246 8536 5217 8537 5214 8537 5246 8537 5246 8538 5214 8538 5244 8538 5244 8539 5209 8539 5243 8539 5214 8540 5209 8540 5244 8540 5243 8541 5208 8541 5242 8541 5209 8542 5208 8542 5243 8542 5242 8543 5208 8543 5241 8543 5208 8544 5207 8544 5241 8544 5241 8545 5207 8545 5228 8545 5207 8546 4343 8546 5228 8546 4648 8547 4762 8547 5255 8547 4649 8548 4648 8548 5255 8548 4649 8549 5255 8549 5256 8549 5257 8550 4649 8550 5256 8550 5258 8551 4651 8551 5257 8551 5260 8552 5262 8552 5259 8552 5261 8553 5258 8553 5262 8553 5263 8554 5260 8554 5264 8554 4654 8555 4653 8555 5261 8555 5266 8556 5264 8556 5265 8556 5267 8557 5263 8557 5264 8557 5266 8558 5265 8558 5268 8558 5271 8559 4831 8559 4828 8559 5271 8560 5268 8560 4831 8560 5271 8561 5270 8561 5268 8561 5272 8562 5273 8562 5270 8562 5272 8563 5270 8563 5271 8563 4716 8564 4717 8564 4718 8564 5274 8565 4715 8565 5272 8565 5259 8566 5258 8566 5257 8566 5259 8567 5257 8567 5256 8567 5262 8568 5258 8568 5259 8568 4651 8569 5261 8569 4653 8569 4651 8570 5258 8570 5261 8570 5263 8571 5262 8571 5260 8571 5269 8572 5261 8572 5262 8572 5269 8573 5263 8573 5267 8573 5269 8574 4719 8574 4720 8574 5269 8575 4720 8575 5261 8575 4720 8576 4654 8576 5261 8576 5267 8577 4719 8577 5269 8577 5267 8578 5275 8578 4719 8578 5266 8579 5268 8579 5270 8579 5266 8580 5270 8580 5273 8580 5273 8581 5276 8581 5264 8581 5275 8582 5276 8582 4718 8582 4718 8583 4719 8583 5275 8583 5277 8584 4828 8584 5227 8584 5277 8585 5271 8585 4828 8585 4716 8586 4718 8586 5276 8586 5273 8587 4716 8587 5276 8587 5273 8588 4715 8588 4716 8588 5273 8589 5272 8589 4715 8589 5277 8590 5272 8590 5271 8590 5274 8591 5277 8591 5227 8591 5274 8592 5272 8592 5277 8592 5262 8593 5263 8593 5269 8593 5275 8594 5267 8594 5264 8594 5275 8595 5264 8595 5276 8595 5266 8596 5273 8596 5264 8596 4723 8597 5268 8597 4747 8597 4831 8598 5268 8598 4723 8598 4747 8599 5268 8599 4744 8599 5268 8600 5265 8600 4744 8600 4744 8601 5144 8601 4739 8601 5265 8602 5132 8602 4744 8602 4744 8603 5132 8603 5144 8603 5132 8604 5265 8604 5134 8604 5144 8605 5146 8605 4739 8605 5265 8606 5264 8606 5134 8606 4739 8607 5146 8607 4751 8607 5264 8608 5260 8608 5134 8608 5134 8609 5260 8609 5135 8609 4751 8610 5146 8610 4734 8610 5146 8611 5147 8611 4734 8611 5260 8612 5259 8612 5135 8612 5147 8613 4735 8613 4734 8613 5135 8614 5259 8614 5139 8614 5147 8615 5145 8615 4735 8615 5145 8616 4731 8616 4735 8616 5259 8617 5256 8617 5139 8617 5139 8618 5256 8618 5136 8618 5256 8619 5255 8619 5136 8619 5145 8620 4736 8620 4731 8620 5145 8621 5120 8621 4736 8621 4736 8622 5120 8622 4722 8622 5255 8623 4762 8623 5136 8623 4762 8624 5125 8624 5136 8624 5125 8625 4762 8625 5126 8625 4722 8626 5114 8626 4755 8626 4762 8627 4766 8627 5126 8627 4766 8628 5128 8628 5126 8628 4766 8629 4764 8629 5128 8629 5112 8630 4760 8630 4756 8630 4764 8631 4761 8631 5128 8631 5120 8632 5116 8632 4722 8632 5116 8633 5114 8633 4722 8633 5114 8634 5112 8634 4756 8634 5114 8635 4756 8635 4755 8635 5112 8636 5108 8636 4760 8636 5110 8637 5128 8637 4761 8637 5278 8638 4167 8638 4678 8638 4166 8639 4167 8639 5278 8639 5045 8640 4668 8640 5279 8640 5043 8641 5045 8641 5279 8641 5043 8642 5279 8642 5280 8642 5028 8643 5043 8643 5280 8643 5028 8644 5280 8644 5281 8644 5026 8645 5028 8645 5281 8645 5026 8646 5281 8646 5282 8646 5021 8647 5026 8647 5282 8647 5017 8648 5021 8648 5282 8648 5017 8649 5282 8649 5283 8649 5016 8650 5017 8650 5283 8650 4678 8651 5283 8651 5278 8651 4678 8652 5016 8652 5283 8652 5284 8653 5279 8653 4667 8653 5279 8654 4668 8654 4667 8654 5285 8655 4667 8655 4726 8655 5285 8656 5284 8656 4667 8656 5285 8657 4726 8657 4729 8657 5286 8658 5285 8658 4729 8658 5286 8659 4729 8659 4732 8659 5286 8660 4732 8660 4721 8660 5287 8661 5286 8661 4721 8661 5287 8662 4721 8662 4752 8662 5287 8663 4752 8663 4754 8663 5288 8664 5287 8664 4754 8664 5288 8665 4754 8665 4757 8665 5289 8666 5288 8666 4757 8666 5289 8667 4757 8667 4759 8667 5289 8668 4759 8668 4753 8668 5109 8669 5289 8669 4753 8669 5109 8670 5113 8670 5289 8670 5278 8671 5283 8671 5282 8671 5278 272 5282 272 5281 272 5278 8672 5281 8672 5280 8672 5278 8673 5280 8673 5279 8673 4161 272 4163 272 4166 272 4158 8674 4161 8674 4166 8674 4154 272 4158 272 4166 272 5115 8675 5289 8675 5113 8675 5115 8676 5287 8676 5288 8676 5115 8677 5288 8677 5289 8677 5115 8678 5286 8678 5287 8678 5115 8679 5285 8679 5286 8679 5117 8680 5284 8680 5285 8680 5117 8681 5285 8681 5115 8681 5117 8682 5279 8682 5284 8682 5121 272 5279 272 5117 272 5121 272 5278 272 5279 272 5121 272 4166 272 5278 272 5121 8683 4154 8683 4166 8683 4652 272 5121 272 5123 272 4652 272 4154 272 5121 272 4640 8684 5127 8684 5107 8684 4650 272 4652 272 5123 272 4642 8685 5127 8685 4640 8685 4644 272 5123 272 5127 272 4644 272 5127 272 4642 272 4647 8686 4650 8686 5123 8686 4644 272 4647 272 5123 272

+
+ + + +

5291 8687 5385 8687 5290 8687 5292 8688 5385 8688 5291 8688 5294 8689 5290 8689 5293 8689 5294 8690 5291 8690 5290 8690 5296 8691 5292 8691 5291 8691 5295 8692 5294 8692 5293 8692 5296 8693 5291 8693 5294 8693 5297 8694 5294 8694 5295 8694 5296 8695 5294 8695 5297 8695 5299 8696 5297 8696 5295 8696 5298 8697 5296 8697 5297 8697 5300 8698 5296 8698 5298 8698 5298 8699 5297 8699 5299 8699 5301 8700 5298 8700 5299 8700 5303 8701 5298 8701 5301 8701 5303 8702 5300 8702 5298 8702 5304 8703 5301 8703 5302 8703 5304 8704 5303 8704 5301 8704 5305 8705 5303 8705 5304 8705 5304 8706 5302 8706 5306 8706 5307 8707 5304 8707 5306 8707 5307 8708 5305 8708 5304 8708 5308 8709 5307 8709 5306 8709 5309 8710 5305 8710 5307 8710 5310 8711 5307 8711 5308 8711 5309 8712 5307 8712 5310 8712 5310 8713 5308 8713 5311 8713 5313 8714 5311 8714 5312 8714 5313 8715 5310 8715 5311 8715 5313 8716 5309 8716 5310 8716 5314 8717 5313 8717 5312 8717 5315 8718 5313 8718 5314 8718 5316 8719 5309 8719 5313 8719 5316 8720 5313 8720 5315 8720 5315 8721 5314 8721 5317 8721 5318 8722 5315 8722 5317 8722 5316 8723 5315 8723 5318 8723 5318 8724 5317 8724 5319 8724 5320 8725 5316 8725 5318 8725 5321 8726 5318 8726 5319 8726 5322 8727 5318 8727 5321 8727 5322 8728 5320 8728 5318 8728 5323 8729 5321 8729 5319 8729 5322 8730 5321 8730 5323 8730 5325 8731 5323 8731 5324 8731 5325 8732 5322 8732 5323 8732 5320 8733 5322 8733 5325 8733 5326 8734 5325 8734 5324 8734 5327 8735 5320 8735 5325 8735 5328 8736 5325 8736 5326 8736 5327 8737 5325 8737 5328 8737 5328 8738 5326 8738 5329 8738 5331 8739 5328 8739 5329 8739 5330 8740 5328 8740 5331 8740 5330 8741 5327 8741 5328 8741 5332 8742 5331 8742 5329 8742 5333 8743 5331 8743 5332 8743 5334 8744 5331 8744 5333 8744 5330 8745 5331 8745 5334 8745 5334 8746 5333 8746 5335 8746 5337 8747 5335 8747 5336 8747 5337 8748 5334 8748 5335 8748 5338 8749 5334 8749 5337 8749 5338 8750 5330 8750 5334 8750 5340 8751 5338 8751 5337 8751 5339 8752 5337 8752 5336 8752 5340 8753 5337 8753 5339 8753 5341 8754 5338 8754 5340 8754 5342 8755 5340 8755 5339 8755 5341 8756 5340 8756 5342 8756 5344 8757 5342 8757 5343 8757 5344 8758 5341 8758 5342 8758 5345 8759 5341 8759 5344 8759 5344 8760 5343 8760 5346 8760 5347 8761 5344 8761 5346 8761 5345 8762 5344 8762 5347 8762 5348 8763 5347 8763 5346 8763 5349 8764 5347 8764 5348 8764 5349 8765 5345 8765 5347 8765 5351 8766 5345 8766 5349 8766 5349 8767 5348 8767 5350 8767 5349 8768 5350 8768 5352 8768 5354 8769 5349 8769 5352 8769 5351 8770 5349 8770 5354 8770 5355 8771 5352 8771 5353 8771 5355 8772 5354 8772 5352 8772 5356 8773 5355 8773 5353 8773 5357 8774 5354 8774 5355 8774 5357 8775 5351 8775 5354 8775 5358 8776 5355 8776 5356 8776 5358 8777 5357 8777 5355 8777 5358 8778 5356 8778 5359 8778 5360 8779 5357 8779 5358 8779 5361 8780 5358 8780 5359 8780 5361 8781 5360 8781 5358 8781 5362 8782 5361 8782 5359 8782 5364 8783 5362 8783 5363 8783 5364 8784 5361 8784 5362 8784 5360 8785 5361 8785 5364 8785 5365 8786 5364 8786 5363 8786 5366 8787 5364 8787 5365 8787 5368 8788 5364 8788 5366 8788 5368 8789 5360 8789 5364 8789 5367 8790 5366 8790 5365 8790 5368 8791 5366 8791 5367 8791 5370 8792 5367 8792 5369 8792 5370 8793 5368 8793 5367 8793 5372 8794 5368 8794 5370 8794 5373 8795 5369 8795 5371 8795 5373 8796 5370 8796 5369 8796 5373 8797 5371 8797 5374 8797 5372 8798 5370 8798 5373 8798 5375 8799 5373 8799 5374 8799 5372 8800 5373 8800 5375 8800 5376 8801 5375 8801 5374 8801 5376 8802 5374 8802 5377 8802 5378 8803 5372 8803 5375 8803 5378 8804 5375 8804 5376 8804 5379 8805 5372 8805 5378 8805 5379 8806 5378 8806 5376 8806 5380 8807 5376 8807 5377 8807 5379 8808 5376 8808 5380 8808 5380 8809 5377 8809 5381 8809 5382 8810 5379 8810 5380 8810 5383 8811 5380 8811 5381 8811 5384 8812 5383 8812 5381 8812 5382 8813 5380 8813 5383 8813 5385 8814 5382 8814 5383 8814 5385 8815 5383 8815 5384 8815 5290 8816 5385 8816 5384 8816 5292 8817 5382 8817 5385 8817 5386 8818 5335 8818 5387 8818 5336 8819 5335 8819 5386 8819 5387 8820 5333 8820 5388 8820 5335 8821 5333 8821 5387 8821 5333 8822 5332 8822 5388 8822 5388 8823 5332 8823 5389 8823 5389 8824 5329 8824 5390 8824 5332 8825 5329 8825 5389 8825 5390 8826 5329 8826 5391 8826 5329 8827 5326 8827 5391 8827 5391 8828 5326 8828 5392 8828 5326 8829 5324 8829 5392 8829 5392 8830 5323 8830 5393 8830 5324 8831 5323 8831 5392 8831 5393 8832 5319 8832 5394 8832 5323 8833 5319 8833 5393 8833 5394 8834 5319 8834 5395 8834 5319 8835 5317 8835 5395 8835 5395 8836 5317 8836 5396 8836 5317 8837 5314 8837 5396 8837 5396 8838 5314 8838 5397 8838 5314 8839 5312 8839 5397 8839 5312 8840 5311 8840 5397 8840 5397 8841 5311 8841 5398 8841 5311 8842 5308 8842 5398 8842 5398 8843 5308 8843 5399 8843 5308 8844 5306 8844 5399 8844 5399 8845 5306 8845 5400 8845 5306 8846 5302 8846 5400 8846 5400 8847 5302 8847 5401 8847 5401 8848 5302 8848 5402 8848 5302 8849 5301 8849 5402 8849 5402 8850 5301 8850 5403 8850 5301 8851 5299 8851 5403 8851 5403 8852 5299 8852 5404 8852 5299 8853 5295 8853 5404 8853 5404 8854 5295 8854 5405 8854 5405 8855 5293 8855 5406 8855 5295 8856 5293 8856 5405 8856 5406 8857 5293 8857 5407 8857 5293 8858 5290 8858 5407 8858 5407 8859 5290 8859 5408 8859 5290 8860 5384 8860 5408 8860 5408 8861 5384 8861 5409 8861 5384 8862 5381 8862 5409 8862 5409 8863 5381 8863 5410 8863 5381 8864 5377 8864 5410 8864 5410 8865 5377 8865 5411 8865 5377 8866 5374 8866 5411 8866 5411 8867 5374 8867 5412 8867 5374 8868 5371 8868 5412 8868 5412 8869 5371 8869 5413 8869 5371 8870 5369 8870 5413 8870 5413 8871 5367 8871 5414 8871 5369 8872 5367 8872 5413 8872 5367 8873 5365 8873 5414 8873 5414 8874 5365 8874 5468 8874 5365 8875 5363 8875 5468 8875 5468 8876 5363 8876 5415 8876 5363 8877 5362 8877 5415 8877 5415 8878 5362 8878 5416 8878 5362 8879 5359 8879 5416 8879 5416 8880 5359 8880 5417 8880 5359 8881 5356 8881 5417 8881 5417 8882 5356 8882 5418 8882 5356 8883 5353 8883 5418 8883 5418 8884 5353 8884 5419 8884 5353 8885 5352 8885 5419 8885 5419 8886 5352 8886 5475 8886 5352 8887 5350 8887 5475 8887 5475 8888 5350 8888 5420 8888 5420 8889 5350 8889 5421 8889 5350 8890 5348 8890 5421 8890 5348 8891 5346 8891 5421 8891 5421 8892 5346 8892 5422 8892 5346 8893 5343 8893 5422 8893 5422 8894 5342 8894 5423 8894 5343 8895 5342 8895 5422 8895 5423 8896 5339 8896 5424 8896 5342 8897 5339 8897 5423 8897 5424 8898 5336 8898 5386 8898 5339 8899 5336 8899 5424 8899 5303 8900 5905 8900 5917 8900 5300 8901 5303 8901 5917 8901 5305 8902 5899 8902 5905 8902 5305 8903 5905 8903 5303 8903 5296 8904 5300 8904 5917 8904 5309 8905 5899 8905 5305 8905 5296 8906 5917 8906 5921 8906 5309 8907 5893 8907 5899 8907 5292 8908 5296 8908 5921 8908 5292 8909 5921 8909 5926 8909 5309 8910 6042 8910 5893 8910 5292 8911 5926 8911 5935 8911 5316 8912 6042 8912 5309 8912 5382 8913 5292 8913 5935 8913 5320 8914 6036 8914 6042 8914 5320 8915 6042 8915 5316 8915 5382 8916 5935 8916 5940 8916 5379 8917 5382 8917 5940 8917 5372 8918 5379 8918 5940 8918 5320 8919 6032 8919 6036 8919 5372 8920 5940 8920 5946 8920 5327 8921 6032 8921 5320 8921 6016 8922 6032 8922 5327 8922 5956 8923 5372 8923 5946 8923 6016 8924 5327 8924 5330 8924 5956 8925 5368 8925 5372 8925 5963 8926 5368 8926 5956 8926 5963 8927 5360 8927 5368 8927 6008 8928 6016 8928 5330 8928 5971 8929 5360 8929 5963 8929 6008 8930 5330 8930 5338 8930 6005 8931 6008 8931 5338 8931 6005 8932 5338 8932 5341 8932 5979 8933 5360 8933 5971 8933 5979 8934 5357 8934 5360 8934 5994 8935 6005 8935 5341 8935 5994 8936 5341 8936 5345 8936 5984 8937 5351 8937 5357 8937 5984 8938 5357 8938 5979 8938 5990 8939 5351 8939 5984 8939 5990 8940 5994 8940 5345 8940 5990 8941 5345 8941 5351 8941 5425 8942 5484 8942 5386 8942 5426 8943 5484 8943 5425 8943 5427 8944 5386 8944 5387 8944 5425 8945 5386 8945 5427 8945 5428 8946 5426 8946 5425 8946 5428 8947 5425 8947 5427 8947 5427 8948 5387 8948 5388 8948 5389 8949 5427 8949 5388 8949 5429 8950 5427 8950 5389 8950 5429 8951 5428 8951 5427 8951 5430 8952 5389 8952 5390 8952 5430 8953 5429 8953 5389 8953 5431 8954 5429 8954 5430 8954 5391 8955 5430 8955 5390 8955 5431 8956 5430 8956 5391 8956 5432 8957 5391 8957 5392 8957 5432 8958 5431 8958 5391 8958 5434 8959 5429 8959 5431 8959 5433 8960 5432 8960 5392 8960 5433 8961 5431 8961 5432 8961 5433 8962 5392 8962 5393 8962 5434 8963 5431 8963 5433 8963 5435 8964 5433 8964 5393 8964 5435 8965 5393 8965 5394 8965 5434 8966 5433 8966 5435 8966 5436 8967 5394 8967 5395 8967 5436 8968 5435 8968 5394 8968 5437 8969 5435 8969 5436 8969 5437 8970 5434 8970 5435 8970 5438 8971 5395 8971 5396 8971 5438 8972 5436 8972 5395 8972 5438 8973 5437 8973 5436 8973 5439 8974 5438 8974 5396 8974 5397 8975 5439 8975 5396 8975 5440 8976 5437 8976 5438 8976 5440 8977 5438 8977 5439 8977 5398 8978 5439 8978 5397 8978 5440 8979 5439 8979 5398 8979 5441 8980 5440 8980 5398 8980 5442 8981 5440 8981 5441 8981 5441 8982 5398 8982 5399 8982 5443 8983 5441 8983 5399 8983 5444 8984 5441 8984 5443 8984 5442 8985 5441 8985 5444 8985 5443 8986 5399 8986 5400 8986 5445 8987 5400 8987 5401 8987 5445 8988 5443 8988 5400 8988 5444 8989 5443 8989 5445 8989 5402 8990 5445 8990 5401 8990 5446 8991 5444 8991 5445 8991 5447 8992 5402 8992 5403 8992 5447 8993 5445 8993 5402 8993 5446 8994 5445 8994 5447 8994 5448 8995 5446 8995 5447 8995 5449 8996 5447 8996 5403 8996 5448 8997 5447 8997 5449 8997 5449 8998 5403 8998 5404 8998 5449 8999 5404 8999 5405 8999 5450 9000 5448 9000 5449 9000 5451 9001 5449 9001 5405 9001 5451 9002 5450 9002 5449 9002 5406 9003 5451 9003 5405 9003 5452 9004 5451 9004 5406 9004 5450 9005 5451 9005 5452 9005 5452 9006 5406 9006 5407 9006 5453 9007 5450 9007 5452 9007 5454 9008 5452 9008 5407 9008 5408 9009 5454 9009 5407 9009 5453 9010 5452 9010 5454 9010 5455 9011 5408 9011 5409 9011 5455 9012 5454 9012 5408 9012 5456 9013 5454 9013 5455 9013 5453 9014 5454 9014 5456 9014 5457 9015 5455 9015 5409 9015 5457 9016 5456 9016 5455 9016 5410 9017 5457 9017 5409 9017 5458 9018 5456 9018 5457 9018 5459 9019 5410 9019 5411 9019 5459 9020 5457 9020 5410 9020 5459 9021 5458 9021 5457 9021 5460 9022 5459 9022 5411 9022 5461 9023 5458 9023 5459 9023 5461 9024 5459 9024 5460 9024 5460 9025 5411 9025 5412 9025 5462 9026 5460 9026 5412 9026 5461 9027 5460 9027 5462 9027 5463 9028 5461 9028 5462 9028 5462 9029 5412 9029 5413 9029 5464 9030 5462 9030 5413 9030 5463 9031 5462 9031 5464 9031 5465 9032 5463 9032 5464 9032 5464 9033 5413 9033 5414 9033 5466 9034 5464 9034 5414 9034 5467 9035 5463 9035 5465 9035 5465 9036 5464 9036 5466 9036 5468 9037 5466 9037 5414 9037 5465 9038 5466 9038 5468 9038 5469 9039 5465 9039 5468 9039 5467 9040 5465 9040 5469 9040 5469 9041 5468 9041 5415 9041 5416 9042 5469 9042 5415 9042 5470 9043 5469 9043 5416 9043 5471 9044 5467 9044 5469 9044 5471 9045 5469 9045 5470 9045 5417 9046 5470 9046 5416 9046 5472 9047 5470 9047 5417 9047 5471 9048 5470 9048 5472 9048 5473 9049 5471 9049 5472 9049 5474 9050 5417 9050 5418 9050 5474 9051 5472 9051 5417 9051 5473 9052 5472 9052 5474 9052 5474 9053 5418 9053 5419 9053 5476 9054 5473 9054 5474 9054 5475 9055 5474 9055 5419 9055 5477 9056 5474 9056 5475 9056 5476 9057 5474 9057 5477 9057 5477 9058 5475 9058 5420 9058 5476 9059 5477 9059 5478 9059 5421 9060 5477 9060 5420 9060 5479 9061 5477 9061 5421 9061 5478 9062 5477 9062 5479 9062 5480 9063 5479 9063 5421 9063 5478 9064 5479 9064 5480 9064 5480 9065 5421 9065 5422 9065 5481 9066 5478 9066 5480 9066 5423 9067 5480 9067 5422 9067 5482 9068 5480 9068 5423 9068 5482 9069 5481 9069 5480 9069 5483 9070 5423 9070 5424 9070 5483 9071 5482 9071 5423 9071 5484 9072 5481 9072 5482 9072 5484 9073 5482 9073 5483 9073 5424 9074 5386 9074 5484 9074 5484 9075 5483 9075 5424 9075 5426 9076 5481 9076 5484 9076 5461 9077 5463 9077 5664 9077 5461 9078 5664 9078 5674 9078 5458 9079 5674 9079 5683 9079 5458 9080 5461 9080 5674 9080 5467 9081 5657 9081 5664 9081 5467 9082 5664 9082 5463 9082 5456 9083 5458 9083 5683 9083 5456 9084 5683 9084 5688 9084 5467 9085 5650 9085 5657 9085 5453 9086 5456 9086 5688 9086 5471 9087 5650 9087 5467 9087 5453 9088 5688 9088 5693 9088 5471 9089 5645 9089 5650 9089 5450 9090 5453 9090 5693 9090 5473 9091 5645 9091 5471 9091 5473 9092 5640 9092 5645 9092 5448 9093 5693 9093 5707 9093 5448 9094 5450 9094 5693 9094 5476 9095 5640 9095 5473 9095 5476 9096 5632 9096 5640 9096 5446 9097 5448 9097 5707 9097 5478 9098 5632 9098 5476 9098 5716 9099 5446 9099 5707 9099 5624 9100 5632 9100 5478 9100 5716 9101 5444 9101 5446 9101 5618 9102 5624 9102 5478 9102 5618 9103 5478 9103 5481 9103 5716 9104 5442 9104 5444 9104 5725 9105 5442 9105 5716 9105 5725 9106 5440 9106 5442 9106 5729 9107 5440 9107 5725 9107 5608 9108 5618 9108 5481 9108 5729 9109 5437 9109 5440 9109 5608 9110 5481 9110 5426 9110 5579 9111 5437 9111 5729 9111 5608 9112 5426 9112 5428 9112 5579 9113 5434 9113 5437 9113 5598 9114 5608 9114 5428 9114 5598 9115 5428 9115 5429 9115 5587 9116 5434 9116 5579 9116 5587 9117 5598 9117 5429 9117 5587 9118 5429 9118 5434 9118 5487 9119 5485 9119 5486 9119 5487 9120 5486 9120 5488 9120 5487 9121 5488 9121 5489 9121 5490 9122 5487 9122 5489 9122 5490 9123 5489 9123 5491 9123 5492 9124 5490 9124 5491 9124 5492 9125 5491 9125 5493 9125 5494 9126 5492 9126 5493 9126 5494 9127 5493 9127 5495 9127 5496 9128 5494 9128 5495 9128 5496 9129 5495 9129 5497 9129 5498 9130 5496 9130 5497 9130 5498 9131 5497 9131 5499 9131 5500 9132 5498 9132 5499 9132 5501 9133 5500 9133 5499 9133 5501 9134 5499 9134 5502 9134 5503 9135 5501 9135 5502 9135 5504 9136 5502 9136 5505 9136 5504 9137 5503 9137 5502 9137 5504 9138 5505 9138 5506 9138 5507 9139 5504 9139 5506 9139 5507 9140 5506 9140 5508 9140 5509 9141 5507 9141 5508 9141 5509 9142 5508 9142 5510 9142 5511 9143 5510 9143 5512 9143 5511 9144 5509 9144 5510 9144 5513 9145 5511 9145 5512 9145 5513 9146 5512 9146 5514 9146 5515 9147 5513 9147 5514 9147 5515 9148 5514 9148 5516 9148 5517 9149 5515 9149 5516 9149 5517 9150 5516 9150 5518 9150 5517 9151 5518 9151 5519 9151 5520 9152 5517 9152 5519 9152 5520 9153 5519 9153 5521 9153 5522 9154 5520 9154 5521 9154 5522 9155 5521 9155 5523 9155 5524 9156 5522 9156 5523 9156 5525 9157 5523 9157 5526 9157 5525 9158 5524 9158 5523 9158 5485 9159 5525 9159 5526 9159 5485 9160 5526 9160 5486 9160 5527 9161 5528 9161 5529 9161 5530 9162 5527 9162 5529 9162 5530 9163 5529 9163 5531 9163 5532 9164 5530 9164 5531 9164 5533 9165 5532 9165 5531 9165 5533 9166 5531 9166 5534 9166 5535 9167 5534 9167 5536 9167 5535 9168 5533 9168 5534 9168 5535 9169 5536 9169 5537 9169 5538 9170 5535 9170 5537 9170 5538 9171 5537 9171 5539 9171 5540 9172 5538 9172 5539 9172 5540 9173 5539 9173 5541 9173 5542 9174 5540 9174 5541 9174 5543 9175 5542 9175 5541 9175 5543 9176 5541 9176 5544 9176 5545 9177 5543 9177 5544 9177 5545 9178 5544 9178 5546 9178 5547 9179 5545 9179 5546 9179 5547 9180 5546 9180 5548 9180 5549 9181 5547 9181 5548 9181 5549 9182 5548 9182 5550 9182 5551 9183 5549 9183 5550 9183 5551 9184 5550 9184 5552 9184 5553 9185 5551 9185 5552 9185 5553 9186 5552 9186 5554 9186 5555 9187 5553 9187 5554 9187 5556 9188 5555 9188 5554 9188 5556 9189 5554 9189 5557 9189 5558 9190 5556 9190 5557 9190 5558 9191 5557 9191 5559 9191 5560 9192 5558 9192 5559 9192 5560 9193 5559 9193 5561 9193 5560 9194 5561 9194 5562 9194 5563 9195 5560 9195 5562 9195 5564 9196 5562 9196 5565 9196 5564 9197 5563 9197 5562 9197 5566 9198 5564 9198 5565 9198 5566 9199 5565 9199 5567 9199 5568 9200 5566 9200 5567 9200 5568 9201 5567 9201 5569 9201 5527 9202 5569 9202 5528 9202 5527 9203 5568 9203 5569 9203 5572 9204 5571 9204 5570 9204 5572 9205 5573 9205 5571 9205 5574 9206 5729 9206 5573 9206 5572 9207 5570 9207 5575 9207 5576 9208 5573 9208 5572 9208 5574 9209 5573 9209 5576 9209 5575 9210 5576 9210 5572 9210 5574 9211 5579 9211 5729 9211 5578 9212 5575 9212 5577 9212 5578 9213 5576 9213 5575 9213 5580 9214 5576 9214 5578 9214 5580 9215 5574 9215 5576 9215 5581 9216 5578 9216 5577 9216 5582 9217 5578 9217 5581 9217 5579 9218 5574 9218 5580 9218 5582 9219 5580 9219 5578 9219 5583 9220 5580 9220 5582 9220 5584 9221 5582 9221 5581 9221 5583 9222 5579 9222 5580 9222 5585 9223 5582 9223 5584 9223 5583 9224 5582 9224 5585 9224 5586 9225 5585 9225 5584 9225 5587 9226 5579 9226 5583 9226 5588 9227 5586 9227 5584 9227 5589 9228 5583 9228 5585 9228 5587 9229 5583 9229 5589 9229 5589 9230 5585 9230 5586 9230 5590 9231 5586 9231 5588 9231 5590 9232 5588 9232 5591 9232 5590 9233 5589 9233 5586 9233 5592 9234 5589 9234 5590 9234 5593 9235 5590 9235 5591 9235 5587 9236 5589 9236 5592 9236 5593 9237 5591 9237 5594 9237 5595 9238 5590 9238 5593 9238 5595 9239 5592 9239 5590 9239 5596 9240 5593 9240 5594 9240 5596 9241 5595 9241 5593 9241 5597 9242 5596 9242 5594 9242 5598 9243 5592 9243 5595 9243 5598 9244 5587 9244 5592 9244 5599 9245 5596 9245 5597 9245 5601 9246 5596 9246 5599 9246 5601 9247 5595 9247 5596 9247 5599 9248 5597 9248 5600 9248 5601 9249 5598 9249 5595 9249 5602 9250 5598 9250 5601 9250 5604 9251 5600 9251 5603 9251 5604 9252 5599 9252 5600 9252 5601 9253 5599 9253 5604 9253 5605 9254 5601 9254 5604 9254 5606 9255 5604 9255 5603 9255 5605 9256 5602 9256 5601 9256 5606 9257 5605 9257 5604 9257 5606 9258 5603 9258 5607 9258 5608 9259 5598 9259 5602 9259 5608 9260 5602 9260 5605 9260 5610 9261 5605 9261 5606 9261 5608 9262 5605 9262 5610 9262 5609 9263 5606 9263 5607 9263 5610 9264 5606 9264 5609 9264 5611 9265 5610 9265 5609 9265 5611 9266 5609 9266 5612 9266 5613 9267 5610 9267 5611 9267 5613 9268 5608 9268 5610 9268 5613 9269 5611 9269 5614 9269 5615 9270 5611 9270 5612 9270 5614 9271 5611 9271 5615 9271 5616 9272 5615 9272 5612 9272 5618 9273 5608 9273 5613 9273 5618 9274 5614 9274 5615 9274 5618 9275 5613 9275 5614 9275 5617 9276 5615 9276 5616 9276 5619 9277 5615 9277 5617 9277 5619 9278 5618 9278 5615 9278 5621 9279 5617 9279 5620 9279 5621 9280 5619 9280 5617 9280 5623 9281 5619 9281 5621 9281 5618 9282 5619 9282 5623 9282 5623 9283 5620 9283 5622 9283 5623 9284 5621 9284 5620 9284 5624 9285 5618 9285 5623 9285 5625 9286 5623 9286 5622 9286 5625 9287 5624 9287 5623 9287 5627 9288 5622 9288 5626 9288 5627 9289 5625 9289 5622 9289 5629 9290 5625 9290 5627 9290 5629 9291 5624 9291 5625 9291 5628 9292 5627 9292 5626 9292 5630 9293 5627 9293 5628 9293 5629 9294 5627 9294 5630 9294 5630 9295 5628 9295 5631 9295 5632 9296 5624 9296 5629 9296 5632 9297 5629 9297 5630 9297 5633 9298 5630 9298 5631 9298 5632 9299 5630 9299 5633 9299 5633 9300 5631 9300 5634 9300 5635 9301 5633 9301 5634 9301 5636 9302 5635 9302 5634 9302 5637 9303 5633 9303 5635 9303 5637 9304 5632 9304 5633 9304 5638 9305 5635 9305 5636 9305 5638 9306 5637 9306 5635 9306 5638 9307 5636 9307 5639 9307 5640 9308 5632 9308 5637 9308 5641 9309 5637 9309 5638 9309 5641 9310 5640 9310 5637 9310 5642 9311 5638 9311 5639 9311 5642 9312 5641 9312 5638 9312 5642 9313 5639 9313 5643 9313 5644 9314 5641 9314 5642 9314 5645 9315 5641 9315 5644 9315 5645 9316 5640 9316 5641 9316 5644 9317 5642 9317 5643 9317 5648 9318 5643 9318 5646 9318 5647 9319 5645 9319 5644 9319 5648 9320 5644 9320 5643 9320 5647 9321 5644 9321 5648 9321 5651 9322 5647 9322 5648 9322 5650 9323 5647 9323 5651 9323 5651 9324 5646 9324 5649 9324 5651 9325 5648 9325 5646 9325 5650 9326 5645 9326 5647 9326 5653 9327 5650 9327 5651 9327 5652 9328 5651 9328 5649 9328 5654 9329 5651 9329 5652 9329 5653 9330 5651 9330 5654 9330 5655 9331 5654 9331 5652 9331 5656 9332 5654 9332 5655 9332 5657 9333 5650 9333 5653 9333 5656 9334 5653 9334 5654 9334 5659 9335 5655 9335 5658 9335 5657 9336 5653 9336 5656 9336 5659 9337 5656 9337 5655 9337 5657 9338 5656 9338 5659 9338 5660 9339 5659 9339 5658 9339 5661 9340 5657 9340 5659 9340 5661 9341 5659 9341 5660 9341 5663 9342 5661 9342 5660 9342 5663 9343 5657 9343 5661 9343 5664 9344 5657 9344 5663 9344 5663 9345 5660 9345 5662 9345 5666 9346 5662 9346 5665 9346 5666 9347 5663 9347 5662 9347 5664 9348 5663 9348 5666 9348 5668 9349 5665 9349 5667 9349 5669 9350 5664 9350 5666 9350 5668 9351 5666 9351 5665 9351 5669 9352 5666 9352 5668 9352 5671 9353 5668 9353 5667 9353 5669 9354 5668 9354 5671 9354 5671 9355 5667 9355 5670 9355 5674 9356 5664 9356 5669 9356 5673 9357 5669 9357 5671 9357 5672 9358 5671 9358 5670 9358 5674 9359 5669 9359 5673 9359 5675 9360 5671 9360 5672 9360 5673 9361 5671 9361 5675 9361 5677 9362 5675 9362 5672 9362 5676 9363 5674 9363 5673 9363 5679 9364 5673 9364 5675 9364 5683 9365 5674 9365 5676 9365 5678 9366 5675 9366 5677 9366 5676 9367 5673 9367 5679 9367 5679 9368 5675 9368 5678 9368 5680 9369 5676 9369 5679 9369 5682 9370 5678 9370 5681 9370 5682 9371 5679 9371 5678 9371 5680 9372 5679 9372 5682 9372 5683 9373 5676 9373 5680 9373 5684 9374 5682 9374 5681 9374 5684 9375 5680 9375 5682 9375 5686 9376 5680 9376 5684 9376 5684 9377 5681 9377 5685 9377 5686 9378 5683 9378 5680 9378 5688 9379 5683 9379 5686 9379 5689 9380 5685 9380 5687 9380 5689 9381 5684 9381 5685 9381 5689 9382 5686 9382 5684 9382 5691 9383 5686 9383 5689 9383 5690 9384 5689 9384 5687 9384 5691 9385 5688 9385 5686 9385 5691 9386 5689 9386 5690 9386 5693 9387 5688 9387 5691 9387 5694 9388 5690 9388 5692 9388 5694 9389 5691 9389 5690 9389 5693 9390 5691 9390 5694 9390 5696 9391 5692 9391 5695 9391 5694 9392 5692 9392 5696 9392 5697 9393 5693 9393 5694 9393 5697 9394 5694 9394 5696 9394 5698 9395 5696 9395 5695 9395 5699 9396 5693 9396 5697 9396 5697 9397 5696 9397 5698 9397 5698 9398 5695 9398 5700 9398 5701 9399 5698 9399 5700 9399 5701 9400 5697 9400 5698 9400 5703 9401 5697 9401 5701 9401 5703 9402 5699 9402 5697 9402 5701 9403 5700 9403 5702 9403 5707 9404 5693 9404 5699 9404 5707 9405 5699 9405 5703 9405 5705 9406 5702 9406 5704 9406 5705 9407 5701 9407 5702 9407 5706 9408 5703 9408 5701 9408 5707 9409 5703 9409 5706 9409 5706 9410 5701 9410 5705 9410 5708 9411 5705 9411 5704 9411 5709 9412 5705 9412 5708 9412 5709 9413 5706 9413 5705 9413 5712 9414 5706 9414 5709 9414 5710 9415 5706 9415 5712 9415 5712 9416 5708 9416 5711 9416 5712 9417 5709 9417 5708 9417 5707 9418 5706 9418 5710 9418 5710 9419 5712 9419 5713 9419 5715 9420 5711 9420 5714 9420 5715 9421 5712 9421 5711 9421 5715 9422 5713 9422 5712 9422 5716 9423 5707 9423 5710 9423 5718 9424 5714 9424 5717 9424 5716 9425 5710 9425 5713 9425 5718 9426 5715 9426 5714 9426 5719 9427 5715 9427 5718 9427 5719 9428 5713 9428 5715 9428 5716 9429 5713 9429 5719 9429 5722 9430 5719 9430 5718 9430 5721 9431 5719 9431 5722 9431 5720 9432 5718 9432 5717 9432 5721 9433 5716 9433 5719 9433 5722 9434 5718 9434 5720 9434 5723 9435 5721 9435 5722 9435 5723 9436 5722 9436 5720 9436 5725 9437 5721 9437 5723 9437 5724 9438 5723 9438 5720 9438 5725 9439 5716 9439 5721 9439 5726 9440 5723 9440 5724 9440 5725 9441 5723 9441 5726 9441 5727 9442 5726 9442 5724 9442 5728 9443 5727 9443 5724 9443 5728 9444 5570 9444 5571 9444 5729 9445 5726 9445 5727 9445 5571 9446 5727 9446 5728 9446 5729 9447 5725 9447 5726 9447 5573 9448 5727 9448 5571 9448 5573 9449 5729 9449 5727 9449 5570 9450 5730 9450 5731 9450 5575 9451 5570 9451 5731 9451 5575 9452 5731 9452 5732 9452 5577 9453 5575 9453 5732 9453 5577 9454 5732 9454 5733 9454 5581 9455 5577 9455 5733 9455 5581 9456 5733 9456 5734 9456 5584 9457 5734 9457 5735 9457 5584 9458 5581 9458 5734 9458 5584 9459 5735 9459 5736 9459 5588 9460 5584 9460 5736 9460 5591 9461 5588 9461 5736 9461 5591 9462 5736 9462 5737 9462 5594 9463 5737 9463 5738 9463 5594 9464 5591 9464 5737 9464 5594 9465 5738 9465 5739 9465 5597 9466 5594 9466 5739 9466 5597 9467 5739 9467 5740 9467 5600 9468 5597 9468 5740 9468 5600 9469 5740 9469 5741 9469 5603 9470 5600 9470 5741 9470 5603 9471 5741 9471 5742 9471 5607 9472 5603 9472 5742 9472 5607 9473 5742 9473 5867 9473 5609 9474 5607 9474 5867 9474 5609 9475 5867 9475 5743 9475 5609 9476 5743 9476 5744 9476 5612 9477 5609 9477 5744 9477 5612 9478 5744 9478 5745 9478 5616 9479 5612 9479 5745 9479 5616 9480 5745 9480 5858 9480 5617 9481 5616 9481 5858 9481 5620 9482 5617 9482 5858 9482 5620 9483 5858 9483 5746 9483 5622 9484 5620 9484 5746 9484 5622 9485 5746 9485 5854 9485 5622 9486 5854 9486 5747 9486 5626 9487 5622 9487 5747 9487 5626 9488 5747 9488 5748 9488 5628 9489 5626 9489 5748 9489 5631 9490 5628 9490 5748 9490 5631 9491 5748 9491 5749 9491 5634 9492 5631 9492 5749 9492 5634 9493 5749 9493 5750 9493 5636 9494 5634 9494 5750 9494 5636 9495 5750 9495 5751 9495 5639 9496 5636 9496 5751 9496 5639 9497 5751 9497 5752 9497 5643 9498 5639 9498 5752 9498 5643 9499 5752 9499 5753 9499 5646 9500 5753 9500 5754 9500 5646 9501 5643 9501 5753 9501 5649 9502 5646 9502 5754 9502 5649 9503 5754 9503 5837 9503 5652 9504 5649 9504 5837 9504 5652 9505 5837 9505 5755 9505 5652 9506 5755 9506 5756 9506 5655 9507 5652 9507 5756 9507 5658 9508 5655 9508 5756 9508 5658 9509 5756 9509 5757 9509 5660 9510 5658 9510 5757 9510 5660 9511 5757 9511 5758 9511 5662 9512 5660 9512 5758 9512 5662 9513 5758 9513 5759 9513 5665 9514 5662 9514 5759 9514 5665 9515 5759 9515 5760 9515 5667 9516 5665 9516 5760 9516 5667 9517 5760 9517 5761 9517 5670 9518 5667 9518 5761 9518 5672 9519 5761 9519 5762 9519 5672 9520 5670 9520 5761 9520 5672 9521 5762 9521 5763 9521 5677 9522 5672 9522 5763 9522 5677 9523 5763 9523 5764 9523 5678 9524 5677 9524 5764 9524 5681 9525 5678 9525 5764 9525 5681 9526 5764 9526 5765 9526 5681 9527 5765 9527 5766 9527 5685 9528 5681 9528 5766 9528 5685 9529 5766 9529 5767 9529 5687 9530 5685 9530 5767 9530 5687 9531 5767 9531 5768 9531 5690 9532 5687 9532 5768 9532 5690 9533 5768 9533 5769 9533 5692 9534 5690 9534 5769 9534 5695 9535 5769 9535 5770 9535 5695 9536 5692 9536 5769 9536 5695 9537 5770 9537 5771 9537 5700 9538 5771 9538 5772 9538 5700 9539 5695 9539 5771 9539 5702 9540 5772 9540 5773 9540 5702 9541 5700 9541 5772 9541 5704 9542 5702 9542 5773 9542 5704 9543 5773 9543 5774 9543 5708 9544 5704 9544 5774 9544 5711 9545 5774 9545 5775 9545 5711 9546 5708 9546 5774 9546 5714 9547 5775 9547 5776 9547 5714 9548 5711 9548 5775 9548 5714 9549 5776 9549 5777 9549 5717 9550 5714 9550 5777 9550 5717 9551 5777 9551 5778 9551 5720 9552 5778 9552 5779 9552 5720 9553 5717 9553 5778 9553 5724 9554 5720 9554 5779 9554 5724 9555 5779 9555 5780 9555 5728 9556 5780 9556 5781 9556 5728 9557 5724 9557 5780 9557 5570 9558 5781 9558 5730 9558 5570 9559 5728 9559 5781 9559 5782 9560 5730 9560 5781 9560 5784 9561 5783 9561 5782 9561 5785 9562 5781 9562 5780 9562 5785 9563 5782 9563 5781 9563 5789 9564 5885 9564 5784 9564 5786 9565 5782 9565 5785 9565 5784 9566 5782 9566 5786 9566 5787 9567 5785 9567 5780 9567 5786 9568 5785 9568 5787 9568 5787 9569 5780 9569 5779 9569 5788 9570 5786 9570 5787 9570 5788 9571 5787 9571 5779 9571 5789 9572 5784 9572 5786 9572 5790 9573 5786 9573 5788 9573 5789 9574 5786 9574 5790 9574 5778 9575 5788 9575 5779 9575 5790 9576 5788 9576 5778 9576 5791 9577 5789 9577 5790 9577 5792 9578 5778 9578 5777 9578 5792 9579 5790 9579 5778 9579 5793 9580 5790 9580 5792 9580 5796 9581 5789 9581 5791 9581 5792 9582 5777 9582 5776 9582 5791 9583 5790 9583 5793 9583 5794 9584 5792 9584 5776 9584 5793 9585 5792 9585 5794 9585 5775 9586 5794 9586 5776 9586 5795 9587 5793 9587 5794 9587 5795 9588 5791 9588 5793 9588 5796 9589 5791 9589 5795 9589 5797 9590 5794 9590 5775 9590 5795 9591 5794 9591 5797 9591 5774 9592 5797 9592 5775 9592 5798 9593 5797 9593 5774 9593 5799 9594 5796 9594 5795 9594 5800 9595 5797 9595 5798 9595 5800 9596 5795 9596 5797 9596 5773 9597 5798 9597 5774 9597 5800 9598 5799 9598 5795 9598 5801 9599 5798 9599 5773 9599 5801 9600 5800 9600 5798 9600 5801 9601 5773 9601 5772 9601 5802 9602 5800 9602 5801 9602 5802 9603 5799 9603 5800 9603 5803 9604 5801 9604 5772 9604 5802 9605 5801 9605 5803 9605 5803 9606 5772 9606 5771 9606 5804 9607 5799 9607 5802 9607 5805 9608 5803 9608 5771 9608 5806 9609 5803 9609 5805 9609 5806 9610 5802 9610 5803 9610 5804 9611 5802 9611 5806 9611 5805 9612 5771 9612 5770 9612 5807 9613 5770 9613 5769 9613 5807 9614 5805 9614 5770 9614 5806 9615 5805 9615 5807 9615 5768 9616 5807 9616 5769 9616 5809 9617 5804 9617 5806 9617 5808 9618 5806 9618 5807 9618 5809 9619 5806 9619 5808 9619 5767 9620 5807 9620 5768 9620 5810 9621 5807 9621 5767 9621 5808 9622 5807 9622 5810 9622 5812 9623 5804 9623 5809 9623 5811 9624 5809 9624 5808 9624 5812 9625 5809 9625 5811 9625 5811 9626 5808 9626 5810 9626 5813 9627 5767 9627 5766 9627 5813 9628 5810 9628 5767 9628 5813 9629 5811 9629 5810 9629 5814 9630 5811 9630 5813 9630 5814 9631 5812 9631 5811 9631 5765 9632 5813 9632 5766 9632 5814 9633 5813 9633 5765 9633 5815 9634 5812 9634 5814 9634 5816 9635 5765 9635 5764 9635 5817 9636 5815 9636 5814 9636 5816 9637 5814 9637 5765 9637 5817 9638 5814 9638 5816 9638 5819 9639 5764 9639 5763 9639 5819 9640 5816 9640 5764 9640 5818 9641 5815 9641 5817 9641 5819 9642 5817 9642 5816 9642 5818 9643 5817 9643 5819 9643 5820 9644 5763 9644 5762 9644 5820 9645 5819 9645 5763 9645 5821 9646 5818 9646 5819 9646 5821 9647 5819 9647 5820 9647 5761 9648 5820 9648 5762 9648 5822 9649 5820 9649 5761 9649 5823 9650 5820 9650 5822 9650 5823 9651 5821 9651 5820 9651 5823 9652 5818 9652 5821 9652 5760 9653 5822 9653 5761 9653 5825 9654 5822 9654 5760 9654 5824 9655 5818 9655 5823 9655 5823 9656 5822 9656 5825 9656 5759 9657 5825 9657 5760 9657 5826 9658 5823 9658 5825 9658 5824 9659 5823 9659 5826 9659 5827 9660 5759 9660 5758 9660 5827 9661 5825 9661 5759 9661 5826 9662 5825 9662 5827 9662 5830 9663 5824 9663 5826 9663 5828 9664 5826 9664 5827 9664 5829 9665 5827 9665 5758 9665 5830 9666 5826 9666 5828 9666 5829 9667 5828 9667 5827 9667 5757 9668 5829 9668 5758 9668 5831 9669 5828 9669 5829 9669 5832 9670 5757 9670 5756 9670 5832 9671 5829 9671 5757 9671 5831 9672 5830 9672 5828 9672 5832 9673 5831 9673 5829 9673 5833 9674 5830 9674 5831 9674 5833 9675 5831 9675 5832 9675 5835 9676 5756 9676 5755 9676 5835 9677 5832 9677 5756 9677 5834 9678 5830 9678 5833 9678 5833 9679 5832 9679 5835 9679 5836 9680 5833 9680 5835 9680 5836 9681 5835 9681 5755 9681 5834 9682 5833 9682 5836 9682 5837 9683 5836 9683 5755 9683 5838 9684 5836 9684 5837 9684 5839 9685 5834 9685 5836 9685 5838 9686 5837 9686 5754 9686 5839 9687 5836 9687 5838 9687 5840 9688 5834 9688 5839 9688 5753 9689 5838 9689 5754 9689 5841 9690 5838 9690 5753 9690 5839 9691 5838 9691 5841 9691 5840 9692 5839 9692 5841 9692 5842 9693 5753 9693 5752 9693 5842 9694 5841 9694 5753 9694 5842 9695 5752 9695 5751 9695 5843 9696 5841 9696 5842 9696 5844 9697 5841 9697 5843 9697 5844 9698 5840 9698 5841 9698 5843 9699 5842 9699 5751 9699 5845 9700 5843 9700 5751 9700 5845 9701 5751 9701 5750 9701 5846 9702 5843 9702 5845 9702 5847 9703 5843 9703 5846 9703 5847 9704 5844 9704 5843 9704 5846 9705 5845 9705 5750 9705 5749 9706 5846 9706 5750 9706 5849 9707 5844 9707 5847 9707 5848 9708 5846 9708 5749 9708 5848 9709 5847 9709 5846 9709 5748 9710 5848 9710 5749 9710 5849 9711 5847 9711 5848 9711 5850 9712 5848 9712 5748 9712 5850 9713 5849 9713 5848 9713 5851 9714 5748 9714 5747 9714 5851 9715 5850 9715 5748 9715 5853 9716 5850 9716 5851 9716 5853 9717 5849 9717 5850 9717 5852 9718 5849 9718 5853 9718 5854 9719 5851 9719 5747 9719 5855 9720 5851 9720 5854 9720 5855 9721 5853 9721 5851 9721 5852 9722 5853 9722 5855 9722 5856 9723 5855 9723 5854 9723 5856 9724 5854 9724 5746 9724 5857 9725 5855 9725 5856 9725 5857 9726 5852 9726 5855 9726 5858 9727 5856 9727 5746 9727 5857 9728 5856 9728 5858 9728 5859 9729 5852 9729 5857 9729 5860 9730 5857 9730 5858 9730 5860 9731 5859 9731 5857 9731 5860 9732 5858 9732 5745 9732 5861 9733 5860 9733 5745 9733 5862 9734 5860 9734 5861 9734 5862 9735 5859 9735 5860 9735 5863 9736 5859 9736 5862 9736 5744 9737 5861 9737 5745 9737 5864 9738 5861 9738 5744 9738 5864 9739 5862 9739 5861 9739 5866 9740 5859 9740 5863 9740 5743 9741 5864 9741 5744 9741 5865 9742 5862 9742 5864 9742 5865 9743 5863 9743 5862 9743 5866 9744 5863 9744 5865 9744 5867 9745 5864 9745 5743 9745 5865 9746 5864 9746 5867 9746 5868 9747 5866 9747 5865 9747 5869 9748 5867 9748 5742 9748 5869 9749 5865 9749 5867 9749 5868 9750 5865 9750 5869 9750 5870 9751 5866 9751 5868 9751 5741 9752 5869 9752 5742 9752 5871 9753 5869 9753 5741 9753 5868 9754 5869 9754 5871 9754 5872 9755 5868 9755 5871 9755 5870 9756 5868 9756 5872 9756 5871 9757 5741 9757 5740 9757 5739 9758 5871 9758 5740 9758 5872 9759 5871 9759 5739 9759 5873 9760 5872 9760 5739 9760 5873 9761 5739 9761 5738 9761 5874 9762 5870 9762 5872 9762 5874 9763 5872 9763 5873 9763 5875 9764 5873 9764 5738 9764 5875 9765 5874 9765 5873 9765 5737 9766 5875 9766 5738 9766 5876 9767 5874 9767 5875 9767 5877 9768 5737 9768 5736 9768 5877 9769 5875 9769 5737 9769 5877 9770 5876 9770 5875 9770 5878 9771 5877 9771 5736 9771 5879 9772 5874 9772 5876 9772 5878 9773 5876 9773 5877 9773 5879 9774 5876 9774 5878 9774 5878 9775 5736 9775 5735 9775 5880 9776 5878 9776 5735 9776 5881 9777 5874 9777 5879 9777 5880 9778 5879 9778 5878 9778 5734 9779 5880 9779 5735 9779 5881 9780 5879 9780 5880 9780 5882 9781 5880 9781 5734 9781 5882 9782 5881 9782 5880 9782 5733 9783 5882 9783 5734 9783 5883 9784 5881 9784 5882 9784 5732 9785 5882 9785 5733 9785 5884 9786 5882 9786 5732 9786 5883 9787 5882 9787 5884 9787 5884 9788 5732 9788 5731 9788 5885 9789 5881 9789 5883 9789 5885 9790 5883 9790 5884 9790 5886 9791 5884 9791 5731 9791 5886 9792 5885 9792 5884 9792 5730 9793 5886 9793 5731 9793 5886 9794 5730 9794 5782 9794 5886 9795 5782 9795 5783 9795 5783 9796 5885 9796 5886 9796 5885 9797 5783 9797 5784 9797 5531 9798 5796 9798 5534 9798 5534 9799 5796 9799 5799 9799 5531 9800 5789 9800 5796 9800 5536 9801 5534 9801 5799 9801 5529 9802 5789 9802 5531 9802 5536 9803 5799 9803 5804 9803 5537 9804 5536 9804 5804 9804 5528 9805 5789 9805 5529 9805 5528 9806 5885 9806 5789 9806 5539 9807 5537 9807 5804 9807 5539 9808 5804 9808 5812 9808 5539 9809 5812 9809 5815 9809 5569 9810 5885 9810 5528 9810 5569 9811 5881 9811 5885 9811 5541 9812 5539 9812 5815 9812 5567 9813 5881 9813 5569 9813 5541 9814 5815 9814 5818 9814 5565 9815 5881 9815 5567 9815 5565 9816 5874 9816 5881 9816 5544 9817 5818 9817 5824 9817 5544 9818 5541 9818 5818 9818 5824 9819 5546 9819 5544 9819 5874 9820 5565 9820 5562 9820 5830 9821 5546 9821 5824 9821 5870 9822 5874 9822 5562 9822 5830 9823 5548 9823 5546 9823 5866 9824 5562 9824 5561 9824 5866 9825 5870 9825 5562 9825 5834 9826 5548 9826 5830 9826 5866 9827 5561 9827 5559 9827 5834 9828 5550 9828 5548 9828 5840 9829 5550 9829 5834 9829 5859 9830 5866 9830 5559 9830 5859 9831 5559 9831 5557 9831 5852 9832 5859 9832 5557 9832 5844 9833 5550 9833 5840 9833 5844 9834 5552 9834 5550 9834 5844 9835 5554 9835 5552 9835 5852 9836 5557 9836 5554 9836 5849 9837 5554 9837 5844 9837 5849 9838 5852 9838 5554 9838 5890 9839 5888 9839 5887 9839 5892 9840 5889 9840 5888 9840 5891 9841 5889 9841 5892 9841 5892 9842 5888 9842 5890 9842 5893 9843 6042 9843 5891 9843 5895 9844 5890 9844 5894 9844 5895 9845 5892 9845 5890 9845 5896 9846 5892 9846 5895 9846 5896 9847 5891 9847 5892 9847 5893 9848 5891 9848 5896 9848 5896 9849 5895 9849 5894 9849 5898 9850 5894 9850 5897 9850 5898 9851 5896 9851 5894 9851 5899 9852 5893 9852 5896 9852 5901 9853 5896 9853 5898 9853 5899 9854 5896 9854 5901 9854 5898 9855 5897 9855 5900 9855 5902 9856 5898 9856 5900 9856 5902 9857 5901 9857 5898 9857 5902 9858 5900 9858 5903 9858 5904 9859 5901 9859 5902 9859 5906 9860 5902 9860 5903 9860 5905 9861 5899 9861 5901 9861 5906 9862 5904 9862 5902 9862 5906 9863 5903 9863 5907 9863 5905 9864 5901 9864 5904 9864 5908 9865 5904 9865 5906 9865 5909 9866 5906 9866 5907 9866 5905 9867 5904 9867 5908 9867 5910 9868 5906 9868 5909 9868 5912 9869 5905 9869 5908 9869 5911 9870 5906 9870 5910 9870 5911 9871 5908 9871 5906 9871 5912 9872 5908 9872 5911 9872 5914 9873 5909 9873 5913 9873 5914 9874 5910 9874 5909 9874 5911 9875 5910 9875 5914 9875 5917 9876 5905 9876 5912 9876 5915 9877 5911 9877 5914 9877 5916 9878 5914 9878 5913 9878 5917 9879 5911 9879 5915 9879 5917 9880 5912 9880 5911 9880 5915 9881 5914 9881 5916 9881 5919 9882 5917 9882 5915 9882 5920 9883 5916 9883 5918 9883 5920 9884 5915 9884 5916 9884 5919 9885 5915 9885 5920 9885 5921 9886 5917 9886 5919 9886 5922 9887 5919 9887 5920 9887 5921 9888 5919 9888 5922 9888 5923 9889 5920 9889 5918 9889 5922 9890 5920 9890 5923 9890 5925 9891 5923 9891 5924 9891 5925 9892 5922 9892 5923 9892 5927 9893 5921 9893 5922 9893 5926 9894 5921 9894 5927 9894 5927 9895 5922 9895 5925 9895 5928 9896 5925 9896 5924 9896 5928 9897 5927 9897 5925 9897 5929 9898 5928 9898 5924 9898 5926 9899 5927 9899 5928 9899 5931 9900 5929 9900 5930 9900 5931 9901 5928 9901 5929 9901 5932 9902 5928 9902 5931 9902 5932 9903 5926 9903 5928 9903 5931 9904 5930 9904 5933 9904 5934 9905 5932 9905 5931 9905 5935 9906 5926 9906 5932 9906 5934 9907 5931 9907 5933 9907 5935 9908 5932 9908 5934 9908 5936 9909 5934 9909 5933 9909 5937 9910 5936 9910 5933 9910 5938 9911 5934 9911 5936 9911 5935 9912 5934 9912 5938 9912 5939 9913 5936 9913 5937 9913 5940 9914 5935 9914 5938 9914 5939 9915 5938 9915 5936 9915 5941 9916 5939 9916 5937 9916 5943 9917 5938 9917 5939 9917 5940 9918 5938 9918 5943 9918 5943 9919 5939 9919 5941 9919 5944 9920 5941 9920 5942 9920 5944 9921 5943 9921 5941 9921 5945 9922 5944 9922 5942 9922 5946 9923 5940 9923 5943 9923 5946 9924 5943 9924 5944 9924 5948 9925 5946 9925 5944 9925 5949 9926 5945 9926 5947 9926 5949 9927 5944 9927 5945 9927 5948 9928 5944 9928 5949 9928 5946 9929 5948 9929 5950 9929 5950 9930 5948 9930 5949 9930 5951 9931 5949 9931 5947 9931 5952 9932 5946 9932 5950 9932 5950 9933 5949 9933 5951 9933 5952 9934 5956 9934 5946 9934 5953 9935 5950 9935 5951 9935 5953 9936 5952 9936 5950 9936 5955 9937 5951 9937 5954 9937 5956 9938 5952 9938 5953 9938 5953 9939 5951 9939 5955 9939 5955 9940 5954 9940 5957 9940 5958 9941 5953 9941 5955 9941 5959 9942 5953 9942 5958 9942 5959 9943 5956 9943 5953 9943 5958 9944 5955 9944 5957 9944 5961 9945 5957 9945 5960 9945 5961 9946 5958 9946 5957 9946 5961 9947 5959 9947 5958 9947 5963 9948 5959 9948 5961 9948 5963 9949 5956 9949 5959 9949 5964 9950 5960 9950 5962 9950 5964 9951 5961 9951 5960 9951 5966 9952 5961 9952 5964 9952 5966 9953 5963 9953 5961 9953 5965 9954 5964 9954 5962 9954 5967 9955 5964 9955 5965 9955 5967 9956 5966 9956 5964 9956 5969 9957 5966 9957 5967 9957 5968 9958 5967 9958 5965 9958 5969 9959 5963 9959 5966 9959 5970 9960 5967 9960 5968 9960 5971 9961 5963 9961 5969 9961 5969 9962 5967 9962 5970 9962 5970 9963 5968 9963 5972 9963 5969 9964 5970 9964 5973 9964 5973 9965 5970 9965 5972 9965 5971 9966 5969 9966 5973 9966 5975 9967 5972 9967 5974 9967 5975 9968 5973 9968 5972 9968 5977 9969 5971 9969 5973 9969 5977 9970 5973 9970 5975 9970 5976 9971 5975 9971 5974 9971 5978 9972 5975 9972 5976 9972 5979 9973 5971 9973 5977 9973 5978 9974 5977 9974 5975 9974 5980 9975 5978 9975 5976 9975 5979 9976 5977 9976 5978 9976 5981 9977 5978 9977 5980 9977 5982 9978 5980 9978 5976 9978 5979 9979 5978 9979 5981 9979 5983 9980 5980 9980 5982 9980 5983 9981 5981 9981 5980 9981 5985 9982 5981 9982 5983 9982 5985 9983 5979 9983 5981 9983 5987 9984 5982 9984 5986 9984 5987 9985 5983 9985 5982 9985 5984 9986 5979 9986 5985 9986 5985 9987 5983 9987 5987 9987 5988 9988 5987 9988 5986 9988 5989 9989 5987 9989 5988 9989 5989 9990 5985 9990 5987 9990 5990 9991 5984 9991 5985 9991 5990 9992 5985 9992 5989 9992 5989 9993 5988 9993 5991 9993 5992 9994 5990 9994 5989 9994 5992 9995 5989 9995 5991 9995 5995 9996 5991 9996 5993 9996 5994 9997 5990 9997 5992 9997 5995 9998 5992 9998 5991 9998 5994 9999 5992 9999 5995 9999 5995 10000 5993 10000 5996 10000 5997 10001 5995 10001 5996 10001 5999 10002 5995 10002 5997 10002 5999 10003 5994 10003 5995 10003 5998 10004 5997 10004 5996 10004 6000 10005 5997 10005 5998 10005 6002 10006 5997 10006 6000 10006 6002 10007 5999 10007 5997 10007 6001 10008 6000 10008 5998 10008 6002 10009 5994 10009 5999 10009 6005 10010 5994 10010 6002 10010 6003 10011 6000 10011 6001 10011 6005 10012 6002 10012 6004 10012 6004 10013 6000 10013 6003 10013 6004 10014 6002 10014 6000 10014 6004 10015 6003 10015 6006 10015 6007 10016 6004 10016 6006 10016 6005 10017 6004 10017 6007 10017 6010 10018 6006 10018 6009 10018 6010 10019 6007 10019 6006 10019 6011 10020 6007 10020 6010 10020 6011 10021 6005 10021 6007 10021 6008 10022 6005 10022 6011 10022 6012 10023 6010 10023 6009 10023 6013 10024 6008 10024 6011 10024 6011 10025 6010 10025 6012 10025 6015 10026 6011 10026 6012 10026 6013 10027 6011 10027 6015 10027 6015 10028 6012 10028 6014 10028 6016 10029 6008 10029 6013 10029 6018 10030 6014 10030 6017 10030 6018 10031 6015 10031 6014 10031 6018 10032 6013 10032 6015 10032 6016 10033 6013 10033 6018 10033 6020 10034 6017 10034 6019 10034 6020 10035 6018 10035 6017 10035 6022 10036 6018 10036 6020 10036 6022 10037 6016 10037 6018 10037 6021 10038 6020 10038 6019 10038 6024 10039 6016 10039 6022 10039 6023 10040 6020 10040 6021 10040 6023 10041 6022 10041 6020 10041 6025 10042 6022 10042 6023 10042 6027 10043 6022 10043 6025 10043 6026 10044 6023 10044 6021 10044 6027 10045 6024 10045 6022 10045 6025 10046 6023 10046 6026 10046 6032 10047 6016 10047 6024 10047 6029 10048 6026 10048 6028 10048 6029 10049 6025 10049 6026 10049 6032 10050 6024 10050 6027 10050 6030 10051 6025 10051 6029 10051 6030 10052 6027 10052 6025 10052 6031 10053 6029 10053 6028 10053 6032 10054 6027 10054 6030 10054 6033 10055 6029 10055 6031 10055 6033 10056 6030 10056 6029 10056 6032 10057 6030 10057 6033 10057 6034 10058 6033 10058 6031 10058 6036 10059 6033 10059 6037 10059 6036 10060 6032 10060 6033 10060 6037 10061 6034 10061 6035 10061 6037 10062 6033 10062 6034 10062 6039 10063 6036 10063 6037 10063 6038 10064 6037 10064 6035 10064 6040 10065 6037 10065 6038 10065 6040 10066 6039 10066 6037 10066 6040 10067 6038 10067 6041 10067 6043 10068 6040 10068 6041 10068 6042 10069 6036 10069 6039 10069 6043 10070 6039 10070 6040 10070 6042 10071 6039 10071 6043 10071 6044 10072 6043 10072 6041 10072 6044 10073 5887 10073 5888 10073 5889 10074 6042 10074 6043 10074 6044 10075 5888 10075 5889 10075 5889 10076 6043 10076 6044 10076 5891 10077 6042 10077 5889 10077 6045 10078 5887 10078 6044 10078 6045 10079 6044 10079 6041 10079 6046 10080 6045 10080 6041 10080 6047 10081 6041 10081 6038 10081 6047 10082 6046 10082 6041 10082 6048 10083 6038 10083 6035 10083 6048 10084 6047 10084 6038 10084 6049 10085 6035 10085 6034 10085 6049 10086 6048 10086 6035 10086 6050 10087 6049 10087 6034 10087 6050 10088 6034 10088 6031 10088 6051 10089 6050 10089 6031 10089 6051 10090 6031 10090 6028 10090 6052 10091 6051 10091 6028 10091 6052 10092 6028 10092 6026 10092 6053 10093 6052 10093 6026 10093 6053 10094 6026 10094 6021 10094 6054 10095 6053 10095 6021 10095 6054 10096 6021 10096 6019 10096 6055 10097 6054 10097 6019 10097 6055 10098 6019 10098 6017 10098 6056 10099 6055 10099 6017 10099 6056 10100 6017 10100 6014 10100 6057 10101 6014 10101 6012 10101 6057 10102 6056 10102 6014 10102 6058 10103 6012 10103 6009 10103 6058 10104 6057 10104 6012 10104 6059 10105 6009 10105 6006 10105 6059 10106 6058 10106 6009 10106 6060 10107 6006 10107 6003 10107 6060 10108 6059 10108 6006 10108 6060 10109 6003 10109 6001 10109 6061 10110 6060 10110 6001 10110 6061 10111 6001 10111 5998 10111 6062 10112 6061 10112 5998 10112 6063 10113 5998 10113 5996 10113 6063 10114 6062 10114 5998 10114 6064 10115 5996 10115 5993 10115 6064 10116 6063 10116 5996 10116 6065 10117 5993 10117 5991 10117 6065 10118 6064 10118 5993 10118 6065 10119 5991 10119 5988 10119 6066 10120 6065 10120 5988 10120 6066 10121 5988 10121 5986 10121 6067 10122 6066 10122 5986 10122 6067 10123 5986 10123 5982 10123 6068 10124 6067 10124 5982 10124 6068 10125 5982 10125 5976 10125 6069 10126 6068 10126 5976 10126 6069 10127 5976 10127 5974 10127 6070 10128 6069 10128 5974 10128 6070 10129 5974 10129 5972 10129 6071 10130 6070 10130 5972 10130 6071 10131 5972 10131 5968 10131 6072 10132 6071 10132 5968 10132 6073 10133 6072 10133 5968 10133 6073 10134 5968 10134 5965 10134 6073 10135 5965 10135 5962 10135 6074 10136 6073 10136 5962 10136 6074 10137 5962 10137 5960 10137 6075 10138 6074 10138 5960 10138 6075 10139 5960 10139 5957 10139 6076 10140 6075 10140 5957 10140 6076 10141 5957 10141 5954 10141 6077 10142 6076 10142 5954 10142 6077 10143 5954 10143 5951 10143 6078 10144 6077 10144 5951 10144 6078 10145 5951 10145 5947 10145 6079 10146 6078 10146 5947 10146 6079 10147 5947 10147 5945 10147 6080 10148 6079 10148 5945 10148 6081 10149 5945 10149 5942 10149 6081 10150 6080 10150 5945 10150 6082 10151 5942 10151 5941 10151 6082 10152 6081 10152 5942 10152 6082 10153 5941 10153 5937 10153 6083 10154 6082 10154 5937 10154 6084 10155 6083 10155 5937 10155 6084 10156 5937 10156 5933 10156 6085 10157 6084 10157 5933 10157 6085 10158 5933 10158 5930 10158 6085 10159 5930 10159 5929 10159 6175 10160 6085 10160 5929 10160 6086 10161 6175 10161 5929 10161 6086 10162 5929 10162 5924 10162 6087 10163 6086 10163 5924 10163 6087 10164 5924 10164 5923 10164 6088 10165 6087 10165 5923 10165 6088 10166 5923 10166 5918 10166 6089 10167 6088 10167 5918 10167 6090 10168 5918 10168 5916 10168 6090 10169 6089 10169 5918 10169 6091 10170 5916 10170 5913 10170 6091 10171 6090 10171 5916 10171 6091 10172 5913 10172 5909 10172 6092 10173 6091 10173 5909 10173 6093 10174 6092 10174 5909 10174 6093 10175 5909 10175 5907 10175 6093 10176 5907 10176 5903 10176 6094 10177 6093 10177 5903 10177 6094 10178 5903 10178 5900 10178 6095 10179 6094 10179 5900 10179 6096 10180 6095 10180 5900 10180 6096 10181 5900 10181 5897 10181 6096 10182 5897 10182 5894 10182 6199 10183 6096 10183 5894 10183 6097 10184 6199 10184 5894 10184 6097 10185 5894 10185 5890 10185 6098 10186 6097 10186 5890 10186 6098 10187 5890 10187 5887 10187 6045 10188 6098 10188 5887 10188 6099 10189 6100 10189 6045 10189 6101 10190 6100 10190 6099 10190 6046 10191 6099 10191 6045 10191 6102 10192 6202 10192 6101 10192 6101 10193 6099 10193 6046 10193 6103 10194 6101 10194 6046 10194 6102 10195 6101 10195 6103 10195 6103 10196 6046 10196 6047 10196 6104 10197 6102 10197 6103 10197 6048 10198 6103 10198 6047 10198 6104 10199 6103 10199 6048 10199 6105 10200 6102 10200 6104 10200 6108 10201 6102 10201 6105 10201 6106 10202 6048 10202 6049 10202 6106 10203 6104 10203 6048 10203 6106 10204 6105 10204 6104 10204 6107 10205 6049 10205 6050 10205 6107 10206 6106 10206 6049 10206 6107 10207 6105 10207 6106 10207 6109 10208 6105 10208 6107 10208 6051 10209 6107 10209 6050 10209 6110 10210 6107 10210 6051 10210 6109 10211 6108 10211 6105 10211 6109 10212 6107 10212 6110 10212 6052 10213 6110 10213 6051 10213 6111 10214 6110 10214 6052 10214 6111 10215 6109 10215 6110 10215 6112 10216 6108 10216 6109 10216 6112 10217 6109 10217 6111 10217 6113 10218 6111 10218 6052 10218 6113 10219 6052 10219 6053 10219 6113 10220 6053 10220 6054 10220 6114 10221 6113 10221 6054 10221 6112 10222 6111 10222 6113 10222 6116 10223 6113 10223 6114 10223 6116 10224 6112 10224 6113 10224 6055 10225 6114 10225 6054 10225 6115 10226 6112 10226 6116 10226 6117 10227 6114 10227 6055 10227 6116 10228 6114 10228 6117 10228 6117 10229 6055 10229 6056 10229 6118 10230 6116 10230 6117 10230 6118 10231 6115 10231 6116 10231 6119 10232 6117 10232 6056 10232 6120 10233 6117 10233 6119 10233 6120 10234 6118 10234 6117 10234 6057 10235 6119 10235 6056 10235 6121 10236 6115 10236 6118 10236 6058 10237 6119 10237 6057 10237 6122 10238 6119 10238 6058 10238 6122 10239 6120 10239 6119 10239 6123 10240 6120 10240 6122 10240 6123 10241 6118 10241 6120 10241 6121 10242 6118 10242 6123 10242 6124 10243 6058 10243 6059 10243 6124 10244 6122 10244 6058 10244 6124 10245 6123 10245 6122 10245 6125 10246 6124 10246 6059 10246 6126 10247 6123 10247 6124 10247 6125 10248 6059 10248 6060 10248 6121 10249 6123 10249 6126 10249 6126 10250 6124 10250 6125 10250 6127 10251 6121 10251 6126 10251 6128 10252 6125 10252 6060 10252 6129 10253 6125 10253 6128 10253 6129 10254 6126 10254 6125 10254 6127 10255 6126 10255 6129 10255 6061 10256 6128 10256 6060 10256 6129 10257 6128 10257 6061 10257 6129 10258 6061 10258 6062 10258 6130 10259 6127 10259 6129 10259 6131 10260 6129 10260 6062 10260 6130 10261 6129 10261 6131 10261 6131 10262 6062 10262 6063 10262 6132 10263 6127 10263 6130 10263 6133 10264 6063 10264 6064 10264 6133 10265 6131 10265 6063 10265 6134 10266 6131 10266 6133 10266 6134 10267 6130 10267 6131 10267 6134 10268 6132 10268 6130 10268 6135 10269 6132 10269 6134 10269 6136 10270 6134 10270 6133 10270 6065 10271 6133 10271 6064 10271 6136 10272 6133 10272 6065 10272 6135 10273 6134 10273 6136 10273 6137 10274 6136 10274 6065 10274 6066 10275 6137 10275 6065 10275 6138 10276 6136 10276 6137 10276 6138 10277 6135 10277 6136 10277 6139 10278 6066 10278 6067 10278 6140 10279 6066 10279 6139 10279 6140 10280 6137 10280 6066 10280 6140 10281 6138 10281 6137 10281 6143 10282 6135 10282 6138 10282 6141 10283 6138 10283 6140 10283 6142 10284 6139 10284 6067 10284 6141 10285 6140 10285 6139 10285 6141 10286 6139 10286 6142 10286 6068 10287 6142 10287 6067 10287 6143 10288 6138 10288 6141 10288 6069 10289 6142 10289 6068 10289 6144 10290 6143 10290 6141 10290 6145 10291 6142 10291 6069 10291 6145 10292 6141 10292 6142 10292 6144 10293 6141 10293 6145 10293 6146 10294 6145 10294 6069 10294 6148 10295 6143 10295 6144 10295 6147 10296 6145 10296 6146 10296 6147 10297 6144 10297 6145 10297 6070 10298 6146 10298 6069 10298 6148 10299 6144 10299 6147 10299 6147 10300 6146 10300 6070 10300 6147 10301 6070 10301 6071 10301 6149 10302 6148 10302 6147 10302 6150 10303 6147 10303 6071 10303 6149 10304 6147 10304 6150 10304 6072 10305 6150 10305 6071 10305 6151 10306 6150 10306 6072 10306 6149 10307 6150 10307 6151 10307 6151 10308 6072 10308 6073 10308 6152 10309 6148 10309 6149 10309 6153 10310 6149 10310 6151 10310 6154 10311 6151 10311 6073 10311 6152 10312 6149 10312 6153 10312 6153 10313 6151 10313 6154 10313 6155 10314 6153 10314 6154 10314 6074 10315 6154 10315 6073 10315 6155 10316 6154 10316 6074 10316 6152 10317 6153 10317 6155 10317 6156 10318 6074 10318 6075 10318 6156 10319 6155 10319 6074 10319 6157 10320 6155 10320 6156 10320 6157 10321 6152 10321 6155 10321 6158 10322 6152 10322 6157 10322 6076 10323 6156 10323 6075 10323 6159 10324 6156 10324 6076 10324 6159 10325 6157 10325 6156 10325 6160 10326 6076 10326 6077 10326 6158 10327 6157 10327 6159 10327 6160 10328 6159 10328 6076 10328 6161 10329 6159 10329 6160 10329 6158 10330 6159 10330 6161 10330 6078 10331 6160 10331 6077 10331 6162 10332 6158 10332 6161 10332 6163 10333 6160 10333 6078 10333 6163 10334 6161 10334 6160 10334 6162 10335 6161 10335 6163 10335 6163 10336 6078 10336 6079 10336 6164 10337 6163 10337 6079 10337 6165 10338 6163 10338 6164 10338 6164 10339 6079 10339 6080 10339 6165 10340 6162 10340 6163 10340 6081 10341 6164 10341 6080 10341 6166 10342 6164 10342 6081 10342 6166 10343 6165 10343 6164 10343 6167 10344 6081 10344 6082 10344 6167 10345 6166 10345 6081 10345 6170 10346 6165 10346 6166 10346 6168 10347 6082 10347 6083 10347 6168 10348 6167 10348 6082 10348 6169 10349 6167 10349 6168 10349 6169 10350 6166 10350 6167 10350 6170 10351 6166 10351 6169 10351 6171 10352 6083 10352 6084 10352 6171 10353 6168 10353 6083 10353 6172 10354 6170 10354 6169 10354 6172 10355 6168 10355 6171 10355 6172 10356 6169 10356 6168 10356 6174 10357 6170 10357 6172 10357 6085 10358 6171 10358 6084 10358 6173 10359 6172 10359 6171 10359 6174 10360 6172 10360 6173 10360 6173 10361 6171 10361 6085 10361 6175 10362 6173 10362 6085 10362 6176 10363 6173 10363 6175 10363 6178 10364 6173 10364 6176 10364 6178 10365 6174 10365 6173 10365 6177 10366 6174 10366 6178 10366 6179 10367 6175 10367 6086 10367 6179 10368 6176 10368 6175 10368 6178 10369 6176 10369 6179 10369 6087 10370 6179 10370 6086 10370 6180 10371 6178 10371 6179 10371 6181 10372 6179 10372 6087 10372 6181 10373 6180 10373 6179 10373 6088 10374 6181 10374 6087 10374 6182 10375 6178 10375 6180 10375 6182 10376 6177 10376 6178 10376 6183 10377 6181 10377 6088 10377 6184 10378 6177 10378 6182 10378 6183 10379 6180 10379 6181 10379 6182 10380 6180 10380 6183 10380 6089 10381 6183 10381 6088 10381 6185 10382 6183 10382 6089 10382 6185 10383 6182 10383 6183 10383 6184 10384 6182 10384 6185 10384 6186 10385 6089 10385 6090 10385 6185 10386 6089 10386 6186 10386 6091 10387 6186 10387 6090 10387 6187 10388 6184 10388 6185 10388 6188 10389 6185 10389 6186 10389 6187 10390 6185 10390 6188 10390 6188 10391 6186 10391 6091 10391 6189 10392 6184 10392 6187 10392 6190 10393 6091 10393 6092 10393 6190 10394 6188 10394 6091 10394 6190 10395 6187 10395 6188 10395 6191 10396 6092 10396 6093 10396 6191 10397 6190 10397 6092 10397 6189 10398 6187 10398 6190 10398 6192 10399 6190 10399 6191 10399 6192 10400 6189 10400 6190 10400 6193 10401 6191 10401 6093 10401 6192 10402 6191 10402 6193 10402 6094 10403 6193 10403 6093 10403 6194 10404 6192 10404 6193 10404 6095 10405 6193 10405 6094 10405 6195 10406 6192 10406 6194 10406 6195 10407 6189 10407 6192 10407 6194 10408 6193 10408 6095 10408 6196 10409 6194 10409 6095 10409 6196 10410 6095 10410 6096 10410 6197 10411 6195 10411 6194 10411 6198 10412 6194 10412 6196 10412 6199 10413 6196 10413 6096 10413 6198 10414 6196 10414 6199 10414 6197 10415 6194 10415 6198 10415 6097 10416 6198 10416 6199 10416 6200 10417 6198 10417 6097 10417 6201 10418 6198 10418 6200 10418 6201 10419 6197 10419 6198 10419 6200 10420 6097 10420 6098 10420 6202 10421 6197 10421 6201 10421 6100 10422 6200 10422 6098 10422 6100 10423 6201 10423 6200 10423 6100 10424 6098 10424 6045 10424 6201 10425 6100 10425 6101 10425 6202 10426 6201 10426 6101 10426 5522 10427 6162 10427 6165 10427 5524 10428 6162 10428 5522 10428 5524 10429 6158 10429 6162 10429 5520 10430 5522 10430 6165 10430 5520 10431 6165 10431 6170 10431 5525 10432 6158 10432 5524 10432 5517 10433 5520 10433 6170 10433 5525 10434 6152 10434 6158 10434 5517 10435 6170 10435 6174 10435 5485 10436 6152 10436 5525 10436 5485 10437 6148 10437 6152 10437 5517 10438 6174 10438 6177 10438 5515 10439 5517 10439 6177 10439 5487 10440 6148 10440 5485 10440 5515 10441 6177 10441 6184 10441 5513 10442 5515 10442 6184 10442 5487 10443 6143 10443 6148 10443 5490 10444 6143 10444 5487 10444 5513 10445 6184 10445 6189 10445 5511 10446 5513 10446 6189 10446 5490 10447 6135 10447 6143 10447 6135 10448 5490 10448 5492 10448 6132 10449 6135 10449 5492 10449 6195 10450 5511 10450 6189 10450 6132 10451 5492 10451 5494 10451 6195 10452 5509 10452 5511 10452 6197 10453 5509 10453 6195 10453 6132 10454 5494 10454 5496 10454 6127 10455 6132 10455 5496 10455 6202 10456 5509 10456 6197 10456 6202 10457 5507 10457 5509 10457 6121 10458 6127 10458 5496 10458 6121 10459 5496 10459 5498 10459 6102 10460 5504 10460 5507 10460 6102 10461 5507 10461 6202 10461 6115 10462 6121 10462 5498 10462 6115 10463 5498 10463 5500 10463 6108 10464 5504 10464 6102 10464 6115 10465 5500 10465 5501 10465 6108 10466 5503 10466 5504 10466 6112 10467 6115 10467 5501 10467 6112 10468 5503 10468 6108 10468 6112 10469 5501 10469 5503 10469 6205 10470 6203 10470 6204 10470 6205 10471 6204 10471 6206 10471 6207 10472 6205 10472 6206 10472 6208 10473 6206 10473 6209 10473 6208 10474 6207 10474 6206 10474 6210 10475 6208 10475 6209 10475 6211 10476 6210 10476 6209 10476 6211 10477 6209 10477 6212 10477 6213 10478 6211 10478 6212 10478 6213 10479 6212 10479 6214 10479 6215 10480 6213 10480 6214 10480 6216 10481 6215 10481 6214 10481 6216 10482 6214 10482 6217 10482 6218 10483 6216 10483 6217 10483 6219 10484 6218 10484 6217 10484 6219 10485 6217 10485 6220 10485 6463 10486 6219 10486 6220 10486 6221 10487 6220 10487 6222 10487 6221 10488 6463 10488 6220 10488 6223 10489 6221 10489 6222 10489 6224 10490 6223 10490 6222 10490 6225 10491 6224 10491 6222 10491 6225 10492 6222 10492 6226 10492 6227 10493 6225 10493 6226 10493 6228 10494 6227 10494 6226 10494 6229 10495 6228 10495 6226 10495 6229 10496 6226 10496 6230 10496 6231 10497 6229 10497 6230 10497 6232 10498 6230 10498 6233 10498 6232 10499 6231 10499 6230 10499 6234 10500 6232 10500 6233 10500 6235 10501 6234 10501 6233 10501 6235 10502 6233 10502 6236 10502 6237 10503 6235 10503 6236 10503 6238 10504 6237 10504 6236 10504 6238 10505 6236 10505 6239 10505 6240 10506 6238 10506 6239 10506 6240 10507 6239 10507 6241 10507 6242 10508 6240 10508 6241 10508 6242 10509 6241 10509 6243 10509 6244 10510 6242 10510 6243 10510 6245 10511 6244 10511 6243 10511 6245 10512 6243 10512 6246 10512 6501 10513 6245 10513 6246 10513 6247 10514 6501 10514 6246 10514 6248 10515 6247 10515 6246 10515 6249 10516 6246 10516 6250 10516 6249 10517 6248 10517 6246 10517 6251 10518 6249 10518 6250 10518 6251 10519 6250 10519 6252 10519 6253 10520 6251 10520 6252 10520 6254 10521 6252 10521 6255 10521 6254 10522 6253 10522 6252 10522 6256 10523 6254 10523 6255 10523 6257 10524 6255 10524 6258 10524 6257 10525 6256 10525 6255 10525 6259 10526 6257 10526 6258 10526 6260 10527 6259 10527 6258 10527 6261 10528 6258 10528 6262 10528 6261 10529 6260 10529 6258 10529 6263 10530 6261 10530 6262 10530 6264 10531 6263 10531 6262 10531 6264 10532 6262 10532 6265 10532 6526 10533 6264 10533 6265 10533 6266 10534 6526 10534 6265 10534 6266 10535 6265 10535 6267 10535 6268 10536 6266 10536 6267 10536 6269 10537 6268 10537 6267 10537 6269 10538 6267 10538 6270 10538 6271 10539 6269 10539 6270 10539 6203 10540 6271 10540 6270 10540 6203 10541 6270 10541 6204 10541 6272 10542 6338 10542 6273 10542 6272 10543 6273 10543 6275 10543 6274 10544 6272 10544 6275 10544 6274 10545 6275 10545 6276 10545 6277 10546 6276 10546 6278 10546 6277 10547 6274 10547 6276 10547 6277 10548 6278 10548 6279 10548 6280 10549 6277 10549 6279 10549 6280 10550 6279 10550 6427 10550 6280 10551 6427 10551 6281 10551 6282 10552 6281 10552 6283 10552 6282 10553 6280 10553 6281 10553 6282 10554 6283 10554 6284 10554 6285 10555 6282 10555 6284 10555 6285 10556 6284 10556 6418 10556 6286 10557 6285 10557 6418 10557 6286 10558 6418 10558 6287 10558 6286 10559 6287 10559 6288 10559 6286 10560 6288 10560 6410 10560 6289 10561 6286 10561 6410 10561 6289 10562 6410 10562 6290 10562 6291 10563 6289 10563 6290 10563 6291 10564 6290 10564 6292 10564 6291 10565 6292 10565 6293 10565 6294 10566 6291 10566 6293 10566 6294 10567 6293 10567 6295 10567 6294 10568 6295 10568 6296 10568 6297 10569 6294 10569 6296 10569 6297 10570 6296 10570 6298 10570 6299 10571 6297 10571 6298 10571 6299 10572 6298 10572 6300 10572 6299 10573 6300 10573 6301 10573 6302 10574 6301 10574 6303 10574 6302 10575 6299 10575 6301 10575 6302 10576 6303 10576 6392 10576 6304 10577 6392 10577 6389 10577 6304 10578 6302 10578 6392 10578 6304 10579 6389 10579 6305 10579 6304 10580 6305 10580 6306 10580 6307 10581 6304 10581 6306 10581 6307 10582 6306 10582 6308 10582 6309 10583 6307 10583 6308 10583 6309 10584 6308 10584 6310 10584 6309 10585 6310 10585 6311 10585 6312 10586 6309 10586 6311 10586 6312 10587 6311 10587 6313 10587 6312 10588 6313 10588 6314 10588 6312 10589 6314 10589 6315 10589 6316 10590 6312 10590 6315 10590 6316 10591 6315 10591 6317 10591 6316 10592 6317 10592 6318 10592 6319 10593 6316 10593 6318 10593 6319 10594 6318 10594 6320 10594 6321 10595 6319 10595 6320 10595 6321 10596 6320 10596 6322 10596 6321 10597 6322 10597 6323 10597 6324 10598 6321 10598 6323 10598 6324 10599 6323 10599 6325 10599 6324 10600 6325 10600 6326 10600 6327 10601 6324 10601 6326 10601 6327 10602 6326 10602 6328 10602 6327 10603 6328 10603 6356 10603 6329 10604 6356 10604 6330 10604 6329 10605 6327 10605 6356 10605 6331 10606 6330 10606 6349 10606 6331 10607 6329 10607 6330 10607 6331 10608 6349 10608 6332 10608 6331 10609 6332 10609 6333 10609 6334 10610 6331 10610 6333 10610 6334 10611 6333 10611 6335 10611 6336 10612 6335 10612 6337 10612 6336 10613 6334 10613 6335 10613 6336 10614 6337 10614 6338 10614 6272 10615 6336 10615 6338 10615 6340 10616 6438 10616 6339 10616 6340 10617 6437 10617 6438 10617 6341 10618 6339 10618 6338 10618 6340 10619 6339 10619 6341 10619 6341 10620 6338 10620 6337 10620 6342 10621 6340 10621 6341 10621 6335 10622 6341 10622 6337 10622 6344 10623 6437 10623 6340 10623 6343 10624 6340 10624 6342 10624 6343 10625 6341 10625 6335 10625 6344 10626 6340 10626 6343 10626 6343 10627 6342 10627 6341 10627 6345 10628 6343 10628 6335 10628 6345 10629 6335 10629 6333 10629 6346 10630 6343 10630 6345 10630 6346 10631 6344 10631 6343 10631 6347 10632 6344 10632 6346 10632 6332 10633 6345 10633 6333 10633 6348 10634 6345 10634 6332 10634 6348 10635 6346 10635 6345 10635 6348 10636 6347 10636 6346 10636 6349 10637 6348 10637 6332 10637 6350 10638 6348 10638 6349 10638 6351 10639 6348 10639 6350 10639 6351 10640 6347 10640 6348 10640 6330 10641 6350 10641 6349 10641 6352 10642 6351 10642 6350 10642 6353 10643 6350 10643 6330 10643 6352 10644 6347 10644 6351 10644 6353 10645 6352 10645 6350 10645 6355 10646 6347 10646 6352 10646 6354 10647 6353 10647 6330 10647 6354 10648 6352 10648 6353 10648 6357 10649 6352 10649 6354 10649 6356 10650 6354 10650 6330 10650 6355 10651 6352 10651 6357 10651 6358 10652 6356 10652 6328 10652 6358 10653 6354 10653 6356 10653 6357 10654 6354 10654 6358 10654 6359 10655 6355 10655 6357 10655 6359 10656 6357 10656 6358 10656 6326 10657 6358 10657 6328 10657 6360 10658 6358 10658 6326 10658 6360 10659 6359 10659 6358 10659 6362 10660 6355 10660 6359 10660 6361 10661 6359 10661 6360 10661 6325 10662 6360 10662 6326 10662 6362 10663 6359 10663 6361 10663 6325 10664 6361 10664 6360 10664 6363 10665 6362 10665 6361 10665 6363 10666 6361 10666 6325 10666 6364 10667 6325 10667 6323 10667 6363 10668 6325 10668 6364 10668 6365 10669 6362 10669 6363 10669 6366 10670 6363 10670 6364 10670 6366 10671 6365 10671 6363 10671 6322 10672 6364 10672 6323 10672 6366 10673 6364 10673 6322 10673 6367 10674 6365 10674 6366 10674 6368 10675 6322 10675 6320 10675 6368 10676 6366 10676 6322 10676 6367 10677 6366 10677 6368 10677 6318 10678 6368 10678 6320 10678 6369 10679 6368 10679 6318 10679 6370 10680 6368 10680 6369 10680 6370 10681 6367 10681 6368 10681 6370 10682 6365 10682 6367 10682 6317 10683 6369 10683 6318 10683 6371 10684 6369 10684 6317 10684 6371 10685 6370 10685 6369 10685 6371 10686 6317 10686 6315 10686 6372 10687 6370 10687 6371 10687 6373 10688 6371 10688 6315 10688 6372 10689 6371 10689 6373 10689 6314 10690 6373 10690 6315 10690 6374 10691 6372 10691 6373 10691 6375 10692 6373 10692 6314 10692 6377 10693 6372 10693 6374 10693 6375 10694 6374 10694 6373 10694 6313 10695 6375 10695 6314 10695 6376 10696 6375 10696 6313 10696 6376 10697 6374 10697 6375 10697 6377 10698 6374 10698 6376 10698 6378 10699 6313 10699 6311 10699 6378 10700 6376 10700 6313 10700 6379 10701 6378 10701 6311 10701 6380 10702 6377 10702 6376 10702 6379 10703 6311 10703 6310 10703 6380 10704 6376 10704 6378 10704 6380 10705 6378 10705 6379 10705 6381 10706 6379 10706 6310 10706 6382 10707 6380 10707 6379 10707 6383 10708 6377 10708 6380 10708 6382 10709 6379 10709 6381 10709 6381 10710 6310 10710 6308 10710 6383 10711 6380 10711 6382 10711 6384 10712 6381 10712 6308 10712 6384 10713 6382 10713 6381 10713 6385 10714 6308 10714 6306 10714 6385 10715 6384 10715 6308 10715 6386 10716 6384 10716 6385 10716 6386 10717 6382 10717 6384 10717 6387 10718 6382 10718 6386 10718 6387 10719 6383 10719 6382 10719 6305 10720 6385 10720 6306 10720 6388 10721 6385 10721 6305 10721 6388 10722 6386 10722 6385 10722 6390 10723 6383 10723 6387 10723 6387 10724 6386 10724 6388 10724 6388 10725 6305 10725 6389 10725 6390 10726 6387 10726 6388 10726 6391 10727 6388 10727 6389 10727 6391 10728 6390 10728 6388 10728 6391 10729 6389 10729 6392 10729 6393 10730 6391 10730 6392 10730 6393 10731 6390 10731 6391 10731 6393 10732 6392 10732 6303 10732 6394 10733 6390 10733 6393 10733 6395 10734 6393 10734 6303 10734 6394 10735 6393 10735 6395 10735 6396 10736 6390 10736 6394 10736 6395 10737 6303 10737 6301 10737 6396 10738 6394 10738 6395 10738 6300 10739 6395 10739 6301 10739 6397 10740 6395 10740 6300 10740 6397 10741 6396 10741 6395 10741 6397 10742 6300 10742 6298 10742 6398 10743 6397 10743 6298 10743 6398 10744 6298 10744 6296 10744 6399 10745 6396 10745 6397 10745 6400 10746 6397 10746 6398 10746 6399 10747 6397 10747 6400 10747 6295 10748 6398 10748 6296 10748 6400 10749 6398 10749 6295 10749 6401 10750 6400 10750 6295 10750 6402 10751 6400 10751 6401 10751 6401 10752 6295 10752 6293 10752 6402 10753 6399 10753 6400 10753 6403 10754 6401 10754 6293 10754 6404 10755 6401 10755 6403 10755 6405 10756 6399 10756 6402 10756 6404 10757 6402 10757 6401 10757 6403 10758 6293 10758 6292 10758 6405 10759 6402 10759 6404 10759 6406 10760 6403 10760 6292 10760 6406 10761 6404 10761 6403 10761 6405 10762 6404 10762 6406 10762 6407 10763 6406 10763 6292 10763 6409 10764 6292 10764 6290 10764 6407 10765 6405 10765 6406 10765 6409 10766 6407 10766 6292 10766 6408 10767 6405 10767 6407 10767 6410 10768 6409 10768 6290 10768 6411 10769 6407 10769 6409 10769 6411 10770 6408 10770 6407 10770 6412 10771 6409 10771 6410 10771 6412 10772 6411 10772 6409 10772 6413 10773 6411 10773 6412 10773 6288 10774 6412 10774 6410 10774 6413 10775 6408 10775 6411 10775 6414 10776 6412 10776 6288 10776 6414 10777 6413 10777 6412 10777 6415 10778 6288 10778 6287 10778 6415 10779 6414 10779 6288 10779 6416 10780 6414 10780 6415 10780 6416 10781 6413 10781 6414 10781 6417 10782 6408 10782 6413 10782 6417 10783 6413 10783 6416 10783 6418 10784 6415 10784 6287 10784 6419 10785 6415 10785 6418 10785 6419 10786 6416 10786 6415 10786 6420 10787 6418 10787 6284 10787 6417 10788 6416 10788 6419 10788 6420 10789 6419 10789 6418 10789 6420 10790 6417 10790 6419 10790 6421 10791 6420 10791 6284 10791 6422 10792 6417 10792 6420 10792 6422 10793 6420 10793 6421 10793 6283 10794 6421 10794 6284 10794 6423 10795 6421 10795 6283 10795 6425 10796 6417 10796 6422 10796 6422 10797 6421 10797 6423 10797 6424 10798 6422 10798 6423 10798 6281 10799 6423 10799 6283 10799 6425 10800 6422 10800 6424 10800 6424 10801 6423 10801 6281 10801 6426 10802 6424 10802 6281 10802 6426 10803 6281 10803 6427 10803 6425 10804 6424 10804 6426 10804 6428 10805 6427 10805 6279 10805 6429 10806 6425 10806 6426 10806 6428 10807 6426 10807 6427 10807 6429 10808 6426 10808 6428 10808 6430 10809 6425 10809 6429 10809 6431 10810 6429 10810 6428 10810 6428 10811 6279 10811 6278 10811 6432 10812 6428 10812 6278 10812 6430 10813 6429 10813 6431 10813 6432 10814 6431 10814 6428 10814 6432 10815 6278 10815 6276 10815 6433 10816 6432 10816 6276 10816 6431 10817 6432 10817 6433 10817 6434 10818 6430 10818 6431 10818 6435 10819 6431 10819 6433 10819 6433 10820 6276 10820 6275 10820 6437 10821 6430 10821 6434 10821 6434 10822 6431 10822 6435 10822 6436 10823 6433 10823 6275 10823 6436 10824 6435 10824 6433 10824 6434 10825 6435 10825 6436 10825 6438 10826 6434 10826 6436 10826 6439 10827 6436 10827 6275 10827 6438 10828 6436 10828 6439 10828 6439 10829 6275 10829 6273 10829 6437 10830 6434 10830 6438 10830 6439 10831 6273 10831 6338 10831 6439 10832 6338 10832 6339 10832 6339 10833 6438 10833 6439 10833 5512 10834 6347 10834 6355 10834 5514 10835 5512 10835 6355 10835 5510 10836 6347 10836 5512 10836 5514 10837 6355 10837 6362 10837 5510 10838 6344 10838 6347 10838 5508 10839 6344 10839 5510 10839 5516 10840 5514 10840 6362 10840 5508 10841 6437 10841 6344 10841 5506 10842 6437 10842 5508 10842 5516 10843 6362 10843 6365 10843 5518 10844 5516 10844 6365 10844 5518 10845 6365 10845 6370 10845 5505 10846 6437 10846 5506 10846 5519 10847 5518 10847 6370 10847 5505 10848 6430 10848 6437 10848 5502 10849 6430 10849 5505 10849 5521 10850 5519 10850 6370 10850 6425 10851 6430 10851 5502 10851 6372 10852 5521 10852 6370 10852 6377 10853 5521 10853 6372 10853 6425 10854 5502 10854 5499 10854 6377 10855 5523 10855 5521 10855 6417 10856 6425 10856 5499 10856 6377 10857 5526 10857 5523 10857 6417 10858 5499 10858 5497 10858 6383 10859 5526 10859 6377 10859 6408 10860 6417 10860 5497 10860 6383 10861 5486 10861 5526 10861 6390 10862 5486 10862 6383 10862 6408 10863 5497 10863 5495 10863 6390 10864 5488 10864 5486 10864 6396 10865 5488 10865 6390 10865 6408 10866 5495 10866 5493 10866 6405 10867 6408 10867 5493 10867 6396 10868 5489 10868 5488 10868 6405 10869 5493 10869 5491 10869 6399 10870 5489 10870 6396 10870 6399 10871 6405 10871 5491 10871 6399 10872 5491 10872 5489 10872 6443 10873 6440 10873 6203 10873 6443 10874 6441 10874 6440 10874 6442 10875 6441 10875 6443 10875 6443 10876 6203 10876 6205 10876 6444 10877 6443 10877 6205 10877 6445 10878 6443 10878 6444 10878 6446 10879 6534 10879 6442 10879 6445 10880 6442 10880 6443 10880 6444 10881 6205 10881 6207 10881 6446 10882 6442 10882 6445 10882 6447 10883 6444 10883 6207 10883 6447 10884 6445 10884 6444 10884 6208 10885 6447 10885 6207 10885 6448 10886 6446 10886 6445 10886 6448 10887 6445 10887 6447 10887 6449 10888 6448 10888 6447 10888 6210 10889 6447 10889 6208 10889 6449 10890 6447 10890 6210 10890 6450 10891 6448 10891 6449 10891 6451 10892 6449 10892 6210 10892 6450 10893 6449 10893 6451 10893 6451 10894 6210 10894 6211 10894 6453 10895 6448 10895 6450 10895 6452 10896 6211 10896 6213 10896 6452 10897 6451 10897 6211 10897 6454 10898 6451 10898 6452 10898 6454 10899 6450 10899 6451 10899 6453 10900 6450 10900 6454 10900 6455 10901 6453 10901 6454 10901 6454 10902 6452 10902 6456 10902 6456 10903 6452 10903 6213 10903 6456 10904 6213 10904 6215 10904 6455 10905 6454 10905 6456 10905 6455 10906 6456 10906 6457 10906 6216 10907 6456 10907 6215 10907 6457 10908 6456 10908 6216 10908 6460 10909 6453 10909 6455 10909 6459 10910 6216 10910 6218 10910 6459 10911 6457 10911 6216 10911 6458 10912 6455 10912 6457 10912 6460 10913 6455 10913 6458 10913 6458 10914 6457 10914 6459 10914 6461 10915 6459 10915 6218 10915 6458 10916 6459 10916 6461 10916 6461 10917 6218 10917 6219 10917 6462 10918 6458 10918 6461 10918 6460 10919 6458 10919 6462 10919 6463 10920 6461 10920 6219 10920 6464 10921 6461 10921 6463 10921 6464 10922 6462 10922 6461 10922 6465 10923 6464 10923 6463 10923 6465 10924 6463 10924 6221 10924 6466 10925 6462 10925 6464 10925 6466 10926 6464 10926 6465 10926 6467 10927 6460 10927 6462 10927 6466 10928 6465 10928 6221 10928 6467 10929 6462 10929 6466 10929 6468 10930 6466 10930 6221 10930 6468 10931 6221 10931 6223 10931 6469 10932 6467 10932 6466 10932 6470 10933 6466 10933 6468 10933 6469 10934 6466 10934 6470 10934 6468 10935 6223 10935 6224 10935 6470 10936 6468 10936 6224 10936 6471 10937 6467 10937 6469 10937 6472 10938 6224 10938 6225 10938 6472 10939 6470 10939 6224 10939 6473 10940 6470 10940 6472 10940 6473 10941 6469 10941 6470 10941 6471 10942 6469 10942 6473 10942 6472 10943 6225 10943 6227 10943 6475 10944 6471 10944 6473 10944 6474 10945 6472 10945 6227 10945 6474 10946 6473 10946 6472 10946 6475 10947 6473 10947 6474 10947 6474 10948 6227 10948 6228 10948 6476 10949 6471 10949 6475 10949 6477 10950 6475 10950 6474 10950 6229 10951 6474 10951 6228 10951 6476 10952 6475 10952 6477 10952 6477 10953 6474 10953 6229 10953 6479 10954 6476 10954 6477 10954 6478 10955 6229 10955 6231 10955 6478 10956 6477 10956 6229 10956 6479 10957 6477 10957 6478 10957 6478 10958 6231 10958 6232 10958 6480 10959 6479 10959 6478 10959 6483 10960 6476 10960 6479 10960 6481 10961 6478 10961 6232 10961 6481 10962 6480 10962 6478 10962 6483 10963 6479 10963 6480 10963 6234 10964 6481 10964 6232 10964 6482 10965 6481 10965 6234 10965 6482 10966 6480 10966 6481 10966 6483 10967 6480 10967 6482 10967 6235 10968 6482 10968 6234 10968 6484 10969 6482 10969 6235 10969 6483 10970 6482 10970 6484 10970 6485 10971 6484 10971 6235 10971 6485 10972 6235 10972 6237 10972 6486 10973 6484 10973 6485 10973 6483 10974 6484 10974 6486 10974 6487 10975 6485 10975 6237 10975 6488 10976 6483 10976 6486 10976 6487 10977 6486 10977 6485 10977 6489 10978 6486 10978 6487 10978 6490 10979 6483 10979 6488 10979 6238 10980 6487 10980 6237 10980 6488 10981 6486 10981 6489 10981 6489 10982 6487 10982 6238 10982 6491 10983 6489 10983 6238 10983 6491 10984 6238 10984 6240 10984 6492 10985 6488 10985 6489 10985 6492 10986 6490 10986 6488 10986 6492 10987 6489 10987 6491 10987 6493 10988 6491 10988 6240 10988 6493 10989 6492 10989 6491 10989 6493 10990 6240 10990 6242 10990 6496 10991 6490 10991 6492 10991 6495 10992 6493 10992 6242 10992 6494 10993 6492 10993 6493 10993 6496 10994 6492 10994 6494 10994 6494 10995 6493 10995 6495 10995 6244 10996 6495 10996 6242 10996 6494 10997 6495 10997 6244 10997 6498 10998 6244 10998 6245 10998 6499 10999 6496 10999 6494 10999 6498 11000 6494 11000 6244 11000 6499 11001 6494 11001 6498 11001 6497 11002 6496 11002 6499 11002 6500 11003 6498 11003 6245 11003 6502 11004 6498 11004 6500 11004 6502 11005 6499 11005 6498 11005 6500 11006 6245 11006 6501 11006 6497 11007 6499 11007 6502 11007 6247 11008 6500 11008 6501 11008 6503 11009 6500 11009 6247 11009 6503 11010 6502 11010 6500 11010 6504 11011 6502 11011 6503 11011 6503 11012 6247 11012 6248 11012 6497 11013 6502 11013 6504 11013 6504 11014 6503 11014 6248 11014 6505 11015 6497 11015 6504 11015 6506 11016 6504 11016 6248 11016 6507 11017 6248 11017 6249 11017 6505 11018 6504 11018 6506 11018 6506 11019 6248 11019 6507 11019 6508 11020 6505 11020 6506 11020 6251 11021 6507 11021 6249 11021 6508 11022 6506 11022 6507 11022 6509 11023 6507 11023 6251 11023 6508 11024 6507 11024 6509 11024 6510 11025 6508 11025 6509 11025 6253 11026 6509 11026 6251 11026 6510 11027 6509 11027 6253 11027 6511 11028 6508 11028 6510 11028 6511 11029 6505 11029 6508 11029 6512 11030 6510 11030 6253 11030 6512 11031 6253 11031 6254 11031 6517 11032 6505 11032 6511 11032 6511 11033 6510 11033 6512 11033 6513 11034 6512 11034 6254 11034 6514 11035 6512 11035 6513 11035 6256 11036 6513 11036 6254 11036 6514 11037 6511 11037 6512 11037 6515 11038 6513 11038 6256 11038 6514 11039 6517 11039 6511 11039 6514 11040 6513 11040 6515 11040 6515 11041 6256 11041 6257 11041 6516 11042 6514 11042 6515 11042 6517 11043 6514 11043 6516 11043 6259 11044 6515 11044 6257 11044 6516 11045 6515 11045 6259 11045 6518 11046 6516 11046 6259 11046 6519 11047 6517 11047 6516 11047 6518 11048 6259 11048 6260 11048 6520 11049 6516 11049 6518 11049 6519 11050 6516 11050 6520 11050 6520 11051 6518 11051 6260 11051 6261 11052 6520 11052 6260 11052 6521 11053 6520 11053 6261 11053 6522 11054 6521 11054 6261 11054 6522 11055 6261 11055 6263 11055 6521 11056 6519 11056 6520 11056 6523 11057 6519 11057 6521 11057 6524 11058 6521 11058 6522 11058 6264 11059 6522 11059 6263 11059 6523 11060 6521 11060 6524 11060 6524 11061 6522 11061 6264 11061 6525 11062 6524 11062 6264 11062 6525 11063 6264 11063 6526 11063 6525 11064 6523 11064 6524 11064 6527 11065 6525 11065 6526 11065 6528 11066 6523 11066 6525 11066 6528 11067 6525 11067 6527 11067 6527 11068 6526 11068 6266 11068 6530 11069 6523 11069 6528 11069 6529 11070 6527 11070 6266 11070 6529 11071 6528 11071 6527 11071 6268 11072 6529 11072 6266 11072 6530 11073 6528 11073 6529 11073 6531 11074 6529 11074 6268 11074 6531 11075 6530 11075 6529 11075 6532 11076 6268 11076 6269 11076 6532 11077 6531 11077 6268 11077 6271 11078 6532 11078 6269 11078 6533 11079 6531 11079 6532 11079 6533 11080 6530 11080 6531 11080 6440 11081 6532 11081 6271 11081 6440 11082 6533 11082 6532 11082 6534 11083 6530 11083 6533 11083 6271 11084 6203 11084 6440 11084 6441 11085 6533 11085 6440 11085 6533 11086 6441 11086 6442 11086 6533 11087 6442 11087 6534 11087 5545 11088 6497 11088 5543 11088 5542 11089 5543 11089 6497 11089 5542 11090 6497 11090 6505 11090 5545 11091 6496 11091 6497 11091 5547 11092 6496 11092 5545 11092 5540 11093 5542 11093 6505 11093 5547 11094 6490 11094 6496 11094 5549 11095 6490 11095 5547 11095 5540 11096 6505 11096 6517 11096 5538 11097 5540 11097 6517 11097 5551 11098 6483 11098 6490 11098 5551 11099 6490 11099 5549 11099 5535 11100 5538 11100 6517 11100 5535 11101 6517 11101 6519 11101 5553 11102 6483 11102 5551 11102 5533 11103 5535 11103 6519 11103 5555 11104 6483 11104 5553 11104 5555 11105 6476 11105 6483 11105 5533 11106 6519 11106 6523 11106 5556 11107 6476 11107 5555 11107 6523 11108 5532 11108 5533 11108 6471 11109 6476 11109 5556 11109 6530 11110 5532 11110 6523 11110 6530 11111 5530 11111 5532 11111 6471 11112 5556 11112 5558 11112 6530 11113 5527 11113 5530 11113 6467 11114 6471 11114 5558 11114 6534 11115 5527 11115 6530 11115 6467 11116 5558 11116 5560 11116 6460 11117 6467 11117 5560 11117 6534 11118 5568 11118 5527 11118 6446 11119 5568 11119 6534 11119 6460 11120 5560 11120 5563 11120 6448 11121 5568 11121 6446 11121 6448 11122 5566 11122 5568 11122 6460 11123 5563 11123 5564 11123 6453 11124 5566 11124 6448 11124 6453 11125 6460 11125 5564 11125 6453 11126 5564 11126 5566 11126 6537 11127 6535 11127 6536 11127 6538 11128 6537 11128 6536 11128 6538 11129 6536 11129 6539 11129 6540 11130 6538 11130 6539 11130 6541 11131 6539 11131 6542 11131 6541 11132 6540 11132 6539 11132 6543 11133 6541 11133 6542 11133 6543 11134 6542 11134 6544 11134 6545 11135 6543 11135 6544 11135 6546 11136 6545 11136 6544 11136 6547 11137 6546 11137 6544 11137 6547 11138 6544 11138 6548 11138 6549 11139 6547 11139 6548 11139 6549 11140 6548 11140 6550 11140 6551 11141 6549 11141 6550 11141 6552 11142 6551 11142 6550 11142 6552 11143 6550 11143 6553 11143 6554 11144 6552 11144 6553 11144 6555 11145 6554 11145 6553 11145 6556 11146 6555 11146 6553 11146 6557 11147 6553 11147 6558 11147 6557 11148 6556 11148 6553 11148 6559 11149 6557 11149 6558 11149 6560 11150 6559 11150 6558 11150 6560 11151 6558 11151 6561 11151 6562 11152 6560 11152 6561 11152 6563 11153 6562 11153 6561 11153 6563 11154 6561 11154 6564 11154 6565 11155 6563 11155 6564 11155 6565 11156 6564 11156 6566 11156 6567 11157 6565 11157 6566 11157 6568 11158 6567 11158 6566 11158 6568 11159 6566 11159 6569 11159 6570 11160 6568 11160 6569 11160 6571 11161 6569 11161 6572 11161 6571 11162 6570 11162 6569 11162 6573 11163 6571 11163 6572 11163 6574 11164 6573 11164 6572 11164 6574 11165 6572 11165 6575 11165 6576 11166 6574 11166 6575 11166 6577 11167 6576 11167 6575 11167 6577 11168 6575 11168 6578 11168 6579 11169 6577 11169 6578 11169 6580 11170 6579 11170 6578 11170 6580 11171 6578 11171 6581 11171 6582 11172 6580 11172 6581 11172 6583 11173 6581 11173 6584 11173 6583 11174 6582 11174 6581 11174 6585 11175 6583 11175 6584 11175 6586 11176 6585 11176 6584 11176 6587 11177 6586 11177 6584 11177 6587 11178 6584 11178 6588 11178 6589 11179 6587 11179 6588 11179 6590 11180 6589 11180 6588 11180 6591 11181 6590 11181 6588 11181 6591 11182 6588 11182 6592 11182 6593 11183 6591 11183 6592 11183 6594 11184 6593 11184 6592 11184 6595 11185 6592 11185 6596 11185 6595 11186 6594 11186 6592 11186 6597 11187 6595 11187 6596 11187 6598 11188 6597 11188 6596 11188 6599 11189 6596 11189 6600 11189 6599 11190 6598 11190 6596 11190 6601 11191 6599 11191 6600 11191 6601 11192 6600 11192 6602 11192 6603 11193 6601 11193 6602 11193 6604 11194 6603 11194 6602 11194 6604 11195 6602 11195 6605 11195 6606 11196 6604 11196 6605 11196 6607 11197 6606 11197 6605 11197 6608 11198 6607 11198 6605 11198 6608 11199 6605 11199 6609 11199 6610 11200 6608 11200 6609 11200 6611 11201 6610 11201 6609 11201 6612 11202 6611 11202 6609 11202 6612 11203 6609 11203 6613 11203 6535 11204 6612 11204 6613 11204 6535 11205 6613 11205 6536 11205 6614 11206 6689 11206 6615 11206 6616 11207 6614 11207 6615 11207 6616 11208 6615 11208 6617 11208 6616 11209 6617 11209 6618 11209 6619 11210 6616 11210 6618 11210 6619 11211 6618 11211 6620 11211 6619 11212 6620 11212 6621 11212 6619 11213 6621 11213 6622 11213 6623 11214 6619 11214 6622 11214 6623 11215 6622 11215 6624 11215 6623 11216 6624 11216 6625 11216 6623 11217 6625 11217 6626 11217 6627 11218 6623 11218 6626 11218 6627 11219 6626 11219 6628 11219 6627 11220 6628 11220 6629 11220 6630 11221 6627 11221 6629 11221 6630 11222 6629 11222 6631 11222 6630 11223 6631 11223 6632 11223 6633 11224 6630 11224 6632 11224 6633 11225 6632 11225 6634 11225 6633 11226 6634 11226 6635 11226 6636 11227 6633 11227 6635 11227 6636 11228 6635 11228 6637 11228 6636 11229 6637 11229 6638 11229 6639 11230 6636 11230 6638 11230 6639 11231 6638 11231 6640 11231 6639 11232 6640 11232 6641 11232 6642 11233 6639 11233 6641 11233 6642 11234 6641 11234 6643 11234 6642 11235 6643 11235 6644 11235 6645 11236 6642 11236 6644 11236 6645 11237 6644 11237 6646 11237 6645 11238 6646 11238 6647 11238 6645 11239 6647 11239 6648 11239 6649 11240 6645 11240 6648 11240 6649 11241 6648 11241 6650 11241 6649 11242 6650 11242 6651 11242 6652 11243 6649 11243 6651 11243 6652 11244 6651 11244 6653 11244 6652 11245 6653 11245 6654 11245 6652 11246 6654 11246 6656 11246 6655 11247 6652 11247 6656 11247 6655 11248 6656 11248 6657 11248 6658 11249 6655 11249 6657 11249 6658 11250 6657 11250 6659 11250 6658 11251 6659 11251 6660 11251 6661 11252 6658 11252 6660 11252 6661 11253 6660 11253 6662 11253 6663 11254 6662 11254 6664 11254 6663 11255 6661 11255 6662 11255 6663 11256 6664 11256 6665 11256 6666 11257 6663 11257 6665 11257 6666 11258 6665 11258 6667 11258 6666 11259 6667 11259 6668 11259 6669 11260 6668 11260 6670 11260 6669 11261 6666 11261 6668 11261 6669 11262 6670 11262 6671 11262 6669 11263 6671 11263 6672 11263 6673 11264 6669 11264 6672 11264 6673 11265 6672 11265 6674 11265 6673 11266 6674 11266 6717 11266 6673 11267 6717 11267 6675 11267 6676 11268 6673 11268 6675 11268 6676 11269 6675 11269 6714 11269 6676 11270 6714 11270 6711 11270 6677 11271 6711 11271 6678 11271 6677 11272 6676 11272 6711 11272 6677 11273 6678 11273 6706 11273 6677 11274 6706 11274 6679 11274 6680 11275 6679 11275 6681 11275 6680 11276 6677 11276 6679 11276 6682 11277 6680 11277 6681 11277 6682 11278 6681 11278 6683 11278 6682 11279 6683 11279 6684 11279 6685 11280 6684 11280 6697 11280 6685 11281 6682 11281 6684 11281 6685 11282 6697 11282 6686 11282 6687 11283 6685 11283 6686 11283 6687 11284 6686 11284 6688 11284 6687 11285 6688 11285 6689 11285 6614 11286 6687 11286 6689 11286 6692 11287 6794 11287 6793 11287 6688 11288 6690 11288 6689 11288 6692 11289 6793 11289 6691 11289 6693 11290 6690 11290 6688 11290 6694 11291 6794 11291 6692 11291 6693 11292 6691 11292 6690 11292 6692 11293 6691 11293 6693 11293 6686 11294 6693 11294 6688 11294 6695 11295 6692 11295 6693 11295 6696 11296 6693 11296 6686 11296 6694 11297 6692 11297 6695 11297 6695 11298 6693 11298 6696 11298 6697 11299 6696 11299 6686 11299 6698 11300 6696 11300 6697 11300 6698 11301 6695 11301 6696 11301 6684 11302 6698 11302 6697 11302 6701 11303 6694 11303 6695 11303 6699 11304 6695 11304 6698 11304 6700 11305 6698 11305 6684 11305 6701 11306 6695 11306 6699 11306 6699 11307 6698 11307 6700 11307 6683 11308 6700 11308 6684 11308 6702 11309 6700 11309 6683 11309 6702 11310 6699 11310 6700 11310 6681 11311 6702 11311 6683 11311 6701 11312 6699 11312 6702 11312 6704 11313 6701 11313 6702 11313 6703 11314 6702 11314 6681 11314 6705 11315 6702 11315 6703 11315 6679 11316 6703 11316 6681 11316 6704 11317 6702 11317 6705 11317 6705 11318 6703 11318 6679 11318 6706 11319 6705 11319 6679 11319 6707 11320 6704 11320 6705 11320 6708 11321 6705 11321 6706 11321 6709 11322 6706 11322 6678 11322 6707 11323 6705 11323 6708 11323 6709 11324 6708 11324 6706 11324 6710 11325 6708 11325 6709 11325 6711 11326 6709 11326 6678 11326 6710 11327 6707 11327 6708 11327 6711 11328 6710 11328 6709 11328 6712 11329 6707 11329 6710 11329 6713 11330 6710 11330 6711 11330 6712 11331 6710 11331 6713 11331 6713 11332 6711 11332 6714 11332 6715 11333 6712 11333 6713 11333 6716 11334 6714 11334 6675 11334 6716 11335 6713 11335 6714 11335 6715 11336 6713 11336 6716 11336 6717 11337 6716 11337 6675 11337 6718 11338 6712 11338 6715 11338 6719 11339 6716 11339 6717 11339 6719 11340 6715 11340 6716 11340 6718 11341 6715 11341 6719 11341 6719 11342 6717 11342 6674 11342 6719 11343 6674 11343 6672 11343 6721 11344 6712 11344 6718 11344 6720 11345 6718 11345 6719 11345 6720 11346 6719 11346 6672 11346 6720 11347 6672 11347 6671 11347 6721 11348 6718 11348 6720 11348 6670 11349 6720 11349 6671 11349 6722 11350 6720 11350 6670 11350 6721 11351 6720 11351 6722 11351 6723 11352 6721 11352 6722 11352 6724 11353 6670 11353 6668 11353 6724 11354 6722 11354 6670 11354 6723 11355 6722 11355 6724 11355 6667 11356 6724 11356 6668 11356 6725 11357 6721 11357 6723 11357 6725 11358 6723 11358 6724 11358 6726 11359 6667 11359 6665 11359 6726 11360 6724 11360 6667 11360 6727 11361 6721 11361 6725 11361 6726 11362 6725 11362 6724 11362 6727 11363 6725 11363 6726 11363 6728 11364 6726 11364 6665 11364 6728 11365 6727 11365 6726 11365 6728 11366 6665 11366 6664 11366 6729 11367 6727 11367 6728 11367 6730 11368 6728 11368 6664 11368 6729 11369 6728 11369 6730 11369 6732 11370 6727 11370 6729 11370 6662 11371 6730 11371 6664 11371 6731 11372 6730 11372 6662 11372 6731 11373 6729 11373 6730 11373 6732 11374 6729 11374 6731 11374 6733 11375 6662 11375 6660 11375 6733 11376 6731 11376 6662 11376 6734 11377 6731 11377 6733 11377 6732 11378 6731 11378 6734 11378 6733 11379 6660 11379 6659 11379 6736 11380 6733 11380 6659 11380 6735 11381 6732 11381 6734 11381 6736 11382 6734 11382 6733 11382 6737 11383 6734 11383 6736 11383 6657 11384 6736 11384 6659 11384 6737 11385 6735 11385 6734 11385 6738 11386 6736 11386 6657 11386 6738 11387 6737 11387 6736 11387 6656 11388 6738 11388 6657 11388 6739 11389 6737 11389 6738 11389 6739 11390 6735 11390 6737 11390 6740 11391 6738 11391 6656 11391 6741 11392 6738 11392 6740 11392 6741 11393 6739 11393 6738 11393 6654 11394 6740 11394 6656 11394 6742 11395 6735 11395 6739 11395 6743 11396 6654 11396 6653 11396 6742 11397 6739 11397 6741 11397 6743 11398 6740 11398 6654 11398 6744 11399 6740 11399 6743 11399 6744 11400 6741 11400 6740 11400 6742 11401 6741 11401 6744 11401 6743 11402 6653 11402 6651 11402 6745 11403 6744 11403 6743 11403 6745 11404 6742 11404 6744 11404 6746 11405 6743 11405 6651 11405 6748 11406 6742 11406 6745 11406 6745 11407 6743 11407 6746 11407 6746 11408 6651 11408 6650 11408 6747 11409 6745 11409 6746 11409 6747 11410 6746 11410 6650 11410 6748 11411 6745 11411 6747 11411 6749 11412 6748 11412 6747 11412 6750 11413 6650 11413 6648 11413 6750 11414 6747 11414 6650 11414 6749 11415 6747 11415 6750 11415 6750 11416 6648 11416 6647 11416 6751 11417 6750 11417 6647 11417 6646 11418 6751 11418 6647 11418 6752 11419 6748 11419 6749 11419 6751 11420 6749 11420 6750 11420 6752 11421 6749 11421 6751 11421 6753 11422 6751 11422 6646 11422 6644 11423 6753 11423 6646 11423 6754 11424 6751 11424 6753 11424 6754 11425 6752 11425 6751 11425 6755 11426 6753 11426 6644 11426 6756 11427 6752 11427 6754 11427 6755 11428 6754 11428 6753 11428 6755 11429 6644 11429 6643 11429 6757 11430 6754 11430 6755 11430 6756 11431 6754 11431 6757 11431 6757 11432 6755 11432 6643 11432 6641 11433 6757 11433 6643 11433 6758 11434 6756 11434 6757 11434 6759 11435 6757 11435 6641 11435 6758 11436 6757 11436 6759 11436 6640 11437 6759 11437 6641 11437 6761 11438 6759 11438 6760 11438 6761 11439 6758 11439 6759 11439 6760 11440 6759 11440 6640 11440 6762 11441 6758 11441 6761 11441 6762 11442 6756 11442 6758 11442 6638 11443 6760 11443 6640 11443 6763 11444 6638 11444 6637 11444 6763 11445 6760 11445 6638 11445 6763 11446 6761 11446 6760 11446 6764 11447 6761 11447 6763 11447 6762 11448 6761 11448 6764 11448 6635 11449 6763 11449 6637 11449 6765 11450 6763 11450 6635 11450 6765 11451 6764 11451 6763 11451 6766 11452 6764 11452 6765 11452 6766 11453 6762 11453 6764 11453 6767 11454 6635 11454 6634 11454 6767 11455 6765 11455 6635 11455 6768 11456 6762 11456 6766 11456 6769 11457 6765 11457 6767 11457 6768 11458 6765 11458 6769 11458 6632 11459 6767 11459 6634 11459 6768 11460 6766 11460 6765 11460 6769 11461 6767 11461 6632 11461 6770 11462 6632 11462 6631 11462 6771 11463 6768 11463 6769 11463 6770 11464 6769 11464 6632 11464 6771 11465 6769 11465 6770 11465 6772 11466 6768 11466 6771 11466 6629 11467 6770 11467 6631 11467 6773 11468 6770 11468 6629 11468 6773 11469 6771 11469 6770 11469 6772 11470 6771 11470 6773 11470 6774 11471 6629 11471 6628 11471 6774 11472 6773 11472 6629 11472 6775 11473 6772 11473 6773 11473 6775 11474 6773 11474 6774 11474 6776 11475 6772 11475 6775 11475 6626 11476 6774 11476 6628 11476 6777 11477 6774 11477 6626 11477 6775 11478 6774 11478 6777 11478 6625 11479 6777 11479 6626 11479 6778 11480 6775 11480 6777 11480 6780 11481 6775 11481 6778 11481 6776 11482 6775 11482 6780 11482 6778 11483 6777 11483 6625 11483 6779 11484 6625 11484 6624 11484 6779 11485 6778 11485 6625 11485 6781 11486 6776 11486 6780 11486 6782 11487 6778 11487 6779 11487 6782 11488 6780 11488 6778 11488 6783 11489 6624 11489 6622 11489 6783 11490 6779 11490 6624 11490 6781 11491 6780 11491 6782 11491 6783 11492 6782 11492 6779 11492 6784 11493 6782 11493 6783 11493 6783 11494 6622 11494 6621 11494 6781 11495 6782 11495 6784 11495 6786 11496 6621 11496 6620 11496 6786 11497 6783 11497 6621 11497 6785 11498 6781 11498 6784 11498 6786 11499 6784 11499 6783 11499 6786 11500 6785 11500 6784 11500 6787 11501 6785 11501 6786 11501 6788 11502 6786 11502 6620 11502 6787 11503 6781 11503 6785 11503 6788 11504 6620 11504 6618 11504 6789 11505 6786 11505 6788 11505 6787 11506 6786 11506 6789 11506 6789 11507 6788 11507 6618 11507 6791 11508 6787 11508 6789 11508 6617 11509 6789 11509 6618 11509 6790 11510 6787 11510 6791 11510 6791 11511 6789 11511 6617 11511 6792 11512 6617 11512 6615 11512 6792 11513 6791 11513 6617 11513 6793 11514 6791 11514 6792 11514 6793 11515 6790 11515 6791 11515 6794 11516 6790 11516 6793 11516 6615 11517 6689 11517 6690 11517 6792 11518 6615 11518 6690 11518 6792 11519 6690 11519 6691 11519 6792 11520 6691 11520 6793 11520 6331 11521 6704 11521 6329 11521 6329 11522 6704 11522 6707 11522 6327 11523 6329 11523 6707 11523 6331 11524 6701 11524 6704 11524 6334 11525 6694 11525 6701 11525 6334 11526 6701 11526 6331 11526 6327 11527 6707 11527 6712 11527 6336 11528 6694 11528 6334 11528 6324 11529 6327 11529 6712 11529 6272 11530 6694 11530 6336 11530 6324 11531 6712 11531 6721 11531 6272 11532 6794 11532 6694 11532 6321 11533 6324 11533 6721 11533 6274 11534 6790 11534 6794 11534 6274 11535 6794 11535 6272 11535 6319 11536 6321 11536 6721 11536 6277 11537 6787 11537 6790 11537 6277 11538 6790 11538 6274 11538 6316 11539 6319 11539 6721 11539 6277 11540 6781 11540 6787 11540 6280 11541 6781 11541 6277 11541 6727 11542 6316 11542 6721 11542 6312 11543 6316 11543 6727 11543 6732 11544 6312 11544 6727 11544 6776 11545 6781 11545 6280 11545 6282 11546 6776 11546 6280 11546 6732 11547 6309 11547 6312 11547 6776 11548 6282 11548 6285 11548 6735 11549 6309 11549 6732 11549 6772 11550 6776 11550 6285 11550 6286 11551 6772 11551 6285 11551 6735 11552 6307 11552 6309 11552 6768 11553 6772 11553 6286 11553 6742 11554 6307 11554 6735 11554 6742 11555 6304 11555 6307 11555 6768 11556 6286 11556 6289 11556 6748 11557 6304 11557 6742 11557 6762 11558 6768 11558 6289 11558 6748 11559 6302 11559 6304 11559 6762 11560 6289 11560 6291 11560 6752 11561 6302 11561 6748 11561 6752 11562 6299 11562 6302 11562 6762 11563 6291 11563 6294 11563 6756 11564 6762 11564 6294 11564 6752 11565 6297 11565 6299 11565 6756 11566 6297 11566 6752 11566 6756 11567 6294 11567 6297 11567 6537 11568 6795 11568 6535 11568 6796 11569 6795 11569 6537 11569 6798 11570 6537 11570 6538 11570 6798 11571 6796 11571 6537 11571 6799 11572 6796 11572 6798 11572 6797 11573 6796 11573 6799 11573 6540 11574 6798 11574 6538 11574 6800 11575 6797 11575 6799 11575 6800 11576 6799 11576 6798 11576 6801 11577 6798 11577 6540 11577 6801 11578 6800 11578 6798 11578 6802 11579 6797 11579 6800 11579 6541 11580 6801 11580 6540 11580 6802 11581 6800 11581 6801 11581 6803 11582 6801 11582 6541 11582 6803 11583 6802 11583 6801 11583 6803 11584 6541 11584 6543 11584 6805 11585 6802 11585 6803 11585 6804 11586 6803 11586 6543 11586 6805 11587 6803 11587 6804 11587 6804 11588 6543 11588 6545 11588 6807 11589 6802 11589 6805 11589 6806 11590 6804 11590 6545 11590 6806 11591 6805 11591 6804 11591 6807 11592 6805 11592 6806 11592 6546 11593 6806 11593 6545 11593 6808 11594 6546 11594 6547 11594 6808 11595 6806 11595 6546 11595 6809 11596 6806 11596 6808 11596 6549 11597 6808 11597 6547 11597 6809 11598 6807 11598 6806 11598 6810 11599 6808 11599 6549 11599 6809 11600 6808 11600 6810 11600 6811 11601 6807 11601 6809 11601 6551 11602 6810 11602 6549 11602 6812 11603 6809 11603 6810 11603 6813 11604 6551 11604 6552 11604 6812 11605 6811 11605 6809 11605 6813 11606 6810 11606 6551 11606 6813 11607 6812 11607 6810 11607 6813 11608 6552 11608 6554 11608 6814 11609 6811 11609 6812 11609 6815 11610 6813 11610 6554 11610 6815 11611 6812 11611 6813 11611 6814 11612 6812 11612 6815 11612 6555 11613 6815 11613 6554 11613 6816 11614 6815 11614 6555 11614 6816 11615 6814 11615 6815 11615 6816 11616 6555 11616 6556 11616 6817 11617 6814 11617 6816 11617 6819 11618 6556 11618 6557 11618 6817 11619 6816 11619 6818 11619 6819 11620 6816 11620 6556 11620 6818 11621 6816 11621 6819 11621 6559 11622 6819 11622 6557 11622 6820 11623 6817 11623 6818 11623 6820 11624 6818 11624 6819 11624 6821 11625 6559 11625 6560 11625 6821 11626 6819 11626 6559 11626 6820 11627 6819 11627 6821 11627 6822 11628 6820 11628 6821 11628 6823 11629 6560 11629 6562 11629 6823 11630 6821 11630 6560 11630 6824 11631 6820 11631 6822 11631 6824 11632 6817 11632 6820 11632 6823 11633 6822 11633 6821 11633 6563 11634 6823 11634 6562 11634 6825 11635 6823 11635 6563 11635 6825 11636 6822 11636 6823 11636 6826 11637 6822 11637 6825 11637 6824 11638 6822 11638 6826 11638 6827 11639 6825 11639 6563 11639 6827 11640 6563 11640 6565 11640 6828 11641 6824 11641 6826 11641 6827 11642 6826 11642 6825 11642 6829 11643 6827 11643 6565 11643 6829 11644 6826 11644 6827 11644 6828 11645 6826 11645 6829 11645 6567 11646 6829 11646 6565 11646 6830 11647 6829 11647 6567 11647 6831 11648 6828 11648 6829 11648 6831 11649 6829 11649 6830 11649 6832 11650 6567 11650 6568 11650 6832 11651 6830 11651 6567 11651 6833 11652 6828 11652 6831 11652 6832 11653 6831 11653 6830 11653 6834 11654 6831 11654 6832 11654 6835 11655 6832 11655 6568 11655 6835 11656 6568 11656 6570 11656 6833 11657 6831 11657 6834 11657 6835 11658 6834 11658 6832 11658 6836 11659 6834 11659 6835 11659 6571 11660 6835 11660 6570 11660 6836 11661 6835 11661 6571 11661 6838 11662 6834 11662 6836 11662 6837 11663 6836 11663 6571 11663 6838 11664 6833 11664 6834 11664 6841 11665 6833 11665 6838 11665 6573 11666 6837 11666 6571 11666 6839 11667 6836 11667 6837 11667 6839 11668 6838 11668 6836 11668 6574 11669 6837 11669 6573 11669 6840 11670 6837 11670 6574 11670 6841 11671 6838 11671 6839 11671 6840 11672 6839 11672 6837 11672 6841 11673 6839 11673 6840 11673 6842 11674 6840 11674 6574 11674 6843 11675 6841 11675 6840 11675 6842 11676 6574 11676 6576 11676 6844 11677 6840 11677 6842 11677 6843 11678 6840 11678 6844 11678 6844 11679 6842 11679 6576 11679 6845 11680 6843 11680 6844 11680 6577 11681 6844 11681 6576 11681 6845 11682 6844 11682 6577 11682 6846 11683 6843 11683 6845 11683 6847 11684 6845 11684 6577 11684 6846 11685 6845 11685 6847 11685 6847 11686 6577 11686 6579 11686 6848 11687 6843 11687 6846 11687 6849 11688 6847 11688 6579 11688 6849 11689 6846 11689 6847 11689 6849 11690 6579 11690 6580 11690 6850 11691 6846 11691 6849 11691 6850 11692 6848 11692 6846 11692 6851 11693 6580 11693 6582 11693 6851 11694 6849 11694 6580 11694 6852 11695 6849 11695 6851 11695 6850 11696 6849 11696 6852 11696 6853 11697 6852 11697 6851 11697 6854 11698 6848 11698 6850 11698 6583 11699 6851 11699 6582 11699 6853 11700 6851 11700 6583 11700 6854 11701 6850 11701 6852 11701 6854 11702 6852 11702 6853 11702 6855 11703 6853 11703 6583 11703 6854 11704 6853 11704 6855 11704 6855 11705 6583 11705 6585 11705 6856 11706 6855 11706 6585 11706 6856 11707 6585 11707 6586 11707 6857 11708 6854 11708 6855 11708 6857 11709 6855 11709 6856 11709 6858 11710 6856 11710 6586 11710 6587 11711 6858 11711 6586 11711 6860 11712 6856 11712 6858 11712 6857 11713 6856 11713 6860 11713 6859 11714 6857 11714 6860 11714 6589 11715 6858 11715 6587 11715 6860 11716 6858 11716 6589 11716 6859 11717 6854 11717 6857 11717 6859 11718 6860 11718 6861 11718 6590 11719 6860 11719 6589 11719 6861 11720 6860 11720 6590 11720 6862 11721 6859 11721 6861 11721 6591 11722 6861 11722 6590 11722 6863 11723 6861 11723 6591 11723 6864 11724 6859 11724 6862 11724 6862 11725 6861 11725 6863 11725 6593 11726 6863 11726 6591 11726 6865 11727 6863 11727 6593 11727 6865 11728 6862 11728 6863 11728 6864 11729 6862 11729 6865 11729 6866 11730 6593 11730 6594 11730 6867 11731 6864 11731 6865 11731 6866 11732 6865 11732 6593 11732 6867 11733 6865 11733 6866 11733 6595 11734 6866 11734 6594 11734 6868 11735 6866 11735 6595 11735 6868 11736 6867 11736 6866 11736 6868 11737 6595 11737 6597 11737 6869 11738 6864 11738 6867 11738 6869 11739 6867 11739 6868 11739 6870 11740 6597 11740 6598 11740 6871 11741 6597 11741 6870 11741 6871 11742 6868 11742 6597 11742 6871 11743 6869 11743 6868 11743 6599 11744 6870 11744 6598 11744 6872 11745 6871 11745 6870 11745 6601 11746 6870 11746 6599 11746 6873 11747 6870 11747 6601 11747 6872 11748 6869 11748 6871 11748 6873 11749 6872 11749 6870 11749 6874 11750 6869 11750 6872 11750 6875 11751 6872 11751 6873 11751 6873 11752 6601 11752 6603 11752 6875 11753 6874 11753 6872 11753 6876 11754 6873 11754 6603 11754 6876 11755 6875 11755 6873 11755 6877 11756 6875 11756 6876 11756 6604 11757 6876 11757 6603 11757 6874 11758 6875 11758 6877 11758 6878 11759 6876 11759 6604 11759 6878 11760 6877 11760 6876 11760 6879 11761 6874 11761 6877 11761 6879 11762 6877 11762 6878 11762 6880 11763 6604 11763 6606 11763 6880 11764 6878 11764 6604 11764 6881 11765 6879 11765 6878 11765 6881 11766 6878 11766 6880 11766 6882 11767 6606 11767 6607 11767 6882 11768 6880 11768 6606 11768 6883 11769 6879 11769 6881 11769 6882 11770 6881 11770 6880 11770 6884 11771 6881 11771 6882 11771 6608 11772 6882 11772 6607 11772 6883 11773 6881 11773 6884 11773 6885 11774 6882 11774 6608 11774 6884 11775 6882 11775 6885 11775 6886 11776 6884 11776 6885 11776 6885 11777 6608 11777 6610 11777 6887 11778 6885 11778 6610 11778 6886 11779 6883 11779 6884 11779 6890 11780 6883 11780 6886 11780 6888 11781 6886 11781 6885 11781 6888 11782 6885 11782 6887 11782 6611 11783 6887 11783 6610 11783 6889 11784 6887 11784 6611 11784 6890 11785 6886 11785 6888 11785 6889 11786 6888 11786 6887 11786 6612 11787 6889 11787 6611 11787 6891 11788 6888 11788 6889 11788 6795 11789 6889 11789 6612 11789 6891 11790 6890 11790 6888 11790 6891 11791 6889 11791 6795 11791 6795 11792 6612 11792 6535 11792 6796 11793 6891 11793 6795 11793 6797 11794 6891 11794 6796 11794 6890 11795 6891 11795 6797 11795 6246 11796 6243 11796 6854 11796 6246 11797 6854 11797 6859 11797 6243 11798 6848 11798 6854 11798 6241 11799 6848 11799 6243 11799 6246 11800 6859 11800 6864 11800 6250 11801 6246 11801 6864 11801 6239 11802 6848 11802 6241 11802 6252 11803 6250 11803 6864 11803 6236 11804 6848 11804 6239 11804 6236 11805 6843 11805 6848 11805 6255 11806 6864 11806 6869 11806 6255 11807 6252 11807 6864 11807 6236 11808 6841 11808 6843 11808 6233 11809 6841 11809 6236 11809 6258 11810 6255 11810 6869 11810 6233 11811 6833 11811 6841 11811 6258 11812 6869 11812 6874 11812 6262 11813 6258 11813 6874 11813 6230 11814 6833 11814 6233 11814 6230 11815 6828 11815 6833 11815 6262 11816 6874 11816 6879 11816 6226 11817 6828 11817 6230 11817 6879 11818 6265 11818 6262 11818 6883 11819 6265 11819 6879 11819 6883 11820 6267 11820 6265 11820 6824 11821 6828 11821 6226 11821 6222 11822 6824 11822 6226 11822 6890 11823 6267 11823 6883 11823 6817 11824 6824 11824 6222 11824 6890 11825 6270 11825 6267 11825 6817 11826 6222 11826 6220 11826 6890 11827 6204 11827 6270 11827 6814 11828 6817 11828 6220 11828 6797 11829 6204 11829 6890 11829 6814 11830 6220 11830 6217 11830 6811 11831 6814 11831 6217 11831 6797 11832 6206 11832 6204 11832 6802 11833 6206 11833 6797 11833 6802 11834 6209 11834 6206 11834 6811 11835 6217 11835 6214 11835 6807 11836 6811 11836 6214 11836 6807 11837 6209 11837 6802 11837 6807 11838 6214 11838 6212 11838 6807 11839 6212 11839 6209 11839 6894 11840 6892 11840 6893 11840 6895 11841 6894 11841 6893 11841 6895 11842 6893 11842 6896 11842 6897 11843 6895 11843 6896 11843 6898 11844 6897 11844 6896 11844 6898 11845 6896 11845 6899 11845 6900 11846 6898 11846 6899 11846 6901 11847 6900 11847 6899 11847 6901 11848 6899 11848 6902 11848 6903 11849 6901 11849 6902 11849 6904 11850 6903 11850 6902 11850 6905 11851 6904 11851 6902 11851 6905 11852 6902 11852 6906 11852 6907 11853 6905 11853 6906 11853 6907 11854 6906 11854 6908 11854 6909 11855 6907 11855 6908 11855 6910 11856 6908 11856 6911 11856 6910 11857 6909 11857 6908 11857 6912 11858 6910 11858 6911 11858 6912 11859 6911 11859 6913 11859 6914 11860 6912 11860 6913 11860 6915 11861 6914 11861 6913 11861 6916 11862 6913 11862 6917 11862 6916 11863 6915 11863 6913 11863 6918 11864 6916 11864 6917 11864 6918 11865 6917 11865 6919 11865 6920 11866 6918 11866 6919 11866 6921 11867 6920 11867 6919 11867 6922 11868 6921 11868 6919 11868 6922 11869 6919 11869 6923 11869 6924 11870 6922 11870 6923 11870 6924 11871 6923 11871 6925 11871 6926 11872 6924 11872 6925 11872 6927 11873 6926 11873 6925 11873 6928 11874 6927 11874 6925 11874 6928 11875 6925 11875 6929 11875 6930 11876 6928 11876 6929 11876 6930 11877 6929 11877 6931 11877 6932 11878 6930 11878 6931 11878 6933 11879 6932 11879 6931 11879 6933 11880 6931 11880 6934 11880 6935 11881 6933 11881 6934 11881 6936 11882 6935 11882 6934 11882 6936 11883 6934 11883 6937 11883 7225 11884 6936 11884 6937 11884 7228 11885 7225 11885 6937 11885 6938 11886 7228 11886 6937 11886 6938 11887 6937 11887 6939 11887 6940 11888 6938 11888 6939 11888 6940 11889 6939 11889 6941 11889 6942 11890 6940 11890 6941 11890 6943 11891 6942 11891 6941 11891 6943 11892 6941 11892 6944 11892 6945 11893 6943 11893 6944 11893 6946 11894 6945 11894 6944 11894 6947 11895 6944 11895 6948 11895 6947 11896 6946 11896 6944 11896 6949 11897 6947 11897 6948 11897 6949 11898 6948 11898 6950 11898 6951 11899 6949 11899 6950 11899 6951 11900 6950 11900 6952 11900 6953 11901 6951 11901 6952 11901 6954 11902 6953 11902 6952 11902 6955 11903 6952 11903 6956 11903 6955 11904 6954 11904 6952 11904 6957 11905 6955 11905 6956 11905 6958 11906 6956 11906 6959 11906 6958 11907 6957 11907 6956 11907 6960 11908 6958 11908 6959 11908 6961 11909 6959 11909 6962 11909 6961 11910 6960 11910 6959 11910 6963 11911 6961 11911 6962 11911 6964 11912 6963 11912 6962 11912 6964 11913 6962 11913 6965 11913 6966 11914 6964 11914 6965 11914 6967 11915 6966 11915 6965 11915 6968 11916 6967 11916 6965 11916 6968 11917 6965 11917 6969 11917 6970 11918 6968 11918 6969 11918 6971 11919 6970 11919 6969 11919 6971 11920 6969 11920 6972 11920 6973 11921 6971 11921 6972 11921 6892 11922 6973 11922 6972 11922 6892 11923 6972 11923 6893 11923 6974 11924 6975 11924 7166 11924 6976 11925 6974 11925 7166 11925 6976 11926 7166 11926 6977 11926 6978 11927 6976 11927 6977 11927 6978 11928 6977 11928 6979 11928 6978 11929 6979 11929 6980 11929 6981 11930 6980 11930 6982 11930 6981 11931 6978 11931 6980 11931 6981 11932 6982 11932 6983 11932 6981 11933 6983 11933 6984 11933 6985 11934 6981 11934 6984 11934 6985 11935 6984 11935 6986 11935 6985 11936 6986 11936 6987 11936 6988 11937 6985 11937 6987 11937 6988 11938 6987 11938 6989 11938 6990 11939 6988 11939 6989 11939 6990 11940 6989 11940 6991 11940 6990 11941 6991 11941 7143 11941 6992 11942 6990 11942 7143 11942 6992 11943 7143 11943 7141 11943 6992 11944 7141 11944 7138 11944 6993 11945 6992 11945 7138 11945 6993 11946 7138 11946 6994 11946 6995 11947 6993 11947 6994 11947 6995 11948 6994 11948 7134 11948 6995 11949 7134 11949 7132 11949 6996 11950 6995 11950 7132 11950 6996 11951 7132 11951 6997 11951 6998 11952 6996 11952 6997 11952 6998 11953 6997 11953 6999 11953 6998 11954 6999 11954 7000 11954 7001 11955 6998 11955 7000 11955 7001 11956 7000 11956 7002 11956 7001 11957 7002 11957 7003 11957 7004 11958 7001 11958 7003 11958 7004 11959 7003 11959 7005 11959 7006 11960 7004 11960 7005 11960 7006 11961 7005 11961 7007 11961 7006 11962 7007 11962 7112 11962 7008 11963 7006 11963 7112 11963 7008 11964 7112 11964 7009 11964 7010 11965 7009 11965 7011 11965 7010 11966 7008 11966 7009 11966 7010 11967 7011 11967 7012 11967 7013 11968 7010 11968 7012 11968 7013 11969 7012 11969 7014 11969 7013 11970 7014 11970 7015 11970 7013 11971 7015 11971 7016 11971 7017 11972 7013 11972 7016 11972 7017 11973 7016 11973 7018 11973 7019 11974 7017 11974 7018 11974 7019 11975 7018 11975 7020 11975 7019 11976 7020 11976 7021 11976 7022 11977 7021 11977 7023 11977 7022 11978 7019 11978 7021 11978 7022 11979 7023 11979 7024 11979 7025 11980 7024 11980 7026 11980 7025 11981 7022 11981 7024 11981 7025 11982 7026 11982 7027 11982 7025 11983 7027 11983 7028 11983 7029 11984 7025 11984 7028 11984 7029 11985 7028 11985 7030 11985 7029 11986 7030 11986 7081 11986 7031 11987 7029 11987 7081 11987 7031 11988 7081 11988 7032 11988 7031 11989 7032 11989 7034 11989 7033 11990 7031 11990 7034 11990 7033 11991 7034 11991 7035 11991 7036 11992 7035 11992 7037 11992 7036 11993 7033 11993 7035 11993 7036 11994 7037 11994 7038 11994 7039 11995 7038 11995 7040 11995 7039 11996 7036 11996 7038 11996 7039 11997 7040 11997 7041 11997 7039 11998 7041 11998 7042 11998 7043 11999 7039 11999 7042 11999 7043 12000 7042 12000 7044 12000 7043 12001 7044 12001 7045 12001 7046 12002 7043 12002 7045 12002 7046 12003 7045 12003 7047 12003 7046 12004 7047 12004 7048 12004 7049 12005 7046 12005 7048 12005 7049 12006 7048 12006 7050 12006 7049 12007 7050 12007 7057 12007 7049 12008 7057 12008 7051 12008 6974 12009 7049 12009 7051 12009 6974 12010 7051 12010 6975 12010 7052 12011 6975 12011 7051 12011 7055 12012 7052 12012 7051 12012 7055 12013 7053 12013 7052 12013 7056 12014 7053 12014 7055 12014 7056 12015 7054 12015 7053 12015 7058 12016 7054 12016 7056 12016 7057 12017 7055 12017 7051 12017 7056 12018 7055 12018 7057 12018 7059 12019 7057 12019 7050 12019 7059 12020 7056 12020 7057 12020 7059 12021 7058 12021 7056 12021 7048 12022 7059 12022 7050 12022 7060 12023 7058 12023 7059 12023 7061 12024 7059 12024 7048 12024 7061 12025 7060 12025 7059 12025 7061 12026 7048 12026 7047 12026 7063 12027 7061 12027 7047 12027 7062 12028 7060 12028 7064 12028 7063 12029 7047 12029 7045 12029 7064 12030 7060 12030 7061 12030 7065 12031 7063 12031 7045 12031 7065 12032 7061 12032 7063 12032 7064 12033 7061 12033 7065 12033 7065 12034 7045 12034 7044 12034 7066 12035 7064 12035 7065 12035 7066 12036 7062 12036 7064 12036 7067 12037 7065 12037 7044 12037 7067 12038 7044 12038 7042 12038 7066 12039 7065 12039 7067 12039 7068 12040 7062 12040 7066 12040 7068 12041 7066 12041 7067 12041 7069 12042 7042 12042 7041 12042 7069 12043 7067 12043 7042 12043 7070 12044 7067 12044 7069 12044 7040 12045 7069 12045 7041 12045 7070 12046 7068 12046 7067 12046 7071 12047 7069 12047 7040 12047 7070 12048 7069 12048 7071 12048 7038 12049 7071 12049 7040 12049 7073 12050 7068 12050 7070 12050 7072 12051 7070 12051 7071 12051 7073 12052 7070 12052 7072 12052 7072 12053 7071 12053 7038 12053 7074 12054 7038 12054 7037 12054 7074 12055 7072 12055 7038 12055 7075 12056 7072 12056 7074 12056 7073 12057 7072 12057 7075 12057 7035 12058 7074 12058 7037 12058 7075 12059 7074 12059 7035 12059 7076 12060 7073 12060 7075 12060 7077 12061 7075 12061 7035 12061 7076 12062 7075 12062 7077 12062 7077 12063 7035 12063 7034 12063 7078 12064 7073 12064 7076 12064 7079 12065 7076 12065 7077 12065 7079 12066 7034 12066 7032 12066 7079 12067 7077 12067 7034 12067 7078 12068 7076 12068 7079 12068 7081 12069 7079 12069 7032 12069 7080 12070 7079 12070 7081 12070 7080 12071 7078 12071 7079 12071 7082 12072 7078 12072 7080 12072 7083 12073 7080 12073 7081 12073 7084 12074 7080 12074 7083 12074 7082 12075 7080 12075 7084 12075 7083 12076 7081 12076 7030 12076 7085 12077 7083 12077 7030 12077 7085 12078 7084 12078 7083 12078 7085 12079 7030 12079 7028 12079 7086 12080 7082 12080 7084 12080 7086 12081 7084 12081 7085 12081 7087 12082 7086 12082 7085 12082 7027 12083 7085 12083 7028 12083 7087 12084 7085 12084 7027 12084 7088 12085 7086 12085 7087 12085 7089 12086 7087 12086 7027 12086 7088 12087 7087 12087 7089 12087 7089 12088 7027 12088 7026 12088 7090 12089 7089 12089 7026 12089 7090 12090 7088 12090 7089 12090 7091 12091 7086 12091 7088 12091 7092 12092 7088 12092 7090 12092 7091 12093 7088 12093 7092 12093 7024 12094 7090 12094 7026 12094 7092 12095 7090 12095 7024 12095 7093 12096 7092 12096 7024 12096 7093 12097 7024 12097 7023 12097 7091 12098 7092 12098 7093 12098 7094 12099 7091 12099 7093 12099 7095 12100 7093 12100 7023 12100 7094 12101 7093 12101 7095 12101 7095 12102 7023 12102 7021 12102 7096 12103 7091 12103 7094 12103 7097 12104 7094 12104 7095 12104 7098 12105 7094 12105 7097 12105 7020 12106 7095 12106 7021 12106 7098 12107 7096 12107 7094 12107 7097 12108 7095 12108 7020 12108 7099 12109 7097 12109 7020 12109 7098 12110 7097 12110 7099 12110 7099 12111 7020 12111 7018 12111 7100 12112 7098 12112 7099 12112 7101 12113 7098 12113 7100 12113 7101 12114 7096 12114 7098 12114 7016 12115 7099 12115 7018 12115 7100 12116 7099 12116 7016 12116 7102 12117 7100 12117 7016 12117 7103 12118 7100 12118 7102 12118 7015 12119 7102 12119 7016 12119 7103 12120 7101 12120 7100 12120 7104 12121 7102 12121 7015 12121 7104 12122 7103 12122 7102 12122 7104 12123 7015 12123 7014 12123 7105 12124 7103 12124 7104 12124 7106 12125 7103 12125 7105 12125 7105 12126 7104 12126 7014 12126 7106 12127 7101 12127 7103 12127 7012 12128 7105 12128 7014 12128 7107 12129 7105 12129 7012 12129 7108 12130 7101 12130 7106 12130 7108 12131 7105 12131 7107 12131 7108 12132 7106 12132 7105 12132 7011 12133 7107 12133 7012 12133 7109 12134 7011 12134 7009 12134 7109 12135 7107 12135 7011 12135 7110 12136 7107 12136 7109 12136 7110 12137 7108 12137 7107 12137 7111 12138 7108 12138 7110 12138 7112 12139 7109 12139 7009 12139 7113 12140 7109 12140 7112 12140 7113 12141 7110 12141 7109 12141 7111 12142 7110 12142 7113 12142 7114 12143 7112 12143 7007 12143 7114 12144 7113 12144 7112 12144 7115 12145 7113 12145 7114 12145 7115 12146 7111 12146 7113 12146 7116 12147 7007 12147 7005 12147 7116 12148 7114 12148 7007 12148 7117 12149 7114 12149 7116 12149 7117 12150 7115 12150 7114 12150 7118 12151 7005 12151 7003 12151 7118 12152 7116 12152 7005 12152 7119 12153 7115 12153 7117 12153 7117 12154 7116 12154 7118 12154 7120 12155 7118 12155 7003 12155 7117 12156 7118 12156 7120 12156 7121 12157 7119 12157 7117 12157 7002 12158 7120 12158 7003 12158 7122 12159 7117 12159 7120 12159 7121 12160 7117 12160 7122 12160 7123 12161 7120 12161 7002 12161 7125 12162 7119 12162 7121 12162 7123 12163 7122 12163 7120 12163 7123 12164 7002 12164 7000 12164 7124 12165 7123 12165 7000 12165 7124 12166 7122 12166 7123 12166 7125 12167 7121 12167 7122 12167 7125 12168 7122 12168 7124 12168 7124 12169 7000 12169 6999 12169 7126 12170 7125 12170 7124 12170 7127 12171 7124 12171 6999 12171 7128 12172 7124 12172 7127 12172 6997 12173 7127 12173 6999 12173 7126 12174 7124 12174 7128 12174 7129 12175 7127 12175 6997 12175 7129 12176 7128 12176 7127 12176 7131 12177 7128 12177 7129 12177 7131 12178 7126 12178 7128 12178 7130 12179 7126 12179 7131 12179 7132 12180 7129 12180 6997 12180 7133 12181 7129 12181 7132 12181 7133 12182 7131 12182 7129 12182 7133 12183 7132 12183 7134 12183 7135 12184 7133 12184 7134 12184 7135 12185 7131 12185 7133 12185 7136 12186 7131 12186 7135 12186 7135 12187 7134 12187 6994 12187 7136 12188 7130 12188 7131 12188 7137 12189 7135 12189 6994 12189 7139 12190 7130 12190 7136 12190 7136 12191 7135 12191 7137 12191 7138 12192 7137 12192 6994 12192 7140 12193 7137 12193 7138 12193 7140 12194 7136 12194 7137 12194 7140 12195 7139 12195 7136 12195 7142 12196 7138 12196 7141 12196 7142 12197 7140 12197 7138 12197 7142 12198 7139 12198 7140 12198 7143 12199 7142 12199 7141 12199 7144 12200 7142 12200 7143 12200 7144 12201 7139 12201 7142 12201 7145 12202 7139 12202 7144 12202 7146 12203 7143 12203 6991 12203 7146 12204 7144 12204 7143 12204 6989 12205 7146 12205 6991 12205 7147 12206 7144 12206 7146 12206 7148 12207 7144 12207 7147 12207 7148 12208 7145 12208 7144 12208 7147 12209 7146 12209 6989 12209 7149 12210 7147 12210 6989 12210 7149 12211 6989 12211 6987 12211 7150 12212 7147 12212 7149 12212 7150 12213 7148 12213 7147 12213 6987 12214 7150 12214 7149 12214 7152 12215 7148 12215 7150 12215 7151 12216 7150 12216 6987 12216 7152 12217 7150 12217 7151 12217 7151 12218 6987 12218 6986 12218 7151 12219 6986 12219 6984 12219 7153 12220 7151 12220 6984 12220 7154 12221 7151 12221 7153 12221 7154 12222 7152 12222 7151 12222 7153 12223 6984 12223 6983 12223 7155 12224 7153 12224 6983 12224 7156 12225 7152 12225 7154 12225 7154 12226 7153 12226 7155 12226 6982 12227 7155 12227 6983 12227 7157 12228 7154 12228 7155 12228 7158 12229 7155 12229 6982 12229 7158 12230 7157 12230 7155 12230 7158 12231 6982 12231 6980 12231 7156 12232 7154 12232 7157 12232 7159 12233 7157 12233 7158 12233 7159 12234 7158 12234 6980 12234 6979 12235 7159 12235 6980 12235 7160 12236 7156 12236 7157 12236 7162 12237 7156 12237 7160 12237 7160 12238 7157 12238 7159 12238 7161 12239 6979 12239 6977 12239 7161 12240 7159 12240 6979 12240 7163 12241 7159 12241 7161 12241 7163 12242 7160 12242 7159 12242 7162 12243 7160 12243 7163 12243 7164 12244 7161 12244 6977 12244 7164 12245 7163 12245 7161 12245 7165 12246 7163 12246 7164 12246 7165 12247 7162 12247 7163 12247 7166 12248 7164 12248 6977 12248 7054 12249 7162 12249 7165 12249 6975 12250 7164 12250 7166 12250 7164 12251 6975 12251 7052 12251 7164 12252 7052 12252 7053 12252 7165 12253 7164 12253 7053 12253 7165 12254 7053 12254 7054 12254 6680 12255 7062 12255 7068 12255 6682 12256 7062 12256 6680 12256 6677 12257 6680 12257 7068 12257 6677 12258 7068 12258 7073 12258 6685 12259 7062 12259 6682 12259 6685 12260 7060 12260 7062 12260 6676 12261 6677 12261 7073 12261 6687 12262 7058 12262 7060 12262 6687 12263 7060 12263 6685 12263 6676 12264 7073 12264 7078 12264 6614 12265 7058 12265 6687 12265 6673 12266 6676 12266 7078 12266 6614 12267 7054 12267 7058 12267 6673 12268 7078 12268 7082 12268 6616 12269 7054 12269 6614 12269 6669 12270 6673 12270 7082 12270 6616 12271 7162 12271 7054 12271 6619 12272 7162 12272 6616 12272 7086 12273 6669 12273 7082 12273 6666 12274 6669 12274 7086 12274 6619 12275 7156 12275 7162 12275 7091 12276 6666 12276 7086 12276 6623 12277 7152 12277 7156 12277 6623 12278 7156 12278 6619 12278 6663 12279 6666 12279 7091 12279 7091 12280 6661 12280 6663 12280 7096 12281 6661 12281 7091 12281 6627 12282 7152 12282 6623 12282 7148 12283 7152 12283 6627 12283 7096 12284 6658 12284 6661 12284 7145 12285 7148 12285 6627 12285 6630 12286 7145 12286 6627 12286 7101 12287 6658 12287 7096 12287 7101 12288 6655 12288 6658 12288 7139 12289 7145 12289 6630 12289 7139 12290 6630 12290 6633 12290 7108 12291 6655 12291 7101 12291 7108 12292 6652 12292 6655 12292 7111 12293 6652 12293 7108 12293 7130 12294 6633 12294 6636 12294 7130 12295 7139 12295 6633 12295 7111 12296 6649 12296 6652 12296 7130 12297 6636 12297 6639 12297 7115 12298 6649 12298 7111 12298 7115 12299 6645 12299 6649 12299 7126 12300 7130 12300 6639 12300 7119 12301 6645 12301 7115 12301 7126 12302 6639 12302 6642 12302 7125 12303 7126 12303 6642 12303 7119 12304 6642 12304 6645 12304 7125 12305 6642 12305 7119 12305 7167 12306 6892 12306 6894 12306 7170 12307 7167 12307 6894 12307 7170 12308 7168 12308 7167 12308 7169 12309 7168 12309 7170 12309 6895 12310 7170 12310 6894 12310 7171 12311 7170 12311 6895 12311 7171 12312 7169 12312 7170 12312 7172 12313 7169 12313 7171 12313 7171 12314 6895 12314 6897 12314 7173 12315 7171 12315 6897 12315 7174 12316 6897 12316 6898 12316 7174 12317 7173 12317 6897 12317 7175 12318 7171 12318 7173 12318 7175 12319 7172 12319 7171 12319 7176 12320 7174 12320 6898 12320 7175 12321 7174 12321 7176 12321 7175 12322 7173 12322 7174 12322 7176 12323 6898 12323 6900 12323 7177 12324 7176 12324 6900 12324 7178 12325 7172 12325 7175 12325 7177 12326 7175 12326 7176 12326 7178 12327 7175 12327 7177 12327 6901 12328 7177 12328 6900 12328 7179 12329 7177 12329 6901 12329 7180 12330 7177 12330 7179 12330 7180 12331 7178 12331 7177 12331 7179 12332 6901 12332 6903 12332 7181 12333 7180 12333 7179 12333 7182 12334 7180 12334 7181 12334 6904 12335 7179 12335 6903 12335 7181 12336 7179 12336 6904 12336 7184 12337 7178 12337 7180 12337 7183 12338 7181 12338 6904 12338 7184 12339 7180 12339 7182 12339 7182 12340 7181 12340 7183 12340 6905 12341 7183 12341 6904 12341 7185 12342 7184 12342 7182 12342 7185 12343 7182 12343 7183 12343 6907 12344 7183 12344 6905 12344 7186 12345 7183 12345 6907 12345 7186 12346 7185 12346 7183 12346 7187 12347 7186 12347 6907 12347 7188 12348 7184 12348 7185 12348 7189 12349 7185 12349 7186 12349 7187 12350 6907 12350 6909 12350 7188 12351 7185 12351 7189 12351 7189 12352 7186 12352 7187 12352 7190 12353 7187 12353 6909 12353 7189 12354 7187 12354 7190 12354 7190 12355 6909 12355 6910 12355 7188 12356 7189 12356 7190 12356 7191 12357 7190 12357 6910 12357 7192 12358 7188 12358 7190 12358 7191 12359 6910 12359 6912 12359 7192 12360 7190 12360 7191 12360 7194 12361 7191 12361 6912 12361 7192 12362 7191 12362 7194 12362 7193 12363 7188 12363 7192 12363 7194 12364 6912 12364 6914 12364 7195 12365 7192 12365 7194 12365 7196 12366 7192 12366 7195 12366 7195 12367 7194 12367 6914 12367 7197 12368 7192 12368 7196 12368 7197 12369 7193 12369 7192 12369 6915 12370 7195 12370 6914 12370 7196 12371 7195 12371 6915 12371 7198 12372 6915 12372 6916 12372 7198 12373 7196 12373 6915 12373 7199 12374 7196 12374 7198 12374 6918 12375 7198 12375 6916 12375 7199 12376 7197 12376 7196 12376 7200 12377 7198 12377 6918 12377 7201 12378 7197 12378 7199 12378 7199 12379 7198 12379 7200 12379 6920 12380 7200 12380 6918 12380 7202 12381 7200 12381 6920 12381 7202 12382 7199 12382 7200 12382 7202 12383 7201 12383 7199 12383 7203 12384 6920 12384 6921 12384 7203 12385 7202 12385 6920 12385 7205 12386 7202 12386 7203 12386 7205 12387 7201 12387 7202 12387 7204 12388 7201 12388 7205 12388 7206 12389 7205 12389 7203 12389 7206 12390 7204 12390 7205 12390 6922 12391 7203 12391 6921 12391 6922 12392 7206 12392 7203 12392 7207 12393 7204 12393 7206 12393 7208 12394 7206 12394 6922 12394 7207 12395 7206 12395 7208 12395 7208 12396 6922 12396 6924 12396 7209 12397 7208 12397 6924 12397 7210 12398 7208 12398 7209 12398 6926 12399 7209 12399 6924 12399 7210 12400 7207 12400 7208 12400 7211 12401 7207 12401 7210 12401 6927 12402 7209 12402 6926 12402 7212 12403 7209 12403 6927 12403 7210 12404 7209 12404 7212 12404 7214 12405 7207 12405 7211 12405 7211 12406 7210 12406 7212 12406 6928 12407 7212 12407 6927 12407 7213 12408 7212 12408 6928 12408 7213 12409 7211 12409 7212 12409 7214 12410 7211 12410 7213 12410 6930 12411 7213 12411 6928 12411 7215 12412 7213 12412 6930 12412 7216 12413 7213 12413 7215 12413 7216 12414 7214 12414 7213 12414 7217 12415 7214 12415 7216 12415 6932 12416 7215 12416 6930 12416 7218 12417 7215 12417 6932 12417 7219 12418 7214 12418 7217 12418 7218 12419 7216 12419 7215 12419 7217 12420 7216 12420 7218 12420 7219 12421 7217 12421 7218 12421 6933 12422 7218 12422 6932 12422 7220 12423 7218 12423 6933 12423 7220 12424 7219 12424 7218 12424 7221 12425 7219 12425 7220 12425 7222 12426 6933 12426 6935 12426 7222 12427 7220 12427 6933 12427 7223 12428 7220 12428 7222 12428 7223 12429 7221 12429 7220 12429 6936 12430 7222 12430 6935 12430 7224 12431 7222 12431 6936 12431 7223 12432 7222 12432 7224 12432 7227 12433 7219 12433 7221 12433 7225 12434 7224 12434 6936 12434 7227 12435 7221 12435 7223 12435 7226 12436 7224 12436 7225 12436 7227 12437 7224 12437 7226 12437 7227 12438 7223 12438 7224 12438 7226 12439 7225 12439 7228 12439 7229 12440 7226 12440 7228 12440 7230 12441 7226 12441 7229 12441 7230 12442 7227 12442 7226 12442 6938 12443 7229 12443 7228 12443 7231 12444 7227 12444 7230 12444 7232 12445 6938 12445 6940 12445 7232 12446 7229 12446 6938 12446 7233 12447 7229 12447 7232 12447 7233 12448 7230 12448 7229 12448 6942 12449 7232 12449 6940 12449 7231 12450 7230 12450 7233 12450 7234 12451 7232 12451 6942 12451 7234 12452 7233 12452 7232 12452 7234 12453 6942 12453 6943 12453 7236 12454 7231 12454 7233 12454 7236 12455 7233 12455 7234 12455 7237 12456 7234 12456 6943 12456 7235 12457 7231 12457 7236 12457 7237 12458 7236 12458 7234 12458 6945 12459 7237 12459 6943 12459 7238 12460 7236 12460 7237 12460 7239 12461 7237 12461 6945 12461 7238 12462 7237 12462 7239 12462 7239 12463 6945 12463 6946 12463 7238 12464 7235 12464 7236 12464 7240 12465 7238 12465 7239 12465 7241 12466 7239 12466 6946 12466 7241 12467 7240 12467 7239 12467 7241 12468 6946 12468 6947 12468 7242 12469 7238 12469 7240 12469 7242 12470 7235 12470 7238 12470 7243 12471 7241 12471 6947 12471 7244 12472 7241 12472 7243 12472 7244 12473 7240 12473 7241 12473 6949 12474 7243 12474 6947 12474 7244 12475 7242 12475 7240 12475 6949 12476 7244 12476 7243 12476 7245 12477 7244 12477 6949 12477 7246 12478 7244 12478 7245 12478 7246 12479 7242 12479 7244 12479 7245 12480 6949 12480 6951 12480 7247 12481 7245 12481 6951 12481 7246 12482 7245 12482 7247 12482 7248 12483 7242 12483 7246 12483 6953 12484 7247 12484 6951 12484 7249 12485 7247 12485 6953 12485 7249 12486 7246 12486 7247 12486 7250 12487 7246 12487 7249 12487 7248 12488 7246 12488 7250 12488 6954 12489 7249 12489 6953 12489 7251 12490 7249 12490 6954 12490 7250 12491 7249 12491 7251 12491 6955 12492 7251 12492 6954 12492 7252 12493 7250 12493 7251 12493 7253 12494 7250 12494 7252 12494 7253 12495 7248 12495 7250 12495 6957 12496 7251 12496 6955 12496 7252 12497 7251 12497 6957 12497 6958 12498 7252 12498 6957 12498 7255 12499 7248 12499 7253 12499 7254 12500 7252 12500 6958 12500 7253 12501 7252 12501 7254 12501 7254 12502 6958 12502 6960 12502 7255 12503 7253 12503 7254 12503 7256 12504 6960 12504 6961 12504 7256 12505 7254 12505 6960 12505 7255 12506 7254 12506 7256 12506 6963 12507 7256 12507 6961 12507 7258 12508 7255 12508 7256 12508 7259 12509 7256 12509 6963 12509 7258 12510 7256 12510 7259 12510 7259 12511 6963 12511 6964 12511 7257 12512 7255 12512 7258 12512 7260 12513 7258 12513 7259 12513 7261 12514 6964 12514 6966 12514 7261 12515 7259 12515 6964 12515 7260 12516 7257 12516 7258 12516 7262 12517 7257 12517 7260 12517 7260 12518 7259 12518 7261 12518 7263 12519 7260 12519 7261 12519 6967 12520 7261 12520 6966 12520 7264 12521 7261 12521 6967 12521 7262 12522 7260 12522 7263 12522 7263 12523 7261 12523 7264 12523 7265 12524 7262 12524 7263 12524 7266 12525 7263 12525 7264 12525 7265 12526 7263 12526 7266 12526 6968 12527 7264 12527 6967 12527 7267 12528 7264 12528 6968 12528 7266 12529 7264 12529 7267 12529 7268 12530 7265 12530 7266 12530 6970 12531 7267 12531 6968 12531 7269 12532 7266 12532 7267 12532 7268 12533 7266 12533 7269 12533 6971 12534 7267 12534 6970 12534 7269 12535 7267 12535 6971 12535 7265 12536 7268 12536 7271 12536 7270 12537 7269 12537 6971 12537 6973 12538 7270 12538 6971 12538 7272 12539 7268 12539 7269 12539 7271 12540 7268 12540 7272 12540 7272 12541 7269 12541 7270 12541 7273 12542 7270 12542 6973 12542 7273 12543 7272 12543 7270 12543 7168 12544 7272 12544 7273 12544 6892 12545 7273 12545 6973 12545 7271 12546 7272 12546 7168 12546 7273 12547 6892 12547 7167 12547 7168 12548 7273 12548 7167 12548 7169 12549 7271 12549 7168 12549 6584 12550 7231 12550 7235 12550 6581 12551 7231 12551 6584 12551 6588 12552 6584 12552 7235 12552 6578 12553 7231 12553 6581 12553 6588 12554 7235 12554 7242 12554 6578 12555 7227 12555 7231 12555 6592 12556 6588 12556 7242 12556 6575 12557 7227 12557 6578 12557 6592 12558 7242 12558 7248 12558 6575 12559 7219 12559 7227 12559 6596 12560 6592 12560 7248 12560 6572 12561 7219 12561 6575 12561 6572 12562 7214 12562 7219 12562 6596 12563 7248 12563 7255 12563 6600 12564 6596 12564 7255 12564 6569 12565 7214 12565 6572 12565 6602 12566 6600 12566 7255 12566 7257 12567 6602 12567 7255 12567 6566 12568 7207 12568 7214 12568 6566 12569 7214 12569 6569 12569 6564 12570 7207 12570 6566 12570 7204 12571 7207 12571 6564 12571 6605 12572 6602 12572 7257 12572 7262 12573 6605 12573 7257 12573 7265 12574 6605 12574 7262 12574 6561 12575 7204 12575 6564 12575 7265 12576 6609 12576 6605 12576 7201 12577 7204 12577 6561 12577 6558 12578 7201 12578 6561 12578 7271 12579 6609 12579 7265 12579 7197 12580 7201 12580 6558 12580 7169 12581 6609 12581 7271 12581 7197 12582 6558 12582 6553 12582 7169 12583 6613 12583 6609 12583 7193 12584 7197 12584 6553 12584 7169 12585 6536 12585 6613 12585 7172 12586 6536 12586 7169 12586 7193 12587 6553 12587 6550 12587 7188 12588 7193 12588 6550 12588 7172 12589 6539 12589 6536 12589 7188 12590 6550 12590 6548 12590 7172 12591 6542 12591 6539 12591 7178 12592 6542 12592 7172 12592 7184 12593 7188 12593 6548 12593 7184 12594 6548 12594 6544 12594 7178 12595 6544 12595 6542 12595 7178 12596 7184 12596 6544 12596 7277 12597 7275 12597 7274 12597 7279 12598 7275 12598 7277 12598 7280 12599 7275 12599 7279 12599 7280 12600 7276 12600 7275 12600 7281 12601 7276 12601 7280 12601 7281 12602 7278 12602 7276 12602 7282 12603 7279 12603 7277 12603 7280 12604 7279 12604 7282 12604 7283 12605 7280 12605 7282 12605 7285 12606 7281 12606 7280 12606 7284 12607 7283 12607 7282 12607 7285 12608 7280 12608 7283 12608 7286 12609 7283 12609 7284 12609 7286 12610 7285 12610 7283 12610 7286 12611 7284 12611 7287 12611 7288 12612 7281 12612 7285 12612 7289 12613 7285 12613 7286 12613 7290 12614 7286 12614 7287 12614 7289 12615 7286 12615 7290 12615 7288 12616 7285 12616 7289 12616 7291 12617 7290 12617 7287 12617 7292 12618 7289 12618 7290 12618 7292 12619 7288 12619 7289 12619 7293 12620 7290 12620 7291 12620 7292 12621 7290 12621 7293 12621 7294 12622 7292 12622 7293 12622 7295 12623 7293 12623 7291 12623 7294 12624 7293 12624 7295 12624 7297 12625 7292 12625 7294 12625 7298 12626 7295 12626 7296 12626 7298 12627 7294 12627 7295 12627 7297 12628 7288 12628 7292 12628 7299 12629 7294 12629 7298 12629 7299 12630 7297 12630 7294 12630 7300 12631 7298 12631 7296 12631 7299 12632 7298 12632 7300 12632 7300 12633 7296 12633 7301 12633 7302 12634 7297 12634 7299 12634 7303 12635 7300 12635 7301 12635 7304 12636 7297 12636 7302 12636 7305 12637 7300 12637 7303 12637 7305 12638 7299 12638 7300 12638 7305 12639 7302 12639 7299 12639 7306 12640 7303 12640 7301 12640 7307 12641 7303 12641 7306 12641 7308 12642 7303 12642 7307 12642 7308 12643 7305 12643 7303 12643 7308 12644 7302 12644 7305 12644 7304 12645 7302 12645 7308 12645 7309 12646 7307 12646 7306 12646 7310 12647 7307 12647 7309 12647 7311 12648 7307 12648 7310 12648 7311 12649 7308 12649 7307 12649 7312 12650 7308 12650 7311 12650 7304 12651 7308 12651 7312 12651 7311 12652 7310 12652 7313 12652 7314 12653 7311 12653 7313 12653 7316 12654 7311 12654 7314 12654 7316 12655 7312 12655 7311 12655 7315 12656 7314 12656 7313 12656 7317 12657 7314 12657 7315 12657 7318 12658 7314 12658 7317 12658 7318 12659 7316 12659 7314 12659 7319 12660 7316 12660 7318 12660 7321 12661 7317 12661 7320 12661 7321 12662 7318 12662 7317 12662 7322 12663 7312 12663 7316 12663 7319 12664 7318 12664 7321 12664 7322 12665 7316 12665 7319 12665 7323 12666 7321 12666 7320 12666 7323 12667 7319 12667 7321 12667 7323 12668 7320 12668 7324 12668 7322 12669 7319 12669 7323 12669 7325 12670 7323 12670 7324 12670 7322 12671 7323 12671 7325 12671 7326 12672 7325 12672 7324 12672 7328 12673 7322 12673 7325 12673 7329 12674 7326 12674 7327 12674 7329 12675 7325 12675 7326 12675 7330 12676 7325 12676 7329 12676 7330 12677 7328 12677 7325 12677 7331 12678 7329 12678 7327 12678 7332 12679 7328 12679 7330 12679 7333 12680 7329 12680 7331 12680 7330 12681 7329 12681 7333 12681 7334 12682 7333 12682 7331 12682 7335 12683 7332 12683 7330 12683 7336 12684 7333 12684 7334 12684 7336 12685 7330 12685 7333 12685 7335 12686 7330 12686 7336 12686 7336 12687 7334 12687 7337 12687 7338 12688 7332 12688 7335 12688 7339 12689 7335 12689 7336 12689 7338 12690 7335 12690 7339 12690 7341 12691 7337 12691 7340 12691 7341 12692 7336 12692 7337 12692 7339 12693 7336 12693 7341 12693 7342 12694 7341 12694 7340 12694 7343 12695 7341 12695 7342 12695 7343 12696 7339 12696 7341 12696 7343 12697 7338 12697 7339 12697 7345 12698 7342 12698 7344 12698 7343 12699 7342 12699 7345 12699 7345 12700 7344 12700 7346 12700 7347 12701 7338 12701 7343 12701 7348 12702 7343 12702 7345 12702 7347 12703 7343 12703 7348 12703 7349 12704 7345 12704 7346 12704 7348 12705 7345 12705 7349 12705 7350 12706 7348 12706 7349 12706 7350 12707 7347 12707 7348 12707 7350 12708 7349 12708 7351 12708 7352 12709 7347 12709 7350 12709 7353 12710 7350 12710 7351 12710 7353 12711 7352 12711 7350 12711 7354 12712 7353 12712 7351 12712 7357 12713 7347 12713 7352 12713 7355 12714 7353 12714 7354 12714 7357 12715 7353 12715 7355 12715 7357 12716 7352 12716 7353 12716 7355 12717 7354 12717 7356 12717 7358 12718 7355 12718 7356 12718 7360 12719 7355 12719 7358 12719 7360 12720 7357 12720 7355 12720 7359 12721 7358 12721 7356 12721 7361 12722 7358 12722 7359 12722 7360 12723 7358 12723 7361 12723 7362 12724 7357 12724 7360 12724 7363 12725 7360 12725 7361 12725 7364 12726 7361 12726 7359 12726 7362 12727 7360 12727 7363 12727 7365 12728 7361 12728 7364 12728 7365 12729 7363 12729 7361 12729 7367 12730 7362 12730 7363 12730 7365 12731 7364 12731 7366 12731 7367 12732 7363 12732 7365 12732 7370 12733 7362 12733 7367 12733 7368 12734 7365 12734 7366 12734 7367 12735 7365 12735 7368 12735 7368 12736 7366 12736 7369 12736 7371 12737 7367 12737 7368 12737 7370 12738 7367 12738 7371 12738 7372 12739 7368 12739 7369 12739 7373 12740 7368 12740 7372 12740 7373 12741 7371 12741 7368 12741 7374 12742 7371 12742 7373 12742 7370 12743 7371 12743 7374 12743 7375 12744 7373 12744 7372 12744 7375 12745 7374 12745 7373 12745 7376 12746 7375 12746 7372 12746 7377 12747 7374 12747 7375 12747 7378 12748 7375 12748 7376 12748 7379 12749 7370 12749 7374 12749 7377 12750 7375 12750 7378 12750 7379 12751 7374 12751 7377 12751 7380 12752 7378 12752 7376 12752 7381 12753 7378 12753 7380 12753 7381 12754 7377 12754 7378 12754 7382 12755 7377 12755 7381 12755 7379 12756 7377 12756 7382 12756 7384 12757 7379 12757 7382 12757 7383 12758 7381 12758 7380 12758 7382 12759 7381 12759 7383 12759 7386 12760 7382 12760 7383 12760 7386 12761 7383 12761 7385 12761 7388 12762 7382 12762 7386 12762 7388 12763 7384 12763 7382 12763 7387 12764 7386 12764 7385 12764 7389 12765 7386 12765 7387 12765 7388 12766 7386 12766 7389 12766 7392 12767 7384 12767 7388 12767 7390 12768 7389 12768 7387 12768 7391 12769 7389 12769 7390 12769 7392 12770 7388 12770 7389 12770 7393 12771 7389 12771 7391 12771 7393 12772 7392 12772 7389 12772 7391 12773 7390 12773 7394 12773 7395 12774 7391 12774 7394 12774 7397 12775 7384 12775 7392 12775 7393 12776 7391 12776 7395 12776 7397 12777 7392 12777 7393 12777 7395 12778 7394 12778 7396 12778 7398 12779 7395 12779 7396 12779 7399 12780 7395 12780 7398 12780 7399 12781 7393 12781 7395 12781 7399 12782 7397 12782 7393 12782 7400 12783 7398 12783 7396 12783 7402 12784 7397 12784 7399 12784 7401 12785 7398 12785 7400 12785 7401 12786 7399 12786 7398 12786 7402 12787 7399 12787 7401 12787 7404 12788 7400 12788 7403 12788 7404 12789 7401 12789 7400 12789 7405 12790 7401 12790 7404 12790 7405 12791 7402 12791 7401 12791 7406 12792 7404 12792 7403 12792 7405 12793 7404 12793 7406 12793 7406 12794 7403 12794 7407 12794 7408 12795 7406 12795 7407 12795 7411 12796 7402 12796 7405 12796 7408 12797 7405 12797 7406 12797 7409 12798 7405 12798 7408 12798 7411 12799 7405 12799 7409 12799 7410 12800 7408 12800 7407 12800 7412 12801 7408 12801 7410 12801 7409 12802 7408 12802 7412 12802 7413 12803 7412 12803 7410 12803 7414 12804 7412 12804 7413 12804 7415 12805 7412 12805 7414 12805 7415 12806 7409 12806 7412 12806 7411 12807 7409 12807 7415 12807 7416 12808 7414 12808 7413 12808 7418 12809 7411 12809 7415 12809 7417 12810 7414 12810 7416 12810 7415 12811 7414 12811 7417 12811 7419 12812 7415 12812 7417 12812 7418 12813 7415 12813 7419 12813 7420 12814 7417 12814 7416 12814 7421 12815 7417 12815 7420 12815 7421 12816 7419 12816 7417 12816 7423 12817 7419 12817 7421 12817 7422 12818 7421 12818 7420 12818 7418 12819 7419 12819 7423 12819 7424 12820 7421 12820 7422 12820 7423 12821 7421 12821 7424 12821 7425 12822 7418 12822 7423 12822 7424 12823 7422 12823 7426 12823 7425 12824 7423 12824 7427 12824 7427 12825 7423 12825 7424 12825 7428 12826 7424 12826 7426 12826 7428 12827 7427 12827 7424 12827 7428 12828 7426 12828 7429 12828 7430 12829 7427 12829 7428 12829 7425 12830 7427 12830 7430 12830 7432 12831 7428 12831 7429 12831 7432 12832 7429 12832 7431 12832 7430 12833 7428 12833 7432 12833 7433 12834 7425 12834 7430 12834 7434 12835 7430 12835 7432 12835 7433 12836 7430 12836 7434 12836 7436 12837 7431 12837 7435 12837 7436 12838 7432 12838 7431 12838 7434 12839 7432 12839 7436 12839 7440 12840 7425 12840 7433 12840 7438 12841 7435 12841 7437 12841 7438 12842 7436 12842 7435 12842 7438 12843 7434 12843 7436 12843 7440 12844 7434 12844 7438 12844 7440 12845 7433 12845 7434 12845 7441 12846 7437 12846 7439 12846 7441 12847 7438 12847 7437 12847 7442 12848 7438 12848 7441 12848 7442 12849 7440 12849 7438 12849 7443 12850 7441 12850 7439 12850 7443 12851 7442 12851 7441 12851 7444 12852 7443 12852 7439 12852 7276 12853 7442 12853 7443 12853 7276 12854 7440 12854 7442 12854 7444 12855 7274 12855 7275 12855 7275 12856 7443 12856 7444 12856 7276 12857 7443 12857 7275 12857 7278 12858 7440 12858 7276 12858 7445 12859 7274 12859 7444 12859 7446 12860 7444 12860 7439 12860 7446 12861 7445 12861 7444 12861 7447 12862 7446 12862 7439 12862 7447 12863 7439 12863 7437 12863 7448 12864 7447 12864 7437 12864 7448 12865 7437 12865 7435 12865 7449 12866 7448 12866 7435 12866 7449 12867 7435 12867 7431 12867 7450 12868 7449 12868 7431 12868 7450 12869 7431 12869 7429 12869 7451 12870 7450 12870 7429 12870 7451 12871 7429 12871 7426 12871 7452 12872 7451 12872 7426 12872 7452 12873 7426 12873 7422 12873 7453 12874 7452 12874 7422 12874 7453 12875 7422 12875 7420 12875 7454 12876 7453 12876 7420 12876 7454 12877 7420 12877 7416 12877 7455 12878 7416 12878 7413 12878 7455 12879 7454 12879 7416 12879 7456 12880 7413 12880 7410 12880 7456 12881 7455 12881 7413 12881 7457 12882 7410 12882 7407 12882 7457 12883 7456 12883 7410 12883 7458 12884 7407 12884 7403 12884 7458 12885 7457 12885 7407 12885 7459 12886 7458 12886 7403 12886 7459 12887 7403 12887 7400 12887 7460 12888 7459 12888 7400 12888 7461 12889 7460 12889 7400 12889 7461 12890 7400 12890 7396 12890 7462 12891 7461 12891 7396 12891 7462 12892 7396 12892 7394 12892 7463 12893 7462 12893 7394 12893 7463 12894 7394 12894 7390 12894 7464 12895 7463 12895 7390 12895 7464 12896 7390 12896 7387 12896 7465 12897 7464 12897 7387 12897 7465 12898 7387 12898 7385 12898 7466 12899 7385 12899 7383 12899 7466 12900 7465 12900 7385 12900 7466 12901 7383 12901 7380 12901 7467 12902 7380 12902 7376 12902 7467 12903 7466 12903 7380 12903 7468 12904 7467 12904 7376 12904 7468 12905 7376 12905 7372 12905 7469 12906 7468 12906 7372 12906 7469 12907 7372 12907 7369 12907 7470 12908 7469 12908 7369 12908 7470 12909 7369 12909 7366 12909 7471 12910 7470 12910 7366 12910 7472 12911 7366 12911 7364 12911 7472 12912 7471 12912 7366 12912 7473 12913 7472 12913 7364 12913 7473 12914 7364 12914 7359 12914 7474 12915 7473 12915 7359 12915 7474 12916 7359 12916 7356 12916 7475 12917 7474 12917 7356 12917 7475 12918 7356 12918 7354 12918 7476 12919 7475 12919 7354 12919 7476 12920 7354 12920 7351 12920 7476 12921 7351 12921 7349 12921 7477 12922 7476 12922 7349 12922 7477 12923 7349 12923 7346 12923 7478 12924 7477 12924 7346 12924 7478 12925 7346 12925 7344 12925 7479 12926 7478 12926 7344 12926 7479 12927 7344 12927 7342 12927 7479 12928 7342 12928 7340 12928 7480 12929 7479 12929 7340 12929 7480 12930 7340 12930 7337 12930 7481 12931 7480 12931 7337 12931 7481 12932 7337 12932 7334 12932 7482 12933 7481 12933 7334 12933 7482 12934 7334 12934 7331 12934 7483 12935 7482 12935 7331 12935 7483 12936 7331 12936 7327 12936 7484 12937 7483 12937 7327 12937 7484 12938 7326 12938 7324 12938 7484 12939 7327 12939 7326 12939 7485 12940 7484 12940 7324 12940 7485 12941 7324 12941 7320 12941 7486 12942 7485 12942 7320 12942 7487 12943 7486 12943 7320 12943 7487 12944 7320 12944 7317 12944 7487 12945 7317 12945 7315 12945 7488 12946 7487 12946 7315 12946 7488 12947 7313 12947 7310 12947 7488 12948 7315 12948 7313 12948 7489 12949 7488 12949 7310 12949 7489 12950 7310 12950 7309 12950 7490 12951 7489 12951 7309 12951 7490 12952 7309 12952 7306 12952 7491 12953 7490 12953 7306 12953 7491 12954 7306 12954 7301 12954 7492 12955 7491 12955 7301 12955 7493 12956 7301 12956 7296 12956 7493 12957 7492 12957 7301 12957 7494 12958 7296 12958 7295 12958 7494 12959 7493 12959 7296 12959 7495 12960 7494 12960 7295 12960 7495 12961 7295 12961 7291 12961 7496 12962 7495 12962 7291 12962 7496 12963 7291 12963 7287 12963 7497 12964 7496 12964 7287 12964 7497 12965 7287 12965 7284 12965 7498 12966 7284 12966 7282 12966 7498 12967 7497 12967 7284 12967 7498 12968 7282 12968 7277 12968 7499 12969 7498 12969 7277 12969 7500 12970 7499 12970 7277 12970 7500 12971 7277 12971 7274 12971 7445 12972 7500 12972 7274 12972 7039 12973 7043 12973 7297 12973 7043 12974 7288 12974 7297 12974 7039 12975 7297 12975 7304 12975 7046 12976 7288 12976 7043 12976 7036 12977 7304 12977 7312 12977 7036 12978 7039 12978 7304 12978 7049 12979 7288 12979 7046 12979 7049 12980 7281 12980 7288 12980 7033 12981 7036 12981 7312 12981 6974 12982 7281 12982 7049 12982 7033 12983 7312 12983 7322 12983 6974 12984 7278 12984 7281 12984 7031 12985 7033 12985 7322 12985 7328 12986 7031 12986 7322 12986 6976 12987 7278 12987 6974 12987 7029 12988 7031 12988 7328 12988 6976 12989 7440 12989 7278 12989 6978 12990 7440 12990 6976 12990 7025 12991 7029 12991 7328 12991 7332 12992 7025 12992 7328 12992 6981 12993 7425 12993 7440 12993 6981 12994 7440 12994 6978 12994 7338 12995 7025 12995 7332 12995 7022 12996 7025 12996 7338 12996 6985 12997 7425 12997 6981 12997 7347 12998 7022 12998 7338 12998 7347 12999 7019 12999 7022 12999 7418 13000 6985 13000 6988 13000 7418 13001 7425 13001 6985 13001 6990 13002 7418 13002 6988 13002 7357 13003 7017 13003 7019 13003 7357 13004 7019 13004 7347 13004 7411 13005 7418 13005 6990 13005 7411 13006 6990 13006 6992 13006 7357 13007 7013 13007 7017 13007 7362 13008 7013 13008 7357 13008 7402 13009 6992 13009 6993 13009 7402 13010 7411 13010 6992 13010 7362 13011 7010 13011 7013 13011 7402 13012 6993 13012 6995 13012 7370 13013 7010 13013 7362 13013 7370 13014 7008 13014 7010 13014 7397 13015 7402 13015 6995 13015 7397 13016 6995 13016 6996 13016 7370 13017 7006 13017 7008 13017 7397 13018 6996 13018 6998 13018 7384 13019 7397 13019 6998 13019 7379 13020 7006 13020 7370 13020 7379 13021 7004 13021 7006 13021 7384 13022 6998 13022 7001 13022 7384 13023 7001 13023 7004 13023 7384 13024 7004 13024 7379 13024 7503 13025 7502 13025 7501 13025 7503 13026 7504 13026 7502 13026 7446 13027 7501 13027 7445 13027 7505 13028 7501 13028 7446 13028 7503 13029 7501 13029 7505 13029 7447 13030 7505 13030 7446 13030 7506 13031 7505 13031 7447 13031 7506 13032 7503 13032 7505 13032 7507 13033 7447 13033 7448 13033 7507 13034 7506 13034 7447 13034 7508 13035 7506 13035 7507 13035 7508 13036 7503 13036 7506 13036 7449 13037 7507 13037 7448 13037 7509 13038 7507 13038 7449 13038 7509 13039 7508 13039 7507 13039 7512 13040 7503 13040 7508 13040 7512 13041 7508 13041 7510 13041 7509 13042 7449 13042 7450 13042 7510 13043 7508 13043 7509 13043 7511 13044 7509 13044 7450 13044 7511 13045 7510 13045 7509 13045 7512 13046 7510 13046 7511 13046 7513 13047 7450 13047 7451 13047 7513 13048 7511 13048 7450 13048 7514 13049 7512 13049 7511 13049 7514 13050 7511 13050 7513 13050 7452 13051 7513 13051 7451 13051 7516 13052 7513 13052 7452 13052 7512 13053 7514 13053 7515 13053 7516 13054 7514 13054 7513 13054 7515 13055 7514 13055 7516 13055 7453 13056 7516 13056 7452 13056 7517 13057 7516 13057 7453 13057 7518 13058 7512 13058 7515 13058 7519 13059 7516 13059 7517 13059 7519 13060 7515 13060 7516 13060 7454 13061 7517 13061 7453 13061 7520 13062 7517 13062 7454 13062 7518 13063 7515 13063 7519 13063 7519 13064 7517 13064 7520 13064 7521 13065 7520 13065 7454 13065 7522 13066 7519 13066 7520 13066 7521 13067 7454 13067 7455 13067 7518 13068 7519 13068 7522 13068 7522 13069 7520 13069 7521 13069 7523 13070 7521 13070 7455 13070 7523 13071 7522 13071 7521 13071 7523 13072 7455 13072 7456 13072 7526 13073 7518 13073 7522 13073 7524 13074 7522 13074 7523 13074 7525 13075 7523 13075 7456 13075 7526 13076 7522 13076 7524 13076 7524 13077 7523 13077 7525 13077 7527 13078 7525 13078 7456 13078 7527 13079 7456 13079 7457 13079 7524 13080 7525 13080 7527 13080 7528 13081 7524 13081 7527 13081 7458 13082 7527 13082 7457 13082 7526 13083 7524 13083 7528 13083 7529 13084 7527 13084 7458 13084 7529 13085 7528 13085 7527 13085 7530 13086 7528 13086 7529 13086 7530 13087 7526 13087 7528 13087 7529 13088 7458 13088 7459 13088 7460 13089 7529 13089 7459 13089 7531 13090 7529 13090 7460 13090 7530 13091 7529 13091 7531 13091 7532 13092 7460 13092 7461 13092 7532 13093 7531 13093 7460 13093 7532 13094 7530 13094 7531 13094 7533 13095 7530 13095 7532 13095 7462 13096 7532 13096 7461 13096 7534 13097 7533 13097 7532 13097 7535 13098 7532 13098 7462 13098 7534 13099 7532 13099 7535 13099 7535 13100 7462 13100 7463 13100 7464 13101 7535 13101 7463 13101 7536 13102 7535 13102 7464 13102 7536 13103 7534 13103 7535 13103 7537 13104 7534 13104 7536 13104 7538 13105 7464 13105 7465 13105 7539 13106 7534 13106 7537 13106 7539 13107 7533 13107 7534 13107 7536 13108 7464 13108 7538 13108 7537 13109 7536 13109 7538 13109 7540 13110 7538 13110 7465 13110 7537 13111 7538 13111 7540 13111 7540 13112 7465 13112 7466 13112 7541 13113 7537 13113 7540 13113 7539 13114 7537 13114 7541 13114 7542 13115 7539 13115 7541 13115 7543 13116 7540 13116 7466 13116 7541 13117 7540 13117 7543 13117 7543 13118 7466 13118 7467 13118 7542 13119 7541 13119 7543 13119 7544 13120 7543 13120 7467 13120 7545 13121 7543 13121 7544 13121 7545 13122 7542 13122 7543 13122 7544 13123 7467 13123 7468 13123 7546 13124 7545 13124 7544 13124 7549 13125 7542 13125 7545 13125 7547 13126 7544 13126 7468 13126 7546 13127 7544 13127 7547 13127 7547 13128 7468 13128 7469 13128 7549 13129 7545 13129 7546 13129 7548 13130 7546 13130 7547 13130 7470 13131 7547 13131 7469 13131 7550 13132 7546 13132 7548 13132 7550 13133 7549 13133 7546 13133 7551 13134 7547 13134 7470 13134 7551 13135 7548 13135 7547 13135 7552 13136 7548 13136 7551 13136 7552 13137 7550 13137 7548 13137 7553 13138 7470 13138 7471 13138 7553 13139 7551 13139 7470 13139 7552 13140 7551 13140 7553 13140 7554 13141 7552 13141 7553 13141 7472 13142 7553 13142 7471 13142 7554 13143 7550 13143 7552 13143 7556 13144 7550 13144 7554 13144 7555 13145 7553 13145 7472 13145 7555 13146 7554 13146 7553 13146 7473 13147 7555 13147 7472 13147 7557 13148 7554 13148 7555 13148 7557 13149 7556 13149 7554 13149 7474 13150 7555 13150 7473 13150 7560 13151 7556 13151 7557 13151 7558 13152 7555 13152 7474 13152 7557 13153 7555 13153 7558 13153 7559 13154 7557 13154 7558 13154 7560 13155 7557 13155 7559 13155 7475 13156 7558 13156 7474 13156 7561 13157 7558 13157 7475 13157 7559 13158 7558 13158 7561 13158 7562 13159 7559 13159 7561 13159 7563 13160 7559 13160 7562 13160 7563 13161 7560 13161 7559 13161 7476 13162 7561 13162 7475 13162 7564 13163 7560 13163 7563 13163 7562 13164 7561 13164 7476 13164 7565 13165 7562 13165 7476 13165 7563 13166 7562 13166 7565 13166 7477 13167 7565 13167 7476 13167 7566 13168 7565 13168 7477 13168 7566 13169 7563 13169 7565 13169 7567 13170 7563 13170 7566 13170 7567 13171 7564 13171 7563 13171 7568 13172 7477 13172 7478 13172 7569 13173 7477 13173 7568 13173 7569 13174 7566 13174 7477 13174 7569 13175 7567 13175 7566 13175 7570 13176 7567 13176 7569 13176 7479 13177 7568 13177 7478 13177 7570 13178 7569 13178 7568 13178 7571 13179 7568 13179 7479 13179 7571 13180 7570 13180 7568 13180 7480 13181 7571 13181 7479 13181 7572 13182 7570 13182 7571 13182 7573 13183 7571 13183 7480 13183 7572 13184 7567 13184 7570 13184 7573 13185 7572 13185 7571 13185 7573 13186 7480 13186 7481 13186 7574 13187 7572 13187 7573 13187 7575 13188 7573 13188 7481 13188 7574 13189 7573 13189 7575 13189 7482 13190 7575 13190 7481 13190 7576 13191 7575 13191 7482 13191 7576 13192 7574 13192 7575 13192 7577 13193 7574 13193 7576 13193 7579 13194 7572 13194 7574 13194 7578 13195 7482 13195 7483 13195 7578 13196 7576 13196 7482 13196 7579 13197 7574 13197 7577 13197 7577 13198 7576 13198 7578 13198 7580 13199 7577 13199 7578 13199 7579 13200 7577 13200 7580 13200 7581 13201 7483 13201 7484 13201 7581 13202 7578 13202 7483 13202 7581 13203 7580 13203 7578 13203 7582 13204 7579 13204 7580 13204 7582 13205 7580 13205 7581 13205 7485 13206 7581 13206 7484 13206 7583 13207 7582 13207 7581 13207 7583 13208 7581 13208 7485 13208 7584 13209 7485 13209 7486 13209 7584 13210 7583 13210 7485 13210 7585 13211 7583 13211 7584 13211 7487 13212 7584 13212 7486 13212 7583 13213 7586 13213 7582 13213 7586 13214 7583 13214 7585 13214 7585 13215 7584 13215 7487 13215 7587 13216 7487 13216 7488 13216 7587 13217 7585 13217 7487 13217 7588 13218 7585 13218 7587 13218 7586 13219 7585 13219 7588 13219 7588 13220 7587 13220 7488 13220 7489 13221 7588 13221 7488 13221 7589 13222 7586 13222 7588 13222 7590 13223 7588 13223 7489 13223 7591 13224 7588 13224 7590 13224 7589 13225 7588 13225 7591 13225 7590 13226 7489 13226 7490 13226 7491 13227 7590 13227 7490 13227 7592 13228 7590 13228 7491 13228 7592 13229 7591 13229 7590 13229 7593 13230 7591 13230 7592 13230 7593 13231 7589 13231 7591 13231 7594 13232 7491 13232 7492 13232 7594 13233 7592 13233 7491 13233 7593 13234 7592 13234 7594 13234 7493 13235 7594 13235 7492 13235 7595 13236 7594 13236 7493 13236 7595 13237 7593 13237 7594 13237 7596 13238 7595 13238 7493 13238 7596 13239 7493 13239 7494 13239 7597 13240 7595 13240 7596 13240 7597 13241 7593 13241 7595 13241 7598 13242 7593 13242 7597 13242 7495 13243 7596 13243 7494 13243 7599 13244 7596 13244 7495 13244 7599 13245 7597 13245 7596 13245 7598 13246 7597 13246 7600 13246 7600 13247 7597 13247 7599 13247 7603 13248 7598 13248 7600 13248 7599 13249 7495 13249 7496 13249 7601 13250 7599 13250 7496 13250 7602 13251 7599 13251 7601 13251 7602 13252 7600 13252 7599 13252 7603 13253 7600 13253 7602 13253 7497 13254 7601 13254 7496 13254 7604 13255 7601 13255 7497 13255 7604 13256 7602 13256 7601 13256 7605 13257 7604 13257 7497 13257 7605 13258 7602 13258 7604 13258 7606 13259 7602 13259 7605 13259 7606 13260 7603 13260 7602 13260 7498 13261 7605 13261 7497 13261 7607 13262 7605 13262 7498 13262 7608 13263 7605 13263 7607 13263 7608 13264 7606 13264 7605 13264 7607 13265 7498 13265 7499 13265 7609 13266 7607 13266 7499 13266 7609 13267 7608 13267 7607 13267 7609 13268 7499 13268 7500 13268 7500 13269 7445 13269 7501 13269 7609 13270 7500 13270 7501 13270 7504 13271 7606 13271 7608 13271 7609 13272 7501 13272 7502 13272 7502 13273 7608 13273 7609 13273 7608 13274 7502 13274 7504 13274 6941 13275 7567 13275 7572 13275 6944 13276 6941 13276 7572 13276 6939 13277 7567 13277 6941 13277 6944 13278 7572 13278 7579 13278 6937 13279 7567 13279 6939 13279 6937 13280 7564 13280 7567 13280 6948 13281 6944 13281 7579 13281 6948 13282 7579 13282 7582 13282 6950 13283 6948 13283 7582 13283 6937 13284 7560 13284 7564 13284 6934 13285 7560 13285 6937 13285 6952 13286 6950 13286 7582 13286 6952 13287 7582 13287 7586 13287 6934 13288 7556 13288 7560 13288 6931 13289 7556 13289 6934 13289 6931 13290 7550 13290 7556 13290 6956 13291 6952 13291 7586 13291 7589 13292 6956 13292 7586 13292 6929 13293 7550 13293 6931 13293 6959 13294 6956 13294 7589 13294 6929 13295 7549 13295 7550 13295 6925 13296 7549 13296 6929 13296 7593 13297 6959 13297 7589 13297 6962 13298 6959 13298 7593 13298 6925 13299 7542 13299 7549 13299 6962 13300 7593 13300 7598 13300 6923 13301 7542 13301 6925 13301 7598 13302 6965 13302 6962 13302 7539 13303 7542 13303 6923 13303 7603 13304 6965 13304 7598 13304 6919 13305 7539 13305 6923 13305 7533 13306 7539 13306 6919 13306 7603 13307 6969 13307 6965 13307 6917 13308 7533 13308 6919 13308 7606 13309 6969 13309 7603 13309 6972 13310 6969 13310 7606 13310 7504 13311 6972 13311 7606 13311 6913 13312 7533 13312 6917 13312 7530 13313 7533 13313 6913 13313 7504 13314 6893 13314 6972 13314 7526 13315 7530 13315 6913 13315 7526 13316 6913 13316 6911 13316 7503 13317 6893 13317 7504 13317 7526 13318 6911 13318 6908 13318 7503 13319 6896 13319 6893 13319 7518 13320 7526 13320 6908 13320 7512 13321 6896 13321 7503 13321 7518 13322 6908 13322 6906 13322 7512 13323 6899 13323 6896 13323 7518 13324 6906 13324 6902 13324 7512 13325 6902 13325 6899 13325 7512 13326 7518 13326 6902 13326

+
+ + + +

7612 13327 7611 13327 7610 13327 7612 13328 7704 13328 7611 13328 7614 13329 7704 13329 7612 13329 7612 13330 7610 13330 7615 13330 7616 13331 7612 13331 7615 13331 7617 13332 7612 13332 7616 13332 7617 13333 7614 13333 7612 13333 7617 13334 7613 13334 7614 13334 7618 13335 7617 13335 7616 13335 7619 13336 7618 13336 7616 13336 7620 13337 7618 13337 7619 13337 7620 13338 7617 13338 7618 13338 7621 13339 7617 13339 7620 13339 7620 13340 7619 13340 7622 13340 7621 13341 7620 13341 7623 13341 7623 13342 7620 13342 7622 13342 7624 13343 7623 13343 7622 13343 7625 13344 7621 13344 7623 13344 7626 13345 7623 13345 7624 13345 7625 13346 7623 13346 7626 13346 7627 13347 7626 13347 7624 13347 7628 13348 7626 13348 7627 13348 7625 13349 7626 13349 7628 13349 7628 13350 7627 13350 7629 13350 7625 13351 7628 13351 7630 13351 7631 13352 7628 13352 7629 13352 7630 13353 7628 13353 7631 13353 7634 13354 7630 13354 7631 13354 7632 13355 7625 13355 7630 13355 7633 13356 7630 13356 7634 13356 7632 13357 7630 13357 7633 13357 7636 13358 7634 13358 7635 13358 7636 13359 7633 13359 7634 13359 7638 13360 7635 13360 7637 13360 7638 13361 7636 13361 7635 13361 7638 13362 7633 13362 7636 13362 7639 13363 7633 13363 7638 13363 7632 13364 7633 13364 7639 13364 7639 13365 7638 13365 7637 13365 7641 13366 7632 13366 7639 13366 7640 13367 7639 13367 7637 13367 7641 13368 7639 13368 7640 13368 7643 13369 7640 13369 7642 13369 7643 13370 7641 13370 7640 13370 7645 13371 7642 13371 7644 13371 7645 13372 7643 13372 7642 13372 7646 13373 7641 13373 7643 13373 7646 13374 7643 13374 7645 13374 7646 13375 7645 13375 7647 13375 7649 13376 7646 13376 7647 13376 7650 13377 7647 13377 7648 13377 7649 13378 7647 13378 7650 13378 7650 13379 7648 13379 7651 13379 7652 13380 7650 13380 7651 13380 7653 13381 7652 13381 7651 13381 7654 13382 7650 13382 7652 13382 7654 13383 7649 13383 7650 13383 7655 13384 7652 13384 7653 13384 7656 13385 7652 13385 7655 13385 7656 13386 7654 13386 7652 13386 7657 13387 7656 13387 7655 13387 7658 13388 7656 13388 7657 13388 7658 13389 7654 13389 7656 13389 7658 13390 7657 13390 7659 13390 7659 13391 7657 13391 7660 13391 7661 13392 7659 13392 7660 13392 7662 13393 7659 13393 7661 13393 7658 13394 7659 13394 7662 13394 7664 13395 7661 13395 7663 13395 7664 13396 7662 13396 7661 13396 7665 13397 7664 13397 7663 13397 7665 13398 7662 13398 7664 13398 7667 13399 7662 13399 7665 13399 7666 13400 7665 13400 7663 13400 7667 13401 7658 13401 7662 13401 7669 13402 7665 13402 7666 13402 7669 13403 7667 13403 7665 13403 7668 13404 7669 13404 7666 13404 7671 13405 7668 13405 7670 13405 7671 13406 7669 13406 7668 13406 7672 13407 7667 13407 7669 13407 7672 13408 7669 13408 7671 13408 7673 13409 7671 13409 7670 13409 7673 13410 7672 13410 7671 13410 7673 13411 7670 13411 7674 13411 7675 13412 7673 13412 7674 13412 7675 13413 7672 13413 7673 13413 7677 13414 7672 13414 7675 13414 7675 13415 7674 13415 7676 13415 7678 13416 7675 13416 7676 13416 7678 13417 7677 13417 7675 13417 7679 13418 7678 13418 7676 13418 7679 13419 7676 13419 7680 13419 7681 13420 7678 13420 7679 13420 7681 13421 7677 13421 7678 13421 7681 13422 7679 13422 7680 13422 7683 13423 7677 13423 7681 13423 7682 13424 7681 13424 7680 13424 7684 13425 7681 13425 7682 13425 7683 13426 7681 13426 7684 13426 7684 13427 7682 13427 7685 13427 7686 13428 7683 13428 7684 13428 7687 13429 7684 13429 7685 13429 7686 13430 7684 13430 7687 13430 7690 13431 7686 13431 7687 13431 7690 13432 7687 13432 7689 13432 7688 13433 7683 13433 7686 13433 7688 13434 7686 13434 7690 13434 7691 13435 7690 13435 7689 13435 7692 13436 7688 13436 7690 13436 7693 13437 7690 13437 7691 13437 7692 13438 7690 13438 7693 13438 7694 13439 7693 13439 7691 13439 7695 13440 7693 13440 7694 13440 7696 13441 7693 13441 7695 13441 7696 13442 7692 13442 7693 13442 7697 13443 7695 13443 7694 13443 7698 13444 7695 13444 7697 13444 7696 13445 7695 13445 7698 13445 7700 13446 7696 13446 7698 13446 7701 13447 7698 13447 7699 13447 7700 13448 7698 13448 7701 13448 7701 13449 7699 13449 7702 13449 7703 13450 7701 13450 7702 13450 7704 13451 7701 13451 7703 13451 7704 13452 7700 13452 7701 13452 7703 13453 7702 13453 7611 13453 7613 13454 7700 13454 7704 13454 7703 13455 7611 13455 7704 13455 7613 13456 7704 13456 7614 13456 7745 13457 7657 13457 7705 13457 7657 13458 7655 13458 7705 13458 7705 13459 7655 13459 7706 13459 7655 13460 7653 13460 7706 13460 7653 13461 7651 13461 7706 13461 7706 13462 7651 13462 7707 13462 7651 13463 7648 13463 7707 13463 7648 13464 7647 13464 7707 13464 7707 13465 7647 13465 7708 13465 7647 13466 7645 13466 7708 13466 7708 13467 7645 13467 7709 13467 7645 13468 7644 13468 7709 13468 7709 13469 7644 13469 7710 13469 7644 13470 7642 13470 7710 13470 7710 13471 7640 13471 7711 13471 7642 13472 7640 13472 7710 13472 7711 13473 7640 13473 7712 13473 7640 13474 7637 13474 7712 13474 7712 13475 7637 13475 7713 13475 7637 13476 7635 13476 7713 13476 7713 13477 7635 13477 7714 13477 7635 13478 7634 13478 7714 13478 7714 13479 7634 13479 7715 13479 7634 13480 7631 13480 7715 13480 7631 13481 7629 13481 7715 13481 7715 13482 7629 13482 7716 13482 7716 13483 7629 13483 7717 13483 7629 13484 7627 13484 7717 13484 7717 13485 7627 13485 7718 13485 7627 13486 7624 13486 7718 13486 7718 13487 7624 13487 7719 13487 7624 13488 7622 13488 7719 13488 7719 13489 7622 13489 7720 13489 7720 13490 7622 13490 7721 13490 7622 13491 7619 13491 7721 13491 7721 13492 7619 13492 7722 13492 7722 13493 7616 13493 7723 13493 7619 13494 7616 13494 7722 13494 7723 13495 7616 13495 7724 13495 7616 13496 7615 13496 7724 13496 7615 13497 7610 13497 7724 13497 7724 13498 7610 13498 7725 13498 7610 13499 7611 13499 7725 13499 7725 13500 7611 13500 7726 13500 7611 13501 7702 13501 7726 13501 7726 13502 7702 13502 7727 13502 7702 13503 7699 13503 7727 13503 7699 13504 7698 13504 7727 13504 7727 13505 7698 13505 7728 13505 7698 13506 7697 13506 7728 13506 7728 13507 7697 13507 7729 13507 7697 13508 7694 13508 7729 13508 7729 13509 7694 13509 7730 13509 7694 13510 7691 13510 7730 13510 7730 13511 7691 13511 7731 13511 7731 13512 7691 13512 7732 13512 7691 13513 7689 13513 7732 13513 7732 13514 7689 13514 7733 13514 7689 13515 7687 13515 7733 13515 7733 13516 7687 13516 7734 13516 7687 13517 7685 13517 7734 13517 7734 13518 7685 13518 7735 13518 7685 13519 7682 13519 7735 13519 7682 13520 7680 13520 7735 13520 7735 13521 7680 13521 7736 13521 7680 13522 7676 13522 7736 13522 7736 13523 7676 13523 7737 13523 7737 13524 7676 13524 7738 13524 7676 13525 7674 13525 7738 13525 7738 13526 7674 13526 7739 13526 7674 13527 7670 13527 7739 13527 7739 13528 7670 13528 7740 13528 7740 13529 7668 13529 7741 13529 7670 13530 7668 13530 7740 13530 7741 13531 7666 13531 7742 13531 7668 13532 7666 13532 7741 13532 7742 13533 7666 13533 7743 13533 7666 13534 7663 13534 7743 13534 7743 13535 7663 13535 7744 13535 7663 13536 7661 13536 7744 13536 7661 13537 7660 13537 7744 13537 7744 13538 7660 13538 7745 13538 7660 13539 7657 13539 7745 13539 7625 13540 8222 13540 7621 13540 7625 13541 8217 13541 8222 13541 7617 13542 7621 13542 8222 13542 7617 13543 8222 13543 8234 13543 7625 13544 8207 13544 8217 13544 7617 13545 8234 13545 8240 13545 7613 13546 7617 13546 8240 13546 7632 13547 8207 13547 7625 13547 7632 13548 8355 13548 8207 13548 7613 13549 8240 13549 8244 13549 7700 13550 7613 13550 8244 13550 7632 13551 8346 13551 8355 13551 7641 13552 8346 13552 7632 13552 7700 13553 8244 13553 8254 13553 7696 13554 7700 13554 8254 13554 7696 13555 8254 13555 8261 13555 7641 13556 8341 13556 8346 13556 7692 13557 7696 13557 8261 13557 7646 13558 8341 13558 7641 13558 8328 13559 8341 13559 7646 13559 8272 13560 7692 13560 8261 13560 8272 13561 7688 13561 7692 13561 8328 13562 7646 13562 7649 13562 8272 13563 7683 13563 7688 13563 8276 13564 7683 13564 8272 13564 8328 13565 7649 13565 7654 13565 8324 13566 8328 13566 7654 13566 8320 13567 8324 13567 7654 13567 8320 13568 7654 13568 7658 13568 8287 13569 7683 13569 8276 13569 8287 13570 7677 13570 7683 13570 8310 13571 8320 13571 7658 13571 8303 13572 8310 13572 7658 13572 8295 13573 7677 13573 8287 13573 8295 13574 7672 13574 7677 13574 8303 13575 7658 13575 7667 13575 8295 13576 7667 13576 7672 13576 8303 13577 7667 13577 8295 13577 7747 13578 7798 13578 7746 13578 7746 13579 7745 13579 7705 13579 7748 13580 7705 13580 7706 13580 7748 13581 7746 13581 7705 13581 7747 13582 7746 13582 7748 13582 7749 13583 7748 13583 7706 13583 7747 13584 7748 13584 7749 13584 7750 13585 7706 13585 7707 13585 7750 13586 7749 13586 7706 13586 7751 13587 7749 13587 7750 13587 7751 13588 7747 13588 7749 13588 7752 13589 7750 13589 7707 13589 7751 13590 7750 13590 7752 13590 7752 13591 7707 13591 7708 13591 7753 13592 7751 13592 7752 13592 7753 13593 7752 13593 7708 13593 7709 13594 7753 13594 7708 13594 7755 13595 7753 13595 7709 13595 7755 13596 7754 13596 7753 13596 7710 13597 7755 13597 7709 13597 7756 13598 7754 13598 7755 13598 7711 13599 7755 13599 7710 13599 7757 13600 7754 13600 7756 13600 7711 13601 7756 13601 7755 13601 7758 13602 7756 13602 7711 13602 7757 13603 7756 13603 7758 13603 7759 13604 7711 13604 7712 13604 7758 13605 7711 13605 7759 13605 7760 13606 7759 13606 7712 13606 7758 13607 7759 13607 7760 13607 7761 13608 7757 13608 7758 13608 7713 13609 7760 13609 7712 13609 7761 13610 7758 13610 7760 13610 7762 13611 7713 13611 7714 13611 7762 13612 7760 13612 7713 13612 7762 13613 7761 13613 7760 13613 7763 13614 7761 13614 7762 13614 7764 13615 7714 13615 7715 13615 7764 13616 7762 13616 7714 13616 7764 13617 7763 13617 7762 13617 7765 13618 7764 13618 7715 13618 7716 13619 7765 13619 7715 13619 7765 13620 7763 13620 7764 13620 7766 13621 7763 13621 7765 13621 7766 13622 7716 13622 7717 13622 7766 13623 7765 13623 7716 13623 7718 13624 7766 13624 7717 13624 7767 13625 7718 13625 7719 13625 7767 13626 7766 13626 7718 13626 7768 13627 7766 13627 7767 13627 7767 13628 7719 13628 7720 13628 7721 13629 7767 13629 7720 13629 7769 13630 7767 13630 7721 13630 7770 13631 7767 13631 7769 13631 7768 13632 7767 13632 7770 13632 7722 13633 7769 13633 7721 13633 7771 13634 7769 13634 7722 13634 7771 13635 7770 13635 7769 13635 7723 13636 7771 13636 7722 13636 7724 13637 7771 13637 7723 13637 7772 13638 7771 13638 7724 13638 7772 13639 7770 13639 7771 13639 7773 13640 7770 13640 7772 13640 7774 13641 7772 13641 7724 13641 7725 13642 7774 13642 7724 13642 7774 13643 7773 13643 7772 13643 7775 13644 7774 13644 7725 13644 7775 13645 7725 13645 7726 13645 7776 13646 7774 13646 7775 13646 7776 13647 7773 13647 7774 13647 7776 13648 7775 13648 7726 13648 7777 13649 7773 13649 7776 13649 7778 13650 7726 13650 7727 13650 7778 13651 7776 13651 7726 13651 7777 13652 7776 13652 7778 13652 7779 13653 7777 13653 7778 13653 7778 13654 7727 13654 7728 13654 7779 13655 7778 13655 7728 13655 7780 13656 7777 13656 7779 13656 7779 13657 7728 13657 7729 13657 7781 13658 7779 13658 7729 13658 7780 13659 7779 13659 7781 13659 7781 13660 7729 13660 7730 13660 7782 13661 7781 13661 7730 13661 7782 13662 7780 13662 7781 13662 7731 13663 7782 13663 7730 13663 7783 13664 7731 13664 7732 13664 7783 13665 7782 13665 7731 13665 7783 13666 7732 13666 7733 13666 7784 13667 7782 13667 7783 13667 7785 13668 7733 13668 7734 13668 7785 13669 7783 13669 7733 13669 7786 13670 7783 13670 7785 13670 7784 13671 7783 13671 7786 13671 7735 13672 7785 13672 7734 13672 7787 13673 7785 13673 7735 13673 7786 13674 7785 13674 7787 13674 7788 13675 7786 13675 7787 13675 7736 13676 7787 13676 7735 13676 7789 13677 7788 13677 7787 13677 7789 13678 7787 13678 7736 13678 7788 13679 7789 13679 7790 13679 7737 13680 7789 13680 7736 13680 7790 13681 7789 13681 7737 13681 7790 13682 7737 13682 7738 13682 7791 13683 7790 13683 7738 13683 7791 13684 7788 13684 7790 13684 7792 13685 7791 13685 7738 13685 7739 13686 7792 13686 7738 13686 7740 13687 7792 13687 7739 13687 7793 13688 7792 13688 7740 13688 7794 13689 7791 13689 7792 13689 7793 13690 7794 13690 7792 13690 7741 13691 7793 13691 7740 13691 7795 13692 7741 13692 7742 13692 7795 13693 7793 13693 7741 13693 7795 13694 7794 13694 7793 13694 7795 13695 7742 13695 7743 13695 7796 13696 7794 13696 7795 13696 7797 13697 7795 13697 7743 13697 7796 13698 7795 13698 7797 13698 7744 13699 7797 13699 7743 13699 7799 13700 7797 13700 7744 13700 7799 13701 7796 13701 7797 13701 7799 13702 7798 13702 7796 13702 7745 13703 7799 13703 7744 13703 7798 13704 7799 13704 7800 13704 7800 13705 7799 13705 7745 13705 7800 13706 7745 13706 7746 13706 7798 13707 7800 13707 7746 13707 7782 13708 7981 13708 7780 13708 7780 13709 7981 13709 7988 13709 7782 13710 7976 13710 7981 13710 7780 13711 7988 13711 7995 13711 7784 13712 7976 13712 7782 13712 7777 13713 7780 13713 7995 13713 7784 13714 7967 13714 7976 13714 7786 13715 7967 13715 7784 13715 7777 13716 7995 13716 8002 13716 7788 13717 7967 13717 7786 13717 7773 13718 7777 13718 8002 13718 7788 13719 7958 13719 7967 13719 7773 13720 8002 13720 8012 13720 7791 13721 7958 13721 7788 13721 7770 13722 7773 13722 8012 13722 7791 13723 7953 13723 7958 13723 7794 13724 7953 13724 7791 13724 7794 13725 7946 13725 7953 13725 7770 13726 8012 13726 8017 13726 7794 13727 7941 13727 7946 13727 7768 13728 7770 13728 8017 13728 8024 13729 7768 13729 8017 13729 8024 13730 7766 13730 7768 13730 7941 13731 7794 13731 7796 13731 7936 13732 7941 13732 7796 13732 7936 13733 7796 13733 7798 13733 8036 13734 7766 13734 8024 13734 8036 13735 7763 13735 7766 13735 8036 13736 7761 13736 7763 13736 7923 13737 7936 13737 7798 13737 7889 13738 7761 13738 8036 13738 7923 13739 7798 13739 7747 13739 7891 13740 7761 13740 7889 13740 7891 13741 7757 13741 7761 13741 7897 13742 7757 13742 7891 13742 7916 13743 7923 13743 7747 13743 7897 13744 7754 13744 7757 13744 7916 13745 7747 13745 7751 13745 7911 13746 7916 13746 7751 13746 7903 13747 7754 13747 7897 13747 7903 13748 7753 13748 7754 13748 7911 13749 7751 13749 7753 13749 7911 13750 7753 13750 7903 13750 7801 13751 7802 13751 7803 13751 7804 13752 7801 13752 7803 13752 7804 13753 7803 13753 7805 13753 7806 13754 7804 13754 7805 13754 7807 13755 7806 13755 7805 13755 7807 13756 7805 13756 7808 13756 7807 13757 7808 13757 7809 13757 7810 13758 7807 13758 7809 13758 7810 13759 7809 13759 7811 13759 7812 13760 7810 13760 7811 13760 7812 13761 7811 13761 7813 13761 7814 13762 7812 13762 7813 13762 7814 13763 7813 13763 7815 13763 7816 13764 7814 13764 7815 13764 7816 13765 7815 13765 7817 13765 7818 13766 7816 13766 7817 13766 7819 13767 7818 13767 7817 13767 7819 13768 7817 13768 7820 13768 7821 13769 7819 13769 7820 13769 7821 13770 7820 13770 7822 13770 7823 13771 7821 13771 7822 13771 7823 13772 7822 13772 7824 13772 7823 13773 7824 13773 7825 13773 7826 13774 7823 13774 7825 13774 7826 13775 7825 13775 7827 13775 7828 13776 7826 13776 7827 13776 7828 13777 7827 13777 7829 13777 7830 13778 7828 13778 7829 13778 7830 13779 7829 13779 7831 13779 7832 13780 7830 13780 7831 13780 7832 13781 7831 13781 7833 13781 7834 13782 7832 13782 7833 13782 7834 13783 7833 13783 7835 13783 7836 13784 7834 13784 7835 13784 7836 13785 7835 13785 7837 13785 7838 13786 7836 13786 7837 13786 7838 13787 7837 13787 7839 13787 7840 13788 7838 13788 7839 13788 7840 13789 7839 13789 7841 13789 7842 13790 7840 13790 7841 13790 7843 13791 7841 13791 7844 13791 7843 13792 7842 13792 7841 13792 7843 13793 7844 13793 7802 13793 7801 13794 7843 13794 7802 13794 7847 13795 7845 13795 7846 13795 7847 13796 7846 13796 7848 13796 7849 13797 7847 13797 7848 13797 7849 13798 7848 13798 7850 13798 7851 13799 7849 13799 7850 13799 7851 13800 7850 13800 7852 13800 7853 13801 7851 13801 7852 13801 7853 13802 7852 13802 7854 13802 7855 13803 7853 13803 7854 13803 7855 13804 7854 13804 7856 13804 7857 13805 7855 13805 7856 13805 7857 13806 7856 13806 7858 13806 7859 13807 7857 13807 7858 13807 7859 13808 7858 13808 7860 13808 7861 13809 7859 13809 7860 13809 7861 13810 7860 13810 7862 13810 7863 13811 7861 13811 7862 13811 7864 13812 7863 13812 7862 13812 7864 13813 7862 13813 7865 13813 7866 13814 7864 13814 7865 13814 7866 13815 7865 13815 7867 13815 7868 13816 7866 13816 7867 13816 7868 13817 7867 13817 7869 13817 7870 13818 7868 13818 7869 13818 7870 13819 7869 13819 7871 13819 7872 13820 7870 13820 7871 13820 7872 13821 7871 13821 7873 13821 7874 13822 7872 13822 7873 13822 7874 13823 7873 13823 7875 13823 7876 13824 7874 13824 7875 13824 7876 13825 7875 13825 7877 13825 7878 13826 7876 13826 7877 13826 7878 13827 7877 13827 7879 13827 7880 13828 7878 13828 7879 13828 7880 13829 7879 13829 7881 13829 7882 13830 7880 13830 7881 13830 7883 13831 7882 13831 7881 13831 7883 13832 7881 13832 7884 13832 7885 13833 7883 13833 7884 13833 7885 13834 7884 13834 7886 13834 7845 13835 7886 13835 7846 13835 7845 13836 7885 13836 7886 13836 7890 13837 7888 13837 7887 13837 7890 13838 7889 13838 7888 13838 7890 13839 7887 13839 7892 13839 7893 13840 7890 13840 7892 13840 7893 13841 7892 13841 7894 13841 7891 13842 7889 13842 7890 13842 7895 13843 7890 13843 7893 13843 7891 13844 7890 13844 7895 13844 7896 13845 7893 13845 7894 13845 7897 13846 7891 13846 7895 13846 7898 13847 7893 13847 7896 13847 7895 13848 7893 13848 7898 13848 7900 13849 7897 13849 7895 13849 7899 13850 7898 13850 7896 13850 7899 13851 7895 13851 7898 13851 7900 13852 7895 13852 7899 13852 7899 13853 7896 13853 7901 13853 7903 13854 7897 13854 7900 13854 7904 13855 7899 13855 7901 13855 7900 13856 7899 13856 7904 13856 7904 13857 7901 13857 7902 13857 7903 13858 7900 13858 7904 13858 7906 13859 7903 13859 7904 13859 7904 13860 7902 13860 7905 13860 7908 13861 7905 13861 7907 13861 7908 13862 7904 13862 7905 13862 7906 13863 7904 13863 7908 13863 7911 13864 7903 13864 7906 13864 7910 13865 7907 13865 7909 13865 7910 13866 7908 13866 7907 13866 7912 13867 7908 13867 7910 13867 7912 13868 7906 13868 7908 13868 7911 13869 7906 13869 7912 13869 7910 13870 7909 13870 7913 13870 7914 13871 7910 13871 7913 13871 7914 13872 7912 13872 7910 13872 7916 13873 7911 13873 7912 13873 7916 13874 7912 13874 7914 13874 7915 13875 7914 13875 7913 13875 7917 13876 7916 13876 7914 13876 7917 13877 7914 13877 7915 13877 7919 13878 7915 13878 7918 13878 7919 13879 7917 13879 7915 13879 7920 13880 7917 13880 7919 13880 7920 13881 7916 13881 7917 13881 7921 13882 7919 13882 7918 13882 7922 13883 7919 13883 7921 13883 7922 13884 7920 13884 7919 13884 7923 13885 7920 13885 7922 13885 7923 13886 7916 13886 7920 13886 7924 13887 7922 13887 7921 13887 7923 13888 7922 13888 7924 13888 7924 13889 7921 13889 7925 13889 7926 13890 7924 13890 7925 13890 7928 13891 7924 13891 7926 13891 7928 13892 7923 13892 7924 13892 7927 13893 7926 13893 7925 13893 7929 13894 7926 13894 7927 13894 7931 13895 7923 13895 7928 13895 7929 13896 7928 13896 7926 13896 7930 13897 7929 13897 7927 13897 7931 13898 7928 13898 7929 13898 7936 13899 7923 13899 7931 13899 7933 13900 7930 13900 7932 13900 7933 13901 7929 13901 7930 13901 7933 13902 7931 13902 7929 13902 7934 13903 7931 13903 7933 13903 7936 13904 7931 13904 7934 13904 7937 13905 7932 13905 7935 13905 7937 13906 7933 13906 7932 13906 7937 13907 7934 13907 7933 13907 7937 13908 7935 13908 7938 13908 7939 13909 7937 13909 7938 13909 7939 13910 7934 13910 7937 13910 7940 13911 7934 13911 7939 13911 7940 13912 7936 13912 7934 13912 7941 13913 7936 13913 7940 13913 7939 13914 7938 13914 7942 13914 7943 13915 7939 13915 7942 13915 7943 13916 7940 13916 7939 13916 7941 13917 7940 13917 7943 13917 7943 13918 7942 13918 7944 13918 7945 13919 7941 13919 7943 13919 7946 13920 7941 13920 7945 13920 7947 13921 7943 13921 7944 13921 7945 13922 7943 13922 7947 13922 7947 13923 7944 13923 7948 13923 7949 13924 7947 13924 7948 13924 7950 13925 7945 13925 7947 13925 7946 13926 7945 13926 7950 13926 7951 13927 7947 13927 7949 13927 7950 13928 7947 13928 7951 13928 7951 13929 7949 13929 7952 13929 7953 13930 7946 13930 7950 13930 7954 13931 7951 13931 7952 13931 7954 13932 7950 13932 7951 13932 7953 13933 7950 13933 7954 13933 7956 13934 7952 13934 7955 13934 7956 13935 7954 13935 7952 13935 7956 13936 7955 13936 7957 13936 7960 13937 7956 13937 7957 13937 7958 13938 7953 13938 7954 13938 7959 13939 7956 13939 7960 13939 7959 13940 7954 13940 7956 13940 7959 13941 7958 13941 7954 13941 7961 13942 7959 13942 7960 13942 7963 13943 7959 13943 7961 13943 7961 13944 7960 13944 7962 13944 7963 13945 7958 13945 7959 13945 7964 13946 7961 13946 7962 13946 7965 13947 7961 13947 7964 13947 7965 13948 7963 13948 7961 13948 7967 13949 7963 13949 7965 13949 7967 13950 7958 13950 7963 13950 7966 13951 7964 13951 7962 13951 7966 13952 7965 13952 7964 13952 7968 13953 7965 13953 7966 13953 7967 13954 7965 13954 7968 13954 7969 13955 7968 13955 7966 13955 7969 13956 7966 13956 7970 13956 7971 13957 7969 13957 7970 13957 7971 13958 7968 13958 7969 13958 7973 13959 7968 13959 7971 13959 7972 13960 7971 13960 7970 13960 7973 13961 7967 13961 7968 13961 7974 13962 7971 13962 7972 13962 7973 13963 7971 13963 7974 13963 7974 13964 7972 13964 7975 13964 7977 13965 7974 13965 7975 13965 7976 13966 7967 13966 7973 13966 7977 13967 7973 13967 7974 13967 7976 13968 7973 13968 7977 13968 7977 13969 7975 13969 7978 13969 7980 13970 7977 13970 7978 13970 7979 13971 7977 13971 7980 13971 7981 13972 7977 13972 7979 13972 7981 13973 7976 13973 7977 13973 7983 13974 7980 13974 7982 13974 7983 13975 7979 13975 7980 13975 7983 13976 7981 13976 7979 13976 7984 13977 7983 13977 7982 13977 7984 13978 7982 13978 7985 13978 7986 13979 7983 13979 7984 13979 7986 13980 7981 13980 7983 13980 7986 13981 7984 13981 7985 13981 7988 13982 7981 13982 7986 13982 7989 13983 7985 13983 7987 13983 7989 13984 7986 13984 7985 13984 7990 13985 7986 13985 7989 13985 7990 13986 7988 13986 7986 13986 7991 13987 7989 13987 7987 13987 7993 13988 7988 13988 7990 13988 7991 13989 7990 13989 7989 13989 7992 13990 7990 13990 7991 13990 7993 13991 7990 13991 7992 13991 7995 13992 7988 13992 7993 13992 7992 13993 7991 13993 7994 13993 7996 13994 7992 13994 7994 13994 7993 13995 7992 13995 7996 13995 7997 13996 7996 13996 7994 13996 7998 13997 7996 13997 7997 13997 7999 13998 7996 13998 7998 13998 7999 13999 7993 13999 7996 13999 8000 14000 7998 14000 7997 14000 7995 14001 7993 14001 7999 14001 8002 14002 7995 14002 7999 14002 8003 14003 7999 14003 7998 14003 8003 14004 8000 14004 8001 14004 8003 14005 7998 14005 8000 14005 8004 14006 7999 14006 8003 14006 8006 14007 8003 14007 8001 14007 8002 14008 7999 14008 8004 14008 8006 14009 8004 14009 8003 14009 8005 14010 8006 14010 8001 14010 8007 14011 8004 14011 8006 14011 8002 14012 8004 14012 8007 14012 8008 14013 8006 14013 8005 14013 8008 14014 8007 14014 8006 14014 8009 14015 8008 14015 8005 14015 8011 14016 8009 14016 8010 14016 8011 14017 8008 14017 8009 14017 8012 14018 8002 14018 8007 14018 8011 14019 8007 14019 8008 14019 8012 14020 8007 14020 8011 14020 8014 14021 8010 14021 8013 14021 8014 14022 8011 14022 8010 14022 8012 14023 8011 14023 8014 14023 8015 14024 8014 14024 8013 14024 8017 14025 8012 14025 8014 14025 8018 14026 8014 14026 8015 14026 8017 14027 8014 14027 8018 14027 8018 14028 8015 14028 8016 14028 8020 14029 8017 14029 8018 14029 8021 14030 8016 14030 8019 14030 8021 14031 8018 14031 8016 14031 8020 14032 8018 14032 8021 14032 8022 14033 8021 14033 8019 14033 8020 14034 8021 14034 8022 14034 8023 14035 8022 14035 8019 14035 8025 14036 8022 14036 8023 14036 8024 14037 8017 14037 8020 14037 8025 14038 8020 14038 8022 14038 8027 14039 8020 14039 8025 14039 8025 14040 8023 14040 8026 14040 8024 14041 8020 14041 8027 14041 8028 14042 8025 14042 8026 14042 8028 14043 8027 14043 8025 14043 8028 14044 8026 14044 8029 14044 8030 14045 8028 14045 8029 14045 8030 14046 8027 14046 8028 14046 8033 14047 8027 14047 8030 14047 8032 14048 8027 14048 8033 14048 8031 14049 8030 14049 8029 14049 8033 14050 8030 14050 8031 14050 8032 14051 8024 14051 8027 14051 8032 14052 8033 14052 8034 14052 8035 14053 8033 14053 8031 14053 8034 14054 8033 14054 8035 14054 8036 14055 8024 14055 8032 14055 8036 14056 8032 14056 8034 14056 8037 14057 8034 14057 8035 14057 8037 14058 8035 14058 8038 14058 8040 14059 8037 14059 8038 14059 8039 14060 8036 14060 8034 14060 8040 14061 8034 14061 8037 14061 8039 14062 8034 14062 8040 14062 8041 14063 8040 14063 8038 14063 8041 14064 7887 14064 7888 14064 8040 14065 8041 14065 7888 14065 7889 14066 8036 14066 8039 14066 8040 14067 7888 14067 7889 14067 8039 14068 8040 14068 7889 14068 7887 14069 8042 14069 8043 14069 7887 14070 8043 14070 8044 14070 7892 14071 7887 14071 8044 14071 7892 14072 8044 14072 8045 14072 7894 14073 7892 14073 8045 14073 7894 14074 8045 14074 8046 14074 7896 14075 7894 14075 8046 14075 7896 14076 8046 14076 8047 14076 7901 14077 8047 14077 8048 14077 7901 14078 7896 14078 8047 14078 7902 14079 7901 14079 8048 14079 7902 14080 8048 14080 8049 14080 7905 14081 8049 14081 8050 14081 7905 14082 7902 14082 8049 14082 7907 14083 7905 14083 8050 14083 7907 14084 8050 14084 8051 14084 7909 14085 7907 14085 8051 14085 7909 14086 8051 14086 8052 14086 7913 14087 7909 14087 8052 14087 7913 14088 8052 14088 8053 14088 7915 14089 8053 14089 8054 14089 7915 14090 7913 14090 8053 14090 7918 14091 8054 14091 8055 14091 7918 14092 7915 14092 8054 14092 7918 14093 8055 14093 8056 14093 7921 14094 7918 14094 8056 14094 7921 14095 8056 14095 8057 14095 7925 14096 7921 14096 8057 14096 7925 14097 8057 14097 8058 14097 7927 14098 7925 14098 8058 14098 7927 14099 8058 14099 8059 14099 7930 14100 7927 14100 8059 14100 7930 14101 8059 14101 8060 14101 7932 14102 7930 14102 8060 14102 7932 14103 8060 14103 8061 14103 7935 14104 7932 14104 8061 14104 7935 14105 8061 14105 8062 14105 7938 14106 7935 14106 8062 14106 7938 14107 8062 14107 8063 14107 7942 14108 7938 14108 8063 14108 7942 14109 8063 14109 8064 14109 7944 14110 7942 14110 8064 14110 7944 14111 8064 14111 8065 14111 7948 14112 7944 14112 8065 14112 7948 14113 8065 14113 8066 14113 7949 14114 7948 14114 8066 14114 7949 14115 8066 14115 8067 14115 7952 14116 7949 14116 8067 14116 7952 14117 8067 14117 8068 14117 7955 14118 7952 14118 8068 14118 7955 14119 8068 14119 8069 14119 7957 14120 7955 14120 8069 14120 7957 14121 8069 14121 8070 14121 7960 14122 7957 14122 8070 14122 7962 14123 8070 14123 8071 14123 7962 14124 7960 14124 8070 14124 7962 14125 8071 14125 8072 14125 7966 14126 7962 14126 8072 14126 7966 14127 8072 14127 8073 14127 7970 14128 7966 14128 8073 14128 7972 14129 7970 14129 8073 14129 7972 14130 8073 14130 8074 14130 7972 14131 8074 14131 8075 14131 7975 14132 7972 14132 8075 14132 7978 14133 7975 14133 8075 14133 7978 14134 8075 14134 8076 14134 7980 14135 8076 14135 8139 14135 7980 14136 7978 14136 8076 14136 7982 14137 8139 14137 8077 14137 7982 14138 7980 14138 8139 14138 7985 14139 8077 14139 8078 14139 7985 14140 7982 14140 8077 14140 7987 14141 8078 14141 8079 14141 7987 14142 7985 14142 8078 14142 7987 14143 8079 14143 8080 14143 7991 14144 7987 14144 8080 14144 7994 14145 7991 14145 8080 14145 7994 14146 8080 14146 8081 14146 7997 14147 7994 14147 8081 14147 7997 14148 8081 14148 8082 14148 8000 14149 7997 14149 8082 14149 8000 14150 8082 14150 8083 14150 8001 14151 8000 14151 8083 14151 8001 14152 8083 14152 8084 14152 8005 14153 8084 14153 8085 14153 8005 14154 8001 14154 8084 14154 8009 14155 8005 14155 8085 14155 8010 14156 8085 14156 8086 14156 8010 14157 8009 14157 8085 14157 8010 14158 8086 14158 8087 14158 8013 14159 8010 14159 8087 14159 8015 14160 8087 14160 8088 14160 8015 14161 8013 14161 8087 14161 8016 14162 8015 14162 8088 14162 8019 14163 8088 14163 8089 14163 8019 14164 8016 14164 8088 14164 8019 14165 8089 14165 8090 14165 8023 14166 8019 14166 8090 14166 8023 14167 8090 14167 8091 14167 8026 14168 8023 14168 8091 14168 8026 14169 8091 14169 8092 14169 8029 14170 8026 14170 8092 14170 8029 14171 8092 14171 8093 14171 8031 14172 8029 14172 8093 14172 8035 14173 8093 14173 8094 14173 8035 14174 8031 14174 8093 14174 8035 14175 8094 14175 8095 14175 8038 14176 8095 14176 8096 14176 8038 14177 8035 14177 8095 14177 8041 14178 8096 14178 8042 14178 8041 14179 8038 14179 8096 14179 7887 14180 8041 14180 8042 14180 8098 14181 8042 14181 8096 14181 8099 14182 8200 14182 8097 14182 8098 14183 8097 14183 8042 14183 8100 14184 8099 14184 8097 14184 8100 14185 8097 14185 8098 14185 8095 14186 8098 14186 8096 14186 8101 14187 8098 14187 8095 14187 8101 14188 8100 14188 8098 14188 8101 14189 8095 14189 8094 14189 8102 14190 8099 14190 8100 14190 8103 14191 8100 14191 8101 14191 8102 14192 8100 14192 8103 14192 8103 14193 8101 14193 8094 14193 8104 14194 8094 14194 8093 14194 8104 14195 8103 14195 8094 14195 8105 14196 8103 14196 8104 14196 8102 14197 8103 14197 8105 14197 8092 14198 8104 14198 8093 14198 8106 14199 8104 14199 8092 14199 8106 14200 8105 14200 8104 14200 8107 14201 8092 14201 8091 14201 8107 14202 8106 14202 8092 14202 8108 14203 8102 14203 8105 14203 8108 14204 8105 14204 8106 14204 8109 14205 8106 14205 8107 14205 8110 14206 8107 14206 8091 14206 8110 14207 8091 14207 8090 14207 8109 14208 8108 14208 8106 14208 8109 14209 8107 14209 8110 14209 8111 14210 8108 14210 8109 14210 8112 14211 8109 14211 8110 14211 8089 14212 8110 14212 8090 14212 8113 14213 8110 14213 8089 14213 8112 14214 8110 14214 8113 14214 8111 14215 8109 14215 8112 14215 8114 14216 8112 14216 8113 14216 8113 14217 8089 14217 8088 14217 8115 14218 8113 14218 8088 14218 8111 14219 8112 14219 8114 14219 8115 14220 8114 14220 8113 14220 8115 14221 8088 14221 8087 14221 8116 14222 8115 14222 8087 14222 8116 14223 8114 14223 8115 14223 8117 14224 8114 14224 8116 14224 8117 14225 8111 14225 8114 14225 8118 14226 8087 14226 8086 14226 8118 14227 8116 14227 8087 14227 8119 14228 8116 14228 8118 14228 8117 14229 8116 14229 8119 14229 8120 14230 8118 14230 8086 14230 8120 14231 8119 14231 8118 14231 8120 14232 8086 14232 8085 14232 8121 14233 8117 14233 8119 14233 8122 14234 8120 14234 8085 14234 8119 14235 8120 14235 8122 14235 8084 14236 8122 14236 8085 14236 8121 14237 8119 14237 8122 14237 8123 14238 8122 14238 8084 14238 8126 14239 8117 14239 8121 14239 8123 14240 8121 14240 8122 14240 8124 14241 8121 14241 8123 14241 8123 14242 8084 14242 8083 14242 8125 14243 8123 14243 8083 14243 8126 14244 8121 14244 8124 14244 8124 14245 8123 14245 8125 14245 8125 14246 8083 14246 8082 14246 8127 14247 8126 14247 8124 14247 8128 14248 8125 14248 8082 14248 8128 14249 8124 14249 8125 14249 8127 14250 8124 14250 8128 14250 8081 14251 8128 14251 8082 14251 8129 14252 8126 14252 8127 14252 8127 14253 8128 14253 8130 14253 8131 14254 8128 14254 8081 14254 8130 14255 8128 14255 8131 14255 8080 14256 8131 14256 8081 14256 8129 14257 8127 14257 8130 14257 8132 14258 8131 14258 8080 14258 8132 14259 8130 14259 8131 14259 8129 14260 8130 14260 8132 14260 8133 14261 8080 14261 8079 14261 8133 14262 8132 14262 8080 14262 8078 14263 8133 14263 8079 14263 8134 14264 8132 14264 8133 14264 8134 14265 8129 14265 8132 14265 8135 14266 8133 14266 8078 14266 8134 14267 8133 14267 8135 14267 8135 14268 8078 14268 8077 14268 8136 14269 8129 14269 8134 14269 8137 14270 8134 14270 8135 14270 8137 14271 8135 14271 8077 14271 8138 14272 8136 14272 8134 14272 8138 14273 8134 14273 8137 14273 8139 14274 8137 14274 8077 14274 8140 14275 8138 14275 8137 14275 8141 14276 8139 14276 8076 14276 8141 14277 8137 14277 8139 14277 8142 14278 8136 14278 8138 14278 8140 14279 8137 14279 8141 14279 8142 14280 8138 14280 8140 14280 8075 14281 8141 14281 8076 14281 8143 14282 8140 14282 8141 14282 8143 14283 8142 14283 8140 14283 8143 14284 8141 14284 8075 14284 8144 14285 8143 14285 8075 14285 8144 14286 8075 14286 8074 14286 8145 14287 8143 14287 8144 14287 8146 14288 8143 14288 8145 14288 8147 14289 8144 14289 8074 14289 8146 14290 8142 14290 8143 14290 8145 14291 8144 14291 8147 14291 8147 14292 8074 14292 8073 14292 8149 14293 8146 14293 8145 14293 8148 14294 8147 14294 8073 14294 8148 14295 8145 14295 8147 14295 8149 14296 8145 14296 8148 14296 8148 14297 8073 14297 8072 14297 8150 14298 8072 14298 8071 14298 8150 14299 8148 14299 8072 14299 8151 14300 8148 14300 8150 14300 8151 14301 8149 14301 8148 14301 8152 14302 8071 14302 8070 14302 8152 14303 8150 14303 8071 14303 8151 14304 8150 14304 8152 14304 8153 14305 8149 14305 8151 14305 8154 14306 8151 14306 8152 14306 8155 14307 8149 14307 8153 14307 8153 14308 8151 14308 8154 14308 8154 14309 8152 14309 8070 14309 8154 14310 8070 14310 8069 14310 8155 14311 8153 14311 8154 14311 8068 14312 8154 14312 8069 14312 8156 14313 8154 14313 8068 14313 8155 14314 8154 14314 8156 14314 8158 14315 8155 14315 8156 14315 8157 14316 8068 14316 8067 14316 8157 14317 8156 14317 8068 14317 8158 14318 8156 14318 8157 14318 8066 14319 8157 14319 8067 14319 8160 14320 8158 14320 8157 14320 8159 14321 8155 14321 8158 14321 8160 14322 8157 14322 8066 14322 8161 14323 8158 14323 8160 14323 8162 14324 8160 14324 8066 14324 8159 14325 8158 14325 8161 14325 8161 14326 8160 14326 8162 14326 8065 14327 8162 14327 8066 14327 8064 14328 8162 14328 8065 14328 8163 14329 8159 14329 8161 14329 8164 14330 8162 14330 8064 14330 8164 14331 8161 14331 8162 14331 8163 14332 8161 14332 8164 14332 8063 14333 8164 14333 8064 14333 8165 14334 8164 14334 8063 14334 8165 14335 8163 14335 8164 14335 8166 14336 8163 14336 8165 14336 8167 14337 8165 14337 8063 14337 8167 14338 8063 14338 8062 14338 8167 14339 8166 14339 8165 14339 8168 14340 8062 14340 8061 14340 8168 14341 8167 14341 8062 14341 8169 14342 8166 14342 8167 14342 8169 14343 8167 14343 8168 14343 8060 14344 8168 14344 8061 14344 8170 14345 8168 14345 8060 14345 8170 14346 8169 14346 8168 14346 8171 14347 8166 14347 8169 14347 8171 14348 8169 14348 8170 14348 8172 14349 8060 14349 8059 14349 8172 14350 8170 14350 8060 14350 8173 14351 8170 14351 8172 14351 8172 14352 8059 14352 8058 14352 8171 14353 8170 14353 8173 14353 8174 14354 8172 14354 8058 14354 8175 14355 8171 14355 8173 14355 8174 14356 8173 14356 8172 14356 8174 14357 8058 14357 8057 14357 8176 14358 8173 14358 8174 14358 8176 14359 8175 14359 8173 14359 8177 14360 8174 14360 8057 14360 8176 14361 8174 14361 8177 14361 8177 14362 8057 14362 8056 14362 8178 14363 8176 14363 8177 14363 8179 14364 8177 14364 8056 14364 8178 14365 8177 14365 8179 14365 8175 14366 8176 14366 8178 14366 8179 14367 8056 14367 8055 14367 8180 14368 8175 14368 8178 14368 8181 14369 8179 14369 8055 14369 8181 14370 8178 14370 8179 14370 8180 14371 8178 14371 8181 14371 8181 14372 8055 14372 8054 14372 8182 14373 8175 14373 8180 14373 8183 14374 8181 14374 8054 14374 8183 14375 8180 14375 8181 14375 8182 14376 8180 14376 8183 14376 8053 14377 8183 14377 8054 14377 8184 14378 8183 14378 8053 14378 8185 14379 8182 14379 8183 14379 8185 14380 8183 14380 8184 14380 8186 14381 8053 14381 8052 14381 8186 14382 8184 14382 8053 14382 8051 14383 8186 14383 8052 14383 8187 14384 8184 14384 8186 14384 8187 14385 8185 14385 8184 14385 8187 14386 8186 14386 8051 14386 8188 14387 8182 14387 8185 14387 8189 14388 8051 14388 8050 14388 8188 14389 8185 14389 8187 14389 8189 14390 8187 14390 8051 14390 8190 14391 8187 14391 8189 14391 8191 14392 8188 14392 8187 14392 8189 14393 8050 14393 8049 14393 8191 14394 8187 14394 8190 14394 8192 14395 8189 14395 8049 14395 8192 14396 8190 14396 8189 14396 8192 14397 8191 14397 8190 14397 8192 14398 8049 14398 8048 14398 8193 14399 8192 14399 8048 14399 8194 14400 8192 14400 8193 14400 8047 14401 8193 14401 8048 14401 8194 14402 8191 14402 8192 14402 8195 14403 8194 14403 8193 14403 8196 14404 8047 14404 8046 14404 8196 14405 8193 14405 8047 14405 8195 14406 8193 14406 8196 14406 8196 14407 8046 14407 8045 14407 8197 14408 8195 14408 8196 14408 8197 14409 8194 14409 8195 14409 8198 14410 8196 14410 8045 14410 8198 14411 8197 14411 8196 14411 8199 14412 8194 14412 8197 14412 8198 14413 8045 14413 8044 14413 8043 14414 8198 14414 8044 14414 8200 14415 8198 14415 8043 14415 8200 14416 8197 14416 8198 14416 8200 14417 8199 14417 8197 14417 8043 14418 8042 14418 8097 14418 8200 14419 8043 14419 8097 14419 8099 14420 8199 14420 8200 14420 7850 14421 8108 14421 8111 14421 7852 14422 7850 14422 8111 14422 7852 14423 8111 14423 8117 14423 7848 14424 8108 14424 7850 14424 7848 14425 8102 14425 8108 14425 7854 14426 7852 14426 8117 14426 7848 14427 8099 14427 8102 14427 7856 14428 7854 14428 8117 14428 7846 14429 8099 14429 7848 14429 7856 14430 8117 14430 8126 14430 7846 14431 8199 14431 8099 14431 7858 14432 7856 14432 8126 14432 7886 14433 8199 14433 7846 14433 7858 14434 8126 14434 8129 14434 7886 14435 8194 14435 8199 14435 7860 14436 7858 14436 8129 14436 7884 14437 8194 14437 7886 14437 7884 14438 8191 14438 8194 14438 7860 14439 8129 14439 8136 14439 7884 14440 8188 14440 8191 14440 7862 14441 7860 14441 8136 14441 7881 14442 8188 14442 7884 14442 8142 14443 7862 14443 8136 14443 8182 14444 8188 14444 7881 14444 8182 14445 7881 14445 7879 14445 8146 14446 7862 14446 8142 14446 8146 14447 7865 14447 7862 14447 8175 14448 8182 14448 7879 14448 8149 14449 7865 14449 8146 14449 8175 14450 7879 14450 7877 14450 8149 14451 7867 14451 7865 14451 8155 14452 7867 14452 8149 14452 8171 14453 8175 14453 7877 14453 8155 14454 7869 14454 7867 14454 8166 14455 8171 14455 7877 14455 8166 14456 7877 14456 7875 14456 8159 14457 7869 14457 8155 14457 8159 14458 7871 14458 7869 14458 8163 14459 8166 14459 7875 14459 8163 14460 7875 14460 7873 14460 8159 14461 7873 14461 7871 14461 8163 14462 7873 14462 8159 14462 8205 14463 8203 14463 8202 14463 8204 14464 8203 14464 8205 14464 8206 14465 8202 14465 8201 14465 8205 14466 8202 14466 8206 14466 8207 14467 8355 14467 8204 14467 8208 14468 8204 14468 8205 14468 8207 14469 8204 14469 8208 14469 8209 14470 8205 14470 8206 14470 8210 14471 8205 14471 8209 14471 8210 14472 8208 14472 8205 14472 8211 14473 8208 14473 8210 14473 8212 14474 8210 14474 8209 14474 8211 14475 8207 14475 8208 14475 8211 14476 8210 14476 8212 14476 8213 14477 8212 14477 8209 14477 8217 14478 8207 14478 8211 14478 8215 14479 8212 14479 8213 14479 8215 14480 8211 14480 8212 14480 8216 14481 8213 14481 8214 14481 8215 14482 8217 14482 8211 14482 8215 14483 8213 14483 8216 14483 8218 14484 8215 14484 8216 14484 8220 14485 8214 14485 8219 14485 8221 14486 8215 14486 8218 14486 8220 14487 8216 14487 8214 14487 8221 14488 8217 14488 8215 14488 8220 14489 8218 14489 8216 14489 8222 14490 8217 14490 8221 14490 8223 14491 8220 14491 8219 14491 8224 14492 8220 14492 8223 14492 8224 14493 8218 14493 8220 14493 8224 14494 8221 14494 8218 14494 8226 14495 8223 14495 8225 14495 8226 14496 8224 14496 8223 14496 8227 14497 8221 14497 8224 14497 8222 14498 8221 14498 8227 14498 8227 14499 8224 14499 8226 14499 8228 14500 8226 14500 8225 14500 8229 14501 8222 14501 8227 14501 8229 14502 8227 14502 8226 14502 8230 14503 8226 14503 8228 14503 8230 14504 8229 14504 8226 14504 8231 14505 8229 14505 8230 14505 8233 14506 8228 14506 8232 14506 8233 14507 8230 14507 8228 14507 8234 14508 8229 14508 8231 14508 8234 14509 8222 14509 8229 14509 8231 14510 8230 14510 8233 14510 8233 14511 8232 14511 8235 14511 8236 14512 8231 14512 8233 14512 8236 14513 8233 14513 8235 14513 8234 14514 8231 14514 8236 14514 8237 14515 8236 14515 8235 14515 8238 14516 8234 14516 8236 14516 8239 14517 8236 14517 8237 14517 8238 14518 8236 14518 8239 14518 8240 14519 8234 14519 8238 14519 8242 14520 8237 14520 8241 14520 8242 14521 8239 14521 8237 14521 8243 14522 8239 14522 8242 14522 8243 14523 8238 14523 8239 14523 8243 14524 8240 14524 8238 14524 8245 14525 8242 14525 8241 14525 8244 14526 8240 14526 8243 14526 8245 14527 8243 14527 8242 14527 8244 14528 8243 14528 8245 14528 8245 14529 8241 14529 8246 14529 8247 14530 8245 14530 8246 14530 8249 14531 8245 14531 8247 14531 8247 14532 8246 14532 8248 14532 8249 14533 8244 14533 8245 14533 8250 14534 8249 14534 8247 14534 8251 14535 8247 14535 8248 14535 8250 14536 8247 14536 8251 14536 8252 14537 8250 14537 8251 14537 8254 14538 8244 14538 8249 14538 8252 14539 8249 14539 8250 14539 8252 14540 8251 14540 8253 14540 8254 14541 8249 14541 8252 14541 8256 14542 8252 14542 8253 14542 8255 14543 8252 14543 8256 14543 8254 14544 8252 14544 8255 14544 8257 14545 8255 14545 8256 14545 8258 14546 8257 14546 8256 14546 8259 14547 8255 14547 8257 14547 8260 14548 8257 14548 8258 14548 8259 14549 8254 14549 8255 14549 8261 14550 8254 14550 8259 14550 8259 14551 8257 14551 8260 14551 8262 14552 8260 14552 8258 14552 8263 14553 8260 14553 8262 14553 8259 14554 8260 14554 8263 14554 8263 14555 8261 14555 8259 14555 8264 14556 8263 14556 8262 14556 8265 14557 8263 14557 8264 14557 8266 14558 8261 14558 8263 14558 8266 14559 8263 14559 8265 14559 8268 14560 8264 14560 8267 14560 8268 14561 8265 14561 8264 14561 8269 14562 8265 14562 8268 14562 8269 14563 8266 14563 8265 14563 8272 14564 8261 14564 8266 14564 8270 14565 8268 14565 8267 14565 8270 14566 8269 14566 8268 14566 8270 14567 8267 14567 8271 14567 8272 14568 8266 14568 8269 14568 8273 14569 8269 14569 8270 14569 8273 14570 8272 14570 8269 14570 8273 14571 8270 14571 8271 14571 8274 14572 8273 14572 8271 14572 8275 14573 8273 14573 8274 14573 8275 14574 8272 14574 8273 14574 8276 14575 8272 14575 8275 14575 8278 14576 8274 14576 8277 14576 8278 14577 8275 14577 8274 14577 8279 14578 8278 14578 8277 14578 8280 14579 8275 14579 8278 14579 8276 14580 8275 14580 8280 14580 8280 14581 8278 14581 8279 14581 8283 14582 8279 14582 8281 14582 8282 14583 8276 14583 8280 14583 8280 14584 8279 14584 8283 14584 8284 14585 8283 14585 8281 14585 8285 14586 8280 14586 8283 14586 8285 14587 8282 14587 8280 14587 8285 14588 8283 14588 8284 14588 8287 14589 8276 14589 8282 14589 8286 14590 8285 14590 8284 14590 8287 14591 8282 14591 8285 14591 8288 14592 8285 14592 8286 14592 8289 14593 8285 14593 8288 14593 8289 14594 8287 14594 8285 14594 8290 14595 8288 14595 8286 14595 8291 14596 8288 14596 8290 14596 8291 14597 8289 14597 8288 14597 8293 14598 8290 14598 8292 14598 8293 14599 8291 14599 8290 14599 8293 14600 8289 14600 8291 14600 8295 14601 8287 14601 8289 14601 8295 14602 8289 14602 8293 14602 8296 14603 8293 14603 8292 14603 8295 14604 8293 14604 8296 14604 8296 14605 8292 14605 8294 14605 8297 14606 8296 14606 8294 14606 8295 14607 8296 14607 8299 14607 8299 14608 8296 14608 8297 14608 8300 14609 8297 14609 8298 14609 8300 14610 8299 14610 8297 14610 8303 14611 8295 14611 8299 14611 8301 14612 8300 14612 8298 14612 8302 14613 8300 14613 8301 14613 8302 14614 8299 14614 8300 14614 8303 14615 8299 14615 8302 14615 8304 14616 8302 14616 8301 14616 8305 14617 8302 14617 8304 14617 8305 14618 8303 14618 8302 14618 8307 14619 8304 14619 8306 14619 8307 14620 8305 14620 8304 14620 8308 14621 8305 14621 8307 14621 8309 14622 8307 14622 8306 14622 8310 14623 8303 14623 8305 14623 8308 14624 8307 14624 8309 14624 8310 14625 8305 14625 8308 14625 8311 14626 8308 14626 8309 14626 8311 14627 8309 14627 8312 14627 8313 14628 8310 14628 8308 14628 8313 14629 8308 14629 8311 14629 8315 14630 8312 14630 8314 14630 8315 14631 8311 14631 8312 14631 8313 14632 8311 14632 8315 14632 8316 14633 8315 14633 8314 14633 8320 14634 8310 14634 8313 14634 8316 14635 8314 14635 8317 14635 8316 14636 8313 14636 8315 14636 8319 14637 8313 14637 8316 14637 8320 14638 8313 14638 8319 14638 8321 14639 8317 14639 8318 14639 8321 14640 8316 14640 8317 14640 8319 14641 8316 14641 8321 14641 8323 14642 8319 14642 8321 14642 8324 14643 8319 14643 8323 14643 8321 14644 8318 14644 8322 14644 8324 14645 8320 14645 8319 14645 8326 14646 8321 14646 8322 14646 8326 14647 8323 14647 8321 14647 8325 14648 8326 14648 8322 14648 8327 14649 8323 14649 8326 14649 8327 14650 8324 14650 8323 14650 8328 14651 8324 14651 8327 14651 8330 14652 8325 14652 8329 14652 8330 14653 8326 14653 8325 14653 8331 14654 8326 14654 8330 14654 8331 14655 8327 14655 8326 14655 8332 14656 8330 14656 8329 14656 8328 14657 8327 14657 8331 14657 8334 14658 8331 14658 8330 14658 8334 14659 8328 14659 8331 14659 8333 14660 8330 14660 8332 14660 8334 14661 8330 14661 8333 14661 8336 14662 8334 14662 8333 14662 8336 14663 8333 14663 8335 14663 8338 14664 8334 14664 8336 14664 8337 14665 8336 14665 8335 14665 8338 14666 8328 14666 8334 14666 8339 14667 8336 14667 8337 14667 8341 14668 8328 14668 8338 14668 8338 14669 8336 14669 8339 14669 8340 14670 8339 14670 8337 14670 8341 14671 8338 14671 8339 14671 8343 14672 8340 14672 8342 14672 8343 14673 8339 14673 8340 14673 8344 14674 8339 14674 8343 14674 8344 14675 8341 14675 8339 14675 8345 14676 8343 14676 8342 14676 8346 14677 8341 14677 8344 14677 8344 14678 8343 14678 8345 14678 8347 14679 8344 14679 8345 14679 8347 14680 8346 14680 8344 14680 8347 14681 8345 14681 8348 14681 8350 14682 8347 14682 8348 14682 8350 14683 8348 14683 8349 14683 8351 14684 8347 14684 8350 14684 8351 14685 8346 14685 8347 14685 8353 14686 8346 14686 8351 14686 8352 14687 8350 14687 8349 14687 8354 14688 8350 14688 8352 14688 8354 14689 8351 14689 8350 14689 8354 14690 8353 14690 8351 14690 8355 14691 8346 14691 8353 14691 8357 14692 8352 14692 8356 14692 8357 14693 8354 14693 8352 14693 8358 14694 8354 14694 8357 14694 8358 14695 8353 14695 8354 14695 8355 14696 8353 14696 8358 14696 8357 14697 8356 14697 8359 14697 8358 14698 8357 14698 8360 14698 8360 14699 8359 14699 8201 14699 8360 14700 8201 14700 8202 14700 8360 14701 8357 14701 8359 14701 8360 14702 8202 14702 8203 14702 8358 14703 8360 14703 8203 14703 8358 14704 8203 14704 8204 14704 8355 14705 8358 14705 8204 14705 8361 14706 8201 14706 8359 14706 8362 14707 8361 14707 8359 14707 8362 14708 8359 14708 8356 14708 8363 14709 8362 14709 8356 14709 8363 14710 8356 14710 8352 14710 8364 14711 8352 14711 8349 14711 8364 14712 8363 14712 8352 14712 8365 14713 8349 14713 8348 14713 8365 14714 8364 14714 8349 14714 8366 14715 8348 14715 8345 14715 8366 14716 8365 14716 8348 14716 8367 14717 8366 14717 8345 14717 8367 14718 8345 14718 8342 14718 8368 14719 8367 14719 8342 14719 8368 14720 8342 14720 8340 14720 8369 14721 8368 14721 8340 14721 8369 14722 8340 14722 8337 14722 8370 14723 8369 14723 8337 14723 8370 14724 8337 14724 8335 14724 8371 14725 8370 14725 8335 14725 8371 14726 8335 14726 8333 14726 8371 14727 8333 14727 8332 14727 8372 14728 8371 14728 8332 14728 8372 14729 8332 14729 8329 14729 8373 14730 8372 14730 8329 14730 8373 14731 8329 14731 8325 14731 8374 14732 8373 14732 8325 14732 8374 14733 8325 14733 8322 14733 8375 14734 8374 14734 8322 14734 8375 14735 8322 14735 8318 14735 8376 14736 8375 14736 8318 14736 8376 14737 8318 14737 8317 14737 8377 14738 8376 14738 8317 14738 8377 14739 8317 14739 8314 14739 8442 14740 8377 14740 8314 14740 8378 14741 8442 14741 8314 14741 8378 14742 8314 14742 8312 14742 8379 14743 8378 14743 8312 14743 8379 14744 8312 14744 8309 14744 8379 14745 8309 14745 8306 14745 8380 14746 8379 14746 8306 14746 8380 14747 8306 14747 8304 14747 8381 14748 8380 14748 8304 14748 8381 14749 8304 14749 8301 14749 8382 14750 8381 14750 8301 14750 8382 14751 8301 14751 8298 14751 8383 14752 8382 14752 8298 14752 8383 14753 8298 14753 8297 14753 8384 14754 8383 14754 8297 14754 8385 14755 8297 14755 8294 14755 8385 14756 8384 14756 8297 14756 8385 14757 8294 14757 8292 14757 8386 14758 8385 14758 8292 14758 8386 14759 8292 14759 8290 14759 8387 14760 8386 14760 8290 14760 8387 14761 8290 14761 8286 14761 8388 14762 8387 14762 8286 14762 8389 14763 8286 14763 8284 14763 8389 14764 8388 14764 8286 14764 8389 14765 8284 14765 8281 14765 8390 14766 8389 14766 8281 14766 8390 14767 8281 14767 8279 14767 8391 14768 8390 14768 8279 14768 8391 14769 8279 14769 8277 14769 8392 14770 8391 14770 8277 14770 8392 14771 8277 14771 8274 14771 8393 14772 8392 14772 8274 14772 8393 14773 8274 14773 8271 14773 8394 14774 8393 14774 8271 14774 8394 14775 8271 14775 8267 14775 8395 14776 8394 14776 8267 14776 8395 14777 8267 14777 8264 14777 8396 14778 8395 14778 8264 14778 8396 14779 8264 14779 8262 14779 8396 14780 8262 14780 8258 14780 8397 14781 8396 14781 8258 14781 8398 14782 8258 14782 8256 14782 8398 14783 8397 14783 8258 14783 8398 14784 8256 14784 8253 14784 8399 14785 8398 14785 8253 14785 8399 14786 8253 14786 8251 14786 8488 14787 8399 14787 8251 14787 8488 14788 8251 14788 8248 14788 8400 14789 8488 14789 8248 14789 8400 14790 8248 14790 8246 14790 8401 14791 8400 14791 8246 14791 8401 14792 8246 14792 8241 14792 8402 14793 8401 14793 8241 14793 8402 14794 8241 14794 8237 14794 8403 14795 8402 14795 8237 14795 8403 14796 8237 14796 8235 14796 8403 14797 8235 14797 8232 14797 8404 14798 8403 14798 8232 14798 8404 14799 8232 14799 8228 14799 8405 14800 8404 14800 8228 14800 8406 14801 8228 14801 8225 14801 8406 14802 8405 14802 8228 14802 8406 14803 8225 14803 8223 14803 8407 14804 8406 14804 8223 14804 8408 14805 8223 14805 8219 14805 8408 14806 8407 14806 8223 14806 8408 14807 8219 14807 8214 14807 8409 14808 8408 14808 8214 14808 8409 14809 8214 14809 8213 14809 8410 14810 8409 14810 8213 14810 8410 14811 8213 14811 8209 14811 8515 14812 8410 14812 8209 14812 8411 14813 8515 14813 8209 14813 8411 14814 8209 14814 8206 14814 8412 14815 8411 14815 8206 14815 8412 14816 8206 14816 8201 14816 8361 14817 8412 14817 8201 14817 8414 14818 8361 14818 8362 14818 8414 14819 8413 14819 8361 14819 8414 14820 8362 14820 8363 14820 8416 14821 8413 14821 8414 14821 8416 14822 8519 14822 8413 14822 8415 14823 8519 14823 8416 14823 8417 14824 8414 14824 8363 14824 8417 14825 8416 14825 8414 14825 8418 14826 8416 14826 8417 14826 8417 14827 8363 14827 8364 14827 8415 14828 8416 14828 8418 14828 8365 14829 8417 14829 8364 14829 8419 14830 8417 14830 8365 14830 8419 14831 8418 14831 8417 14831 8419 14832 8415 14832 8418 14832 8420 14833 8415 14833 8419 14833 8366 14834 8419 14834 8365 14834 8421 14835 8419 14835 8366 14835 8422 14836 8419 14836 8421 14836 8420 14837 8419 14837 8422 14837 8423 14838 8366 14838 8367 14838 8423 14839 8421 14839 8366 14839 8423 14840 8422 14840 8421 14840 8368 14841 8423 14841 8367 14841 8425 14842 8423 14842 8368 14842 8424 14843 8420 14843 8422 14843 8425 14844 8422 14844 8423 14844 8424 14845 8422 14845 8425 14845 8369 14846 8425 14846 8368 14846 8426 14847 8425 14847 8369 14847 8427 14848 8420 14848 8424 14848 8424 14849 8425 14849 8426 14849 8428 14850 8369 14850 8370 14850 8427 14851 8424 14851 8426 14851 8428 14852 8426 14852 8369 14852 8429 14853 8426 14853 8428 14853 8371 14854 8428 14854 8370 14854 8429 14855 8427 14855 8426 14855 8430 14856 8428 14856 8371 14856 8429 14857 8428 14857 8430 14857 8372 14858 8430 14858 8371 14858 8431 14859 8430 14859 8372 14859 8431 14860 8429 14860 8430 14860 8431 14861 8427 14861 8429 14861 8432 14862 8372 14862 8373 14862 8434 14863 8427 14863 8431 14863 8432 14864 8431 14864 8372 14864 8433 14865 8431 14865 8432 14865 8374 14866 8432 14866 8373 14866 8434 14867 8431 14867 8433 14867 8435 14868 8432 14868 8374 14868 8435 14869 8433 14869 8432 14869 8435 14870 8374 14870 8375 14870 8437 14871 8433 14871 8435 14871 8437 14872 8434 14872 8433 14872 8438 14873 8435 14873 8375 14873 8438 14874 8437 14874 8435 14874 8436 14875 8434 14875 8437 14875 8439 14876 8437 14876 8438 14876 8376 14877 8438 14877 8375 14877 8439 14878 8438 14878 8376 14878 8436 14879 8437 14879 8439 14879 8441 14880 8376 14880 8377 14880 8440 14881 8436 14881 8439 14881 8441 14882 8439 14882 8376 14882 8440 14883 8439 14883 8441 14883 8442 14884 8441 14884 8377 14884 8443 14885 8436 14885 8440 14885 8444 14886 8441 14886 8442 14886 8444 14887 8440 14887 8441 14887 8444 14888 8442 14888 8378 14888 8445 14889 8436 14889 8443 14889 8446 14890 8440 14890 8444 14890 8446 14891 8443 14891 8440 14891 8447 14892 8378 14892 8379 14892 8445 14893 8443 14893 8446 14893 8446 14894 8444 14894 8378 14894 8446 14895 8378 14895 8447 14895 8448 14896 8446 14896 8447 14896 8445 14897 8446 14897 8448 14897 8380 14898 8447 14898 8379 14898 8448 14899 8447 14899 8380 14899 8381 14900 8448 14900 8380 14900 8449 14901 8448 14901 8381 14901 8449 14902 8445 14902 8448 14902 8450 14903 8449 14903 8381 14903 8450 14904 8381 14904 8382 14904 8451 14905 8449 14905 8450 14905 8451 14906 8445 14906 8449 14906 8383 14907 8450 14907 8382 14907 8452 14908 8450 14908 8383 14908 8452 14909 8451 14909 8450 14909 8453 14910 8451 14910 8452 14910 8384 14911 8452 14911 8383 14911 8454 14912 8452 14912 8384 14912 8453 14913 8452 14913 8454 14913 8454 14914 8384 14914 8385 14914 8455 14915 8453 14915 8454 14915 8386 14916 8454 14916 8385 14916 8456 14917 8454 14917 8386 14917 8456 14918 8455 14918 8454 14918 8457 14919 8455 14919 8456 14919 8387 14920 8456 14920 8386 14920 8457 14921 8453 14921 8455 14921 8458 14922 8453 14922 8457 14922 8459 14923 8456 14923 8387 14923 8457 14924 8456 14924 8459 14924 8388 14925 8459 14925 8387 14925 8460 14926 8453 14926 8458 14926 8458 14927 8457 14927 8459 14927 8461 14928 8458 14928 8459 14928 8462 14929 8388 14929 8389 14929 8462 14930 8459 14930 8388 14930 8460 14931 8458 14931 8461 14931 8461 14932 8459 14932 8462 14932 8463 14933 8461 14933 8462 14933 8463 14934 8462 14934 8389 14934 8464 14935 8461 14935 8463 14935 8465 14936 8389 14936 8390 14936 8465 14937 8463 14937 8389 14937 8464 14938 8460 14938 8461 14938 8464 14939 8463 14939 8465 14939 8466 14940 8465 14940 8390 14940 8467 14941 8465 14941 8466 14941 8464 14942 8465 14942 8467 14942 8391 14943 8466 14943 8390 14943 8469 14944 8460 14944 8464 14944 8468 14945 8391 14945 8392 14945 8469 14946 8464 14946 8467 14946 8468 14947 8466 14947 8391 14947 8470 14948 8466 14948 8468 14948 8470 14949 8467 14949 8466 14949 8469 14950 8467 14950 8470 14950 8393 14951 8468 14951 8392 14951 8471 14952 8468 14952 8393 14952 8470 14953 8468 14953 8471 14953 8473 14954 8469 14954 8470 14954 8472 14955 8471 14955 8393 14955 8472 14956 8470 14956 8471 14956 8474 14957 8470 14957 8472 14957 8472 14958 8393 14958 8394 14958 8474 14959 8473 14959 8470 14959 8475 14960 8472 14960 8394 14960 8476 14961 8473 14961 8474 14961 8475 14962 8474 14962 8472 14962 8395 14963 8475 14963 8394 14963 8477 14964 8474 14964 8475 14964 8476 14965 8474 14965 8477 14965 8477 14966 8475 14966 8395 14966 8477 14967 8395 14967 8478 14967 8479 14968 8476 14968 8477 14968 8478 14969 8395 14969 8396 14969 8479 14970 8473 14970 8476 14970 8480 14971 8477 14971 8478 14971 8479 14972 8477 14972 8480 14972 8480 14973 8478 14973 8396 14973 8481 14974 8480 14974 8396 14974 8481 14975 8396 14975 8397 14975 8482 14976 8480 14976 8481 14976 8482 14977 8479 14977 8480 14977 8398 14978 8481 14978 8397 14978 8483 14979 8481 14979 8398 14979 8484 14980 8479 14980 8482 14980 8483 14981 8482 14981 8481 14981 8484 14982 8482 14982 8483 14982 8485 14983 8483 14983 8398 14983 8486 14984 8483 14984 8485 14984 8486 14985 8484 14985 8483 14985 8399 14986 8485 14986 8398 14986 8487 14987 8485 14987 8399 14987 8487 14988 8486 14988 8485 14988 8489 14989 8486 14989 8487 14989 8489 14990 8484 14990 8486 14990 8488 14991 8487 14991 8399 14991 8490 14992 8487 14992 8488 14992 8489 14993 8487 14993 8490 14993 8491 14994 8490 14994 8488 14994 8400 14995 8491 14995 8488 14995 8494 14996 8490 14996 8491 14996 8492 14997 8490 14997 8494 14997 8492 14998 8489 14998 8490 14998 8493 14999 8491 14999 8400 14999 8494 15000 8491 15000 8493 15000 8401 15001 8493 15001 8400 15001 8494 15002 8493 15002 8401 15002 8495 15003 8494 15003 8401 15003 8496 15004 8494 15004 8495 15004 8496 15005 8492 15005 8494 15005 8498 15006 8489 15006 8492 15006 8497 15007 8401 15007 8402 15007 8497 15008 8495 15008 8401 15008 8498 15009 8492 15009 8496 15009 8496 15010 8495 15010 8497 15010 8499 15011 8496 15011 8497 15011 8403 15012 8497 15012 8402 15012 8498 15013 8496 15013 8499 15013 8500 15014 8497 15014 8403 15014 8501 15015 8499 15015 8497 15015 8501 15016 8497 15016 8500 15016 8404 15017 8500 15017 8403 15017 8502 15018 8499 15018 8501 15018 8503 15019 8500 15019 8404 15019 8502 15020 8498 15020 8499 15020 8503 15021 8501 15021 8500 15021 8502 15022 8501 15022 8503 15022 8405 15023 8503 15023 8404 15023 8504 15024 8503 15024 8405 15024 8505 15025 8502 15025 8503 15025 8505 15026 8503 15026 8504 15026 8406 15027 8504 15027 8405 15027 8506 15028 8502 15028 8505 15028 8505 15029 8504 15029 8406 15029 8507 15030 8505 15030 8406 15030 8407 15031 8507 15031 8406 15031 8507 15032 8506 15032 8505 15032 8508 15033 8507 15033 8407 15033 8408 15034 8508 15034 8407 15034 8509 15035 8507 15035 8508 15035 8510 15036 8507 15036 8509 15036 8510 15037 8506 15037 8507 15037 8511 15038 8508 15038 8408 15038 8511 15039 8509 15039 8508 15039 8409 15040 8511 15040 8408 15040 8512 15041 8509 15041 8511 15041 8512 15042 8510 15042 8509 15042 8513 15043 8409 15043 8410 15043 8513 15044 8511 15044 8409 15044 8513 15045 8512 15045 8511 15045 8515 15046 8513 15046 8410 15046 8514 15047 8510 15047 8512 15047 8512 15048 8513 15048 8516 15048 8516 15049 8513 15049 8515 15049 8514 15050 8512 15050 8516 15050 8517 15051 8515 15051 8411 15051 8517 15052 8516 15052 8515 15052 8517 15053 8411 15053 8412 15053 8518 15054 8516 15054 8517 15054 8518 15055 8517 15055 8412 15055 8519 15056 8516 15056 8518 15056 8519 15057 8514 15057 8516 15057 8361 15058 8518 15058 8412 15058 8518 15059 8361 15059 8413 15059 8518 15060 8413 15060 8519 15060 7838 15061 8479 15061 8484 15061 7840 15062 8479 15062 7838 15062 7840 15063 8473 15063 8479 15063 7836 15064 7838 15064 8484 15064 7842 15065 8473 15065 7840 15065 7836 15066 8484 15066 8489 15066 7843 15067 8469 15067 8473 15067 7843 15068 8473 15068 7842 15068 7834 15069 7836 15069 8489 15069 7843 15070 8460 15070 8469 15070 7834 15071 8489 15071 8498 15071 7801 15072 8460 15072 7843 15072 7832 15073 7834 15073 8498 15073 7804 15074 8460 15074 7801 15074 7830 15075 7832 15075 8498 15075 7804 15076 8453 15076 8460 15076 7830 15077 8498 15077 8502 15077 7830 15078 8502 15078 8506 15078 7806 15079 8453 15079 7804 15079 7828 15080 7830 15080 8506 15080 7806 15081 8451 15081 8453 15081 8451 15082 7806 15082 7807 15082 7826 15083 7828 15083 8506 15083 8510 15084 7826 15084 8506 15084 8445 15085 8451 15085 7807 15085 8514 15086 7826 15086 8510 15086 8445 15087 7807 15087 7810 15087 8514 15088 7823 15088 7826 15088 8436 15089 8445 15089 7810 15089 8436 15090 7810 15090 7812 15090 8519 15091 7823 15091 8514 15091 8519 15092 7821 15092 7823 15092 8415 15093 7821 15093 8519 15093 8436 15094 7812 15094 7814 15094 8434 15095 8436 15095 7814 15095 8415 15096 7819 15096 7821 15096 8427 15097 8434 15097 7814 15097 8427 15098 7814 15098 7816 15098 8420 15099 7819 15099 8415 15099 8420 15100 7818 15100 7819 15100 8427 15101 7818 15101 8420 15101 8427 15102 7816 15102 7818 15102 8522 15103 8520 15103 8521 15103 8522 15104 8521 15104 8523 15104 8757 15105 8522 15105 8523 15105 8524 15106 8757 15106 8523 15106 8525 15107 8524 15107 8523 15107 8526 15108 8525 15108 8523 15108 8526 15109 8523 15109 8527 15109 8767 15110 8526 15110 8527 15110 8528 15111 8767 15111 8527 15111 8528 15112 8527 15112 8529 15112 8530 15113 8528 15113 8529 15113 8531 15114 8530 15114 8529 15114 8532 15115 8531 15115 8529 15115 8532 15116 8529 15116 8533 15116 8534 15117 8532 15117 8533 15117 8535 15118 8533 15118 8536 15118 8535 15119 8534 15119 8533 15119 8537 15120 8535 15120 8536 15120 8538 15121 8536 15121 8539 15121 8538 15122 8537 15122 8536 15122 8540 15123 8538 15123 8539 15123 8541 15124 8540 15124 8539 15124 8542 15125 8541 15125 8539 15125 8542 15126 8539 15126 8543 15126 8544 15127 8542 15127 8543 15127 8545 15128 8544 15128 8543 15128 8545 15129 8543 15129 8546 15129 8547 15130 8545 15130 8546 15130 8548 15131 8547 15131 8546 15131 8548 15132 8546 15132 8549 15132 8550 15133 8548 15133 8549 15133 8550 15134 8549 15134 8551 15134 8803 15135 8550 15135 8551 15135 8806 15136 8551 15136 8552 15136 8806 15137 8803 15137 8551 15137 8553 15138 8806 15138 8552 15138 8554 15139 8553 15139 8552 15139 8554 15140 8552 15140 8555 15140 8556 15141 8554 15141 8555 15141 8556 15142 8555 15142 8557 15142 8558 15143 8556 15143 8557 15143 8559 15144 8557 15144 8560 15144 8559 15145 8558 15145 8557 15145 8561 15146 8559 15146 8560 15146 8561 15147 8560 15147 8562 15147 8563 15148 8561 15148 8562 15148 8564 15149 8563 15149 8562 15149 8564 15150 8562 15150 8565 15150 8566 15151 8564 15151 8565 15151 8567 15152 8566 15152 8565 15152 8568 15153 8567 15153 8565 15153 8568 15154 8565 15154 8569 15154 8829 15155 8568 15155 8569 15155 8570 15156 8569 15156 8571 15156 8570 15157 8829 15157 8569 15157 8572 15158 8570 15158 8571 15158 8573 15159 8571 15159 8574 15159 8573 15160 8572 15160 8571 15160 8575 15161 8573 15161 8574 15161 8575 15162 8574 15162 8576 15162 8577 15163 8575 15163 8576 15163 8578 15164 8576 15164 8579 15164 8578 15165 8577 15165 8576 15165 8580 15166 8578 15166 8579 15166 8580 15167 8579 15167 8581 15167 8582 15168 8580 15168 8581 15168 8583 15169 8582 15169 8581 15169 8584 15170 8583 15170 8581 15170 8584 15171 8581 15171 8585 15171 8520 15172 8584 15172 8585 15172 8520 15173 8585 15173 8521 15173 8586 15174 8587 15174 8588 15174 8589 15175 8588 15175 8751 15175 8589 15176 8586 15176 8588 15176 8589 15177 8751 15177 8590 15177 8591 15178 8590 15178 8745 15178 8591 15179 8589 15179 8590 15179 8591 15180 8745 15180 8592 15180 8593 15181 8591 15181 8592 15181 8593 15182 8592 15182 8594 15182 8593 15183 8594 15183 8595 15183 8596 15184 8593 15184 8595 15184 8596 15185 8595 15185 8597 15185 8596 15186 8597 15186 8598 15186 8599 15187 8598 15187 8600 15187 8599 15188 8596 15188 8598 15188 8599 15189 8600 15189 8601 15189 8602 15190 8599 15190 8601 15190 8602 15191 8601 15191 8603 15191 8602 15192 8603 15192 8604 15192 8605 15193 8604 15193 8606 15193 8605 15194 8602 15194 8604 15194 8605 15195 8606 15195 8607 15195 8608 15196 8605 15196 8607 15196 8608 15197 8607 15197 8609 15197 8608 15198 8609 15198 8610 15198 8611 15199 8608 15199 8610 15199 8611 15200 8610 15200 8718 15200 8611 15201 8718 15201 8715 15201 8611 15202 8715 15202 8612 15202 8613 15203 8611 15203 8612 15203 8613 15204 8612 15204 8614 15204 8615 15205 8614 15205 8616 15205 8615 15206 8613 15206 8614 15206 8615 15207 8616 15207 8706 15207 8617 15208 8615 15208 8706 15208 8617 15209 8706 15209 8618 15209 8617 15210 8618 15210 8619 15210 8620 15211 8617 15211 8619 15211 8620 15212 8619 15212 8621 15212 8620 15213 8621 15213 8622 15213 8623 15214 8620 15214 8622 15214 8623 15215 8622 15215 8624 15215 8623 15216 8624 15216 8625 15216 8626 15217 8623 15217 8625 15217 8626 15218 8625 15218 8692 15218 8626 15219 8692 15219 8689 15219 8626 15220 8689 15220 8627 15220 8628 15221 8626 15221 8627 15221 8628 15222 8627 15222 8629 15222 8630 15223 8628 15223 8629 15223 8630 15224 8629 15224 8631 15224 8630 15225 8631 15225 8632 15225 8633 15226 8630 15226 8632 15226 8633 15227 8632 15227 8634 15227 8635 15228 8634 15228 8636 15228 8635 15229 8633 15229 8634 15229 8635 15230 8636 15230 8637 15230 8638 15231 8635 15231 8637 15231 8638 15232 8637 15232 8639 15232 8638 15233 8639 15233 8640 15233 8641 15234 8638 15234 8640 15234 8641 15235 8640 15235 8642 15235 8641 15236 8642 15236 8643 15236 8644 15237 8641 15237 8643 15237 8644 15238 8643 15238 8645 15238 8646 15239 8644 15239 8645 15239 8646 15240 8645 15240 8647 15240 8646 15241 8647 15241 8648 15241 8646 15242 8648 15242 8649 15242 8650 15243 8646 15243 8649 15243 8650 15244 8649 15244 8651 15244 8586 15245 8651 15245 8587 15245 8586 15246 8650 15246 8651 15246 8651 15247 8652 15247 8587 15247 8654 15248 8753 15248 8653 15248 8655 15249 8652 15249 8651 15249 8655 15250 8653 15250 8652 15250 8656 15251 8653 15251 8655 15251 8649 15252 8655 15252 8651 15252 8656 15253 8655 15253 8649 15253 8657 15254 8653 15254 8656 15254 8657 15255 8654 15255 8653 15255 8648 15256 8656 15256 8649 15256 8658 15257 8656 15257 8648 15257 8659 15258 8654 15258 8657 15258 8658 15259 8657 15259 8656 15259 8647 15260 8658 15260 8648 15260 8659 15261 8657 15261 8658 15261 8660 15262 8658 15262 8647 15262 8660 15263 8647 15263 8645 15263 8659 15264 8658 15264 8660 15264 8660 15265 8645 15265 8643 15265 8661 15266 8659 15266 8660 15266 8662 15267 8660 15267 8643 15267 8661 15268 8660 15268 8662 15268 8663 15269 8662 15269 8643 15269 8664 15270 8662 15270 8663 15270 8664 15271 8661 15271 8662 15271 8663 15272 8643 15272 8642 15272 8640 15273 8663 15273 8642 15273 8665 15274 8663 15274 8640 15274 8666 15275 8661 15275 8664 15275 8665 15276 8664 15276 8663 15276 8666 15277 8664 15277 8665 15277 8667 15278 8665 15278 8640 15278 8639 15279 8667 15279 8640 15279 8668 15280 8665 15280 8667 15280 8668 15281 8666 15281 8665 15281 8669 15282 8639 15282 8637 15282 8669 15283 8667 15283 8639 15283 8669 15284 8668 15284 8667 15284 8670 15285 8666 15285 8668 15285 8670 15286 8668 15286 8669 15286 8671 15287 8669 15287 8637 15287 8670 15288 8669 15288 8671 15288 8672 15289 8670 15289 8671 15289 8673 15290 8666 15290 8670 15290 8636 15291 8671 15291 8637 15291 8674 15292 8671 15292 8636 15292 8673 15293 8670 15293 8672 15293 8674 15294 8672 15294 8671 15294 8675 15295 8672 15295 8674 15295 8673 15296 8672 15296 8675 15296 8634 15297 8674 15297 8636 15297 8676 15298 8674 15298 8634 15298 8675 15299 8674 15299 8676 15299 8677 15300 8676 15300 8634 15300 8679 15301 8673 15301 8675 15301 8678 15302 8675 15302 8676 15302 8678 15303 8676 15303 8677 15303 8677 15304 8634 15304 8632 15304 8679 15305 8675 15305 8678 15305 8680 15306 8677 15306 8632 15306 8681 15307 8679 15307 8678 15307 8680 15308 8678 15308 8677 15308 8681 15309 8678 15309 8680 15309 8680 15310 8632 15310 8631 15310 8682 15311 8681 15311 8680 15311 8687 15312 8681 15312 8682 15312 8687 15313 8679 15313 8681 15313 8683 15314 8680 15314 8631 15314 8682 15315 8680 15315 8683 15315 8683 15316 8631 15316 8629 15316 8684 15317 8682 15317 8683 15317 8684 15318 8687 15318 8682 15318 8685 15319 8683 15319 8629 15319 8685 15320 8684 15320 8683 15320 8686 15321 8629 15321 8627 15321 8687 15322 8684 15322 8685 15322 8686 15323 8685 15323 8629 15323 8688 15324 8685 15324 8686 15324 8688 15325 8687 15325 8685 15325 8689 15326 8686 15326 8627 15326 8690 15327 8686 15327 8689 15327 8690 15328 8688 15328 8686 15328 8691 15329 8687 15329 8688 15329 8691 15330 8688 15330 8690 15330 8692 15331 8690 15331 8689 15331 8693 15332 8687 15332 8691 15332 8694 15333 8692 15333 8625 15333 8694 15334 8690 15334 8692 15334 8695 15335 8690 15335 8694 15335 8695 15336 8691 15336 8690 15336 8694 15337 8625 15337 8624 15337 8696 15338 8691 15338 8695 15338 8696 15339 8693 15339 8691 15339 8622 15340 8694 15340 8624 15340 8697 15341 8694 15341 8622 15341 8697 15342 8695 15342 8694 15342 8696 15343 8695 15343 8697 15343 8699 15344 8696 15344 8697 15344 8698 15345 8697 15345 8622 15345 8693 15346 8696 15346 8699 15346 8698 15347 8622 15347 8621 15347 8699 15348 8697 15348 8698 15348 8700 15349 8698 15349 8621 15349 8700 15350 8699 15350 8698 15350 8619 15351 8700 15351 8621 15351 8702 15352 8700 15352 8619 15352 8702 15353 8699 15353 8700 15353 8701 15354 8693 15354 8699 15354 8703 15355 8699 15355 8702 15355 8701 15356 8699 15356 8703 15356 8702 15357 8619 15357 8618 15357 8704 15358 8702 15358 8618 15358 8705 15359 8703 15359 8702 15359 8701 15360 8703 15360 8705 15360 8705 15361 8702 15361 8704 15361 8704 15362 8618 15362 8706 15362 8708 15363 8706 15363 8616 15363 8707 15364 8705 15364 8704 15364 8708 15365 8704 15365 8706 15365 8707 15366 8704 15366 8708 15366 8709 15367 8705 15367 8707 15367 8709 15368 8701 15368 8705 15368 8710 15369 8708 15369 8616 15369 8710 15370 8707 15370 8708 15370 8614 15371 8710 15371 8616 15371 8711 15372 8707 15372 8710 15372 8711 15373 8709 15373 8707 15373 8712 15374 8614 15374 8612 15374 8712 15375 8710 15375 8614 15375 8713 15376 8710 15376 8712 15376 8713 15377 8711 15377 8710 15377 8716 15378 8709 15378 8711 15378 8714 15379 8713 15379 8712 15379 8715 15380 8712 15380 8612 15380 8716 15381 8711 15381 8713 15381 8714 15382 8712 15382 8715 15382 8716 15383 8713 15383 8714 15383 8717 15384 8714 15384 8715 15384 8716 15385 8714 15385 8717 15385 8717 15386 8715 15386 8718 15386 8719 15387 8718 15387 8610 15387 8719 15388 8717 15388 8718 15388 8720 15389 8716 15389 8717 15389 8609 15390 8719 15390 8610 15390 8721 15391 8719 15391 8609 15391 8722 15392 8719 15392 8721 15392 8722 15393 8717 15393 8719 15393 8720 15394 8717 15394 8722 15394 8721 15395 8609 15395 8607 15395 8723 15396 8721 15396 8607 15396 8724 15397 8720 15397 8722 15397 8724 15398 8721 15398 8723 15398 8724 15399 8722 15399 8721 15399 8726 15400 8720 15400 8724 15400 8723 15401 8607 15401 8606 15401 8725 15402 8724 15402 8723 15402 8727 15403 8723 15403 8606 15403 8726 15404 8724 15404 8725 15404 8727 15405 8725 15405 8723 15405 8728 15406 8725 15406 8727 15406 8727 15407 8606 15407 8604 15407 8726 15408 8725 15408 8728 15408 8728 15409 8727 15409 8604 15409 8729 15410 8604 15410 8603 15410 8730 15411 8726 15411 8728 15411 8729 15412 8728 15412 8604 15412 8730 15413 8728 15413 8729 15413 8731 15414 8729 15414 8603 15414 8731 15415 8730 15415 8729 15415 8733 15416 8726 15416 8730 15416 8601 15417 8731 15417 8603 15417 8732 15418 8731 15418 8601 15418 8733 15419 8730 15419 8731 15419 8600 15420 8732 15420 8601 15420 8734 15421 8731 15421 8732 15421 8734 15422 8733 15422 8731 15422 8735 15423 8732 15423 8600 15423 8735 15424 8734 15424 8732 15424 8735 15425 8600 15425 8598 15425 8736 15426 8735 15426 8598 15426 8737 15427 8733 15427 8734 15427 8736 15428 8734 15428 8735 15428 8737 15429 8734 15429 8736 15429 8597 15430 8736 15430 8598 15430 8738 15431 8737 15431 8736 15431 8738 15432 8736 15432 8597 15432 8739 15433 8738 15433 8597 15433 8740 15434 8737 15434 8738 15434 8740 15435 8738 15435 8739 15435 8739 15436 8597 15436 8595 15436 8740 15437 8739 15437 8741 15437 8741 15438 8595 15438 8594 15438 8741 15439 8739 15439 8595 15439 8742 15440 8737 15440 8740 15440 8743 15441 8741 15441 8594 15441 8740 15442 8741 15442 8743 15442 8743 15443 8594 15443 8592 15443 8744 15444 8740 15444 8743 15444 8745 15445 8743 15445 8592 15445 8742 15446 8740 15446 8744 15446 8744 15447 8743 15447 8745 15447 8747 15448 8742 15448 8744 15448 8746 15449 8744 15449 8745 15449 8746 15450 8745 15450 8590 15450 8747 15451 8744 15451 8746 15451 8748 15452 8746 15452 8590 15452 8749 15453 8742 15453 8747 15453 8748 15454 8747 15454 8746 15454 8750 15455 8747 15455 8748 15455 8751 15456 8748 15456 8590 15456 8749 15457 8747 15457 8750 15457 8750 15458 8748 15458 8751 15458 8752 15459 8750 15459 8751 15459 8754 15460 8750 15460 8752 15460 8752 15461 8751 15461 8588 15461 8754 15462 8749 15462 8750 15462 8753 15463 8749 15463 8754 15463 8588 15464 8587 15464 8652 15464 8754 15465 8752 15465 8588 15465 8754 15466 8588 15466 8652 15466 8754 15467 8652 15467 8653 15467 8753 15468 8754 15468 8653 15468 7829 15469 7827 15469 8661 15469 7829 15470 8661 15470 8666 15470 7827 15471 8659 15471 8661 15471 7825 15472 8659 15472 7827 15472 7829 15473 8666 15473 8673 15473 7831 15474 7829 15474 8673 15474 7824 15475 8659 15475 7825 15475 7824 15476 8654 15476 8659 15476 7833 15477 7831 15477 8673 15477 7822 15478 8654 15478 7824 15478 7822 15479 8753 15479 8654 15479 7833 15480 8673 15480 8679 15480 7822 15481 8749 15481 8753 15481 7820 15482 8749 15482 7822 15482 7835 15483 7833 15483 8679 15483 7835 15484 8679 15484 8687 15484 7820 15485 8742 15485 8749 15485 7837 15486 7835 15486 8687 15486 7817 15487 8742 15487 7820 15487 8693 15488 7837 15488 8687 15488 7839 15489 7837 15489 8693 15489 8742 15490 7817 15490 7815 15490 8737 15491 8742 15491 7815 15491 8693 15492 7841 15492 7839 15492 8733 15493 8737 15493 7815 15493 8733 15494 7815 15494 7813 15494 8693 15495 7844 15495 7841 15495 8733 15496 7813 15496 7811 15496 8701 15497 7844 15497 8693 15497 8726 15498 8733 15498 7811 15498 8701 15499 7802 15499 7844 15499 8726 15500 7811 15500 7809 15500 8701 15501 7803 15501 7802 15501 8709 15502 7803 15502 8701 15502 8720 15503 8726 15503 7809 15503 8716 15504 7803 15504 8709 15504 8720 15505 7809 15505 7808 15505 8716 15506 7805 15506 7803 15506 8720 15507 7808 15507 7805 15507 8716 15508 8720 15508 7805 15508 8756 15509 8854 15509 8755 15509 8522 15510 8755 15510 8520 15510 8756 15511 8853 15511 8854 15511 8758 15512 8853 15512 8756 15512 8757 15513 8755 15513 8522 15513 8756 15514 8755 15514 8757 15514 8759 15515 8756 15515 8757 15515 8759 15516 8758 15516 8756 15516 8760 15517 8758 15517 8759 15517 8761 15518 8757 15518 8524 15518 8761 15519 8759 15519 8757 15519 8760 15520 8759 15520 8761 15520 8525 15521 8761 15521 8524 15521 8763 15522 8758 15522 8760 15522 8762 15523 8761 15523 8525 15523 8762 15524 8760 15524 8761 15524 8764 15525 8525 15525 8526 15525 8765 15526 8760 15526 8762 15526 8764 15527 8762 15527 8525 15527 8765 15528 8763 15528 8760 15528 8766 15529 8762 15529 8764 15529 8765 15530 8762 15530 8766 15530 8767 15531 8764 15531 8526 15531 8766 15532 8764 15532 8767 15532 8768 15533 8766 15533 8767 15533 8769 15534 8766 15534 8768 15534 8768 15535 8767 15535 8528 15535 8769 15536 8765 15536 8766 15536 8770 15537 8765 15537 8769 15537 8770 15538 8763 15538 8765 15538 8771 15539 8528 15539 8530 15539 8772 15540 8769 15540 8768 15540 8771 15541 8768 15541 8528 15541 8772 15542 8770 15542 8769 15542 8772 15543 8768 15543 8771 15543 8773 15544 8771 15544 8530 15544 8773 15545 8530 15545 8531 15545 8774 15546 8771 15546 8773 15546 8774 15547 8772 15547 8771 15547 8770 15548 8772 15548 8774 15548 8532 15549 8773 15549 8531 15549 8775 15550 8773 15550 8532 15550 8775 15551 8774 15551 8773 15551 8776 15552 8770 15552 8774 15552 8777 15553 8532 15553 8534 15553 8777 15554 8775 15554 8532 15554 8778 15555 8775 15555 8777 15555 8777 15556 8534 15556 8535 15556 8778 15557 8774 15557 8775 15557 8778 15558 8776 15558 8774 15558 8779 15559 8777 15559 8535 15559 8779 15560 8778 15560 8777 15560 8780 15561 8535 15561 8537 15561 8780 15562 8779 15562 8535 15562 8781 15563 8776 15563 8778 15563 8782 15564 8778 15564 8779 15564 8782 15565 8781 15565 8778 15565 8782 15566 8779 15566 8780 15566 8783 15567 8782 15567 8780 15567 8538 15568 8780 15568 8537 15568 8781 15569 8782 15569 8783 15569 8538 15570 8783 15570 8780 15570 8784 15571 8781 15571 8783 15571 8785 15572 8538 15572 8540 15572 8785 15573 8783 15573 8538 15573 8784 15574 8783 15574 8785 15574 8786 15575 8540 15575 8541 15575 8786 15576 8785 15576 8540 15576 8788 15577 8781 15577 8784 15577 8542 15578 8786 15578 8541 15578 8787 15579 8786 15579 8542 15579 8788 15580 8784 15580 8785 15580 8787 15581 8785 15581 8786 15581 8788 15582 8785 15582 8787 15582 8544 15583 8787 15583 8542 15583 8789 15584 8787 15584 8544 15584 8790 15585 8788 15585 8787 15585 8791 15586 8787 15586 8789 15586 8790 15587 8787 15587 8791 15587 8792 15588 8789 15588 8544 15588 8791 15589 8789 15589 8792 15589 8792 15590 8544 15590 8545 15590 8794 15591 8788 15591 8790 15591 8793 15592 8792 15592 8545 15592 8793 15593 8791 15593 8792 15593 8794 15594 8790 15594 8791 15594 8795 15595 8791 15595 8793 15595 8796 15596 8793 15596 8545 15596 8795 15597 8794 15597 8791 15597 8795 15598 8793 15598 8796 15598 8796 15599 8545 15599 8547 15599 8797 15600 8796 15600 8547 15600 8798 15601 8796 15601 8797 15601 8798 15602 8795 15602 8796 15602 8548 15603 8797 15603 8547 15603 8799 15604 8795 15604 8798 15604 8800 15605 8794 15605 8795 15605 8798 15606 8797 15606 8548 15606 8800 15607 8795 15607 8799 15607 8801 15608 8548 15608 8550 15608 8801 15609 8798 15609 8548 15609 8801 15610 8799 15610 8798 15610 8802 15611 8801 15611 8550 15611 8802 15612 8799 15612 8801 15612 8804 15613 8799 15613 8802 15613 8802 15614 8550 15614 8803 15614 8804 15615 8800 15615 8799 15615 8805 15616 8802 15616 8803 15616 8805 15617 8804 15617 8802 15617 8806 15618 8805 15618 8803 15618 8808 15619 8800 15619 8804 15619 8808 15620 8804 15620 8805 15620 8807 15621 8805 15621 8806 15621 8809 15622 8805 15622 8807 15622 8807 15623 8806 15623 8553 15623 8809 15624 8808 15624 8805 15624 8810 15625 8809 15625 8807 15625 8811 15626 8809 15626 8810 15626 8811 15627 8808 15627 8809 15627 8812 15628 8553 15628 8554 15628 8812 15629 8807 15629 8553 15629 8812 15630 8810 15630 8807 15630 8814 15631 8812 15631 8554 15631 8813 15632 8811 15632 8810 15632 8814 15633 8810 15633 8812 15633 8814 15634 8554 15634 8556 15634 8813 15635 8810 15635 8814 15635 8816 15636 8814 15636 8815 15636 8816 15637 8813 15637 8814 15637 8816 15638 8811 15638 8813 15638 8817 15639 8814 15639 8556 15639 8817 15640 8556 15640 8558 15640 8815 15641 8814 15641 8817 15641 8819 15642 8811 15642 8816 15642 8559 15643 8817 15643 8558 15643 8818 15644 8817 15644 8559 15644 8819 15645 8816 15645 8815 15645 8820 15646 8817 15646 8818 15646 8818 15647 8559 15647 8561 15647 8820 15648 8815 15648 8817 15648 8819 15649 8815 15649 8820 15649 8563 15650 8818 15650 8561 15650 8821 15651 8818 15651 8563 15651 8821 15652 8820 15652 8818 15652 8822 15653 8819 15653 8820 15653 8821 15654 8822 15654 8820 15654 8564 15655 8821 15655 8563 15655 8823 15656 8822 15656 8821 15656 8823 15657 8821 15657 8564 15657 8824 15658 8564 15658 8566 15658 8823 15659 8564 15659 8824 15659 8825 15660 8822 15660 8823 15660 8825 15661 8823 15661 8824 15661 8826 15662 8824 15662 8566 15662 8826 15663 8566 15663 8567 15663 8827 15664 8822 15664 8825 15664 8826 15665 8825 15665 8824 15665 8826 15666 8567 15666 8568 15666 8828 15667 8825 15667 8826 15667 8827 15668 8825 15668 8828 15668 8828 15669 8826 15669 8568 15669 8829 15670 8828 15670 8568 15670 8830 15671 8827 15671 8828 15671 8831 15672 8828 15672 8829 15672 8830 15673 8828 15673 8831 15673 8570 15674 8831 15674 8829 15674 8832 15675 8827 15675 8830 15675 8830 15676 8831 15676 8833 15676 8833 15677 8831 15677 8570 15677 8834 15678 8830 15678 8833 15678 8832 15679 8836 15679 8827 15679 8832 15680 8830 15680 8834 15680 8835 15681 8833 15681 8570 15681 8835 15682 8834 15682 8833 15682 8572 15683 8835 15683 8570 15683 8836 15684 8832 15684 8834 15684 8837 15685 8834 15685 8835 15685 8573 15686 8835 15686 8572 15686 8836 15687 8834 15687 8837 15687 8837 15688 8835 15688 8573 15688 8838 15689 8837 15689 8573 15689 8838 15690 8573 15690 8575 15690 8839 15691 8836 15691 8837 15691 8839 15692 8837 15692 8838 15692 8840 15693 8838 15693 8575 15693 8840 15694 8839 15694 8838 15694 8842 15695 8836 15695 8839 15695 8577 15696 8840 15696 8575 15696 8841 15697 8839 15697 8840 15697 8843 15698 8840 15698 8577 15698 8842 15699 8839 15699 8841 15699 8841 15700 8840 15700 8843 15700 8578 15701 8843 15701 8577 15701 8844 15702 8841 15702 8843 15702 8844 15703 8842 15703 8841 15703 8845 15704 8843 15704 8578 15704 8846 15705 8842 15705 8844 15705 8844 15706 8843 15706 8845 15706 8845 15707 8578 15707 8580 15707 8847 15708 8844 15708 8845 15708 8582 15709 8845 15709 8580 15709 8848 15710 8844 15710 8847 15710 8848 15711 8846 15711 8844 15711 8847 15712 8845 15712 8582 15712 8849 15713 8847 15713 8582 15713 8850 15714 8848 15714 8847 15714 8849 15715 8582 15715 8583 15715 8850 15716 8847 15716 8849 15716 8851 15717 8583 15717 8584 15717 8851 15718 8849 15718 8583 15718 8851 15719 8850 15719 8849 15719 8852 15720 8851 15720 8584 15720 8854 15721 8851 15721 8852 15721 8853 15722 8848 15722 8850 15722 8854 15723 8850 15723 8851 15723 8853 15724 8850 15724 8854 15724 8520 15725 8852 15725 8584 15725 8852 15726 8520 15726 8755 15726 8852 15727 8755 15727 8854 15727 7861 15728 8819 15728 8822 15728 7863 15729 8819 15729 7861 15729 7861 15730 8822 15730 8827 15730 7863 15731 8811 15731 8819 15731 7864 15732 8811 15732 7863 15732 7859 15733 7861 15733 8827 15733 7866 15734 8811 15734 7864 15734 7866 15735 8808 15735 8811 15735 7857 15736 7859 15736 8827 15736 7857 15737 8827 15737 8836 15737 7868 15738 8808 15738 7866 15738 7868 15739 8800 15739 8808 15739 7855 15740 7857 15740 8836 15740 7870 15741 8800 15741 7868 15741 7853 15742 8836 15742 8842 15742 7853 15743 7855 15743 8836 15743 7870 15744 8794 15744 8800 15744 7872 15745 8794 15745 7870 15745 7851 15746 7853 15746 8842 15746 7874 15747 8794 15747 7872 15747 8846 15748 7851 15748 8842 15748 8788 15749 8794 15749 7874 15749 8846 15750 7849 15750 7851 15750 8788 15751 7874 15751 7876 15751 8848 15752 7849 15752 8846 15752 8848 15753 7847 15753 7849 15753 8788 15754 7876 15754 7878 15754 8853 15755 7847 15755 8848 15755 8781 15756 8788 15756 7878 15756 8758 15757 7847 15757 8853 15757 8758 15758 7845 15758 7847 15758 8781 15759 7878 15759 7880 15759 8776 15760 8781 15760 7880 15760 8758 15761 7885 15761 7845 15761 8763 15762 7885 15762 8758 15762 8770 15763 8776 15763 7880 15763 8770 15764 7880 15764 7882 15764 8763 15765 7883 15765 7885 15765 8770 15766 7882 15766 7883 15766 8763 15767 8770 15767 7883 15767 8857 15768 8855 15768 8856 15768 8858 15769 8857 15769 8856 15769 8858 15770 8856 15770 8859 15770 8860 15771 8858 15771 8859 15771 8861 15772 8860 15772 8859 15772 8861 15773 8859 15773 8862 15773 8863 15774 8861 15774 8862 15774 8864 15775 8863 15775 8862 15775 8865 15776 8864 15776 8862 15776 8865 15777 8862 15777 8866 15777 9125 15778 8865 15778 8866 15778 8867 15779 9125 15779 8866 15779 8867 15780 8866 15780 8868 15780 8869 15781 8867 15781 8868 15781 8869 15782 8868 15782 8870 15782 8871 15783 8869 15783 8870 15783 8872 15784 8870 15784 8873 15784 8872 15785 8871 15785 8870 15785 8874 15786 8872 15786 8873 15786 8875 15787 8874 15787 8873 15787 8876 15788 8873 15788 8877 15788 8876 15789 8875 15789 8873 15789 8878 15790 8876 15790 8877 15790 8879 15791 8878 15791 8877 15791 8879 15792 8877 15792 8880 15792 8881 15793 8879 15793 8880 15793 8882 15794 8881 15794 8880 15794 8883 15795 8882 15795 8880 15795 8883 15796 8880 15796 8884 15796 8885 15797 8883 15797 8884 15797 8886 15798 8884 15798 8887 15798 8886 15799 8885 15799 8884 15799 8888 15800 8886 15800 8887 15800 8888 15801 8887 15801 8889 15801 8890 15802 8888 15802 8889 15802 8891 15803 8890 15803 8889 15803 8891 15804 8889 15804 8892 15804 9161 15805 8891 15805 8892 15805 8893 15806 9161 15806 8892 15806 8894 15807 8893 15807 8892 15807 8894 15808 8892 15808 8895 15808 8896 15809 8894 15809 8895 15809 8897 15810 8896 15810 8895 15810 8897 15811 8895 15811 8898 15811 8899 15812 8897 15812 8898 15812 8900 15813 8899 15813 8898 15813 8900 15814 8898 15814 8901 15814 8902 15815 8900 15815 8901 15815 8903 15816 8902 15816 8901 15816 9177 15817 8901 15817 8904 15817 9177 15818 8903 15818 8901 15818 8905 15819 9177 15819 8904 15819 8906 15820 8905 15820 8904 15820 8907 15821 8906 15821 8904 15821 8908 15822 8904 15822 8909 15822 8908 15823 8907 15823 8904 15823 8910 15824 8908 15824 8909 15824 8911 15825 8910 15825 8909 15825 8912 15826 8911 15826 8909 15826 8912 15827 8909 15827 8913 15827 8914 15828 8912 15828 8913 15828 8914 15829 8913 15829 8915 15829 8916 15830 8914 15830 8915 15830 8917 15831 8916 15831 8915 15831 8918 15832 8917 15832 8915 15832 8918 15833 8915 15833 8919 15833 8920 15834 8918 15834 8919 15834 8921 15835 8919 15835 8922 15835 8921 15836 8920 15836 8919 15836 8923 15837 8921 15837 8922 15837 8923 15838 8922 15838 8924 15838 8925 15839 8923 15839 8924 15839 8926 15840 8925 15840 8924 15840 8926 15841 8924 15841 8927 15841 8928 15842 8926 15842 8927 15842 8929 15843 8928 15843 8927 15843 8930 15844 8929 15844 8927 15844 8930 15845 8927 15845 8931 15845 8932 15846 8930 15846 8931 15846 8933 15847 8932 15847 8931 15847 8855 15848 8933 15848 8931 15848 8855 15849 8931 15849 8856 15849 8934 15850 8935 15850 9112 15850 8936 15851 9112 15851 8937 15851 8936 15852 8934 15852 9112 15852 8936 15853 8937 15853 8938 15853 8939 15854 8938 15854 8940 15854 8939 15855 8936 15855 8938 15855 8939 15856 8940 15856 9102 15856 8939 15857 9102 15857 8941 15857 8942 15858 8939 15858 8941 15858 8942 15859 8941 15859 8943 15859 8942 15860 8943 15860 8944 15860 8942 15861 8944 15861 9095 15861 8945 15862 8942 15862 9095 15862 8945 15863 9095 15863 8946 15863 8945 15864 8946 15864 8947 15864 8945 15865 8947 15865 8948 15865 8949 15866 8945 15866 8948 15866 8949 15867 8948 15867 8950 15867 8951 15868 8949 15868 8950 15868 8951 15869 8950 15869 8952 15869 8951 15870 8952 15870 8953 15870 8951 15871 8953 15871 8954 15871 8955 15872 8951 15872 8954 15872 8955 15873 8954 15873 8956 15873 8957 15874 8955 15874 8956 15874 8957 15875 8956 15875 8958 15875 8957 15876 8958 15876 8959 15876 8957 15877 8959 15877 8960 15877 8957 15878 8960 15878 8961 15878 8962 15879 8957 15879 8961 15879 8962 15880 8961 15880 8963 15880 8962 15881 8963 15881 8964 15881 8962 15882 8964 15882 8965 15882 8966 15883 8962 15883 8965 15883 8967 15884 8965 15884 8968 15884 8967 15885 8966 15885 8965 15885 8967 15886 8968 15886 8969 15886 8970 15887 8969 15887 8971 15887 8970 15888 8967 15888 8969 15888 8970 15889 8971 15889 8972 15889 8973 15890 8970 15890 8972 15890 8973 15891 8972 15891 8974 15891 8973 15892 8974 15892 9052 15892 8973 15893 9052 15893 9049 15893 8975 15894 8973 15894 9049 15894 8975 15895 9049 15895 8976 15895 8977 15896 8976 15896 8978 15896 8977 15897 8975 15897 8976 15897 8977 15898 8978 15898 8979 15898 8980 15899 8979 15899 9041 15899 8980 15900 8977 15900 8979 15900 8980 15901 9041 15901 8981 15901 8980 15902 8981 15902 8982 15902 8983 15903 8980 15903 8982 15903 8983 15904 8982 15904 9033 15904 8984 15905 8983 15905 9033 15905 8984 15906 9033 15906 8985 15906 8984 15907 8985 15907 8986 15907 8987 15908 8984 15908 8986 15908 8987 15909 8986 15909 8988 15909 8987 15910 8988 15910 8989 15910 8987 15911 8989 15911 8990 15911 8991 15912 8990 15912 8992 15912 8991 15913 8987 15913 8990 15913 8993 15914 8991 15914 8992 15914 8993 15915 8992 15915 9019 15915 8993 15916 9019 15916 8994 15916 8995 15917 8994 15917 8996 15917 8995 15918 8993 15918 8994 15918 8995 15919 8996 15919 8997 15919 8998 15920 8995 15920 8997 15920 8998 15921 8997 15921 9010 15921 8998 15922 9010 15922 8999 15922 8998 15923 8999 15923 9000 15923 8934 15924 8998 15924 9000 15924 8934 15925 9000 15925 9001 15925 8934 15926 9001 15926 8935 15926 9001 15927 9002 15927 8935 15927 9005 15928 9002 15928 9001 15928 9006 15929 9004 15929 9003 15929 9008 15930 9004 15930 9006 15930 9005 15931 9003 15931 9002 15931 9006 15932 9003 15932 9005 15932 9000 15933 9005 15933 9001 15933 8999 15934 9005 15934 9000 15934 9007 15935 9005 15935 8999 15935 9007 15936 9006 15936 9005 15936 9008 15937 9006 15937 9007 15937 9009 15938 9007 15938 8999 15938 9009 15939 9008 15939 9007 15939 9010 15940 9009 15940 8999 15940 9011 15941 9010 15941 8997 15941 9012 15942 9008 15942 9009 15942 9011 15943 9009 15943 9010 15943 9013 15944 9009 15944 9011 15944 9015 15945 9008 15945 9012 15945 9012 15946 9009 15946 9013 15946 9011 15947 8997 15947 8996 15947 9014 15948 9013 15948 9011 15948 9014 15949 9012 15949 9013 15949 9015 15950 9012 15950 9014 15950 9014 15951 9011 15951 8996 15951 9016 15952 9015 15952 9014 15952 9017 15953 8996 15953 8994 15953 9017 15954 9014 15954 8996 15954 9016 15955 9014 15955 9017 15955 9018 15956 9015 15956 9016 15956 9019 15957 9017 15957 8994 15957 9020 15958 9017 15958 9019 15958 9021 15959 9017 15959 9020 15959 9021 15960 9016 15960 9017 15960 8992 15961 9020 15961 9019 15961 9021 15962 9018 15962 9016 15962 9022 15963 9020 15963 8992 15963 9022 15964 9021 15964 9020 15964 8990 15965 9022 15965 8992 15965 9024 15966 9021 15966 9022 15966 9023 15967 9022 15967 8990 15967 9024 15968 9018 15968 9021 15968 9024 15969 9022 15969 9023 15969 8989 15970 9023 15970 8990 15970 9025 15971 9023 15971 8989 15971 9025 15972 9024 15972 9023 15972 9026 15973 9024 15973 9025 15973 9027 15974 9018 15974 9024 15974 9028 15975 8989 15975 8988 15975 9025 15976 8989 15976 9028 15976 9027 15977 9024 15977 9026 15977 8986 15978 9028 15978 8988 15978 9029 15979 9025 15979 9028 15979 9029 15980 9026 15980 9025 15980 9027 15981 9026 15981 9029 15981 9030 15982 9028 15982 8986 15982 9030 15983 9029 15983 9028 15983 9031 15984 9029 15984 9030 15984 8985 15985 9030 15985 8986 15985 9027 15986 9029 15986 9031 15986 9031 15987 9030 15987 8985 15987 9032 15988 9027 15988 9031 15988 9033 15989 9031 15989 8985 15989 9034 15990 9031 15990 9033 15990 9034 15991 9032 15991 9031 15991 9035 15992 9033 15992 8982 15992 9036 15993 9032 15993 9034 15993 9035 15994 9034 15994 9033 15994 9037 15995 9034 15995 9035 15995 8981 15996 9035 15996 8982 15996 9037 15997 9036 15997 9034 15997 9037 15998 9035 15998 8981 15998 9039 15999 9036 15999 9038 15999 9038 16000 9036 16000 9037 16000 9040 16001 9037 16001 8981 16001 9038 16002 9037 16002 9040 16002 9041 16003 9040 16003 8981 16003 9042 16004 9038 16004 9040 16004 8979 16005 9040 16005 9041 16005 9042 16006 9039 16006 9038 16006 9043 16007 9040 16007 8979 16007 9042 16008 9040 16008 9043 16008 9044 16009 9039 16009 9042 16009 9045 16010 8979 16010 8978 16010 9045 16011 9043 16011 8979 16011 9046 16012 9042 16012 9043 16012 9044 16013 9042 16013 9046 16013 9046 16014 9043 16014 9045 16014 9047 16015 9045 16015 8978 16015 9046 16016 9045 16016 9047 16016 9047 16017 8978 16017 8976 16017 9048 16018 9044 16018 9046 16018 9049 16019 9047 16019 8976 16019 9050 16020 9047 16020 9049 16020 9051 16021 9047 16021 9050 16021 9051 16022 9046 16022 9047 16022 9051 16023 9048 16023 9046 16023 9052 16024 9050 16024 9049 16024 9053 16025 9048 16025 9051 16025 9054 16026 9050 16026 9052 16026 9051 16027 9050 16027 9054 16027 9053 16028 9051 16028 9054 16028 8974 16029 9054 16029 9052 16029 9055 16030 9054 16030 8974 16030 9055 16031 9053 16031 9054 16031 9055 16032 8974 16032 8972 16032 9056 16033 9053 16033 9055 16033 9056 16034 9055 16034 9057 16034 9058 16035 8972 16035 8971 16035 9058 16036 9055 16036 8972 16036 9057 16037 9055 16037 9058 16037 8969 16038 9058 16038 8971 16038 9059 16039 9056 16039 9057 16039 9060 16040 9056 16040 9059 16040 9059 16041 9057 16041 9058 16041 9061 16042 9058 16042 8969 16042 9059 16043 9058 16043 9061 16043 9060 16044 9059 16044 9062 16044 9062 16045 9059 16045 9061 16045 8968 16046 9061 16046 8969 16046 9063 16047 9061 16047 8968 16047 9063 16048 9062 16048 9061 16048 9063 16049 8968 16049 8965 16049 9064 16050 9060 16050 9062 16050 9065 16051 9062 16051 9063 16051 9066 16052 9063 16052 8965 16052 9064 16053 9062 16053 9065 16053 9065 16054 9063 16054 9066 16054 9067 16055 9065 16055 9066 16055 9068 16056 9066 16056 8965 16056 9069 16057 9065 16057 9067 16057 9069 16058 9064 16058 9065 16058 9067 16059 9066 16059 9068 16059 8964 16060 9068 16060 8965 16060 9070 16061 9068 16061 8964 16061 9067 16062 9068 16062 9070 16062 9064 16063 9071 16063 9060 16063 9070 16064 8964 16064 8963 16064 9071 16065 9064 16065 9069 16065 9072 16066 9067 16066 9070 16066 9072 16067 9069 16067 9067 16067 9071 16068 9069 16068 9072 16068 9070 16069 8963 16069 8961 16069 9071 16070 9072 16070 9073 16070 9073 16071 9070 16071 8961 16071 9073 16072 9072 16072 9070 16072 9074 16073 8961 16073 8960 16073 9074 16074 9073 16074 8961 16074 9075 16075 9073 16075 9074 16075 8959 16076 9074 16076 8960 16076 9075 16077 9071 16077 9073 16077 9076 16078 9074 16078 8959 16078 9077 16079 9074 16079 9076 16079 9077 16080 9075 16080 9074 16080 8958 16081 9076 16081 8959 16081 9077 16082 9076 16082 8958 16082 9078 16083 9077 16083 8958 16083 9078 16084 8958 16084 8956 16084 9079 16085 9075 16085 9077 16085 9079 16086 9077 16086 9078 16086 8954 16087 9078 16087 8956 16087 9080 16088 9075 16088 9079 16088 9081 16089 9078 16089 8954 16089 9082 16090 9078 16090 9081 16090 8953 16091 9081 16091 8954 16091 9082 16092 9079 16092 9078 16092 9083 16093 9079 16093 9082 16093 9080 16094 9079 16094 9083 16094 9083 16095 9082 16095 9081 16095 9084 16096 9081 16096 8953 16096 9084 16097 9083 16097 9081 16097 8952 16098 9084 16098 8953 16098 9085 16099 9083 16099 9084 16099 9080 16100 9083 16100 9085 16100 9086 16101 8952 16101 8950 16101 9086 16102 9084 16102 8952 16102 9087 16103 9084 16103 9086 16103 9087 16104 9085 16104 9084 16104 9088 16105 9087 16105 9086 16105 9089 16106 9086 16106 8950 16106 9090 16107 9085 16107 9087 16107 9089 16108 9088 16108 9086 16108 9091 16109 9087 16109 9088 16109 8948 16110 9089 16110 8950 16110 9091 16111 9090 16111 9087 16111 9091 16112 9088 16112 9089 16112 8947 16113 9089 16113 8948 16113 9093 16114 9089 16114 8947 16114 9092 16115 9090 16115 9091 16115 9093 16116 9091 16116 9089 16116 9094 16117 9091 16117 9093 16117 8946 16118 9093 16118 8947 16118 9094 16119 9092 16119 9091 16119 9094 16120 9093 16120 8946 16120 9096 16121 9092 16121 9094 16121 9097 16122 8946 16122 9095 16122 9097 16123 9094 16123 8946 16123 9097 16124 9096 16124 9094 16124 9098 16125 9095 16125 8944 16125 9098 16126 9097 16126 9095 16126 9100 16127 9097 16127 9098 16127 8943 16128 9098 16128 8944 16128 9099 16129 9097 16129 9100 16129 9100 16130 9098 16130 8943 16130 9099 16131 9096 16131 9097 16131 8941 16132 9100 16132 8943 16132 9101 16133 9100 16133 8941 16133 9099 16134 9100 16134 9101 16134 9104 16135 9096 16135 9099 16135 9103 16136 8941 16136 9102 16136 9103 16137 9101 16137 8941 16137 9104 16138 9099 16138 9101 16138 9104 16139 9101 16139 9103 16139 9105 16140 9102 16140 8940 16140 9105 16141 9103 16141 9102 16141 9106 16142 9103 16142 9105 16142 9104 16143 9103 16143 9106 16143 8938 16144 9105 16144 8940 16144 9109 16145 9105 16145 8938 16145 9108 16146 9104 16146 9106 16146 9107 16147 9104 16147 9108 16147 9109 16148 9106 16148 9105 16148 9108 16149 9106 16149 9109 16149 9110 16150 9109 16150 8938 16150 9110 16151 9108 16151 9109 16151 8937 16152 9110 16152 8938 16152 9004 16153 9108 16153 9110 16153 9004 16154 9110 16154 9111 16154 9112 16155 9110 16155 8937 16155 9004 16156 9107 16156 9108 16156 9111 16157 9110 16157 9112 16157 9112 16158 8935 16158 9002 16158 9111 16159 9112 16159 9002 16159 9111 16160 9002 16160 9003 16160 9003 16161 9004 16161 9111 16161 8644 16162 9018 16162 8641 16162 8644 16163 9015 16163 9018 16163 8646 16164 9015 16164 8644 16164 8638 16165 8641 16165 9018 16165 8646 16166 9008 16166 9015 16166 8635 16167 8638 16167 9018 16167 8650 16168 9008 16168 8646 16168 8635 16169 9018 16169 9027 16169 8586 16170 9004 16170 9008 16170 8586 16171 9008 16171 8650 16171 8633 16172 8635 16172 9027 16172 8633 16173 9027 16173 9032 16173 8589 16174 9107 16174 9004 16174 8589 16175 9004 16175 8586 16175 8630 16176 8633 16176 9032 16176 9036 16177 8630 16177 9032 16177 9039 16178 8630 16178 9036 16178 8591 16179 9107 16179 8589 16179 8591 16180 9104 16180 9107 16180 8628 16181 8630 16181 9039 16181 8593 16182 9104 16182 8591 16182 9044 16183 8628 16183 9039 16183 8593 16184 9096 16184 9104 16184 8626 16185 8628 16185 9044 16185 8596 16186 9096 16186 8593 16186 9048 16187 8626 16187 9044 16187 9048 16188 8623 16188 8626 16188 9096 16189 8596 16189 8599 16189 9092 16190 9096 16190 8599 16190 9090 16191 9092 16191 8599 16191 9053 16192 8620 16192 8623 16192 9053 16193 8623 16193 9048 16193 9090 16194 8599 16194 8602 16194 9056 16195 8620 16195 9053 16195 9085 16196 9090 16196 8602 16196 9056 16197 8617 16197 8620 16197 9080 16198 9085 16198 8602 16198 9060 16199 8617 16199 9056 16199 9080 16200 8602 16200 8605 16200 9060 16201 8615 16201 8617 16201 9075 16202 9080 16202 8605 16202 9060 16203 8613 16203 8615 16203 9075 16204 8605 16204 8608 16204 9071 16205 8613 16205 9060 16205 9071 16206 8611 16206 8613 16206 9075 16207 8608 16207 8611 16207 9071 16208 9075 16208 8611 16208 8857 16209 9113 16209 8855 16209 9114 16210 9113 16210 9116 16210 9117 16211 9115 16211 9114 16211 9116 16212 9113 16212 8857 16212 9117 16213 9114 16213 9116 16213 9116 16214 8857 16214 8858 16214 9118 16215 9117 16215 9116 16215 8860 16216 9116 16216 8858 16216 9118 16217 9116 16217 8860 16217 9119 16218 9118 16218 8860 16218 9119 16219 8860 16219 8861 16219 9121 16220 9117 16220 9118 16220 9120 16221 9118 16221 9119 16221 9121 16222 9118 16222 9120 16222 9122 16223 9117 16223 9121 16223 8863 16224 9119 16224 8861 16224 9120 16225 9119 16225 8863 16225 9123 16226 9120 16226 8863 16226 9123 16227 9121 16227 9120 16227 9124 16228 8863 16228 8864 16228 9122 16229 9121 16229 9123 16229 9124 16230 9123 16230 8863 16230 9124 16231 8864 16231 8865 16231 9125 16232 9124 16232 8865 16232 9126 16233 9124 16233 9125 16233 9126 16234 9123 16234 9124 16234 9127 16235 9123 16235 9126 16235 9127 16236 9122 16236 9123 16236 9128 16237 9126 16237 9125 16237 9129 16238 9126 16238 9128 16238 9128 16239 9125 16239 8867 16239 9129 16240 9127 16240 9126 16240 9130 16241 9122 16241 9127 16241 9131 16242 9127 16242 9129 16242 9130 16243 9127 16243 9131 16243 9131 16244 9129 16244 9128 16244 9132 16245 9128 16245 8867 16245 9132 16246 9131 16246 9128 16246 9132 16247 8867 16247 8869 16247 9133 16248 9131 16248 9132 16248 9134 16249 9132 16249 8869 16249 9130 16250 9131 16250 9133 16250 9134 16251 9133 16251 9132 16251 9134 16252 8869 16252 8871 16252 9135 16253 9130 16253 9133 16253 9136 16254 9134 16254 8871 16254 9136 16255 9133 16255 9134 16255 9136 16256 8871 16256 8872 16256 9137 16257 9133 16257 9136 16257 9137 16258 9135 16258 9133 16258 8874 16259 9136 16259 8872 16259 9138 16260 9136 16260 8874 16260 9138 16261 9137 16261 9136 16261 9139 16262 9135 16262 9137 16262 9140 16263 8874 16263 8875 16263 9139 16264 9137 16264 9138 16264 9140 16265 9138 16265 8874 16265 9139 16266 9138 16266 9140 16266 8876 16267 9140 16267 8875 16267 9141 16268 9140 16268 8876 16268 9142 16269 9135 16269 9139 16269 9143 16270 9140 16270 9141 16270 9143 16271 9139 16271 9140 16271 8878 16272 9141 16272 8876 16272 9142 16273 9139 16273 9143 16273 9142 16274 9145 16274 9135 16274 9144 16275 9141 16275 8878 16275 9144 16276 9143 16276 9141 16276 9144 16277 9142 16277 9143 16277 9146 16278 8878 16278 8879 16278 9146 16279 9144 16279 8878 16279 9147 16280 9144 16280 9146 16280 9147 16281 9142 16281 9144 16281 9145 16282 9142 16282 9147 16282 9146 16283 8879 16283 8881 16283 9148 16284 9147 16284 9146 16284 9145 16285 9147 16285 9148 16285 9148 16286 9146 16286 8881 16286 9149 16287 8881 16287 8882 16287 9150 16288 9145 16288 9148 16288 9149 16289 9148 16289 8881 16289 8883 16290 9149 16290 8882 16290 9150 16291 9148 16291 9149 16291 9151 16292 9149 16292 8883 16292 9151 16293 9150 16293 9149 16293 9152 16294 9150 16294 9151 16294 9153 16295 8883 16295 8885 16295 9153 16296 9151 16296 8883 16296 9154 16297 9151 16297 9153 16297 9152 16298 9151 16298 9154 16298 9153 16299 8885 16299 8886 16299 9154 16300 9153 16300 8886 16300 9155 16301 9154 16301 8886 16301 9156 16302 9154 16302 9155 16302 9155 16303 8886 16303 8888 16303 9157 16304 9154 16304 9156 16304 9157 16305 9152 16305 9154 16305 9158 16306 9155 16306 8888 16306 9158 16307 9156 16307 9155 16307 8890 16308 9158 16308 8888 16308 8891 16309 9158 16309 8890 16309 9159 16310 9158 16310 8891 16310 9159 16311 9156 16311 9158 16311 9160 16312 9156 16312 9159 16312 9160 16313 9157 16313 9156 16313 9159 16314 8891 16314 9161 16314 9162 16315 9159 16315 9161 16315 9163 16316 9159 16316 9162 16316 9163 16317 9160 16317 9159 16317 9162 16318 9161 16318 8893 16318 9164 16319 9162 16319 8893 16319 9164 16320 9163 16320 9162 16320 9164 16321 8893 16321 8894 16321 9165 16322 9160 16322 9163 16322 9166 16323 9164 16323 8894 16323 9166 16324 8894 16324 8896 16324 9165 16325 9163 16325 9164 16325 9167 16326 9164 16326 9166 16326 9167 16327 9165 16327 9164 16327 8897 16328 9166 16328 8896 16328 9167 16329 9166 16329 8897 16329 9168 16330 9167 16330 8897 16330 9169 16331 9167 16331 9168 16331 9169 16332 9165 16332 9167 16332 9168 16333 8897 16333 8899 16333 9172 16334 9165 16334 9169 16334 9170 16335 8899 16335 8900 16335 9170 16336 9168 16336 8899 16336 9170 16337 9169 16337 9168 16337 9171 16338 9169 16338 9170 16338 8902 16339 9170 16339 8900 16339 9172 16340 9169 16340 9171 16340 9173 16341 9170 16341 8902 16341 9173 16342 9171 16342 9170 16342 9174 16343 9171 16343 9173 16343 9173 16344 8902 16344 8903 16344 9174 16345 9172 16345 9171 16345 9176 16346 9173 16346 8903 16346 9175 16347 9172 16347 9174 16347 9176 16348 9174 16348 9173 16348 9176 16349 8903 16349 9177 16349 9178 16350 9176 16350 9177 16350 9178 16351 9174 16351 9176 16351 9178 16352 9177 16352 8905 16352 9179 16353 9174 16353 9178 16353 9179 16354 9175 16354 9174 16354 9180 16355 8905 16355 8906 16355 9180 16356 9178 16356 8905 16356 9180 16357 9179 16357 9178 16357 8907 16358 9180 16358 8906 16358 9181 16359 9180 16359 8907 16359 9182 16360 9180 16360 9181 16360 9182 16361 9179 16361 9180 16361 9175 16362 9179 16362 9182 16362 9183 16363 8907 16363 8908 16363 9183 16364 9181 16364 8907 16364 9184 16365 9175 16365 9182 16365 8910 16366 9183 16366 8908 16366 9184 16367 9182 16367 9181 16367 9185 16368 9183 16368 8910 16368 9185 16369 9181 16369 9183 16369 9184 16370 9181 16370 9185 16370 9186 16371 9184 16371 9185 16371 9185 16372 8910 16372 8911 16372 9187 16373 8911 16373 8912 16373 9187 16374 9185 16374 8911 16374 9188 16375 9185 16375 9187 16375 9189 16376 9184 16376 9186 16376 9188 16377 9186 16377 9185 16377 9189 16378 9186 16378 9188 16378 8914 16379 9187 16379 8912 16379 9190 16380 9187 16380 8914 16380 9190 16381 9188 16381 9187 16381 9189 16382 9188 16382 9190 16382 8916 16383 9190 16383 8914 16383 9191 16384 9189 16384 9190 16384 9191 16385 9190 16385 9192 16385 9192 16386 8916 16386 8917 16386 9192 16387 9190 16387 8916 16387 9194 16388 9191 16388 9192 16388 9193 16389 9192 16389 8917 16389 9194 16390 9192 16390 9193 16390 8918 16391 9193 16391 8917 16391 9195 16392 9193 16392 8918 16392 9195 16393 9194 16393 9193 16393 9196 16394 9191 16394 9194 16394 9195 16395 8918 16395 8920 16395 9197 16396 9194 16396 9195 16396 9198 16397 9195 16397 8920 16397 9196 16398 9194 16398 9197 16398 9198 16399 9197 16399 9195 16399 9198 16400 8920 16400 8921 16400 9199 16401 9197 16401 9198 16401 9200 16402 9198 16402 8921 16402 9200 16403 9199 16403 9198 16403 9196 16404 9197 16404 9199 16404 8923 16405 9200 16405 8921 16405 9201 16406 9200 16406 8923 16406 9202 16407 9196 16407 9199 16407 9201 16408 9199 16408 9200 16408 8925 16409 9201 16409 8923 16409 9203 16410 9199 16410 9201 16410 9203 16411 9202 16411 9199 16411 8926 16412 9201 16412 8925 16412 9204 16413 9201 16413 8926 16413 9204 16414 9203 16414 9201 16414 9205 16415 9202 16415 9203 16415 8928 16416 9204 16416 8926 16416 9205 16417 9203 16417 9204 16417 9206 16418 9204 16418 8928 16418 9206 16419 8928 16419 8929 16419 9207 16420 9204 16420 9206 16420 9207 16421 9205 16421 9204 16421 9208 16422 9206 16422 8929 16422 9208 16423 9207 16423 9206 16423 9209 16424 9207 16424 9208 16424 8930 16425 9208 16425 8929 16425 9209 16426 9205 16426 9207 16426 9210 16427 9208 16427 8930 16427 9211 16428 9205 16428 9209 16428 9209 16429 9208 16429 9210 16429 9210 16430 8930 16430 8932 16430 9213 16431 9210 16431 9212 16431 9213 16432 9209 16432 9210 16432 8933 16433 9210 16433 8932 16433 9213 16434 9211 16434 9209 16434 9212 16435 9210 16435 8933 16435 8933 16436 8855 16436 9113 16436 9212 16437 8933 16437 9113 16437 9212 16438 9113 16438 9114 16438 9114 16439 9213 16439 9212 16439 9115 16440 9213 16440 9114 16440 9211 16441 9213 16441 9115 16441 8562 16442 8560 16442 9175 16442 8557 16443 9175 16443 8560 16443 8557 16444 9172 16444 9175 16444 8565 16445 8562 16445 9175 16445 8565 16446 9175 16446 9184 16446 8555 16447 9172 16447 8557 16447 8569 16448 8565 16448 9184 16448 8552 16449 9172 16449 8555 16449 8552 16450 9165 16450 9172 16450 8569 16451 9184 16451 9189 16451 8571 16452 8569 16452 9189 16452 8551 16453 9165 16453 8552 16453 8571 16454 9189 16454 9191 16454 8551 16455 9160 16455 9165 16455 8549 16456 9160 16456 8551 16456 8574 16457 8571 16457 9191 16457 8574 16458 9191 16458 9196 16458 8549 16459 9157 16459 9160 16459 8546 16460 9157 16460 8549 16460 8546 16461 9152 16461 9157 16461 8576 16462 8574 16462 9196 16462 8576 16463 9196 16463 9202 16463 8543 16464 9152 16464 8546 16464 9202 16465 8579 16465 8576 16465 9150 16466 9152 16466 8543 16466 9205 16467 8579 16467 9202 16467 9205 16468 8581 16468 8579 16468 9145 16469 9150 16469 8543 16469 8539 16470 9145 16470 8543 16470 9211 16471 8581 16471 9205 16471 9211 16472 8585 16472 8581 16472 9145 16473 8539 16473 8536 16473 9135 16474 9145 16474 8536 16474 9211 16475 8521 16475 8585 16475 9115 16476 8521 16476 9211 16476 9135 16477 8536 16477 8533 16477 9117 16478 8521 16478 9115 16478 9117 16479 8523 16479 8521 16479 9122 16480 8523 16480 9117 16480 9130 16481 8533 16481 8529 16481 9130 16482 9135 16482 8533 16482 9122 16483 8527 16483 8523 16483 9130 16484 8529 16484 8527 16484 9122 16485 9130 16485 8527 16485 9216 16486 9214 16486 9215 16486 9217 16487 9216 16487 9215 16487 9217 16488 9215 16488 9218 16488 9219 16489 9217 16489 9218 16489 9219 16490 9218 16490 9220 16490 9221 16491 9219 16491 9220 16491 9222 16492 9221 16492 9220 16492 9222 16493 9220 16493 9223 16493 9224 16494 9222 16494 9223 16494 9225 16495 9224 16495 9223 16495 9225 16496 9223 16496 9226 16496 9227 16497 9225 16497 9226 16497 9227 16498 9226 16498 9228 16498 9229 16499 9227 16499 9228 16499 9230 16500 9229 16500 9228 16500 9230 16501 9228 16501 9231 16501 9232 16502 9230 16502 9231 16502 9232 16503 9231 16503 9233 16503 9234 16504 9232 16504 9233 16504 9235 16505 9234 16505 9233 16505 9235 16506 9233 16506 9236 16506 9237 16507 9235 16507 9236 16507 9238 16508 9237 16508 9236 16508 9239 16509 9236 16509 9240 16509 9239 16510 9238 16510 9236 16510 9241 16511 9239 16511 9240 16511 9241 16512 9240 16512 9242 16512 9243 16513 9241 16513 9242 16513 9244 16514 9243 16514 9242 16514 9244 16515 9242 16515 9245 16515 9246 16516 9244 16516 9245 16516 9247 16517 9246 16517 9245 16517 9247 16518 9245 16518 9248 16518 9249 16519 9247 16519 9248 16519 9250 16520 9249 16520 9248 16520 9250 16521 9248 16521 9251 16521 9252 16522 9250 16522 9251 16522 9253 16523 9252 16523 9251 16523 9253 16524 9251 16524 9254 16524 9255 16525 9253 16525 9254 16525 9256 16526 9255 16526 9254 16526 9257 16527 9256 16527 9254 16527 9257 16528 9254 16528 9258 16528 9259 16529 9257 16529 9258 16529 9260 16530 9259 16530 9258 16530 9261 16531 9260 16531 9258 16531 9261 16532 9258 16532 9262 16532 9263 16533 9261 16533 9262 16533 9264 16534 9263 16534 9262 16534 9264 16535 9262 16535 9265 16535 9266 16536 9264 16536 9265 16536 9267 16537 9266 16537 9265 16537 9267 16538 9265 16538 9268 16538 9269 16539 9267 16539 9268 16539 9270 16540 9269 16540 9268 16540 9271 16541 9268 16541 9272 16541 9271 16542 9270 16542 9268 16542 9273 16543 9271 16543 9272 16543 9274 16544 9273 16544 9272 16544 9275 16545 9274 16545 9272 16545 9275 16546 9272 16546 9276 16546 9277 16547 9276 16547 9278 16547 9277 16548 9275 16548 9276 16548 9279 16549 9277 16549 9278 16549 9280 16550 9278 16550 9281 16550 9280 16551 9279 16551 9278 16551 9282 16552 9280 16552 9281 16552 9283 16553 9282 16553 9281 16553 9283 16554 9281 16554 9284 16554 9285 16555 9283 16555 9284 16555 9286 16556 9285 16556 9284 16556 9287 16557 9284 16557 9288 16557 9287 16558 9286 16558 9284 16558 9289 16559 9287 16559 9288 16559 9289 16560 9288 16560 9290 16560 9291 16561 9289 16561 9290 16561 9292 16562 9291 16562 9290 16562 9293 16563 9292 16563 9290 16563 9293 16564 9290 16564 9294 16564 9295 16565 9293 16565 9294 16565 9296 16566 9295 16566 9294 16566 9296 16567 9294 16567 9297 16567 9298 16568 9296 16568 9297 16568 9298 16569 9297 16569 9215 16569 9214 16570 9298 16570 9215 16570 9299 16571 9300 16571 9301 16571 9302 16572 9299 16572 9301 16572 9302 16573 9301 16573 9303 16573 9304 16574 9302 16574 9303 16574 9304 16575 9303 16575 9305 16575 9304 16576 9305 16576 9306 16576 9307 16577 9304 16577 9306 16577 9307 16578 9306 16578 9308 16578 9307 16579 9308 16579 9309 16579 9310 16580 9307 16580 9309 16580 9310 16581 9309 16581 9478 16581 9310 16582 9478 16582 9311 16582 9312 16583 9310 16583 9311 16583 9312 16584 9311 16584 9313 16584 9314 16585 9312 16585 9313 16585 9314 16586 9313 16586 9469 16586 9314 16587 9469 16587 9315 16587 9316 16588 9314 16588 9315 16588 9316 16589 9315 16589 9317 16589 9316 16590 9317 16590 9318 16590 9319 16591 9316 16591 9318 16591 9319 16592 9318 16592 9320 16592 9321 16593 9320 16593 9322 16593 9321 16594 9319 16594 9320 16594 9321 16595 9322 16595 9323 16595 9321 16596 9323 16596 9325 16596 9324 16597 9321 16597 9325 16597 9324 16598 9325 16598 9326 16598 9324 16599 9326 16599 9327 16599 9328 16600 9324 16600 9327 16600 9328 16601 9327 16601 9329 16601 9330 16602 9328 16602 9329 16602 9330 16603 9329 16603 9331 16603 9330 16604 9331 16604 9332 16604 9333 16605 9330 16605 9332 16605 9333 16606 9332 16606 9334 16606 9333 16607 9334 16607 9335 16607 9336 16608 9333 16608 9335 16608 9336 16609 9335 16609 9337 16609 9336 16610 9337 16610 9338 16610 9339 16611 9336 16611 9338 16611 9339 16612 9338 16612 9340 16612 9341 16613 9339 16613 9340 16613 9341 16614 9340 16614 9342 16614 9341 16615 9342 16615 9432 16615 9341 16616 9432 16616 9343 16616 9344 16617 9341 16617 9343 16617 9344 16618 9343 16618 9345 16618 9346 16619 9344 16619 9345 16619 9346 16620 9345 16620 9426 16620 9346 16621 9426 16621 9347 16621 9348 16622 9346 16622 9347 16622 9348 16623 9347 16623 9349 16623 9348 16624 9349 16624 9417 16624 9350 16625 9417 16625 9351 16625 9350 16626 9348 16626 9417 16626 9350 16627 9351 16627 9352 16627 9353 16628 9350 16628 9352 16628 9353 16629 9411 16629 9354 16629 9353 16630 9352 16630 9411 16630 9353 16631 9354 16631 9355 16631 9356 16632 9353 16632 9355 16632 9356 16633 9355 16633 9357 16633 9356 16634 9357 16634 9358 16634 9359 16635 9356 16635 9358 16635 9359 16636 9358 16636 9360 16636 9359 16637 9360 16637 9361 16637 9362 16638 9361 16638 9398 16638 9362 16639 9359 16639 9361 16639 9362 16640 9398 16640 9363 16640 9364 16641 9363 16641 9365 16641 9364 16642 9362 16642 9363 16642 9364 16643 9365 16643 9366 16643 9364 16644 9366 16644 9367 16644 9368 16645 9364 16645 9367 16645 9368 16646 9367 16646 9369 16646 9370 16647 9368 16647 9369 16647 9370 16648 9369 16648 9371 16648 9370 16649 9371 16649 9385 16649 9370 16650 9385 16650 9372 16650 9373 16651 9370 16651 9372 16651 9373 16652 9372 16652 9374 16652 9373 16653 9374 16653 9375 16653 9299 16654 9375 16654 9300 16654 9299 16655 9373 16655 9375 16655 9378 16656 9300 16656 9375 16656 9378 16657 9376 16657 9300 16657 9380 16658 9376 16658 9378 16658 9380 16659 9377 16659 9376 16659 9379 16660 9377 16660 9380 16660 9379 16661 9380 16661 9381 16661 9374 16662 9378 16662 9375 16662 9382 16663 9378 16663 9374 16663 9382 16664 9380 16664 9378 16664 9381 16665 9380 16665 9382 16665 9383 16666 9379 16666 9381 16666 9372 16667 9382 16667 9374 16667 9384 16668 9381 16668 9382 16668 9383 16669 9381 16669 9384 16669 9384 16670 9382 16670 9372 16670 9384 16671 9372 16671 9385 16671 9386 16672 9384 16672 9385 16672 9386 16673 9383 16673 9384 16673 9386 16674 9385 16674 9371 16674 9387 16675 9383 16675 9386 16675 9388 16676 9386 16676 9371 16676 9369 16677 9388 16677 9371 16677 9389 16678 9386 16678 9388 16678 9387 16679 9386 16679 9389 16679 9390 16680 9388 16680 9369 16680 9390 16681 9389 16681 9388 16681 9367 16682 9390 16682 9369 16682 9391 16683 9387 16683 9389 16683 9392 16684 9390 16684 9367 16684 9393 16685 9390 16685 9392 16685 9393 16686 9389 16686 9390 16686 9391 16687 9389 16687 9393 16687 9366 16688 9392 16688 9367 16688 9394 16689 9392 16689 9366 16689 9394 16690 9393 16690 9392 16690 9395 16691 9391 16691 9393 16691 9395 16692 9393 16692 9394 16692 9394 16693 9366 16693 9365 16693 9396 16694 9394 16694 9365 16694 9397 16695 9394 16695 9396 16695 9397 16696 9395 16696 9394 16696 9363 16697 9396 16697 9365 16697 9398 16698 9396 16698 9363 16698 9401 16699 9395 16699 9397 16699 9399 16700 9396 16700 9398 16700 9399 16701 9397 16701 9396 16701 9401 16702 9397 16702 9399 16702 9400 16703 9399 16703 9398 16703 9361 16704 9400 16704 9398 16704 9402 16705 9399 16705 9400 16705 9401 16706 9399 16706 9402 16706 9360 16707 9400 16707 9361 16707 9404 16708 9400 16708 9360 16708 9404 16709 9402 16709 9400 16709 9403 16710 9401 16710 9402 16710 9405 16711 9360 16711 9358 16711 9406 16712 9402 16712 9404 16712 9406 16713 9403 16713 9402 16713 9405 16714 9404 16714 9360 16714 9406 16715 9404 16715 9405 16715 9357 16716 9405 16716 9358 16716 9407 16717 9405 16717 9357 16717 9406 16718 9405 16718 9407 16718 9408 16719 9403 16719 9406 16719 9408 16720 9406 16720 9407 16720 9355 16721 9407 16721 9357 16721 9409 16722 9407 16722 9355 16722 9410 16723 9407 16723 9409 16723 9408 16724 9407 16724 9410 16724 9409 16725 9355 16725 9354 16725 9413 16726 9403 16726 9408 16726 9411 16727 9409 16727 9354 16727 9412 16728 9409 16728 9411 16728 9412 16729 9410 16729 9409 16729 9413 16730 9408 16730 9410 16730 9412 16731 9413 16731 9410 16731 9414 16732 9411 16732 9352 16732 9414 16733 9412 16733 9411 16733 9415 16734 9412 16734 9414 16734 9413 16735 9412 16735 9415 16735 9416 16736 9352 16736 9351 16736 9416 16737 9414 16737 9352 16737 9415 16738 9414 16738 9416 16738 9417 16739 9416 16739 9351 16739 9418 16740 9413 16740 9415 16740 9419 16741 9416 16741 9417 16741 9419 16742 9415 16742 9416 16742 9418 16743 9415 16743 9419 16743 9420 16744 9419 16744 9417 16744 9420 16745 9418 16745 9419 16745 9421 16746 9418 16746 9420 16746 9420 16747 9417 16747 9349 16747 9422 16748 9420 16748 9349 16748 9423 16749 9418 16749 9421 16749 9421 16750 9420 16750 9422 16750 9347 16751 9422 16751 9349 16751 9424 16752 9422 16752 9347 16752 9425 16753 9422 16753 9424 16753 9425 16754 9421 16754 9422 16754 9426 16755 9424 16755 9347 16755 9423 16756 9421 16756 9425 16756 9428 16757 9423 16757 9425 16757 9427 16758 9424 16758 9426 16758 9427 16759 9425 16759 9424 16759 9428 16760 9425 16760 9427 16760 9427 16761 9426 16761 9345 16761 9429 16762 9427 16762 9345 16762 9429 16763 9428 16763 9427 16763 9430 16764 9345 16764 9343 16764 9430 16765 9429 16765 9345 16765 9431 16766 9429 16766 9430 16766 9431 16767 9428 16767 9429 16767 9432 16768 9430 16768 9343 16768 9433 16769 9428 16769 9431 16769 9434 16770 9430 16770 9432 16770 9434 16771 9431 16771 9430 16771 9435 16772 9431 16772 9434 16772 9436 16773 9432 16773 9342 16773 9433 16774 9431 16774 9435 16774 9436 16775 9434 16775 9432 16775 9435 16776 9434 16776 9436 16776 9340 16777 9436 16777 9342 16777 9437 16778 9436 16778 9340 16778 9435 16779 9436 16779 9437 16779 9438 16780 9433 16780 9435 16780 9439 16781 9435 16781 9437 16781 9438 16782 9435 16782 9439 16782 9338 16783 9437 16783 9340 16783 9439 16784 9437 16784 9338 16784 9440 16785 9338 16785 9337 16785 9440 16786 9439 16786 9338 16786 9441 16787 9439 16787 9440 16787 9441 16788 9438 16788 9439 16788 9440 16789 9337 16789 9335 16789 9442 16790 9440 16790 9335 16790 9445 16791 9438 16791 9441 16791 9442 16792 9441 16792 9440 16792 9443 16793 9441 16793 9442 16793 9442 16794 9335 16794 9334 16794 9445 16795 9441 16795 9443 16795 9444 16796 9442 16796 9334 16796 9443 16797 9442 16797 9444 16797 9444 16798 9334 16798 9332 16798 9446 16799 9443 16799 9444 16799 9445 16800 9443 16800 9446 16800 9332 16801 9446 16801 9444 16801 9447 16802 9446 16802 9332 16802 9447 16803 9332 16803 9331 16803 9448 16804 9445 16804 9446 16804 9449 16805 9446 16805 9447 16805 9329 16806 9447 16806 9331 16806 9448 16807 9446 16807 9449 16807 9449 16808 9447 16808 9329 16808 9450 16809 9449 16809 9329 16809 9448 16810 9449 16810 9450 16810 9451 16811 9329 16811 9327 16811 9451 16812 9450 16812 9329 16812 9326 16813 9451 16813 9327 16813 9452 16814 9448 16814 9450 16814 9453 16815 9451 16815 9326 16815 9454 16816 9451 16816 9453 16816 9454 16817 9450 16817 9451 16817 9455 16818 9450 16818 9454 16818 9453 16819 9326 16819 9325 16819 9455 16820 9452 16820 9450 16820 9456 16821 9453 16821 9325 16821 9456 16822 9454 16822 9453 16822 9455 16823 9454 16823 9456 16823 9457 16824 9325 16824 9323 16824 9457 16825 9456 16825 9325 16825 9458 16826 9452 16826 9455 16826 9459 16827 9456 16827 9457 16827 9459 16828 9455 16828 9456 16828 9322 16829 9457 16829 9323 16829 9458 16830 9455 16830 9459 16830 9460 16831 9457 16831 9322 16831 9460 16832 9459 16832 9457 16832 9460 16833 9322 16833 9320 16833 9461 16834 9459 16834 9460 16834 9462 16835 9460 16835 9320 16835 9461 16836 9460 16836 9462 16836 9458 16837 9459 16837 9461 16837 9318 16838 9462 16838 9320 16838 9463 16839 9462 16839 9318 16839 9463 16840 9461 16840 9462 16840 9464 16841 9458 16841 9461 16841 9465 16842 9461 16842 9463 16842 9464 16843 9461 16843 9465 16843 9466 16844 9463 16844 9318 16844 9465 16845 9463 16845 9466 16845 9466 16846 9318 16846 9317 16846 9465 16847 9466 16847 9467 16847 9468 16848 9466 16848 9317 16848 9468 16849 9467 16849 9466 16849 9315 16850 9468 16850 9317 16850 9467 16851 9464 16851 9465 16851 9469 16852 9468 16852 9315 16852 9470 16853 9464 16853 9467 16853 9467 16854 9468 16854 9469 16854 9471 16855 9467 16855 9469 16855 9470 16856 9467 16856 9471 16856 9472 16857 9471 16857 9469 16857 9472 16858 9469 16858 9313 16858 9473 16859 9470 16859 9471 16859 9313 16860 9471 16860 9472 16860 9474 16861 9471 16861 9313 16861 9473 16862 9471 16862 9474 16862 9475 16863 9313 16863 9311 16863 9475 16864 9474 16864 9313 16864 9476 16865 9474 16865 9475 16865 9473 16866 9474 16866 9476 16866 9478 16867 9475 16867 9311 16867 9477 16868 9473 16868 9476 16868 9476 16869 9475 16869 9478 16869 9479 16870 9476 16870 9478 16870 9477 16871 9476 16871 9479 16871 9309 16872 9479 16872 9478 16872 9480 16873 9309 16873 9308 16873 9480 16874 9479 16874 9309 16874 9481 16875 9479 16875 9480 16875 9481 16876 9477 16876 9479 16876 9483 16877 9477 16877 9481 16877 9306 16878 9480 16878 9308 16878 9482 16879 9480 16879 9306 16879 9482 16880 9481 16880 9480 16880 9483 16881 9481 16881 9482 16881 9305 16882 9482 16882 9306 16882 9484 16883 9482 16883 9305 16883 9483 16884 9482 16884 9484 16884 9485 16885 9305 16885 9303 16885 9485 16886 9484 16886 9305 16886 9486 16887 9484 16887 9485 16887 9301 16888 9485 16888 9303 16888 9486 16889 9483 16889 9484 16889 9487 16890 9485 16890 9301 16890 9488 16891 9483 16891 9486 16891 9487 16892 9486 16892 9485 16892 9377 16893 9486 16893 9487 16893 9488 16894 9486 16894 9377 16894 9376 16895 9301 16895 9300 16895 9376 16896 9487 16896 9301 16896 9376 16897 9377 16897 9487 16897 9488 16898 9377 16898 9379 16898 8995 16899 9391 16899 8993 16899 8993 16900 9391 16900 9395 16900 8995 16901 9387 16901 9391 16901 8993 16902 9395 16902 9401 16902 8998 16903 9387 16903 8995 16903 8991 16904 8993 16904 9401 16904 8998 16905 9383 16905 9387 16905 8987 16906 9401 16906 9403 16906 8987 16907 8991 16907 9401 16907 8934 16908 9379 16908 9383 16908 8934 16909 9383 16909 8998 16909 8984 16910 8987 16910 9403 16910 8934 16911 9488 16911 9379 16911 8936 16912 9488 16912 8934 16912 9413 16913 8984 16913 9403 16913 8983 16914 8984 16914 9413 16914 8939 16915 9483 16915 9488 16915 8939 16916 9488 16916 8936 16916 8980 16917 8983 16917 9413 16917 9418 16918 8980 16918 9413 16918 8942 16919 9477 16919 9483 16919 8942 16920 9483 16920 8939 16920 8977 16921 8980 16921 9418 16921 9423 16922 8977 16922 9418 16922 9473 16923 9477 16923 8942 16923 9423 16924 8975 16924 8977 16924 9473 16925 8942 16925 8945 16925 9470 16926 9473 16926 8945 16926 9428 16927 8973 16927 8975 16927 9428 16928 8975 16928 9423 16928 9464 16929 9470 16929 8945 16929 9433 16930 8973 16930 9428 16930 9464 16931 8945 16931 8949 16931 9433 16932 8970 16932 8973 16932 9464 16933 8949 16933 8951 16933 9433 16934 8967 16934 8970 16934 9458 16935 9464 16935 8951 16935 9438 16936 8967 16936 9433 16936 9458 16937 8951 16937 8955 16937 9445 16938 8966 16938 8967 16938 9445 16939 8967 16939 9438 16939 9445 16940 8962 16940 8966 16940 9452 16941 9458 16941 8955 16941 9452 16942 8955 16942 8957 16942 9448 16943 8962 16943 9445 16943 9448 16944 8957 16944 8962 16944 9448 16945 9452 16945 8957 16945 9491 16946 9592 16946 9489 16946 9490 16947 9592 16947 9491 16947 9216 16948 9489 16948 9214 16948 9491 16949 9489 16949 9216 16949 9217 16950 9491 16950 9216 16950 9492 16951 9491 16951 9217 16951 9490 16952 9491 16952 9492 16952 9493 16953 9490 16953 9492 16953 9492 16954 9217 16954 9219 16954 9493 16955 9492 16955 9494 16955 9494 16956 9492 16956 9219 16956 9221 16957 9494 16957 9219 16957 9495 16958 9494 16958 9221 16958 9495 16959 9493 16959 9494 16959 9495 16960 9221 16960 9222 16960 9496 16961 9493 16961 9495 16961 9497 16962 9493 16962 9496 16962 9496 16963 9495 16963 9222 16963 9498 16964 9222 16964 9224 16964 9496 16965 9222 16965 9498 16965 9499 16966 9496 16966 9498 16966 9225 16967 9498 16967 9224 16967 9499 16968 9497 16968 9496 16968 9501 16969 9497 16969 9499 16969 9500 16970 9499 16970 9498 16970 9227 16971 9498 16971 9225 16971 9500 16972 9498 16972 9227 16972 9501 16973 9499 16973 9500 16973 9502 16974 9500 16974 9227 16974 9503 16975 9500 16975 9502 16975 9503 16976 9501 16976 9500 16976 9502 16977 9227 16977 9229 16977 9504 16978 9501 16978 9503 16978 9505 16979 9503 16979 9502 16979 9230 16980 9502 16980 9229 16980 9504 16981 9503 16981 9505 16981 9505 16982 9502 16982 9230 16982 9506 16983 9230 16983 9232 16983 9506 16984 9505 16984 9230 16984 9504 16985 9505 16985 9507 16985 9507 16986 9505 16986 9506 16986 9508 16987 9504 16987 9507 16987 9234 16988 9506 16988 9232 16988 9509 16989 9506 16989 9234 16989 9509 16990 9507 16990 9506 16990 9510 16991 9507 16991 9509 16991 9235 16992 9509 16992 9234 16992 9510 16993 9508 16993 9507 16993 9511 16994 9509 16994 9235 16994 9511 16995 9235 16995 9237 16995 9511 16996 9510 16996 9509 16996 9513 16997 9508 16997 9510 16997 9512 16998 9508 16998 9513 16998 9513 16999 9510 16999 9511 16999 9514 17000 9237 17000 9238 17000 9514 17001 9511 17001 9237 17001 9513 17002 9511 17002 9514 17002 9239 17003 9514 17003 9238 17003 9515 17004 9514 17004 9239 17004 9515 17005 9513 17005 9514 17005 9512 17006 9513 17006 9515 17006 9516 17007 9239 17007 9241 17007 9516 17008 9515 17008 9239 17008 9516 17009 9512 17009 9515 17009 9517 17010 9512 17010 9516 17010 9518 17011 9516 17011 9241 17011 9518 17012 9241 17012 9243 17012 9517 17013 9516 17013 9518 17013 9519 17014 9512 17014 9517 17014 9520 17015 9517 17015 9518 17015 9244 17016 9518 17016 9243 17016 9521 17017 9518 17017 9244 17017 9521 17018 9520 17018 9518 17018 9519 17019 9517 17019 9520 17019 9522 17020 9244 17020 9246 17020 9522 17021 9521 17021 9244 17021 9522 17022 9520 17022 9521 17022 9519 17023 9520 17023 9522 17023 9524 17024 9246 17024 9247 17024 9524 17025 9522 17025 9246 17025 9525 17026 9522 17026 9524 17026 9525 17027 9519 17027 9522 17027 9523 17028 9519 17028 9525 17028 9249 17029 9524 17029 9247 17029 9526 17030 9524 17030 9249 17030 9526 17031 9525 17031 9524 17031 9527 17032 9525 17032 9526 17032 9527 17033 9523 17033 9525 17033 9528 17034 9527 17034 9526 17034 9528 17035 9526 17035 9249 17035 9250 17036 9528 17036 9249 17036 9529 17037 9528 17037 9250 17037 9530 17038 9523 17038 9527 17038 9531 17039 9528 17039 9529 17039 9531 17040 9527 17040 9528 17040 9252 17041 9529 17041 9250 17041 9253 17042 9529 17042 9252 17042 9530 17043 9527 17043 9531 17043 9532 17044 9529 17044 9253 17044 9532 17045 9531 17045 9529 17045 9530 17046 9531 17046 9532 17046 9533 17047 9532 17047 9253 17047 9533 17048 9253 17048 9255 17048 9534 17049 9530 17049 9532 17049 9256 17050 9533 17050 9255 17050 9535 17051 9533 17051 9256 17051 9536 17052 9532 17052 9533 17052 9536 17053 9533 17053 9535 17053 9534 17054 9532 17054 9536 17054 9257 17055 9535 17055 9256 17055 9538 17056 9535 17056 9257 17056 9537 17057 9534 17057 9536 17057 9538 17058 9536 17058 9535 17058 9539 17059 9536 17059 9538 17059 9537 17060 9536 17060 9539 17060 9259 17061 9538 17061 9257 17061 9540 17062 9538 17062 9259 17062 9541 17063 9538 17063 9540 17063 9541 17064 9539 17064 9538 17064 9540 17065 9259 17065 9260 17065 9541 17066 9537 17066 9539 17066 9542 17067 9537 17067 9541 17067 9543 17068 9540 17068 9260 17068 9543 17069 9541 17069 9540 17069 9543 17070 9260 17070 9261 17070 9544 17071 9543 17071 9261 17071 9544 17072 9541 17072 9543 17072 9545 17073 9541 17073 9544 17073 9545 17074 9542 17074 9541 17074 9546 17075 9544 17075 9261 17075 9546 17076 9261 17076 9263 17076 9545 17077 9544 17077 9546 17077 9548 17078 9542 17078 9545 17078 9547 17079 9545 17079 9546 17079 9264 17080 9546 17080 9263 17080 9548 17081 9545 17081 9547 17081 9547 17082 9546 17082 9264 17082 9549 17083 9547 17083 9264 17083 9550 17084 9547 17084 9549 17084 9548 17085 9547 17085 9550 17085 9549 17086 9264 17086 9266 17086 9267 17087 9549 17087 9266 17087 9551 17088 9549 17088 9267 17088 9551 17089 9550 17089 9549 17089 9552 17090 9550 17090 9551 17090 9548 17091 9550 17091 9552 17091 9553 17092 9548 17092 9552 17092 9551 17093 9267 17093 9269 17093 9554 17094 9551 17094 9269 17094 9554 17095 9552 17095 9551 17095 9553 17096 9552 17096 9554 17096 9270 17097 9554 17097 9269 17097 9555 17098 9554 17098 9270 17098 9556 17099 9554 17099 9555 17099 9556 17100 9553 17100 9554 17100 9271 17101 9555 17101 9270 17101 9557 17102 9555 17102 9271 17102 9557 17103 9556 17103 9555 17103 9558 17104 9553 17104 9556 17104 9558 17105 9556 17105 9557 17105 9559 17106 9271 17106 9273 17106 9559 17107 9557 17107 9271 17107 9558 17108 9557 17108 9559 17108 9274 17109 9559 17109 9273 17109 9560 17110 9559 17110 9274 17110 9558 17111 9559 17111 9560 17111 9561 17112 9274 17112 9275 17112 9561 17113 9560 17113 9274 17113 9562 17114 9560 17114 9561 17114 9562 17115 9558 17115 9560 17115 9563 17116 9558 17116 9562 17116 9564 17117 9561 17117 9275 17117 9277 17118 9564 17118 9275 17118 9565 17119 9561 17119 9564 17119 9562 17120 9561 17120 9565 17120 9279 17121 9564 17121 9277 17121 9566 17122 9564 17122 9279 17122 9563 17123 9562 17123 9565 17123 9566 17124 9565 17124 9564 17124 9567 17125 9565 17125 9566 17125 9568 17126 9279 17126 9280 17126 9568 17127 9566 17127 9279 17127 9567 17128 9563 17128 9565 17128 9569 17129 9566 17129 9568 17129 9569 17130 9567 17130 9566 17130 9570 17131 9563 17131 9567 17131 9568 17132 9280 17132 9282 17132 9570 17133 9567 17133 9569 17133 9571 17134 9568 17134 9282 17134 9571 17135 9569 17135 9568 17135 9571 17136 9282 17136 9283 17136 9572 17137 9569 17137 9571 17137 9573 17138 9569 17138 9572 17138 9573 17139 9570 17139 9569 17139 9572 17140 9571 17140 9283 17140 9574 17141 9283 17141 9285 17141 9574 17142 9572 17142 9283 17142 9575 17143 9570 17143 9573 17143 9573 17144 9572 17144 9574 17144 9574 17145 9285 17145 9286 17145 9576 17146 9573 17146 9574 17146 9575 17147 9573 17147 9576 17147 9577 17148 9574 17148 9286 17148 9576 17149 9574 17149 9577 17149 9577 17150 9286 17150 9287 17150 9578 17151 9577 17151 9287 17151 9579 17152 9575 17152 9576 17152 9580 17153 9577 17153 9578 17153 9580 17154 9576 17154 9577 17154 9579 17155 9576 17155 9580 17155 9289 17156 9578 17156 9287 17156 9291 17157 9578 17157 9289 17157 9581 17158 9578 17158 9291 17158 9581 17159 9580 17159 9578 17159 9582 17160 9580 17160 9581 17160 9583 17161 9291 17161 9292 17161 9582 17162 9579 17162 9580 17162 9583 17163 9581 17163 9291 17163 9582 17164 9581 17164 9583 17164 9584 17165 9579 17165 9582 17165 9585 17166 9582 17166 9583 17166 9293 17167 9583 17167 9292 17167 9585 17168 9583 17168 9293 17168 9584 17169 9582 17169 9585 17169 9586 17170 9293 17170 9295 17170 9587 17171 9293 17171 9586 17171 9587 17172 9585 17172 9293 17172 9584 17173 9585 17173 9587 17173 9588 17174 9587 17174 9586 17174 9588 17175 9586 17175 9295 17175 9588 17176 9295 17176 9296 17176 9589 17177 9587 17177 9588 17177 9590 17178 9587 17178 9589 17178 9590 17179 9584 17179 9587 17179 9589 17180 9588 17180 9296 17180 9589 17181 9296 17181 9298 17181 9592 17182 9584 17182 9590 17182 9590 17183 9589 17183 9591 17183 9591 17184 9589 17184 9298 17184 9591 17185 9298 17185 9214 17185 9591 17186 9214 17186 9489 17186 9591 17187 9489 17187 9592 17187 9592 17188 9590 17188 9591 17188 8901 17189 9553 17189 8904 17189 8901 17190 9548 17190 9553 17190 8904 17191 9553 17191 9558 17191 8898 17192 9548 17192 8901 17192 8898 17193 9542 17193 9548 17193 8909 17194 8904 17194 9558 17194 8895 17195 9542 17195 8898 17195 8909 17196 9558 17196 9563 17196 8913 17197 8909 17197 9563 17197 8895 17198 9537 17198 9542 17198 8892 17199 9537 17199 8895 17199 8915 17200 8913 17200 9563 17200 8892 17201 9534 17201 9537 17201 8915 17202 9563 17202 9570 17202 8889 17203 9534 17203 8892 17203 9575 17204 8915 17204 9570 17204 8889 17205 9530 17205 9534 17205 8919 17206 8915 17206 9575 17206 8887 17207 9530 17207 8889 17207 8922 17208 8919 17208 9575 17208 8887 17209 9523 17209 9530 17209 8884 17210 9523 17210 8887 17210 9579 17211 8922 17211 9575 17211 9579 17212 8924 17212 8922 17212 8880 17213 9523 17213 8884 17213 9579 17214 8927 17214 8924 17214 9584 17215 8927 17215 9579 17215 9519 17216 9523 17216 8880 17216 8931 17217 8927 17217 9584 17217 8877 17218 9519 17218 8880 17218 9512 17219 9519 17219 8877 17219 9592 17220 8931 17220 9584 17220 9512 17221 8877 17221 8873 17221 9592 17222 8856 17222 8931 17222 9490 17223 8856 17223 9592 17223 9508 17224 9512 17224 8873 17224 9508 17225 8873 17225 8870 17225 9490 17226 8859 17226 8856 17226 9493 17227 8859 17227 9490 17227 9504 17228 8870 17228 8868 17228 9504 17229 9508 17229 8870 17229 9497 17230 8859 17230 9493 17230 9497 17231 8862 17231 8859 17231 9504 17232 8868 17232 8866 17232 9501 17233 8862 17233 9497 17233 9501 17234 9504 17234 8866 17234 9501 17235 8866 17235 8862 17235 9594 17236 9595 17236 9593 17236 9596 17237 9595 17237 9594 17237 9594 17238 9593 17238 9597 17238 9599 17239 9596 17239 9594 17239 9598 17240 9596 17240 9599 17240 9600 17241 9594 17241 9597 17241 9600 17242 9599 17242 9594 17242 9600 17243 9597 17243 9601 17243 9602 17244 9600 17244 9601 17244 9604 17245 9598 17245 9599 17245 9604 17246 9600 17246 9602 17246 9604 17247 9599 17247 9600 17247 9605 17248 9601 17248 9603 17248 9605 17249 9602 17249 9601 17249 9606 17250 9602 17250 9605 17250 9606 17251 9604 17251 9602 17251 9607 17252 9605 17252 9603 17252 9607 17253 9606 17253 9605 17253 9607 17254 9603 17254 9608 17254 9609 17255 9606 17255 9607 17255 9609 17256 9607 17256 9608 17256 9610 17257 9606 17257 9609 17257 9611 17258 9609 17258 9608 17258 9612 17259 9604 17259 9606 17259 9612 17260 9606 17260 9610 17260 9613 17261 9609 17261 9611 17261 9610 17262 9609 17262 9613 17262 9613 17263 9611 17263 9614 17263 9615 17264 9610 17264 9613 17264 9612 17265 9610 17265 9615 17265 9616 17266 9613 17266 9614 17266 9615 17267 9613 17267 9616 17267 9617 17268 9616 17268 9614 17268 9618 17269 9616 17269 9617 17269 9618 17270 9615 17270 9616 17270 9619 17271 9612 17271 9615 17271 9620 17272 9615 17272 9618 17272 9619 17273 9615 17273 9620 17273 9621 17274 9618 17274 9617 17274 9622 17275 9618 17275 9621 17275 9623 17276 9618 17276 9622 17276 9623 17277 9620 17277 9618 17277 9623 17278 9619 17278 9620 17278 9624 17279 9622 17279 9621 17279 9625 17280 9619 17280 9623 17280 9626 17281 9622 17281 9624 17281 9626 17282 9623 17282 9622 17282 9627 17283 9626 17283 9624 17283 9628 17284 9626 17284 9627 17284 9629 17285 9623 17285 9626 17285 9629 17286 9625 17286 9623 17286 9629 17287 9626 17287 9628 17287 9628 17288 9627 17288 9630 17288 9631 17289 9628 17289 9630 17289 9632 17290 9628 17290 9631 17290 9632 17291 9629 17291 9628 17291 9631 17292 9630 17292 9633 17292 9634 17293 9629 17293 9632 17293 9634 17294 9625 17294 9629 17294 9635 17295 9631 17295 9633 17295 9632 17296 9631 17296 9635 17296 9636 17297 9632 17297 9635 17297 9638 17298 9632 17298 9636 17298 9638 17299 9634 17299 9632 17299 9636 17300 9635 17300 9637 17300 9639 17301 9636 17301 9637 17301 9639 17302 9638 17302 9636 17302 9640 17303 9639 17303 9637 17303 9641 17304 9634 17304 9638 17304 9641 17305 9638 17305 9639 17305 9642 17306 9639 17306 9640 17306 9642 17307 9641 17307 9639 17307 9642 17308 9640 17308 9643 17308 9644 17309 9634 17309 9641 17309 9645 17310 9641 17310 9642 17310 9646 17311 9642 17311 9643 17311 9645 17312 9642 17312 9646 17312 9646 17313 9643 17313 9647 17313 9644 17314 9641 17314 9645 17314 9648 17315 9646 17315 9647 17315 9645 17316 9646 17316 9648 17316 9648 17317 9647 17317 9649 17317 9651 17318 9645 17318 9648 17318 9651 17319 9644 17319 9645 17319 9652 17320 9648 17320 9649 17320 9651 17321 9650 17321 9644 17321 9652 17322 9651 17322 9648 17322 9652 17323 9649 17323 9653 17323 9654 17324 9651 17324 9652 17324 9654 17325 9650 17325 9651 17325 9655 17326 9652 17326 9653 17326 9656 17327 9652 17327 9655 17327 9654 17328 9652 17328 9656 17328 9657 17329 9654 17329 9656 17329 9659 17330 9654 17330 9657 17330 9659 17331 9650 17331 9654 17331 9658 17332 9656 17332 9655 17332 9657 17333 9656 17333 9658 17333 9659 17334 9657 17334 9661 17334 9662 17335 9658 17335 9660 17335 9662 17336 9657 17336 9658 17336 9661 17337 9657 17337 9662 17337 9663 17338 9659 17338 9661 17338 9664 17339 9662 17339 9660 17339 9665 17340 9662 17340 9664 17340 9665 17341 9661 17341 9662 17341 9663 17342 9661 17342 9665 17342 9669 17343 9659 17343 9663 17343 9666 17344 9665 17344 9664 17344 9667 17345 9665 17345 9666 17345 9667 17346 9663 17346 9665 17346 9669 17347 9663 17347 9667 17347 9670 17348 9666 17348 9668 17348 9670 17349 9667 17349 9666 17349 9671 17350 9670 17350 9668 17350 9672 17351 9669 17351 9667 17351 9672 17352 9667 17352 9670 17352 9673 17353 9670 17353 9671 17353 9672 17354 9670 17354 9673 17354 9673 17355 9671 17355 9674 17355 9675 17356 9672 17356 9673 17356 9676 17357 9673 17357 9674 17357 9675 17358 9673 17358 9676 17358 9676 17359 9674 17359 9677 17359 9678 17360 9675 17360 9676 17360 9678 17361 9676 17361 9677 17361 9682 17362 9672 17362 9675 17362 9678 17363 9677 17363 9679 17363 9675 17364 9678 17364 9680 17364 9679 17365 9680 17365 9678 17365 9682 17366 9675 17366 9680 17366 9683 17367 9682 17367 9680 17367 9684 17368 9679 17368 9681 17368 9684 17369 9680 17369 9679 17369 9683 17370 9680 17370 9684 17370 9685 17371 9684 17371 9681 17371 9687 17372 9682 17372 9683 17372 9686 17373 9684 17373 9685 17373 9686 17374 9683 17374 9684 17374 9687 17375 9683 17375 9686 17375 9688 17376 9686 17376 9685 17376 9689 17377 9688 17377 9685 17377 9690 17378 9688 17378 9689 17378 9690 17379 9686 17379 9688 17379 9693 17380 9687 17380 9686 17380 9691 17381 9687 17381 9693 17381 9692 17382 9686 17382 9690 17382 9693 17383 9686 17383 9692 17383 9694 17384 9690 17384 9689 17384 9692 17385 9690 17385 9694 17385 9696 17386 9694 17386 9695 17386 9696 17387 9692 17387 9694 17387 9696 17388 9693 17388 9692 17388 9697 17389 9693 17389 9696 17389 9699 17390 9693 17390 9697 17390 9700 17391 9696 17391 9695 17391 9700 17392 9695 17392 9698 17392 9699 17393 9691 17393 9693 17393 9700 17394 9697 17394 9696 17394 9701 17395 9700 17395 9698 17395 9702 17396 9697 17396 9700 17396 9702 17397 9699 17397 9697 17397 9703 17398 9700 17398 9701 17398 9703 17399 9702 17399 9700 17399 9703 17400 9701 17400 9704 17400 9705 17401 9699 17401 9702 17401 9706 17402 9702 17402 9703 17402 9705 17403 9702 17403 9706 17403 9707 17404 9703 17404 9704 17404 9706 17405 9703 17405 9707 17405 9708 17406 9707 17406 9704 17406 9709 17407 9707 17407 9708 17407 9709 17408 9706 17408 9707 17408 9710 17409 9706 17409 9709 17409 9705 17410 9706 17410 9710 17410 9709 17411 9708 17411 9711 17411 9712 17412 9709 17412 9711 17412 9713 17413 9709 17413 9712 17413 9713 17414 9710 17414 9709 17414 9715 17415 9711 17415 9714 17415 9716 17416 9710 17416 9713 17416 9715 17417 9712 17417 9711 17417 9716 17418 9705 17418 9710 17418 9715 17419 9713 17419 9712 17419 9718 17420 9705 17420 9716 17420 9717 17421 9715 17421 9714 17421 9719 17422 9715 17422 9717 17422 9719 17423 9713 17423 9715 17423 9719 17424 9716 17424 9713 17424 9718 17425 9716 17425 9719 17425 9721 17426 9717 17426 9720 17426 9721 17427 9719 17427 9717 17427 9722 17428 9719 17428 9721 17428 9722 17429 9718 17429 9719 17429 9723 17430 9721 17430 9720 17430 9722 17431 9721 17431 9723 17431 9724 17432 9718 17432 9722 17432 9725 17433 9722 17433 9723 17433 9724 17434 9722 17434 9725 17434 9725 17435 9723 17435 9726 17435 9727 17436 9718 17436 9724 17436 9728 17437 9725 17437 9726 17437 9729 17438 9725 17438 9728 17438 9730 17439 9725 17439 9729 17439 9730 17440 9724 17440 9725 17440 9727 17441 9724 17441 9730 17441 9732 17442 9729 17442 9728 17442 9732 17443 9728 17443 9731 17443 9732 17444 9730 17444 9729 17444 9733 17445 9732 17445 9731 17445 9735 17446 9727 17446 9730 17446 9734 17447 9732 17447 9733 17447 9735 17448 9732 17448 9734 17448 9735 17449 9730 17449 9732 17449 9737 17450 9733 17450 9736 17450 9737 17451 9734 17451 9733 17451 9738 17452 9734 17452 9737 17452 9738 17453 9735 17453 9734 17453 9739 17454 9737 17454 9736 17454 9740 17455 9737 17455 9739 17455 9740 17456 9738 17456 9737 17456 9741 17457 9738 17457 9740 17457 9742 17458 9738 17458 9741 17458 9741 17459 9740 17459 9739 17459 9742 17460 9735 17460 9738 17460 9744 17461 9739 17461 9743 17461 9744 17462 9741 17462 9739 17462 9745 17463 9741 17463 9744 17463 9742 17464 9741 17464 9745 17464 9746 17465 9744 17465 9743 17465 9745 17466 9744 17466 9746 17466 9747 17467 9745 17467 9746 17467 9749 17468 9745 17468 9747 17468 9748 17469 9747 17469 9746 17469 9750 17470 9745 17470 9749 17470 9750 17471 9742 17471 9745 17471 9751 17472 9747 17472 9748 17472 9749 17473 9747 17473 9751 17473 9752 17474 9751 17474 9748 17474 9753 17475 9751 17475 9752 17475 9753 17476 9749 17476 9751 17476 9755 17477 9750 17477 9749 17477 9754 17478 9753 17478 9752 17478 9756 17479 9753 17479 9754 17479 9756 17480 9749 17480 9753 17480 9755 17481 9749 17481 9756 17481 9758 17482 9754 17482 9757 17482 9758 17483 9756 17483 9754 17483 9759 17484 9756 17484 9758 17484 9755 17485 9756 17485 9759 17485 9760 17486 9758 17486 9757 17486 9595 17487 9758 17487 9760 17487 9595 17488 9760 17488 9593 17488 9595 17489 9759 17489 9758 17489 9759 17490 9595 17490 9596 17490 9759 17491 9596 17491 9598 17491 9755 17492 9759 17492 9598 17492 9761 17493 9593 17493 9760 17493 9762 17494 9760 17494 9757 17494 9762 17495 9761 17495 9760 17495 9763 17496 9757 17496 9754 17496 9763 17497 9762 17497 9757 17497 9764 17498 9754 17498 9752 17498 9764 17499 9763 17499 9754 17499 9765 17500 9752 17500 9748 17500 9765 17501 9764 17501 9752 17501 9766 17502 9748 17502 9746 17502 9766 17503 9765 17503 9748 17503 9767 17504 9766 17504 9746 17504 9768 17505 9767 17505 9746 17505 9768 17506 9746 17506 9743 17506 9768 17507 9743 17507 9739 17507 9769 17508 9768 17508 9739 17508 9770 17509 9769 17509 9739 17509 9770 17510 9739 17510 9736 17510 9771 17511 9770 17511 9736 17511 9771 17512 9736 17512 9733 17512 9772 17513 9733 17513 9731 17513 9772 17514 9771 17514 9733 17514 9773 17515 9731 17515 9728 17515 9773 17516 9772 17516 9731 17516 9773 17517 9728 17517 9726 17517 9774 17518 9773 17518 9726 17518 9774 17519 9726 17519 9723 17519 9775 17520 9774 17520 9723 17520 9775 17521 9723 17521 9720 17521 9776 17522 9775 17522 9720 17522 9777 17523 9776 17523 9720 17523 9777 17524 9720 17524 9717 17524 9778 17525 9717 17525 9714 17525 9778 17526 9777 17526 9717 17526 9779 17527 9778 17527 9714 17527 9779 17528 9714 17528 9711 17528 9780 17529 9711 17529 9708 17529 9780 17530 9779 17530 9711 17530 9780 17531 9708 17531 9704 17531 9781 17532 9780 17532 9704 17532 9782 17533 9704 17533 9701 17533 9782 17534 9781 17534 9704 17534 9856 17535 9701 17535 9698 17535 9856 17536 9782 17536 9701 17536 9783 17537 9856 17537 9698 17537 9783 17538 9698 17538 9695 17538 9784 17539 9695 17539 9694 17539 9784 17540 9783 17540 9695 17540 9785 17541 9784 17541 9694 17541 9785 17542 9694 17542 9689 17542 9786 17543 9785 17543 9689 17543 9786 17544 9689 17544 9685 17544 9787 17545 9786 17545 9685 17545 9787 17546 9685 17546 9681 17546 9788 17547 9787 17547 9681 17547 9788 17548 9681 17548 9679 17548 9789 17549 9679 17549 9677 17549 9789 17550 9788 17550 9679 17550 9789 17551 9677 17551 9674 17551 9790 17552 9789 17552 9674 17552 9790 17553 9674 17553 9671 17553 9791 17554 9790 17554 9671 17554 9791 17555 9671 17555 9668 17555 9792 17556 9791 17556 9668 17556 9792 17557 9668 17557 9666 17557 9792 17558 9666 17558 9664 17558 9793 17559 9792 17559 9664 17559 9793 17560 9664 17560 9660 17560 9794 17561 9793 17561 9660 17561 9794 17562 9660 17562 9658 17562 9795 17563 9794 17563 9658 17563 9795 17564 9658 17564 9655 17564 9796 17565 9655 17565 9653 17565 9796 17566 9795 17566 9655 17566 9797 17567 9653 17567 9649 17567 9797 17568 9796 17568 9653 17568 9797 17569 9649 17569 9647 17569 9798 17570 9797 17570 9647 17570 9798 17571 9647 17571 9643 17571 9799 17572 9798 17572 9643 17572 9799 17573 9643 17573 9640 17573 9800 17574 9799 17574 9640 17574 9800 17575 9640 17575 9637 17575 9800 17576 9637 17576 9635 17576 9801 17577 9800 17577 9635 17577 9801 17578 9635 17578 9633 17578 9802 17579 9801 17579 9633 17579 9802 17580 9633 17580 9630 17580 9803 17581 9802 17581 9630 17581 9803 17582 9630 17582 9627 17582 9803 17583 9627 17583 9624 17583 9804 17584 9624 17584 9621 17584 9804 17585 9803 17585 9624 17585 9805 17586 9621 17586 9617 17586 9805 17587 9804 17587 9621 17587 9806 17588 9805 17588 9617 17588 9807 17589 9617 17589 9614 17589 9807 17590 9806 17590 9617 17590 9807 17591 9614 17591 9611 17591 9808 17592 9807 17592 9611 17592 9809 17593 9808 17593 9611 17593 9809 17594 9611 17594 9608 17594 9810 17595 9809 17595 9608 17595 9810 17596 9608 17596 9603 17596 9811 17597 9810 17597 9603 17597 9811 17598 9603 17598 9601 17598 9812 17599 9811 17599 9601 17599 9812 17600 9601 17600 9597 17600 9813 17601 9812 17601 9597 17601 9813 17602 9597 17602 9593 17602 9814 17603 9813 17603 9593 17603 9761 17604 9814 17604 9593 17604 9364 17605 9368 17605 9612 17605 9370 17606 9612 17606 9368 17606 9364 17607 9612 17607 9619 17607 9370 17608 9604 17608 9612 17608 9362 17609 9364 17609 9619 17609 9362 17610 9619 17610 9625 17610 9373 17611 9604 17611 9370 17611 9359 17612 9362 17612 9625 17612 9359 17613 9625 17613 9634 17613 9373 17614 9598 17614 9604 17614 9299 17615 9598 17615 9373 17615 9356 17616 9359 17616 9634 17616 9302 17617 9755 17617 9598 17617 9302 17618 9598 17618 9299 17618 9353 17619 9356 17619 9634 17619 9304 17620 9755 17620 9302 17620 9750 17621 9755 17621 9304 17621 9644 17622 9353 17622 9634 17622 9350 17623 9353 17623 9644 17623 9307 17624 9750 17624 9304 17624 9650 17625 9350 17625 9644 17625 9310 17626 9742 17626 9750 17626 9310 17627 9750 17627 9307 17627 9348 17628 9350 17628 9650 17628 9659 17629 9348 17629 9650 17629 9742 17630 9310 17630 9312 17630 9735 17631 9742 17631 9312 17631 9659 17632 9346 17632 9348 17632 9314 17633 9735 17633 9312 17633 9669 17634 9346 17634 9659 17634 9669 17635 9344 17635 9346 17635 9727 17636 9314 17636 9316 17636 9727 17637 9735 17637 9314 17637 9672 17638 9344 17638 9669 17638 9672 17639 9341 17639 9344 17639 9718 17640 9727 17640 9316 17640 9319 17641 9718 17641 9316 17641 9682 17642 9341 17642 9672 17642 9682 17643 9339 17643 9341 17643 9718 17644 9319 17644 9321 17644 9682 17645 9336 17645 9339 17645 9687 17646 9336 17646 9682 17646 9705 17647 9718 17647 9321 17647 9705 17648 9321 17648 9324 17648 9687 17649 9333 17649 9336 17649 9691 17650 9333 17650 9687 17650 9691 17651 9330 17651 9333 17651 9705 17652 9324 17652 9328 17652 9699 17653 9330 17653 9691 17653 9699 17654 9705 17654 9328 17654 9699 17655 9328 17655 9330 17655 9762 17656 9815 17656 9761 17656 9817 17657 9815 17657 9762 17657 9817 17658 9816 17658 9815 17658 9818 17659 9924 17659 9816 17659 9818 17660 9816 17660 9817 17660 9763 17661 9817 17661 9762 17661 9819 17662 9817 17662 9763 17662 9819 17663 9763 17663 9764 17663 9818 17664 9817 17664 9819 17664 9821 17665 9764 17665 9765 17665 9821 17666 9819 17666 9764 17666 9822 17667 9819 17667 9821 17667 9822 17668 9818 17668 9819 17668 9823 17669 9765 17669 9766 17669 9820 17670 9818 17670 9822 17670 9823 17671 9821 17671 9765 17671 9822 17672 9821 17672 9823 17672 9767 17673 9823 17673 9766 17673 9824 17674 9823 17674 9767 17674 9824 17675 9822 17675 9823 17675 9825 17676 9822 17676 9824 17676 9825 17677 9820 17677 9822 17677 9826 17678 9767 17678 9768 17678 9827 17679 9820 17679 9825 17679 9826 17680 9824 17680 9767 17680 9825 17681 9824 17681 9826 17681 9828 17682 9768 17682 9769 17682 9828 17683 9826 17683 9768 17683 9828 17684 9825 17684 9826 17684 9827 17685 9825 17685 9828 17685 9830 17686 9769 17686 9770 17686 9830 17687 9828 17687 9769 17687 9831 17688 9828 17688 9830 17688 9831 17689 9827 17689 9828 17689 9829 17690 9827 17690 9831 17690 9832 17691 9830 17691 9770 17691 9832 17692 9770 17692 9771 17692 9831 17693 9830 17693 9832 17693 9833 17694 9831 17694 9832 17694 9833 17695 9829 17695 9831 17695 9772 17696 9832 17696 9771 17696 9834 17697 9832 17697 9772 17697 9834 17698 9833 17698 9832 17698 9835 17699 9829 17699 9833 17699 9835 17700 9833 17700 9834 17700 9773 17701 9834 17701 9772 17701 9836 17702 9834 17702 9773 17702 9835 17703 9834 17703 9836 17703 9837 17704 9835 17704 9836 17704 9838 17705 9836 17705 9773 17705 9837 17706 9836 17706 9838 17706 9774 17707 9838 17707 9773 17707 9839 17708 9835 17708 9837 17708 9840 17709 9837 17709 9838 17709 9839 17710 9837 17710 9840 17710 9775 17711 9838 17711 9774 17711 9840 17712 9838 17712 9775 17712 9841 17713 9839 17713 9840 17713 9842 17714 9840 17714 9775 17714 9841 17715 9840 17715 9842 17715 9842 17716 9775 17716 9776 17716 9777 17717 9842 17717 9776 17717 9843 17718 9842 17718 9777 17718 9843 17719 9841 17719 9842 17719 9844 17720 9843 17720 9777 17720 9844 17721 9777 17721 9778 17721 9845 17722 9843 17722 9844 17722 9841 17723 9843 17723 9845 17723 9846 17724 9844 17724 9778 17724 9846 17725 9778 17725 9779 17725 9847 17726 9841 17726 9845 17726 9845 17727 9844 17727 9846 17727 9848 17728 9846 17728 9779 17728 9848 17729 9845 17729 9846 17729 9849 17730 9845 17730 9848 17730 9849 17731 9847 17731 9845 17731 9850 17732 9779 17732 9780 17732 9850 17733 9848 17733 9779 17733 9851 17734 9848 17734 9850 17734 9851 17735 9849 17735 9848 17735 9852 17736 9850 17736 9780 17736 9852 17737 9851 17737 9850 17737 9853 17738 9849 17738 9851 17738 9852 17739 9780 17739 9781 17739 9853 17740 9851 17740 9852 17740 9782 17741 9852 17741 9781 17741 9854 17742 9849 17742 9853 17742 9855 17743 9852 17743 9782 17743 9855 17744 9853 17744 9852 17744 9855 17745 9782 17745 9856 17745 9854 17746 9853 17746 9855 17746 9857 17747 9856 17747 9783 17747 9858 17748 9854 17748 9855 17748 9857 17749 9855 17749 9856 17749 9858 17750 9855 17750 9857 17750 9859 17751 9857 17751 9783 17751 9861 17752 9854 17752 9858 17752 9860 17753 9857 17753 9859 17753 9860 17754 9858 17754 9857 17754 9859 17755 9783 17755 9784 17755 9861 17756 9858 17756 9860 17756 9785 17757 9859 17757 9784 17757 9862 17758 9859 17758 9785 17758 9862 17759 9860 17759 9859 17759 9863 17760 9860 17760 9862 17760 9861 17761 9860 17761 9863 17761 9786 17762 9862 17762 9785 17762 9865 17763 9861 17763 9863 17763 9864 17764 9862 17764 9786 17764 9864 17765 9863 17765 9862 17765 9865 17766 9863 17766 9864 17766 9866 17767 9786 17767 9787 17767 9866 17768 9864 17768 9786 17768 9865 17769 9864 17769 9866 17769 9867 17770 9865 17770 9866 17770 9788 17771 9866 17771 9787 17771 9868 17772 9866 17772 9788 17772 9867 17773 9866 17773 9868 17773 9869 17774 9867 17774 9868 17774 9789 17775 9868 17775 9788 17775 9870 17776 9867 17776 9869 17776 9871 17777 9868 17777 9789 17777 9870 17778 9865 17778 9867 17778 9869 17779 9868 17779 9871 17779 9872 17780 9869 17780 9871 17780 9872 17781 9870 17781 9869 17781 9873 17782 9871 17782 9789 17782 9872 17783 9871 17783 9873 17783 9873 17784 9789 17784 9790 17784 9874 17785 9872 17785 9873 17785 9875 17786 9873 17786 9790 17786 9874 17787 9873 17787 9875 17787 9874 17788 9870 17788 9872 17788 9791 17789 9875 17789 9790 17789 9876 17790 9875 17790 9791 17790 9876 17791 9874 17791 9875 17791 9877 17792 9870 17792 9874 17792 9877 17793 9874 17793 9876 17793 9878 17794 9791 17794 9792 17794 9878 17795 9876 17795 9791 17795 9877 17796 9876 17796 9878 17796 9879 17797 9878 17797 9792 17797 9880 17798 9878 17798 9879 17798 9880 17799 9877 17799 9878 17799 9793 17800 9879 17800 9792 17800 9881 17801 9879 17801 9793 17801 9882 17802 9877 17802 9880 17802 9881 17803 9880 17803 9879 17803 9882 17804 9880 17804 9881 17804 9881 17805 9793 17805 9794 17805 9883 17806 9877 17806 9882 17806 9884 17807 9882 17807 9881 17807 9883 17808 9882 17808 9884 17808 9886 17809 9877 17809 9883 17809 9884 17810 9881 17810 9794 17810 9885 17811 9794 17811 9795 17811 9885 17812 9884 17812 9794 17812 9886 17813 9883 17813 9884 17813 9796 17814 9885 17814 9795 17814 9887 17815 9885 17815 9796 17815 9887 17816 9884 17816 9885 17816 9886 17817 9884 17817 9887 17817 9888 17818 9796 17818 9797 17818 9888 17819 9887 17819 9796 17819 9889 17820 9886 17820 9887 17820 9889 17821 9887 17821 9888 17821 9890 17822 9888 17822 9797 17822 9890 17823 9797 17823 9798 17823 9890 17824 9889 17824 9888 17824 9891 17825 9889 17825 9890 17825 9891 17826 9886 17826 9889 17826 9799 17827 9890 17827 9798 17827 9892 17828 9890 17828 9799 17828 9892 17829 9891 17829 9890 17829 9893 17830 9799 17830 9800 17830 9893 17831 9892 17831 9799 17831 9894 17832 9891 17832 9892 17832 9894 17833 9892 17833 9893 17833 9895 17834 9893 17834 9800 17834 9896 17835 9893 17835 9895 17835 9896 17836 9894 17836 9893 17836 9895 17837 9800 17837 9801 17837 9897 17838 9895 17838 9801 17838 9897 17839 9896 17839 9895 17839 9898 17840 9896 17840 9897 17840 9898 17841 9894 17841 9896 17841 9897 17842 9801 17842 9802 17842 9899 17843 9894 17843 9898 17843 9900 17844 9897 17844 9802 17844 9900 17845 9898 17845 9897 17845 9901 17846 9898 17846 9900 17846 9901 17847 9899 17847 9898 17847 9902 17848 9802 17848 9803 17848 9902 17849 9900 17849 9802 17849 9901 17850 9900 17850 9902 17850 9903 17851 9901 17851 9902 17851 9903 17852 9902 17852 9803 17852 9903 17853 9899 17853 9901 17853 9904 17854 9899 17854 9903 17854 9905 17855 9803 17855 9804 17855 9905 17856 9903 17856 9803 17856 9906 17857 9904 17857 9903 17857 9907 17858 9905 17858 9804 17858 9907 17859 9903 17859 9905 17859 9906 17860 9903 17860 9907 17860 9907 17861 9804 17861 9805 17861 9908 17862 9907 17862 9805 17862 9908 17863 9906 17863 9907 17863 9904 17864 9906 17864 9908 17864 9909 17865 9805 17865 9806 17865 9909 17866 9908 17866 9805 17866 9910 17867 9904 17867 9908 17867 9911 17868 9908 17868 9909 17868 9910 17869 9908 17869 9911 17869 9807 17870 9909 17870 9806 17870 9912 17871 9909 17871 9807 17871 9911 17872 9909 17872 9912 17872 9913 17873 9911 17873 9912 17873 9808 17874 9912 17874 9807 17874 9913 17875 9910 17875 9911 17875 9914 17876 9912 17876 9808 17876 9913 17877 9912 17877 9914 17877 9809 17878 9914 17878 9808 17878 9915 17879 9910 17879 9913 17879 9916 17880 9913 17880 9914 17880 9915 17881 9913 17881 9916 17881 9917 17882 9914 17882 9809 17882 9916 17883 9914 17883 9917 17883 9917 17884 9809 17884 9810 17884 9919 17885 9915 17885 9916 17885 9918 17886 9917 17886 9810 17886 9918 17887 9916 17887 9917 17887 9919 17888 9916 17888 9918 17888 9811 17889 9918 17889 9810 17889 9920 17890 9915 17890 9919 17890 9921 17891 9918 17891 9811 17891 9920 17892 9919 17892 9918 17892 9921 17893 9811 17893 9812 17893 9920 17894 9918 17894 9921 17894 9813 17895 9921 17895 9812 17895 9922 17896 9921 17896 9813 17896 9923 17897 9921 17897 9922 17897 9923 17898 9920 17898 9921 17898 9814 17899 9922 17899 9813 17899 9924 17900 9920 17900 9923 17900 9923 17901 9922 17901 9925 17901 9925 17902 9814 17902 9761 17902 9925 17903 9922 17903 9814 17903 9925 17904 9761 17904 9815 17904 9923 17905 9925 17905 9815 17905 9923 17906 9815 17906 9816 17906 9924 17907 9923 17907 9816 17907 9265 17908 9886 17908 9268 17908 9265 17909 9877 17909 9886 17909 9262 17910 9877 17910 9265 17910 9272 17911 9268 17911 9886 17911 9272 17912 9886 17912 9891 17912 9258 17913 9877 17913 9262 17913 9276 17914 9891 17914 9894 17914 9276 17915 9272 17915 9891 17915 9258 17916 9870 17916 9877 17916 9278 17917 9894 17917 9899 17917 9278 17918 9276 17918 9894 17918 9254 17919 9870 17919 9258 17919 9254 17920 9865 17920 9870 17920 9281 17921 9278 17921 9899 17921 9281 17922 9899 17922 9904 17922 9251 17923 9865 17923 9254 17923 9284 17924 9281 17924 9904 17924 9251 17925 9861 17925 9865 17925 9248 17926 9861 17926 9251 17926 9910 17927 9284 17927 9904 17927 9288 17928 9284 17928 9910 17928 9245 17929 9861 17929 9248 17929 9854 17930 9861 17930 9245 17930 9910 17931 9290 17931 9288 17931 9915 17932 9290 17932 9910 17932 9242 17933 9854 17933 9245 17933 9849 17934 9854 17934 9242 17934 9915 17935 9294 17935 9290 17935 9240 17936 9849 17936 9242 17936 9920 17937 9294 17937 9915 17937 9847 17938 9849 17938 9240 17938 9297 17939 9294 17939 9920 17939 9924 17940 9297 17940 9920 17940 9236 17941 9847 17941 9240 17941 9841 17942 9847 17942 9236 17942 9924 17943 9215 17943 9297 17943 9841 17944 9236 17944 9233 17944 9818 17945 9215 17945 9924 17945 9839 17946 9841 17946 9233 17946 9818 17947 9218 17947 9215 17947 9839 17948 9233 17948 9231 17948 9835 17949 9839 17949 9231 17949 9820 17950 9220 17950 9218 17950 9820 17951 9218 17951 9818 17951 9835 17952 9231 17952 9228 17952 9829 17953 9835 17953 9228 17953 9820 17954 9223 17954 9220 17954 9829 17955 9228 17955 9226 17955 9827 17956 9223 17956 9820 17956 9827 17957 9829 17957 9226 17957 9827 17958 9226 17958 9223 17958

+
+ + + +

9928 17959 9926 17959 9927 17959 9928 17960 10021 17960 9926 17960 9930 17961 10021 17961 9928 17961 9930 17962 9929 17962 10021 17962 9931 17963 9928 17963 9927 17963 9932 17964 9928 17964 9931 17964 9930 17965 9928 17965 9932 17965 9932 17966 9931 17966 9933 17966 9936 17967 9930 17967 9932 17967 9934 17968 9932 17968 9933 17968 9935 17969 9930 17969 9936 17969 9936 17970 9932 17970 9934 17970 9937 17971 9936 17971 9934 17971 9938 17972 9936 17972 9937 17972 9935 17973 9936 17973 9938 17973 9939 17974 9938 17974 9937 17974 9940 17975 9935 17975 9938 17975 9941 17976 9938 17976 9939 17976 9940 17977 9938 17977 9941 17977 9941 17978 9939 17978 9942 17978 9943 17979 9940 17979 9941 17979 9945 17980 9941 17980 9942 17980 9946 17981 9941 17981 9945 17981 9944 17982 9940 17982 9943 17982 9946 17983 9943 17983 9941 17983 9943 17984 9946 17984 9945 17984 9948 17985 9945 17985 9947 17985 9948 17986 9943 17986 9945 17986 9950 17987 9943 17987 9948 17987 9944 17988 9943 17988 9950 17988 9948 17989 9947 17989 9949 17989 9951 17990 9948 17990 9949 17990 9951 17991 9950 17991 9948 17991 9951 17992 9949 17992 9952 17992 9953 17993 9950 17993 9951 17993 9954 17994 9951 17994 9952 17994 9954 17995 9953 17995 9951 17995 9955 17996 9954 17996 9952 17996 9953 17997 9954 17997 9956 17997 9957 17998 9954 17998 9955 17998 9958 17999 9954 17999 9957 17999 9956 18000 9954 18000 9958 18000 9960 18001 9956 18001 9958 18001 9961 18002 9957 18002 9959 18002 9961 18003 9958 18003 9957 18003 9960 18004 9958 18004 9961 18004 9962 18005 9961 18005 9959 18005 9964 18006 9962 18006 9963 18006 9964 18007 9961 18007 9962 18007 9965 18008 9960 18008 9961 18008 9965 18009 9961 18009 9964 18009 9966 18010 9964 18010 9963 18010 9967 18011 9964 18011 9966 18011 9965 18012 9964 18012 9967 18012 9968 18013 9967 18013 9966 18013 9969 18014 9965 18014 9967 18014 9971 18015 9968 18015 9970 18015 9971 18016 9967 18016 9968 18016 9971 18017 9969 18017 9967 18017 9971 18018 9970 18018 9972 18018 9973 18019 9971 18019 9972 18019 9969 18020 9971 18020 9973 18020 9973 18021 9972 18021 9974 18021 9975 18022 9973 18022 9974 18022 9976 18023 9969 18023 9973 18023 9976 18024 9973 18024 9975 18024 9978 18025 9969 18025 9976 18025 9977 18026 9975 18026 9974 18026 9978 18027 9976 18027 9975 18027 9979 18028 9975 18028 9977 18028 9978 18029 9975 18029 9979 18029 9980 18030 9979 18030 9977 18030 9981 18031 9979 18031 9980 18031 9982 18032 9978 18032 9979 18032 9983 18033 9979 18033 9981 18033 9983 18034 9982 18034 9979 18034 9984 18035 9983 18035 9981 18035 9984 18036 9982 18036 9983 18036 9984 18037 9981 18037 9985 18037 9987 18038 9982 18038 9984 18038 9988 18039 9985 18039 9986 18039 9988 18040 9984 18040 9985 18040 9987 18041 9984 18041 9988 18041 9989 18042 9988 18042 9986 18042 9989 18043 9987 18043 9988 18043 9990 18044 9987 18044 9989 18044 9991 18045 9987 18045 9990 18045 9993 18046 9989 18046 9992 18046 9993 18047 9990 18047 9989 18047 9993 18048 9991 18048 9990 18048 9993 18049 9992 18049 9994 18049 9995 18050 9991 18050 9993 18050 9997 18051 9994 18051 9996 18051 9997 18052 9993 18052 9994 18052 9997 18053 9995 18053 9993 18053 9997 18054 9996 18054 9998 18054 10000 18055 9995 18055 9997 18055 9999 18056 9995 18056 10000 18056 10000 18057 9997 18057 9998 18057 10001 18058 10000 18058 9998 18058 10002 18059 10000 18059 10001 18059 9999 18060 10000 18060 10002 18060 10003 18061 9999 18061 10002 18061 10002 18062 10001 18062 10004 18062 10003 18063 10002 18063 10005 18063 10005 18064 10002 18064 10004 18064 10006 18065 10005 18065 10004 18065 10007 18066 10005 18066 10006 18066 10003 18067 10005 18067 10007 18067 10008 18068 10007 18068 10006 18068 10010 18069 10008 18069 10009 18069 10011 18070 10003 18070 10007 18070 10010 18071 10007 18071 10008 18071 10011 18072 10007 18072 10010 18072 10012 18073 10010 18073 10009 18073 10011 18074 10010 18074 10012 18074 10014 18075 10011 18075 10012 18075 10015 18076 10012 18076 10013 18076 10014 18077 10012 18077 10015 18077 10015 18078 10013 18078 10016 18078 10017 18079 10015 18079 10016 18079 10018 18080 10011 18080 10014 18080 10014 18081 10015 18081 10017 18081 10018 18082 10014 18082 10017 18082 10019 18083 10017 18083 10016 18083 10018 18084 10017 18084 10019 18084 10021 18085 10019 18085 10020 18085 10021 18086 10018 18086 10019 18086 9929 18087 10018 18087 10021 18087 9926 18088 10021 18088 10020 18088 10022 18089 9974 18089 10023 18089 9974 18090 9972 18090 10023 18090 10023 18091 9972 18091 10024 18091 9972 18092 9970 18092 10024 18092 10024 18093 9970 18093 10025 18093 9970 18094 9968 18094 10025 18094 10025 18095 9968 18095 10026 18095 9968 18096 9966 18096 10026 18096 10026 18097 9966 18097 10027 18097 9966 18098 9963 18098 10027 18098 10027 18099 9963 18099 10028 18099 9963 18100 9962 18100 10028 18100 10028 18101 9962 18101 10029 18101 9962 18102 9959 18102 10029 18102 10029 18103 9959 18103 10073 18103 9959 18104 9957 18104 10073 18104 10073 18105 9957 18105 10030 18105 9957 18106 9955 18106 10030 18106 10030 18107 9955 18107 10076 18107 9955 18108 9952 18108 10076 18108 10076 18109 9952 18109 10031 18109 9952 18110 9949 18110 10031 18110 10031 18111 9949 18111 10032 18111 9949 18112 9947 18112 10032 18112 10032 18113 9947 18113 10033 18113 9947 18114 9945 18114 10033 18114 10033 18115 9945 18115 10034 18115 9945 18116 9942 18116 10034 18116 10034 18117 9942 18117 10035 18117 10035 18118 9942 18118 10036 18118 9942 18119 9939 18119 10036 18119 9939 18120 9937 18120 10036 18120 10036 18121 9937 18121 10037 18121 10037 18122 9937 18122 10038 18122 9937 18123 9934 18123 10038 18123 10038 18124 9934 18124 10039 18124 9934 18125 9933 18125 10039 18125 10039 18126 9933 18126 10040 18126 9933 18127 9931 18127 10040 18127 9931 18128 9927 18128 10040 18128 10040 18129 9927 18129 10041 18129 10041 18130 9927 18130 10042 18130 9927 18131 9926 18131 10042 18131 10042 18132 9926 18132 10043 18132 9926 18133 10020 18133 10043 18133 10020 18134 10019 18134 10043 18134 10043 18135 10019 18135 10044 18135 10019 18136 10016 18136 10044 18136 10044 18137 10016 18137 10045 18137 10045 18138 10016 18138 10046 18138 10016 18139 10013 18139 10046 18139 10046 18140 10013 18140 10047 18140 10013 18141 10012 18141 10047 18141 10047 18142 10012 18142 10048 18142 10012 18143 10009 18143 10048 18143 10048 18144 10009 18144 10049 18144 10049 18145 10009 18145 10050 18145 10009 18146 10008 18146 10050 18146 10050 18147 10008 18147 10051 18147 10008 18148 10006 18148 10051 18148 10051 18149 10006 18149 10052 18149 10006 18150 10004 18150 10052 18150 10004 18151 10001 18151 10052 18151 10052 18152 10001 18152 10053 18152 10001 18153 9998 18153 10053 18153 10053 18154 9998 18154 10054 18154 9998 18155 9996 18155 10054 18155 10054 18156 9996 18156 10055 18156 9996 18157 9994 18157 10055 18157 10055 18158 9994 18158 10056 18158 10056 18159 9992 18159 10057 18159 9994 18160 9992 18160 10056 18160 9992 18161 9989 18161 10057 18161 10057 18162 9989 18162 10058 18162 9989 18163 9986 18163 10058 18163 10058 18164 9986 18164 10059 18164 9986 18165 9985 18165 10059 18165 9985 18166 9981 18166 10059 18166 10059 18167 9981 18167 10060 18167 10060 18168 9981 18168 10061 18168 9981 18169 9980 18169 10061 18169 10061 18170 9980 18170 10062 18170 9980 18171 9977 18171 10062 18171 10062 18172 9977 18172 10022 18172 9977 18173 9974 18173 10022 18173 9935 18174 9940 18174 10540 18174 9940 18175 10532 18175 10540 18175 9944 18176 10532 18176 9940 18176 9930 18177 9935 18177 10540 18177 9930 18178 10540 18178 10546 18178 9944 18179 10526 18179 10532 18179 9944 18180 10521 18180 10526 18180 9930 18181 10546 18181 10558 18181 9929 18182 9930 18182 10558 18182 9950 18183 10521 18183 9944 18183 9953 18184 10667 18184 10521 18184 9953 18185 10521 18185 9950 18185 9929 18186 10558 18186 10565 18186 10018 18187 9929 18187 10565 18187 9956 18188 10667 18188 9953 18188 9956 18189 10659 18189 10667 18189 10011 18190 10018 18190 10565 18190 9960 18191 10659 18191 9956 18191 10011 18192 10565 18192 10575 18192 9960 18193 10652 18193 10659 18193 9965 18194 10652 18194 9960 18194 10579 18195 10011 18195 10575 18195 10579 18196 10003 18196 10011 18196 10647 18197 10652 18197 9965 18197 10647 18198 9965 18198 9969 18198 10585 18199 10003 18199 10579 18199 10641 18200 10647 18200 9969 18200 10596 18201 10003 18201 10585 18201 10635 18202 10641 18202 9969 18202 10635 18203 9969 18203 9978 18203 10596 18204 9999 18204 10003 18204 10601 18205 9995 18205 9999 18205 10601 18206 9999 18206 10596 18206 10628 18207 10635 18207 9978 18207 10601 18208 9991 18208 9995 18208 10618 18209 10628 18209 9978 18209 10618 18210 9978 18210 9982 18210 10618 18211 9982 18211 9987 18211 10601 18212 9987 18212 9991 18212 10611 18213 9987 18213 10601 18213 10618 18214 9987 18214 10611 18214 10063 18215 10117 18215 10022 18215 10063 18216 10022 18216 10023 18216 10064 18217 10063 18217 10023 18217 10065 18218 10116 18218 10063 18218 10065 18219 10063 18219 10064 18219 10064 18220 10023 18220 10024 18220 10066 18221 10065 18221 10064 18221 10025 18222 10064 18222 10024 18222 10066 18223 10064 18223 10025 18223 10067 18224 10065 18224 10066 18224 10068 18225 10066 18225 10025 18225 10067 18226 10066 18226 10068 18226 10068 18227 10025 18227 10026 18227 10069 18228 10068 18228 10026 18228 10067 18229 10068 18229 10069 18229 10027 18230 10069 18230 10026 18230 10028 18231 10069 18231 10027 18231 10070 18232 10067 18232 10069 18232 10071 18233 10069 18233 10028 18233 10070 18234 10069 18234 10071 18234 10071 18235 10028 18235 10029 18235 10072 18236 10070 18236 10071 18236 10073 18237 10071 18237 10029 18237 10072 18238 10071 18238 10073 18238 10030 18239 10072 18239 10073 18239 10075 18240 10072 18240 10030 18240 10075 18241 10070 18241 10072 18241 10074 18242 10070 18242 10075 18242 10076 18243 10075 18243 10030 18243 10077 18244 10075 18244 10076 18244 10078 18245 10076 18245 10031 18245 10078 18246 10077 18246 10076 18246 10077 18247 10074 18247 10075 18247 10078 18248 10031 18248 10032 18248 10079 18249 10077 18249 10078 18249 10032 18250 10079 18250 10078 18250 10074 18251 10077 18251 10079 18251 10034 18252 10032 18252 10033 18252 10080 18253 10032 18253 10034 18253 10080 18254 10079 18254 10032 18254 10081 18255 10079 18255 10080 18255 10081 18256 10074 18256 10079 18256 10082 18257 10080 18257 10034 18257 10035 18258 10082 18258 10034 18258 10081 18259 10080 18259 10082 18259 10036 18260 10082 18260 10035 18260 10083 18261 10081 18261 10082 18261 10084 18262 10082 18262 10036 18262 10083 18263 10082 18263 10084 18263 10037 18264 10084 18264 10036 18264 10085 18265 10037 18265 10038 18265 10085 18266 10084 18266 10037 18266 10085 18267 10083 18267 10084 18267 10039 18268 10085 18268 10038 18268 10086 18269 10085 18269 10039 18269 10086 18270 10083 18270 10085 18270 10087 18271 10086 18271 10039 18271 10088 18272 10039 18272 10040 18272 10088 18273 10087 18273 10039 18273 10041 18274 10088 18274 10040 18274 10087 18275 10088 18275 10041 18275 10089 18276 10087 18276 10041 18276 10089 18277 10086 18277 10087 18277 10042 18278 10089 18278 10041 18278 10090 18279 10089 18279 10042 18279 10090 18280 10042 18280 10043 18280 10090 18281 10043 18281 10044 18281 10091 18282 10089 18282 10090 18282 10092 18283 10090 18283 10044 18283 10091 18284 10090 18284 10092 18284 10092 18285 10044 18285 10045 18285 10093 18286 10092 18286 10045 18286 10091 18287 10092 18287 10093 18287 10093 18288 10045 18288 10046 18288 10094 18289 10093 18289 10046 18289 10094 18290 10046 18290 10047 18290 10094 18291 10091 18291 10093 18291 10095 18292 10048 18292 10049 18292 10095 18293 10047 18293 10048 18293 10095 18294 10094 18294 10047 18294 10096 18295 10094 18295 10095 18295 10095 18296 10049 18296 10050 18296 10097 18297 10096 18297 10095 18297 10097 18298 10095 18298 10050 18298 10051 18299 10097 18299 10050 18299 10098 18300 10097 18300 10051 18300 10099 18301 10051 18301 10052 18301 10098 18302 10096 18302 10097 18302 10100 18303 10096 18303 10098 18303 10098 18304 10051 18304 10099 18304 10101 18305 10052 18305 10053 18305 10101 18306 10099 18306 10052 18306 10101 18307 10098 18307 10099 18307 10102 18308 10098 18308 10101 18308 10101 18309 10053 18309 10054 18309 10100 18310 10098 18310 10102 18310 10103 18311 10101 18311 10054 18311 10102 18312 10101 18312 10103 18312 10104 18313 10054 18313 10055 18313 10104 18314 10103 18314 10054 18314 10104 18315 10102 18315 10103 18315 10105 18316 10102 18316 10104 18316 10105 18317 10100 18317 10102 18317 10104 18318 10055 18318 10106 18318 10106 18319 10055 18319 10056 18319 10107 18320 10104 18320 10106 18320 10107 18321 10105 18321 10104 18321 10108 18322 10107 18322 10106 18322 10108 18323 10106 18323 10056 18323 10108 18324 10056 18324 10057 18324 10109 18325 10108 18325 10057 18325 10110 18326 10108 18326 10109 18326 10110 18327 10107 18327 10108 18327 10109 18328 10057 18328 10058 18328 10111 18329 10109 18329 10058 18329 10059 18330 10111 18330 10058 18330 10112 18331 10110 18331 10109 18331 10112 18332 10111 18332 10059 18332 10112 18333 10109 18333 10111 18333 10112 18334 10059 18334 10060 18334 10113 18335 10110 18335 10112 18335 10114 18336 10112 18336 10060 18336 10113 18337 10112 18337 10114 18337 10114 18338 10060 18338 10061 18338 10115 18339 10114 18339 10061 18339 10115 18340 10061 18340 10062 18340 10113 18341 10114 18341 10115 18341 10116 18342 10113 18342 10115 18342 10117 18343 10115 18343 10062 18343 10116 18344 10115 18344 10117 18344 10022 18345 10117 18345 10062 18345 10117 18346 10063 18346 10116 18346 10096 18347 10302 18347 10094 18347 10091 18348 10094 18348 10302 18348 10091 18349 10302 18349 10307 18349 10096 18350 10289 18350 10302 18350 10100 18351 10289 18351 10096 18351 10091 18352 10307 18352 10314 18352 10100 18353 10281 18353 10289 18353 10091 18354 10314 18354 10323 18354 10089 18355 10091 18355 10323 18355 10100 18356 10276 18356 10281 18356 10105 18357 10276 18357 10100 18357 10089 18358 10323 18358 10326 18358 10107 18359 10276 18359 10105 18359 10086 18360 10326 18360 10333 18360 10086 18361 10089 18361 10326 18361 10107 18362 10270 18362 10276 18362 10083 18363 10086 18363 10333 18363 10083 18364 10333 18364 10338 18364 10107 18365 10263 18365 10270 18365 10110 18366 10263 18366 10107 18366 10345 18367 10083 18367 10338 18367 10263 18368 10110 18368 10113 18368 10351 18369 10083 18369 10345 18369 10252 18370 10263 18370 10113 18370 10351 18371 10081 18371 10083 18371 10249 18372 10113 18372 10116 18372 10249 18373 10252 18373 10113 18373 10357 18374 10081 18374 10351 18374 10357 18375 10074 18375 10081 18375 10208 18376 10074 18376 10357 18376 10243 18377 10249 18377 10116 18377 10211 18378 10074 18378 10208 18378 10243 18379 10116 18379 10065 18379 10233 18380 10243 18380 10065 18380 10218 18381 10074 18381 10211 18381 10233 18382 10065 18382 10067 18382 10218 18383 10070 18383 10074 18383 10225 18384 10070 18384 10218 18384 10225 18385 10067 18385 10070 18385 10225 18386 10233 18386 10067 18386 10118 18387 10119 18387 10120 18387 10121 18388 10118 18388 10120 18388 10121 18389 10120 18389 10122 18389 10123 18390 10121 18390 10122 18390 10123 18391 10122 18391 10124 18391 10125 18392 10123 18392 10124 18392 10125 18393 10124 18393 10126 18393 10127 18394 10125 18394 10126 18394 10127 18395 10126 18395 10128 18395 10129 18396 10127 18396 10128 18396 10129 18397 10128 18397 10130 18397 10131 18398 10129 18398 10130 18398 10131 18399 10130 18399 10132 18399 10133 18400 10131 18400 10132 18400 10133 18401 10132 18401 10134 18401 10135 18402 10133 18402 10134 18402 10135 18403 10134 18403 10136 18403 10137 18404 10135 18404 10136 18404 10137 18405 10136 18405 10138 18405 10139 18406 10137 18406 10138 18406 10139 18407 10138 18407 10140 18407 10141 18408 10139 18408 10140 18408 10141 18409 10140 18409 10142 18409 10141 18410 10142 18410 10143 18410 10144 18411 10141 18411 10143 18411 10144 18412 10143 18412 10145 18412 10146 18413 10144 18413 10145 18413 10147 18414 10146 18414 10145 18414 10147 18415 10145 18415 10148 18415 10147 18416 10148 18416 10149 18416 10150 18417 10147 18417 10149 18417 10150 18418 10149 18418 10151 18418 10152 18419 10150 18419 10151 18419 10152 18420 10151 18420 10153 18420 10154 18421 10152 18421 10153 18421 10154 18422 10153 18422 10155 18422 10156 18423 10154 18423 10155 18423 10156 18424 10155 18424 10157 18424 10158 18425 10156 18425 10157 18425 10159 18426 10157 18426 10160 18426 10159 18427 10158 18427 10157 18427 10161 18428 10159 18428 10160 18428 10161 18429 10160 18429 10119 18429 10118 18430 10161 18430 10119 18430 10162 18431 10163 18431 10164 18431 10165 18432 10162 18432 10164 18432 10166 18433 10165 18433 10164 18433 10166 18434 10164 18434 10167 18434 10166 18435 10167 18435 10168 18435 10169 18436 10166 18436 10168 18436 10170 18437 10169 18437 10168 18437 10170 18438 10168 18438 10171 18438 10172 18439 10170 18439 10171 18439 10172 18440 10171 18440 10173 18440 10174 18441 10172 18441 10173 18441 10174 18442 10173 18442 10175 18442 10176 18443 10174 18443 10175 18443 10177 18444 10176 18444 10175 18444 10177 18445 10175 18445 10178 18445 10179 18446 10177 18446 10178 18446 10179 18447 10178 18447 10180 18447 10181 18448 10179 18448 10180 18448 10181 18449 10180 18449 10182 18449 10181 18450 10182 18450 10183 18450 10184 18451 10181 18451 10183 18451 10184 18452 10183 18452 10185 18452 10186 18453 10184 18453 10185 18453 10186 18454 10185 18454 10187 18454 10188 18455 10186 18455 10187 18455 10189 18456 10188 18456 10187 18456 10189 18457 10187 18457 10190 18457 10191 18458 10189 18458 10190 18458 10191 18459 10190 18459 10192 18459 10193 18460 10191 18460 10192 18460 10193 18461 10192 18461 10194 18461 10195 18462 10193 18462 10194 18462 10195 18463 10194 18463 10196 18463 10197 18464 10195 18464 10196 18464 10197 18465 10196 18465 10198 18465 10199 18466 10197 18466 10198 18466 10199 18467 10198 18467 10200 18467 10201 18468 10199 18468 10200 18468 10202 18469 10201 18469 10200 18469 10202 18470 10200 18470 10203 18470 10162 18471 10203 18471 10163 18471 10162 18472 10202 18472 10203 18472 10205 18473 10206 18473 10204 18473 10205 18474 10359 18474 10206 18474 10208 18475 10359 18475 10205 18475 10209 18476 10204 18476 10207 18476 10205 18477 10204 18477 10209 18477 10210 18478 10209 18478 10207 18478 10211 18479 10208 18479 10205 18479 10212 18480 10205 18480 10209 18480 10213 18481 10209 18481 10210 18481 10211 18482 10205 18482 10212 18482 10213 18483 10212 18483 10209 18483 10215 18484 10213 18484 10214 18484 10215 18485 10212 18485 10213 18485 10216 18486 10212 18486 10215 18486 10211 18487 10212 18487 10216 18487 10217 18488 10215 18488 10214 18488 10218 18489 10211 18489 10216 18489 10216 18490 10215 18490 10217 18490 10219 18491 10216 18491 10217 18491 10221 18492 10216 18492 10219 18492 10220 18493 10219 18493 10217 18493 10221 18494 10218 18494 10216 18494 10222 18495 10219 18495 10220 18495 10222 18496 10221 18496 10219 18496 10223 18497 10222 18497 10220 18497 10225 18498 10218 18498 10221 18498 10224 18499 10222 18499 10223 18499 10227 18500 10222 18500 10224 18500 10227 18501 10221 18501 10222 18501 10224 18502 10223 18502 10226 18502 10225 18503 10221 18503 10227 18503 10228 18504 10224 18504 10226 18504 10228 18505 10227 18505 10224 18505 10230 18506 10226 18506 10229 18506 10228 18507 10225 18507 10227 18507 10230 18508 10228 18508 10226 18508 10233 18509 10225 18509 10228 18509 10232 18510 10228 18510 10230 18510 10231 18511 10230 18511 10229 18511 10232 18512 10230 18512 10231 18512 10233 18513 10228 18513 10232 18513 10234 18514 10232 18514 10231 18514 10235 18515 10232 18515 10234 18515 10235 18516 10233 18516 10232 18516 10236 18517 10235 18517 10234 18517 10237 18518 10236 18518 10234 18518 10238 18519 10235 18519 10236 18519 10236 18520 10237 18520 10239 18520 10238 18521 10233 18521 10235 18521 10240 18522 10238 18522 10236 18522 10241 18523 10236 18523 10239 18523 10243 18524 10233 18524 10238 18524 10240 18525 10236 18525 10241 18525 10242 18526 10241 18526 10239 18526 10243 18527 10238 18527 10240 18527 10244 18528 10240 18528 10241 18528 10245 18529 10241 18529 10242 18529 10244 18530 10243 18530 10240 18530 10244 18531 10241 18531 10245 18531 10246 18532 10244 18532 10245 18532 10248 18533 10244 18533 10246 18533 10248 18534 10243 18534 10244 18534 10247 18535 10246 18535 10245 18535 10249 18536 10243 18536 10248 18536 10251 18537 10247 18537 10250 18537 10251 18538 10246 18538 10247 18538 10248 18539 10246 18539 10251 18539 10252 18540 10248 18540 10251 18540 10253 18541 10251 18541 10250 18541 10252 18542 10249 18542 10248 18542 10255 18543 10251 18543 10253 18543 10252 18544 10251 18544 10255 18544 10253 18545 10250 18545 10254 18545 10256 18546 10253 18546 10254 18546 10257 18547 10253 18547 10256 18547 10255 18548 10253 18548 10257 18548 10258 18549 10252 18549 10255 18549 10258 18550 10255 18550 10257 18550 10257 18551 10256 18551 10259 18551 10263 18552 10252 18552 10258 18552 10260 18553 10257 18553 10259 18553 10260 18554 10258 18554 10257 18554 10262 18555 10258 18555 10260 18555 10261 18556 10260 18556 10259 18556 10263 18557 10258 18557 10262 18557 10264 18558 10260 18558 10261 18558 10262 18559 10260 18559 10264 18559 10265 18560 10264 18560 10261 18560 10266 18561 10263 18561 10262 18561 10266 18562 10262 18562 10264 18562 10266 18563 10264 18563 10265 18563 10268 18564 10265 18564 10267 18564 10268 18565 10266 18565 10265 18565 10269 18566 10268 18566 10267 18566 10270 18567 10263 18567 10266 18567 10270 18568 10266 18568 10268 18568 10270 18569 10268 18569 10269 18569 10271 18570 10269 18570 10267 18570 10272 18571 10269 18571 10271 18571 10270 18572 10269 18572 10272 18572 10273 18573 10270 18573 10272 18573 10272 18574 10271 18574 10274 18574 10275 18575 10272 18575 10274 18575 10273 18576 10272 18576 10275 18576 10276 18577 10270 18577 10273 18577 10275 18578 10274 18578 10277 18578 10278 18579 10273 18579 10275 18579 10279 18580 10275 18580 10277 18580 10278 18581 10276 18581 10273 18581 10279 18582 10278 18582 10275 18582 10279 18583 10277 18583 10280 18583 10281 18584 10276 18584 10278 18584 10282 18585 10278 18585 10279 18585 10283 18586 10279 18586 10280 18586 10282 18587 10279 18587 10283 18587 10284 18588 10278 18588 10282 18588 10281 18589 10278 18589 10284 18589 10284 18590 10282 18590 10283 18590 10284 18591 10283 18591 10285 18591 10288 18592 10281 18592 10284 18592 10286 18593 10284 18593 10285 18593 10288 18594 10284 18594 10286 18594 10286 18595 10285 18595 10287 18595 10289 18596 10281 18596 10288 18596 10290 18597 10288 18597 10286 18597 10293 18598 10288 18598 10290 18598 10291 18599 10286 18599 10287 18599 10290 18600 10286 18600 10291 18600 10289 18601 10288 18601 10293 18601 10292 18602 10290 18602 10291 18602 10293 18603 10290 18603 10292 18603 10294 18604 10292 18604 10291 18604 10295 18605 10289 18605 10293 18605 10296 18606 10292 18606 10294 18606 10296 18607 10293 18607 10292 18607 10295 18608 10293 18608 10296 18608 10297 18609 10289 18609 10295 18609 10296 18610 10294 18610 10298 18610 10299 18611 10295 18611 10296 18611 10300 18612 10296 18612 10298 18612 10299 18613 10297 18613 10295 18613 10300 18614 10299 18614 10296 18614 10302 18615 10289 18615 10297 18615 10301 18616 10300 18616 10298 18616 10302 18617 10297 18617 10299 18617 10304 18618 10299 18618 10300 18618 10302 18619 10299 18619 10304 18619 10303 18620 10300 18620 10301 18620 10304 18621 10300 18621 10303 18621 10306 18622 10303 18622 10305 18622 10306 18623 10304 18623 10303 18623 10308 18624 10304 18624 10306 18624 10308 18625 10302 18625 10304 18625 10307 18626 10302 18626 10308 18626 10309 18627 10306 18627 10305 18627 10310 18628 10306 18628 10309 18628 10310 18629 10308 18629 10306 18629 10312 18630 10308 18630 10310 18630 10311 18631 10310 18631 10309 18631 10313 18632 10310 18632 10311 18632 10314 18633 10307 18633 10308 18633 10312 18634 10310 18634 10313 18634 10314 18635 10308 18635 10312 18635 10316 18636 10312 18636 10313 18636 10317 18637 10312 18637 10316 18637 10315 18638 10313 18638 10311 18638 10317 18639 10314 18639 10312 18639 10316 18640 10313 18640 10315 18640 10319 18641 10315 18641 10318 18641 10319 18642 10316 18642 10315 18642 10319 18643 10317 18643 10316 18643 10317 18644 10323 18644 10314 18644 10321 18645 10318 18645 10320 18645 10321 18646 10319 18646 10318 18646 10322 18647 10319 18647 10321 18647 10322 18648 10317 18648 10319 18648 10323 18649 10317 18649 10322 18649 10324 18650 10321 18650 10320 18650 10322 18651 10321 18651 10324 18651 10324 18652 10320 18652 10325 18652 10326 18653 10323 18653 10322 18653 10328 18654 10322 18654 10324 18654 10326 18655 10322 18655 10328 18655 10327 18656 10324 18656 10325 18656 10328 18657 10324 18657 10327 18657 10330 18658 10326 18658 10328 18658 10331 18659 10327 18659 10329 18659 10331 18660 10328 18660 10327 18660 10330 18661 10328 18661 10331 18661 10332 18662 10331 18662 10329 18662 10333 18663 10326 18663 10330 18663 10334 18664 10331 18664 10332 18664 10334 18665 10330 18665 10331 18665 10333 18666 10330 18666 10334 18666 10335 18667 10334 18667 10332 18667 10335 18668 10333 18668 10334 18668 10337 18669 10332 18669 10336 18669 10337 18670 10335 18670 10332 18670 10338 18671 10333 18671 10335 18671 10340 18672 10336 18672 10339 18672 10340 18673 10337 18673 10336 18673 10341 18674 10337 18674 10340 18674 10341 18675 10335 18675 10337 18675 10338 18676 10335 18676 10341 18676 10343 18677 10340 18677 10339 18677 10343 18678 10341 18678 10340 18678 10343 18679 10339 18679 10342 18679 10345 18680 10338 18680 10341 18680 10346 18681 10341 18681 10343 18681 10344 18682 10343 18682 10342 18682 10346 18683 10345 18683 10341 18683 10346 18684 10343 18684 10344 18684 10347 18685 10346 18685 10344 18685 10347 18686 10344 18686 10348 18686 10349 18687 10346 18687 10347 18687 10349 18688 10345 18688 10346 18688 10347 18689 10348 18689 10350 18689 10351 18690 10345 18690 10349 18690 10352 18691 10347 18691 10350 18691 10352 18692 10349 18692 10347 18692 10352 18693 10350 18693 10353 18693 10354 18694 10349 18694 10352 18694 10354 18695 10351 18695 10349 18695 10356 18696 10353 18696 10355 18696 10356 18697 10352 18697 10353 18697 10354 18698 10352 18698 10356 18698 10357 18699 10351 18699 10354 18699 10359 18700 10354 18700 10356 18700 10358 18701 10356 18701 10355 18701 10360 18702 10356 18702 10358 18702 10359 18703 10357 18703 10354 18703 10359 18704 10356 18704 10360 18704 10206 18705 10359 18705 10360 18705 10206 18706 10360 18706 10358 18706 10206 18707 10358 18707 10204 18707 10208 18708 10357 18708 10359 18708 10204 18709 10361 18709 10362 18709 10207 18710 10204 18710 10362 18710 10207 18711 10362 18711 10363 18711 10210 18712 10207 18712 10363 18712 10213 18713 10363 18713 10364 18713 10213 18714 10210 18714 10363 18714 10214 18715 10364 18715 10510 18715 10214 18716 10213 18716 10364 18716 10214 18717 10510 18717 10365 18717 10217 18718 10214 18718 10365 18718 10217 18719 10365 18719 10366 18719 10220 18720 10217 18720 10366 18720 10223 18721 10220 18721 10366 18721 10223 18722 10366 18722 10367 18722 10226 18723 10367 18723 10368 18723 10226 18724 10223 18724 10367 18724 10229 18725 10368 18725 10499 18725 10229 18726 10226 18726 10368 18726 10229 18727 10499 18727 10369 18727 10231 18728 10229 18728 10369 18728 10234 18729 10369 18729 10370 18729 10234 18730 10231 18730 10369 18730 10237 18731 10370 18731 10371 18731 10237 18732 10234 18732 10370 18732 10239 18733 10237 18733 10371 18733 10239 18734 10371 18734 10491 18734 10242 18735 10239 18735 10491 18735 10242 18736 10491 18736 10489 18736 10245 18737 10242 18737 10489 18737 10245 18738 10489 18738 10372 18738 10247 18739 10245 18739 10372 18739 10247 18740 10372 18740 10373 18740 10250 18741 10247 18741 10373 18741 10250 18742 10373 18742 10374 18742 10254 18743 10250 18743 10374 18743 10254 18744 10374 18744 10375 18744 10256 18745 10254 18745 10375 18745 10256 18746 10375 18746 10376 18746 10259 18747 10256 18747 10376 18747 10259 18748 10376 18748 10377 18748 10261 18749 10259 18749 10377 18749 10261 18750 10377 18750 10474 18750 10265 18751 10261 18751 10474 18751 10265 18752 10474 18752 10378 18752 10267 18753 10265 18753 10378 18753 10267 18754 10378 18754 10379 18754 10267 18755 10379 18755 10380 18755 10271 18756 10267 18756 10380 18756 10271 18757 10380 18757 10381 18757 10274 18758 10271 18758 10381 18758 10274 18759 10381 18759 10382 18759 10277 18760 10274 18760 10382 18760 10277 18761 10382 18761 10461 18761 10280 18762 10277 18762 10461 18762 10280 18763 10461 18763 10460 18763 10283 18764 10280 18764 10460 18764 10283 18765 10460 18765 10383 18765 10285 18766 10283 18766 10383 18766 10285 18767 10383 18767 10457 18767 10287 18768 10285 18768 10457 18768 10287 18769 10457 18769 10384 18769 10291 18770 10287 18770 10384 18770 10291 18771 10384 18771 10385 18771 10291 18772 10385 18772 10450 18772 10294 18773 10291 18773 10450 18773 10294 18774 10450 18774 10386 18774 10298 18775 10386 18775 10387 18775 10298 18776 10294 18776 10386 18776 10301 18777 10298 18777 10387 18777 10301 18778 10387 18778 10388 18778 10303 18779 10301 18779 10388 18779 10305 18780 10388 18780 10389 18780 10305 18781 10303 18781 10388 18781 10305 18782 10389 18782 10390 18782 10309 18783 10390 18783 10391 18783 10309 18784 10305 18784 10390 18784 10311 18785 10309 18785 10391 18785 10311 18786 10391 18786 10392 18786 10315 18787 10311 18787 10392 18787 10315 18788 10392 18788 10393 18788 10315 18789 10393 18789 10394 18789 10318 18790 10315 18790 10394 18790 10318 18791 10394 18791 10395 18791 10320 18792 10318 18792 10395 18792 10320 18793 10395 18793 10396 18793 10325 18794 10396 18794 10397 18794 10325 18795 10320 18795 10396 18795 10327 18796 10397 18796 10398 18796 10327 18797 10325 18797 10397 18797 10329 18798 10327 18798 10398 18798 10329 18799 10398 18799 10399 18799 10332 18800 10399 18800 10400 18800 10332 18801 10329 18801 10399 18801 10336 18802 10332 18802 10400 18802 10336 18803 10400 18803 10401 18803 10339 18804 10336 18804 10401 18804 10339 18805 10401 18805 10402 18805 10342 18806 10339 18806 10402 18806 10342 18807 10402 18807 10403 18807 10344 18808 10342 18808 10403 18808 10344 18809 10403 18809 10404 18809 10348 18810 10344 18810 10404 18810 10350 18811 10404 18811 10405 18811 10350 18812 10348 18812 10404 18812 10353 18813 10350 18813 10405 18813 10355 18814 10405 18814 10406 18814 10355 18815 10353 18815 10405 18815 10355 18816 10406 18816 10407 18816 10358 18817 10355 18817 10407 18817 10204 18818 10407 18818 10361 18818 10204 18819 10358 18819 10407 18819 10407 18820 10408 18820 10361 18820 10410 18821 10409 18821 10408 18821 10411 18822 10409 18822 10410 18822 10406 18823 10408 18823 10407 18823 10410 18824 10408 18824 10406 18824 10412 18825 10411 18825 10410 18825 10413 18826 10406 18826 10405 18826 10413 18827 10410 18827 10406 18827 10412 18828 10410 18828 10413 18828 10414 18829 10411 18829 10412 18829 10415 18830 10412 18830 10413 18830 10416 18831 10413 18831 10405 18831 10416 18832 10405 18832 10404 18832 10415 18833 10413 18833 10416 18833 10414 18834 10412 18834 10415 18834 10417 18835 10415 18835 10416 18835 10417 18836 10414 18836 10415 18836 10403 18837 10416 18837 10404 18837 10418 18838 10416 18838 10403 18838 10417 18839 10416 18839 10418 18839 10419 18840 10414 18840 10417 18840 10420 18841 10418 18841 10403 18841 10420 18842 10417 18842 10418 18842 10419 18843 10417 18843 10420 18843 10420 18844 10403 18844 10402 18844 10421 18845 10420 18845 10402 18845 10422 18846 10420 18846 10421 18846 10422 18847 10419 18847 10420 18847 10401 18848 10421 18848 10402 18848 10423 18849 10421 18849 10401 18849 10422 18850 10421 18850 10423 18850 10400 18851 10423 18851 10401 18851 10425 18852 10422 18852 10423 18852 10424 18853 10422 18853 10425 18853 10424 18854 10419 18854 10422 18854 10425 18855 10423 18855 10400 18855 10399 18856 10425 18856 10400 18856 10426 18857 10425 18857 10399 18857 10426 18858 10399 18858 10398 18858 10427 18859 10425 18859 10426 18859 10427 18860 10424 18860 10425 18860 10428 18861 10426 18861 10398 18861 10429 18862 10426 18862 10428 18862 10429 18863 10427 18863 10426 18863 10428 18864 10398 18864 10397 18864 10430 18865 10428 18865 10397 18865 10430 18866 10429 18866 10428 18866 10396 18867 10430 18867 10397 18867 10427 18868 10429 18868 10431 18868 10431 18869 10429 18869 10430 18869 10395 18870 10430 18870 10396 18870 10432 18871 10430 18871 10395 18871 10433 18872 10427 18872 10431 18872 10432 18873 10431 18873 10430 18873 10433 18874 10431 18874 10432 18874 10434 18875 10395 18875 10394 18875 10434 18876 10432 18876 10395 18876 10435 18877 10432 18877 10434 18877 10433 18878 10432 18878 10435 18878 10393 18879 10434 18879 10394 18879 10435 18880 10434 18880 10393 18880 10436 18881 10433 18881 10435 18881 10437 18882 10393 18882 10392 18882 10437 18883 10435 18883 10393 18883 10438 18884 10435 18884 10437 18884 10436 18885 10435 18885 10438 18885 10391 18886 10437 18886 10392 18886 10440 18887 10436 18887 10438 18887 10439 18888 10437 18888 10391 18888 10439 18889 10438 18889 10437 18889 10440 18890 10438 18890 10439 18890 10441 18891 10391 18891 10390 18891 10439 18892 10391 18892 10441 18892 10442 18893 10436 18893 10440 18893 10443 18894 10390 18894 10389 18894 10443 18895 10441 18895 10390 18895 10442 18896 10440 18896 10439 18896 10444 18897 10442 18897 10439 18897 10443 18898 10439 18898 10441 18898 10444 18899 10439 18899 10443 18899 10388 18900 10443 18900 10389 18900 10445 18901 10443 18901 10388 18901 10444 18902 10443 18902 10445 18902 10387 18903 10445 18903 10388 18903 10447 18904 10442 18904 10444 18904 10446 18905 10444 18905 10445 18905 10447 18906 10444 18906 10446 18906 10448 18907 10445 18907 10387 18907 10446 18908 10445 18908 10448 18908 10448 18909 10387 18909 10386 18909 10449 18910 10446 18910 10448 18910 10449 18911 10448 18911 10386 18911 10450 18912 10449 18912 10386 18912 10451 18913 10446 18913 10449 18913 10453 18914 10446 18914 10451 18914 10453 18915 10447 18915 10446 18915 10451 18916 10449 18916 10450 18916 10451 18917 10450 18917 10452 18917 10452 18918 10450 18918 10385 18918 10454 18919 10447 18919 10453 18919 10451 18920 10452 18920 10385 18920 10454 18921 10453 18921 10451 18921 10455 18922 10451 18922 10385 18922 10454 18923 10451 18923 10455 18923 10455 18924 10385 18924 10384 18924 10456 18925 10454 18925 10455 18925 10457 18926 10455 18926 10384 18926 10456 18927 10455 18927 10457 18927 10458 18928 10454 18928 10456 18928 10459 18929 10457 18929 10383 18929 10459 18930 10456 18930 10457 18930 10458 18931 10456 18931 10459 18931 10460 18932 10459 18932 10383 18932 10463 18933 10458 18933 10459 18933 10462 18934 10458 18934 10463 18934 10463 18935 10460 18935 10461 18935 10462 18936 10454 18936 10458 18936 10463 18937 10459 18937 10460 18937 10463 18938 10461 18938 10464 18938 10464 18939 10461 18939 10382 18939 10465 18940 10462 18940 10463 18940 10465 18941 10463 18941 10464 18941 10466 18942 10464 18942 10382 18942 10466 18943 10382 18943 10381 18943 10467 18944 10462 18944 10465 18944 10466 18945 10465 18945 10464 18945 10468 18946 10465 18946 10466 18946 10467 18947 10465 18947 10468 18947 10380 18948 10466 18948 10381 18948 10468 18949 10466 18949 10380 18949 10469 18950 10468 18950 10380 18950 10471 18951 10468 18951 10469 18951 10379 18952 10469 18952 10380 18952 10471 18953 10467 18953 10468 18953 10470 18954 10467 18954 10471 18954 10472 18955 10469 18955 10379 18955 10471 18956 10469 18956 10472 18956 10378 18957 10472 18957 10379 18957 10473 18958 10471 18958 10472 18958 10473 18959 10470 18959 10471 18959 10474 18960 10472 18960 10378 18960 10473 18961 10472 18961 10474 18961 10476 18962 10470 18962 10473 18962 10475 18963 10473 18963 10474 18963 10477 18964 10474 18964 10377 18964 10477 18965 10475 18965 10474 18965 10478 18966 10473 18966 10475 18966 10476 18967 10473 18967 10478 18967 10477 18968 10478 18968 10475 18968 10376 18969 10477 18969 10377 18969 10479 18970 10477 18970 10376 18970 10479 18971 10478 18971 10477 18971 10480 18972 10478 18972 10479 18972 10480 18973 10476 18973 10478 18973 10375 18974 10479 18974 10376 18974 10481 18975 10479 18975 10375 18975 10482 18976 10479 18976 10481 18976 10482 18977 10480 18977 10479 18977 10481 18978 10375 18978 10374 18978 10483 18979 10481 18979 10374 18979 10482 18980 10481 18980 10483 18980 10373 18981 10483 18981 10374 18981 10484 18982 10482 18982 10483 18982 10484 18983 10483 18983 10373 18983 10485 18984 10482 18984 10484 18984 10486 18985 10373 18985 10372 18985 10487 18986 10482 18986 10485 18986 10486 18987 10484 18987 10373 18987 10487 18988 10480 18988 10482 18988 10485 18989 10484 18989 10486 18989 10488 18990 10486 18990 10372 18990 10488 18991 10485 18991 10486 18991 10490 18992 10487 18992 10485 18992 10489 18993 10488 18993 10372 18993 10490 18994 10485 18994 10488 18994 10488 18995 10489 18995 10491 18995 10493 18996 10487 18996 10490 18996 10492 18997 10488 18997 10491 18997 10492 18998 10490 18998 10488 18998 10493 18999 10490 18999 10492 18999 10492 19000 10491 19000 10371 19000 10494 19001 10493 19001 10492 19001 10495 19002 10492 19002 10371 19002 10494 19003 10492 19003 10495 19003 10370 19004 10495 19004 10371 19004 10496 19005 10493 19005 10494 19005 10497 19006 10495 19006 10370 19006 10494 19007 10495 19007 10497 19007 10497 19008 10370 19008 10369 19008 10498 19009 10494 19009 10497 19009 10498 19010 10496 19010 10494 19010 10499 19011 10497 19011 10369 19011 10500 19012 10497 19012 10499 19012 10500 19013 10498 19013 10497 19013 10500 19014 10499 19014 10368 19014 10501 19015 10498 19015 10500 19015 10502 19016 10500 19016 10368 19016 10501 19017 10496 19017 10498 19017 10501 19018 10500 19018 10502 19018 10502 19019 10368 19019 10367 19019 10503 19020 10496 19020 10501 19020 10504 19021 10502 19021 10367 19021 10504 19022 10501 19022 10502 19022 10366 19023 10504 19023 10367 19023 10505 19024 10503 19024 10501 19024 10505 19025 10501 19025 10504 19025 10506 19026 10504 19026 10366 19026 10505 19027 10504 19027 10506 19027 10507 19028 10505 19028 10506 19028 10365 19029 10506 19029 10366 19029 10507 19030 10506 19030 10365 19030 10503 19031 10505 19031 10508 19031 10508 19032 10505 19032 10507 19032 10509 19033 10503 19033 10508 19033 10510 19034 10507 19034 10365 19034 10511 19035 10507 19035 10510 19035 10511 19036 10508 19036 10507 19036 10512 19037 10510 19037 10364 19037 10513 19038 10509 19038 10508 19038 10512 19039 10511 19039 10510 19039 10513 19040 10511 19040 10512 19040 10513 19041 10508 19041 10511 19041 10363 19042 10512 19042 10364 19042 10514 19043 10512 19043 10363 19043 10514 19044 10513 19044 10512 19044 10515 19045 10513 19045 10514 19045 10516 19046 10509 19046 10513 19046 10362 19047 10514 19047 10363 19047 10517 19048 10514 19048 10362 19048 10516 19049 10513 19049 10515 19049 10517 19050 10515 19050 10514 19050 10516 19051 10515 19051 10517 19051 10517 19052 10362 19052 10361 19052 10517 19053 10361 19053 10408 19053 10517 19054 10408 19054 10409 19054 10409 19055 10516 19055 10517 19055 10516 19056 10409 19056 10411 19056 10168 19057 10419 19057 10424 19057 10168 19058 10167 19058 10419 19058 10164 19059 10419 19059 10167 19059 10164 19060 10414 19060 10419 19060 10168 19061 10424 19061 10427 19061 10171 19062 10168 19062 10427 19062 10163 19063 10411 19063 10414 19063 10163 19064 10414 19064 10164 19064 10171 19065 10427 19065 10433 19065 10173 19066 10171 19066 10433 19066 10173 19067 10433 19067 10436 19067 10163 19068 10516 19068 10411 19068 10203 19069 10516 19069 10163 19069 10203 19070 10509 19070 10516 19070 10175 19071 10173 19071 10436 19071 10175 19072 10436 19072 10442 19072 10200 19073 10509 19073 10203 19073 10200 19074 10503 19074 10509 19074 10178 19075 10175 19075 10442 19075 10503 19076 10200 19076 10198 19076 10447 19077 10178 19077 10442 19077 10496 19078 10503 19078 10198 19078 10454 19079 10178 19079 10447 19079 10454 19080 10180 19080 10178 19080 10496 19081 10198 19081 10196 19081 10454 19082 10182 19082 10180 19082 10493 19083 10496 19083 10196 19083 10493 19084 10196 19084 10194 19084 10454 19085 10183 19085 10182 19085 10462 19086 10183 19086 10454 19086 10487 19087 10194 19087 10192 19087 10487 19088 10493 19088 10194 19088 10467 19089 10183 19089 10462 19089 10480 19090 10487 19090 10192 19090 10467 19091 10185 19091 10183 19091 10480 19092 10192 19092 10190 19092 10470 19093 10185 19093 10467 19093 10470 19094 10187 19094 10185 19094 10480 19095 10190 19095 10187 19095 10476 19096 10187 19096 10470 19096 10476 19097 10480 19097 10187 19097 10518 19098 10519 19098 10673 19098 10521 19099 10672 19099 10520 19099 10522 19100 10519 19100 10518 19100 10522 19101 10520 19101 10519 19101 10521 19102 10520 19102 10522 19102 10522 19103 10518 19103 10523 19103 10525 19104 10521 19104 10522 19104 10526 19105 10521 19105 10525 19105 10524 19106 10522 19106 10523 19106 10525 19107 10522 19107 10524 19107 10526 19108 10525 19108 10528 19108 10529 19109 10524 19109 10527 19109 10529 19110 10525 19110 10524 19110 10528 19111 10525 19111 10529 19111 10529 19112 10527 19112 10530 19112 10531 19113 10529 19113 10530 19113 10532 19114 10526 19114 10528 19114 10533 19115 10529 19115 10531 19115 10533 19116 10528 19116 10529 19116 10532 19117 10528 19117 10533 19117 10534 19118 10531 19118 10530 19118 10533 19119 10531 19119 10534 19119 10535 19120 10532 19120 10533 19120 10537 19121 10534 19121 10536 19121 10537 19122 10533 19122 10534 19122 10535 19123 10533 19123 10537 19123 10538 19124 10537 19124 10536 19124 10540 19125 10532 19125 10535 19125 10538 19126 10535 19126 10537 19126 10539 19127 10538 19127 10536 19127 10540 19128 10535 19128 10538 19128 10541 19129 10538 19129 10539 19129 10540 19130 10538 19130 10541 19130 10541 19131 10539 19131 10542 19131 10543 19132 10541 19132 10542 19132 10545 19133 10541 19133 10543 19133 10545 19134 10540 19134 10541 19134 10544 19135 10543 19135 10542 19135 10546 19136 10540 19136 10545 19136 10545 19137 10543 19137 10544 19137 10547 19138 10545 19138 10544 19138 10548 19139 10545 19139 10547 19139 10546 19140 10545 19140 10548 19140 10548 19141 10547 19141 10549 19141 10552 19142 10549 19142 10550 19142 10551 19143 10546 19143 10548 19143 10552 19144 10548 19144 10549 19144 10551 19145 10548 19145 10552 19145 10553 19146 10546 19146 10551 19146 10555 19147 10550 19147 10554 19147 10555 19148 10552 19148 10550 19148 10555 19149 10551 19149 10552 19149 10553 19150 10551 19150 10555 19150 10558 19151 10546 19151 10553 19151 10556 19152 10555 19152 10554 19152 10557 19153 10555 19153 10556 19153 10557 19154 10553 19154 10555 19154 10558 19155 10553 19155 10557 19155 10559 19156 10557 19156 10556 19156 10560 19157 10557 19157 10559 19157 10558 19158 10557 19158 10560 19158 10562 19159 10560 19159 10559 19159 10562 19160 10558 19160 10560 19160 10561 19161 10562 19161 10559 19161 10564 19162 10558 19162 10562 19162 10565 19163 10558 19163 10564 19163 10566 19164 10561 19164 10563 19164 10566 19165 10562 19165 10561 19165 10564 19166 10562 19166 10566 19166 10566 19167 10563 19167 10567 19167 10565 19168 10564 19168 10566 19168 10568 19169 10566 19169 10567 19169 10569 19170 10568 19170 10567 19170 10570 19171 10566 19171 10568 19171 10570 19172 10565 19172 10566 19172 10571 19173 10568 19173 10569 19173 10572 19174 10568 19174 10571 19174 10572 19175 10570 19175 10568 19175 10573 19176 10565 19176 10570 19176 10573 19177 10570 19177 10572 19177 10575 19178 10565 19178 10573 19178 10574 19179 10572 19179 10571 19179 10576 19180 10572 19180 10574 19180 10576 19181 10573 19181 10572 19181 10578 19182 10573 19182 10576 19182 10578 19183 10575 19183 10573 19183 10577 19184 10576 19184 10574 19184 10578 19185 10576 19185 10577 19185 10579 19186 10575 19186 10578 19186 10581 19187 10577 19187 10580 19187 10581 19188 10578 19188 10577 19188 10579 19189 10578 19189 10581 19189 10582 19190 10581 19190 10580 19190 10583 19191 10579 19191 10581 19191 10584 19192 10581 19192 10582 19192 10584 19193 10583 19193 10581 19193 10584 19194 10582 19194 10586 19194 10583 19195 10585 19195 10579 19195 10587 19196 10584 19196 10586 19196 10587 19197 10583 19197 10584 19197 10587 19198 10586 19198 10588 19198 10589 19199 10587 19199 10588 19199 10585 19200 10583 19200 10587 19200 10592 19201 10585 19201 10587 19201 10590 19202 10587 19202 10589 19202 10592 19203 10587 19203 10590 19203 10591 19204 10589 19204 10588 19204 10590 19205 10589 19205 10591 19205 10596 19206 10585 19206 10592 19206 10593 19207 10590 19207 10591 19207 10594 19208 10590 19208 10593 19208 10594 19209 10592 19209 10590 19209 10596 19210 10592 19210 10594 19210 10595 19211 10594 19211 10593 19211 10598 19212 10596 19212 10594 19212 10597 19213 10594 19213 10595 19213 10599 19214 10594 19214 10597 19214 10598 19215 10594 19215 10599 19215 10601 19216 10596 19216 10598 19216 10599 19217 10597 19217 10600 19217 10602 19218 10598 19218 10599 19218 10601 19219 10598 19219 10602 19219 10604 19220 10600 19220 10603 19220 10604 19221 10599 19221 10600 19221 10602 19222 10599 19222 10604 19222 10604 19223 10603 19223 10605 19223 10606 19224 10602 19224 10604 19224 10607 19225 10604 19225 10605 19225 10601 19226 10602 19226 10606 19226 10606 19227 10604 19227 10607 19227 10608 19228 10606 19228 10607 19228 10609 19229 10607 19229 10605 19229 10608 19230 10601 19230 10606 19230 10610 19231 10607 19231 10609 19231 10611 19232 10601 19232 10608 19232 10608 19233 10607 19233 10610 19233 10612 19234 10608 19234 10610 19234 10610 19235 10609 19235 10613 19235 10612 19236 10611 19236 10608 19236 10614 19237 10610 19237 10613 19237 10614 19238 10612 19238 10610 19238 10614 19239 10613 19239 10615 19239 10616 19240 10611 19240 10612 19240 10617 19241 10614 19241 10615 19241 10617 19242 10612 19242 10614 19242 10616 19243 10612 19243 10617 19243 10617 19244 10615 19244 10619 19244 10618 19245 10611 19245 10616 19245 10620 19246 10617 19246 10619 19246 10621 19247 10617 19247 10620 19247 10621 19248 10616 19248 10617 19248 10620 19249 10619 19249 10622 19249 10618 19250 10616 19250 10621 19250 10623 19251 10620 19251 10622 19251 10624 19252 10620 19252 10623 19252 10624 19253 10621 19253 10620 19253 10625 19254 10621 19254 10624 19254 10625 19255 10618 19255 10621 19255 10626 19256 10624 19256 10623 19256 10625 19257 10624 19257 10626 19257 10627 19258 10626 19258 10623 19258 10628 19259 10618 19259 10625 19259 10629 19260 10625 19260 10626 19260 10630 19261 10626 19261 10627 19261 10628 19262 10625 19262 10629 19262 10631 19263 10626 19263 10630 19263 10631 19264 10629 19264 10626 19264 10631 19265 10628 19265 10629 19265 10632 19266 10631 19266 10630 19266 10634 19267 10631 19267 10632 19267 10634 19268 10628 19268 10631 19268 10634 19269 10632 19269 10633 19269 10635 19270 10628 19270 10634 19270 10637 19271 10633 19271 10636 19271 10639 19272 10635 19272 10634 19272 10637 19273 10634 19273 10633 19273 10639 19274 10634 19274 10637 19274 10638 19275 10637 19275 10636 19275 10640 19276 10637 19276 10638 19276 10640 19277 10639 19277 10637 19277 10641 19278 10635 19278 10639 19278 10643 19279 10639 19279 10640 19279 10641 19280 10639 19280 10643 19280 10642 19281 10640 19281 10638 19281 10643 19282 10640 19282 10642 19282 10645 19283 10642 19283 10644 19283 10645 19284 10643 19284 10642 19284 10646 19285 10645 19285 10644 19285 10647 19286 10641 19286 10643 19286 10648 19287 10643 19287 10645 19287 10648 19288 10647 19288 10643 19288 10648 19289 10645 19289 10646 19289 10650 19290 10648 19290 10646 19290 10651 19291 10648 19291 10650 19291 10651 19292 10647 19292 10648 19292 10650 19293 10646 19293 10649 19293 10652 19294 10647 19294 10651 19294 10651 19295 10650 19295 10649 19295 10654 19296 10651 19296 10649 19296 10655 19297 10649 19297 10653 19297 10654 19298 10649 19298 10655 19298 10656 19299 10652 19299 10651 19299 10656 19300 10651 19300 10654 19300 10657 19301 10654 19301 10655 19301 10656 19302 10654 19302 10657 19302 10657 19303 10655 19303 10658 19303 10659 19304 10652 19304 10656 19304 10661 19305 10656 19305 10657 19305 10660 19306 10657 19306 10658 19306 10661 19307 10657 19307 10660 19307 10659 19308 10656 19308 10661 19308 10663 19309 10660 19309 10662 19309 10663 19310 10661 19310 10660 19310 10664 19311 10661 19311 10663 19311 10659 19312 10661 19312 10664 19312 10665 19313 10663 19313 10662 19313 10666 19314 10663 19314 10665 19314 10666 19315 10664 19315 10663 19315 10667 19316 10659 19316 10664 19316 10668 19317 10666 19317 10665 19317 10668 19318 10664 19318 10666 19318 10670 19319 10664 19319 10668 19319 10669 19320 10668 19320 10665 19320 10670 19321 10667 19321 10664 19321 10671 19322 10668 19322 10669 19322 10672 19323 10667 19323 10670 19323 10670 19324 10668 19324 10671 19324 10673 19325 10671 19325 10669 19325 10671 19326 10673 19326 10519 19326 10521 19327 10667 19327 10672 19327 10671 19328 10519 19328 10520 19328 10520 19329 10670 19329 10671 19329 10672 19330 10670 19330 10520 19330 10675 19331 10674 19331 10673 19331 10675 19332 10673 19332 10669 19332 10676 19333 10675 19333 10669 19333 10677 19334 10669 19334 10665 19334 10677 19335 10676 19335 10669 19335 10678 19336 10665 19336 10662 19336 10678 19337 10677 19337 10665 19337 10679 19338 10662 19338 10660 19338 10679 19339 10678 19339 10662 19339 10680 19340 10679 19340 10660 19340 10680 19341 10660 19341 10658 19341 10681 19342 10680 19342 10658 19342 10681 19343 10658 19343 10655 19343 10682 19344 10681 19344 10655 19344 10682 19345 10655 19345 10653 19345 10682 19346 10653 19346 10649 19346 10683 19347 10682 19347 10649 19347 10683 19348 10649 19348 10646 19348 10684 19349 10683 19349 10646 19349 10685 19350 10646 19350 10644 19350 10685 19351 10684 19351 10646 19351 10686 19352 10644 19352 10642 19352 10686 19353 10685 19353 10644 19353 10687 19354 10642 19354 10638 19354 10687 19355 10686 19355 10642 19355 10687 19356 10638 19356 10636 19356 10753 19357 10687 19357 10636 19357 10688 19358 10636 19358 10633 19358 10688 19359 10753 19359 10636 19359 10689 19360 10633 19360 10632 19360 10689 19361 10688 19361 10633 19361 10690 19362 10632 19362 10630 19362 10690 19363 10689 19363 10632 19363 10690 19364 10630 19364 10627 19364 10691 19365 10690 19365 10627 19365 10692 19366 10691 19366 10627 19366 10692 19367 10627 19367 10623 19367 10693 19368 10623 19368 10622 19368 10693 19369 10692 19369 10623 19369 10694 19370 10622 19370 10619 19370 10694 19371 10693 19371 10622 19371 10695 19372 10619 19372 10615 19372 10695 19373 10694 19373 10619 19373 10695 19374 10615 19374 10613 19374 10696 19375 10695 19375 10613 19375 10696 19376 10613 19376 10609 19376 10697 19377 10696 19377 10609 19377 10697 19378 10609 19378 10605 19378 10698 19379 10697 19379 10605 19379 10699 19380 10698 19380 10605 19380 10699 19381 10605 19381 10603 19381 10700 19382 10699 19382 10603 19382 10700 19383 10603 19383 10600 19383 10700 19384 10600 19384 10597 19384 10701 19385 10700 19385 10597 19385 10701 19386 10597 19386 10595 19386 10702 19387 10701 19387 10595 19387 10703 19388 10702 19388 10595 19388 10703 19389 10595 19389 10593 19389 10704 19390 10703 19390 10593 19390 10704 19391 10593 19391 10591 19391 10704 19392 10591 19392 10588 19392 10705 19393 10704 19393 10588 19393 10706 19394 10705 19394 10588 19394 10706 19395 10588 19395 10586 19395 10706 19396 10586 19396 10582 19396 10707 19397 10706 19397 10582 19397 10707 19398 10582 19398 10580 19398 10708 19399 10707 19399 10580 19399 10708 19400 10580 19400 10577 19400 10709 19401 10708 19401 10577 19401 10709 19402 10577 19402 10574 19402 10710 19403 10709 19403 10574 19403 10710 19404 10574 19404 10571 19404 10711 19405 10710 19405 10571 19405 10712 19406 10571 19406 10569 19406 10712 19407 10711 19407 10571 19407 10713 19408 10569 19408 10567 19408 10713 19409 10712 19409 10569 19409 10714 19410 10713 19410 10567 19410 10714 19411 10567 19411 10563 19411 10715 19412 10714 19412 10563 19412 10715 19413 10563 19413 10561 19413 10716 19414 10715 19414 10561 19414 10716 19415 10561 19415 10559 19415 10717 19416 10716 19416 10559 19416 10717 19417 10559 19417 10556 19417 10718 19418 10717 19418 10556 19418 10718 19419 10556 19419 10554 19419 10719 19420 10718 19420 10554 19420 10719 19421 10554 19421 10550 19421 10720 19422 10719 19422 10550 19422 10721 19423 10720 19423 10550 19423 10721 19424 10550 19424 10549 19424 10721 19425 10549 19425 10547 19425 10722 19426 10721 19426 10547 19426 10722 19427 10547 19427 10544 19427 10723 19428 10722 19428 10544 19428 10723 19429 10544 19429 10542 19429 10724 19430 10542 19430 10539 19430 10724 19431 10723 19431 10542 19431 10725 19432 10539 19432 10536 19432 10725 19433 10724 19433 10539 19433 10725 19434 10536 19434 10534 19434 10726 19435 10725 19435 10534 19435 10726 19436 10534 19436 10530 19436 10727 19437 10726 19437 10530 19437 10727 19438 10530 19438 10527 19438 10728 19439 10727 19439 10527 19439 10728 19440 10527 19440 10524 19440 10729 19441 10728 19441 10524 19441 10729 19442 10524 19442 10523 19442 10730 19443 10523 19443 10518 19443 10730 19444 10729 19444 10523 19444 10674 19445 10730 19445 10518 19445 10674 19446 10518 19446 10673 19446 10675 19447 10731 19447 10674 19447 10732 19448 10731 19448 10675 19448 10734 19449 10733 19449 10732 19449 10735 19450 10675 19450 10676 19450 10735 19451 10732 19451 10675 19451 10734 19452 10732 19452 10735 19452 10736 19453 10676 19453 10677 19453 10736 19454 10735 19454 10676 19454 10736 19455 10677 19455 10678 19455 10737 19456 10735 19456 10736 19456 10738 19457 10735 19457 10737 19457 10738 19458 10734 19458 10735 19458 10737 19459 10736 19459 10678 19459 10739 19460 10678 19460 10679 19460 10739 19461 10737 19461 10678 19461 10740 19462 10737 19462 10739 19462 10740 19463 10738 19463 10737 19463 10680 19464 10739 19464 10679 19464 10744 19465 10734 19465 10738 19465 10741 19466 10739 19466 10680 19466 10744 19467 10738 19467 10740 19467 10740 19468 10739 19468 10741 19468 10741 19469 10680 19469 10681 19469 10742 19470 10740 19470 10741 19470 10743 19471 10741 19471 10681 19471 10744 19472 10740 19472 10742 19472 10742 19473 10741 19473 10743 19473 10682 19474 10743 19474 10681 19474 10745 19475 10743 19475 10682 19475 10745 19476 10742 19476 10743 19476 10746 19477 10742 19477 10745 19477 10683 19478 10745 19478 10682 19478 10747 19479 10745 19479 10683 19479 10746 19480 10744 19480 10742 19480 10746 19481 10745 19481 10747 19481 10684 19482 10747 19482 10683 19482 10748 19483 10744 19483 10746 19483 10749 19484 10746 19484 10747 19484 10750 19485 10747 19485 10684 19485 10748 19486 10746 19486 10749 19486 10749 19487 10747 19487 10750 19487 10685 19488 10750 19488 10684 19488 10751 19489 10749 19489 10750 19489 10686 19490 10750 19490 10685 19490 10751 19491 10750 19491 10686 19491 10751 19492 10748 19492 10749 19492 10752 19493 10686 19493 10687 19493 10752 19494 10751 19494 10686 19494 10753 19495 10752 19495 10687 19495 10754 19496 10748 19496 10751 19496 10754 19497 10751 19497 10752 19497 10755 19498 10752 19498 10753 19498 10756 19499 10752 19499 10755 19499 10756 19500 10754 19500 10752 19500 10688 19501 10755 19501 10753 19501 10757 19502 10754 19502 10756 19502 10758 19503 10756 19503 10755 19503 10689 19504 10755 19504 10688 19504 10757 19505 10756 19505 10758 19505 10758 19506 10755 19506 10689 19506 10759 19507 10689 19507 10690 19507 10758 19508 10689 19508 10759 19508 10760 19509 10758 19509 10759 19509 10760 19510 10757 19510 10758 19510 10691 19511 10759 19511 10690 19511 10761 19512 10759 19512 10691 19512 10762 19513 10757 19513 10760 19513 10761 19514 10760 19514 10759 19514 10763 19515 10691 19515 10692 19515 10763 19516 10761 19516 10691 19516 10765 19517 10761 19517 10763 19517 10764 19518 10761 19518 10765 19518 10764 19519 10760 19519 10761 19519 10765 19520 10763 19520 10692 19520 10764 19521 10762 19521 10760 19521 10693 19522 10765 19522 10692 19522 10766 19523 10762 19523 10764 19523 10767 19524 10765 19524 10693 19524 10768 19525 10765 19525 10767 19525 10768 19526 10764 19526 10765 19526 10766 19527 10764 19527 10768 19527 10767 19528 10693 19528 10694 19528 10769 19529 10694 19529 10695 19529 10769 19530 10767 19530 10694 19530 10768 19531 10767 19531 10769 19531 10770 19532 10768 19532 10769 19532 10766 19533 10768 19533 10770 19533 10696 19534 10769 19534 10695 19534 10770 19535 10769 19535 10696 19535 10771 19536 10766 19536 10770 19536 10772 19537 10770 19537 10696 19537 10773 19538 10766 19538 10771 19538 10772 19539 10771 19539 10770 19539 10697 19540 10772 19540 10696 19540 10774 19541 10697 19541 10698 19541 10774 19542 10772 19542 10697 19542 10775 19543 10772 19543 10774 19543 10775 19544 10771 19544 10772 19544 10773 19545 10771 19545 10775 19545 10699 19546 10774 19546 10698 19546 10776 19547 10774 19547 10699 19547 10776 19548 10775 19548 10774 19548 10777 19549 10773 19549 10775 19549 10778 19550 10699 19550 10700 19550 10777 19551 10775 19551 10776 19551 10778 19552 10776 19552 10699 19552 10779 19553 10776 19553 10778 19553 10779 19554 10777 19554 10776 19554 10780 19555 10778 19555 10700 19555 10779 19556 10778 19556 10780 19556 10701 19557 10780 19557 10700 19557 10781 19558 10779 19558 10780 19558 10782 19559 10779 19559 10781 19559 10782 19560 10777 19560 10779 19560 10702 19561 10780 19561 10701 19561 10783 19562 10780 19562 10702 19562 10783 19563 10781 19563 10780 19563 10784 19564 10781 19564 10783 19564 10703 19565 10783 19565 10702 19565 10784 19566 10782 19566 10781 19566 10786 19567 10783 19567 10703 19567 10785 19568 10783 19568 10786 19568 10785 19569 10784 19569 10783 19569 10786 19570 10703 19570 10704 19570 10705 19571 10786 19571 10704 19571 10787 19572 10786 19572 10705 19572 10785 19573 10786 19573 10787 19573 10788 19574 10784 19574 10785 19574 10789 19575 10787 19575 10705 19575 10790 19576 10785 19576 10787 19576 10789 19577 10705 19577 10706 19577 10788 19578 10785 19578 10790 19578 10790 19579 10787 19579 10789 19579 10791 19580 10789 19580 10706 19580 10791 19581 10790 19581 10789 19581 10791 19582 10706 19582 10707 19582 10792 19583 10788 19583 10790 19583 10792 19584 10790 19584 10791 19584 10791 19585 10707 19585 10708 19585 10793 19586 10792 19586 10791 19586 10794 19587 10791 19587 10708 19587 10795 19588 10788 19588 10792 19588 10793 19589 10791 19589 10794 19589 10795 19590 10792 19590 10793 19590 10709 19591 10794 19591 10708 19591 10796 19592 10793 19592 10794 19592 10796 19593 10794 19593 10709 19593 10795 19594 10793 19594 10796 19594 10710 19595 10796 19595 10709 19595 10797 19596 10795 19596 10796 19596 10798 19597 10796 19597 10710 19597 10797 19598 10796 19598 10798 19598 10798 19599 10710 19599 10711 19599 10799 19600 10797 19600 10798 19600 10800 19601 10795 19601 10797 19601 10712 19602 10798 19602 10711 19602 10800 19603 10797 19603 10799 19603 10712 19604 10799 19604 10798 19604 10805 19605 10795 19605 10800 19605 10801 19606 10799 19606 10712 19606 10800 19607 10799 19607 10801 19607 10801 19608 10712 19608 10713 19608 10802 19609 10800 19609 10801 19609 10803 19610 10801 19610 10713 19610 10802 19611 10801 19611 10803 19611 10714 19612 10803 19612 10713 19612 10805 19613 10800 19613 10802 19613 10804 19614 10803 19614 10714 19614 10802 19615 10803 19615 10804 19615 10806 19616 10802 19616 10804 19616 10715 19617 10804 19617 10714 19617 10806 19618 10805 19618 10802 19618 10806 19619 10804 19619 10715 19619 10808 19620 10805 19620 10806 19620 10807 19621 10715 19621 10716 19621 10807 19622 10806 19622 10715 19622 10808 19623 10806 19623 10807 19623 10807 19624 10716 19624 10717 19624 10809 19625 10807 19625 10717 19625 10809 19626 10808 19626 10807 19626 10718 19627 10809 19627 10717 19627 10810 19628 10808 19628 10809 19628 10811 19629 10809 19629 10718 19629 10810 19630 10809 19630 10811 19630 10719 19631 10811 19631 10718 19631 10812 19632 10810 19632 10811 19632 10720 19633 10811 19633 10719 19633 10812 19634 10811 19634 10720 19634 10813 19635 10720 19635 10721 19635 10813 19636 10812 19636 10720 19636 10814 19637 10810 19637 10812 19637 10815 19638 10721 19638 10722 19638 10815 19639 10813 19639 10721 19639 10816 19640 10813 19640 10815 19640 10816 19641 10812 19641 10813 19641 10814 19642 10812 19642 10816 19642 10723 19643 10815 19643 10722 19643 10817 19644 10815 19644 10723 19644 10817 19645 10816 19645 10815 19645 10817 19646 10814 19646 10816 19646 10818 19647 10814 19647 10817 19647 10819 19648 10723 19648 10724 19648 10819 19649 10817 19649 10723 19649 10820 19650 10817 19650 10819 19650 10818 19651 10817 19651 10820 19651 10821 19652 10820 19652 10819 19652 10725 19653 10819 19653 10724 19653 10821 19654 10819 19654 10725 19654 10822 19655 10820 19655 10821 19655 10822 19656 10818 19656 10820 19656 10823 19657 10821 19657 10725 19657 10822 19658 10821 19658 10823 19658 10726 19659 10823 19659 10725 19659 10825 19660 10726 19660 10727 19660 10824 19661 10822 19661 10823 19661 10825 19662 10823 19662 10726 19662 10825 19663 10824 19663 10823 19663 10826 19664 10822 19664 10824 19664 10827 19665 10822 19665 10826 19665 10828 19666 10825 19666 10727 19666 10828 19667 10824 19667 10825 19667 10826 19668 10824 19668 10828 19668 10728 19669 10828 19669 10727 19669 10829 19670 10826 19670 10828 19670 10827 19671 10826 19671 10829 19671 10829 19672 10828 19672 10728 19672 10830 19673 10827 19673 10829 19673 10729 19674 10829 19674 10728 19674 10830 19675 10829 19675 10729 19675 10831 19676 10827 19676 10830 19676 10730 19677 10830 19677 10729 19677 10832 19678 10830 19678 10730 19678 10731 19679 10730 19679 10674 19679 10832 19680 10831 19680 10830 19680 10731 19681 10832 19681 10730 19681 10832 19682 10731 19682 10732 19682 10832 19683 10732 19683 10733 19683 10831 19684 10832 19684 10733 19684 10158 19685 10795 19685 10156 19685 10158 19686 10788 19686 10795 19686 10154 19687 10156 19687 10795 19687 10154 19688 10795 19688 10805 19688 10159 19689 10788 19689 10158 19689 10152 19690 10154 19690 10805 19690 10159 19691 10784 19691 10788 19691 10152 19692 10805 19692 10808 19692 10161 19693 10784 19693 10159 19693 10150 19694 10808 19694 10810 19694 10150 19695 10152 19695 10808 19695 10118 19696 10784 19696 10161 19696 10118 19697 10782 19697 10784 19697 10147 19698 10150 19698 10810 19698 10121 19699 10782 19699 10118 19699 10121 19700 10777 19700 10782 19700 10147 19701 10810 19701 10814 19701 10121 19702 10773 19702 10777 19702 10146 19703 10147 19703 10814 19703 10146 19704 10814 19704 10818 19704 10123 19705 10773 19705 10121 19705 10144 19706 10146 19706 10818 19706 10766 19707 10773 19707 10123 19707 10822 19708 10144 19708 10818 19708 10141 19709 10144 19709 10822 19709 10766 19710 10123 19710 10125 19710 10827 19711 10141 19711 10822 19711 10762 19712 10766 19712 10125 19712 10762 19713 10125 19713 10127 19713 10831 19714 10141 19714 10827 19714 10831 19715 10139 19715 10141 19715 10757 19716 10762 19716 10127 19716 10733 19717 10139 19717 10831 19717 10757 19718 10127 19718 10129 19718 10754 19719 10757 19719 10129 19719 10734 19720 10137 19720 10139 19720 10734 19721 10139 19721 10733 19721 10734 19722 10135 19722 10137 19722 10754 19723 10129 19723 10131 19723 10748 19724 10754 19724 10131 19724 10744 19725 10135 19725 10734 19725 10744 19726 10133 19726 10135 19726 10744 19727 10748 19727 10131 19727 10744 19728 10131 19728 10133 19728 10835 19729 10833 19729 10834 19729 10835 19730 10834 19730 10836 19730 11072 19731 10835 19731 10836 19731 10837 19732 10836 19732 10838 19732 10837 19733 11072 19733 10836 19733 10839 19734 10837 19734 10838 19734 10840 19735 10839 19735 10838 19735 10840 19736 10838 19736 10841 19736 10842 19737 10840 19737 10841 19737 10843 19738 10842 19738 10841 19738 10844 19739 10843 19739 10841 19739 10844 19740 10841 19740 10845 19740 10846 19741 10844 19741 10845 19741 10846 19742 10845 19742 10847 19742 10848 19743 10846 19743 10847 19743 10849 19744 10848 19744 10847 19744 10849 19745 10847 19745 10850 19745 10851 19746 10849 19746 10850 19746 10852 19747 10851 19747 10850 19747 10853 19748 10850 19748 10854 19748 10853 19749 10852 19749 10850 19749 10855 19750 10853 19750 10854 19750 10856 19751 10855 19751 10854 19751 10856 19752 10854 19752 10857 19752 10858 19753 10856 19753 10857 19753 10859 19754 10858 19754 10857 19754 10859 19755 10857 19755 10860 19755 10861 19756 10859 19756 10860 19756 10862 19757 10861 19757 10860 19757 10862 19758 10860 19758 10863 19758 10864 19759 10862 19759 10863 19759 10864 19760 10863 19760 10865 19760 10866 19761 10864 19761 10865 19761 10867 19762 10866 19762 10865 19762 10868 19763 10867 19763 10865 19763 10868 19764 10865 19764 10869 19764 10870 19765 10868 19765 10869 19765 10870 19766 10869 19766 10871 19766 10872 19767 10870 19767 10871 19767 10873 19768 10871 19768 10874 19768 10873 19769 10872 19769 10871 19769 10875 19770 10873 19770 10874 19770 10875 19771 10874 19771 10876 19771 10877 19772 10875 19772 10876 19772 10878 19773 10877 19773 10876 19773 10879 19774 10878 19774 10876 19774 10879 19775 10876 19775 10880 19775 10881 19776 10879 19776 10880 19776 10882 19777 10881 19777 10880 19777 10883 19778 10882 19778 10880 19778 10883 19779 10880 19779 10884 19779 10885 19780 10883 19780 10884 19780 10886 19781 10884 19781 10887 19781 10886 19782 10885 19782 10884 19782 10888 19783 10886 19783 10887 19783 10889 19784 10888 19784 10887 19784 10890 19785 10887 19785 10891 19785 10890 19786 10889 19786 10887 19786 10892 19787 10890 19787 10891 19787 10893 19788 10892 19788 10891 19788 10894 19789 10893 19789 10891 19789 10894 19790 10891 19790 10895 19790 10896 19791 10894 19791 10895 19791 10897 19792 10896 19792 10895 19792 10897 19793 10895 19793 10898 19793 10899 19794 10897 19794 10898 19794 10900 19795 10899 19795 10898 19795 10900 19796 10898 19796 10901 19796 10902 19797 10900 19797 10901 19797 10903 19798 10902 19798 10901 19798 10833 19799 10903 19799 10901 19799 10833 19800 10901 19800 10834 19800 10904 19801 10966 19801 11068 19801 10904 19802 11068 19802 10905 19802 10906 19803 10904 19803 10905 19803 10906 19804 10905 19804 10907 19804 10906 19805 10907 19805 10908 19805 10906 19806 10908 19806 11059 19806 10909 19807 10906 19807 11059 19807 10909 19808 11059 19808 10911 19808 10910 19809 10909 19809 10911 19809 10910 19810 10911 19810 11055 19810 10910 19811 11055 19811 10912 19811 10910 19812 10912 19812 10913 19812 10914 19813 10910 19813 10913 19813 10914 19814 10913 19814 10915 19814 10916 19815 10914 19815 10915 19815 10916 19816 10915 19816 10917 19816 10916 19817 10917 19817 10918 19817 10919 19818 10916 19818 10918 19818 10919 19819 10918 19819 11042 19819 10919 19820 11042 19820 11040 19820 10920 19821 10919 19821 11040 19821 10920 19822 11040 19822 10921 19822 10922 19823 10920 19823 10921 19823 10922 19824 10921 19824 10923 19824 10922 19825 10923 19825 11032 19825 10924 19826 10922 19826 11032 19826 10924 19827 11032 19827 10925 19827 10924 19828 10925 19828 10926 19828 10927 19829 10924 19829 10926 19829 10927 19830 10926 19830 10928 19830 10927 19831 10928 19831 10929 19831 10930 19832 10927 19832 10929 19832 10930 19833 10929 19833 10931 19833 10930 19834 10931 19834 10932 19834 10933 19835 10930 19835 10932 19835 10933 19836 10932 19836 10934 19836 10933 19837 10934 19837 10935 19837 10933 19838 10935 19838 10936 19838 10937 19839 10933 19839 10936 19839 10937 19840 10936 19840 10938 19840 10937 19841 10938 19841 10939 19841 10940 19842 10937 19842 10939 19842 10940 19843 10939 19843 10941 19843 10940 19844 10941 19844 10942 19844 10943 19845 10942 19845 10944 19845 10943 19846 10940 19846 10942 19846 10943 19847 10944 19847 11000 19847 10945 19848 10943 19848 11000 19848 10945 19849 11000 19849 10946 19849 10947 19850 10945 19850 10946 19850 10947 19851 10946 19851 10995 19851 10947 19852 10995 19852 10948 19852 10947 19853 10948 19853 10949 19853 10950 19854 10947 19854 10949 19854 10950 19855 10949 19855 10951 19855 10952 19856 10951 19856 10953 19856 10952 19857 10950 19857 10951 19857 10952 19858 10953 19858 10985 19858 10954 19859 10952 19859 10985 19859 10954 19860 10985 19860 10955 19860 10954 19861 10955 19861 10956 19861 10957 19862 10954 19862 10956 19862 10957 19863 10956 19863 10958 19863 10959 19864 10957 19864 10958 19864 10959 19865 10958 19865 10960 19865 10959 19866 10960 19866 10961 19866 10962 19867 10959 19867 10961 19867 10962 19868 10961 19868 10963 19868 10964 19869 10963 19869 10965 19869 10964 19870 10962 19870 10963 19870 10964 19871 10965 19871 10966 19871 10904 19872 10964 19872 10966 19872 10969 19873 10968 19873 10967 19873 10965 19874 10967 19874 10966 19874 10970 19875 10967 19875 10965 19875 10970 19876 10969 19876 10967 19876 10971 19877 11067 19877 10969 19877 10972 19878 10965 19878 10963 19878 10972 19879 10970 19879 10965 19879 10973 19880 10969 19880 10970 19880 10973 19881 10971 19881 10969 19881 10974 19882 10970 19882 10972 19882 10961 19883 10972 19883 10963 19883 10974 19884 10973 19884 10970 19884 10974 19885 10972 19885 10961 19885 10975 19886 10971 19886 10973 19886 10976 19887 10961 19887 10960 19887 10976 19888 10974 19888 10961 19888 10977 19889 10974 19889 10976 19889 10977 19890 10973 19890 10974 19890 10975 19891 10973 19891 10977 19891 10978 19892 10976 19892 10960 19892 10979 19893 10976 19893 10978 19893 10979 19894 10977 19894 10976 19894 10975 19895 10977 19895 10979 19895 10958 19896 10978 19896 10960 19896 10956 19897 10978 19897 10958 19897 10980 19898 10978 19898 10956 19898 10981 19899 10975 19899 10979 19899 10980 19900 10979 19900 10978 19900 10981 19901 10979 19901 10980 19901 10982 19902 10956 19902 10955 19902 10982 19903 10980 19903 10956 19903 10983 19904 10980 19904 10982 19904 10981 19905 10980 19905 10983 19905 10988 19906 10981 19906 10983 19906 10984 19907 10983 19907 10982 19907 10985 19908 10982 19908 10955 19908 10984 19909 10982 19909 10985 19909 10986 19910 10983 19910 10984 19910 10986 19911 10988 19911 10983 19911 10987 19912 10985 19912 10953 19912 10987 19913 10984 19913 10985 19913 10987 19914 10986 19914 10984 19914 10987 19915 10953 19915 10951 19915 10990 19916 10988 19916 10986 19916 10989 19917 10987 19917 10951 19917 10990 19918 10986 19918 10987 19918 10990 19919 10987 19919 10989 19919 10991 19920 10988 19920 10990 19920 10949 19921 10989 19921 10951 19921 10992 19922 10989 19922 10949 19922 10990 19923 10989 19923 10992 19923 10993 19924 10990 19924 10992 19924 10991 19925 10990 19925 10993 19925 10948 19926 10992 19926 10949 19926 10994 19927 10992 19927 10948 19927 10994 19928 10993 19928 10992 19928 10996 19929 10993 19929 10994 19929 10995 19930 10994 19930 10948 19930 10996 19931 10991 19931 10993 19931 10997 19932 10994 19932 10995 19932 10998 19933 10991 19933 10996 19933 10996 19934 10994 19934 10997 19934 10997 19935 10995 19935 10946 19935 10999 19936 10996 19936 10997 19936 10998 19937 10996 19937 10999 19937 11000 19938 10997 19938 10946 19938 11001 19939 10998 19939 10999 19939 11002 19940 10997 19940 11000 19940 11002 19941 10999 19941 10997 19941 11001 19942 10999 19942 11002 19942 11003 19943 11002 19943 11000 19943 11003 19944 11000 19944 10944 19944 11004 19945 11003 19945 10944 19945 11005 19946 11003 19946 11004 19946 11005 19947 11002 19947 11003 19947 11005 19948 11001 19948 11002 19948 10942 19949 11004 19949 10944 19949 11006 19950 11005 19950 11004 19950 11006 19951 11004 19951 10942 19951 11008 19952 11001 19952 11005 19952 11007 19953 11001 19953 11008 19953 11008 19954 11005 19954 11006 19954 11006 19955 10942 19955 10941 19955 11009 19956 11008 19956 11006 19956 11010 19957 11006 19957 10941 19957 11010 19958 11009 19958 11006 19958 11010 19959 10941 19959 10939 19959 11007 19960 11008 19960 11009 19960 11007 19961 11009 19961 11010 19961 11011 19962 10939 19962 10938 19962 11011 19963 11010 19963 10939 19963 11012 19964 11007 19964 11010 19964 11012 19965 11010 19965 11011 19965 11013 19966 11007 19966 11012 19966 11014 19967 11011 19967 10938 19967 11014 19968 11012 19968 11011 19968 11014 19969 10938 19969 10936 19969 11013 19970 11012 19970 11014 19970 11015 19971 11014 19971 10936 19971 11016 19972 11014 19972 11015 19972 11017 19973 11007 19973 11013 19973 11016 19974 11013 19974 11014 19974 11017 19975 11013 19975 11016 19975 11018 19976 11015 19976 10936 19976 11016 19977 11015 19977 11018 19977 10935 19978 11018 19978 10936 19978 11019 19979 11016 19979 11018 19979 11020 19980 11016 19980 11019 19980 11020 19981 11017 19981 11016 19981 11018 19982 10935 19982 10934 19982 11021 19983 11019 19983 11018 19983 11021 19984 11018 19984 10934 19984 11021 19985 10934 19985 10932 19985 11020 19986 11019 19986 11021 19986 10931 19987 11021 19987 10932 19987 11020 19988 11021 19988 11022 19988 11022 19989 11021 19989 10931 19989 11023 19990 10931 19990 10929 19990 11023 19991 11022 19991 10931 19991 11024 19992 11020 19992 11022 19992 11025 19993 11023 19993 10929 19993 11025 19994 11022 19994 11023 19994 11024 19995 11022 19995 11025 19995 11026 19996 10929 19996 10928 19996 11026 19997 11025 19997 10929 19997 11027 19998 11025 19998 11026 19998 11027 19999 11024 19999 11025 19999 10926 20000 11026 20000 10928 20000 10926 20001 11027 20001 11026 20001 11028 20002 11027 20002 10926 20002 11029 20003 10926 20003 10925 20003 11028 20004 10926 20004 11029 20004 11030 20005 11024 20005 11027 20005 11030 20006 11027 20006 11028 20006 11031 20007 11028 20007 11029 20007 11032 20008 11029 20008 10925 20008 11033 20009 11029 20009 11032 20009 11034 20010 11028 20010 11031 20010 11034 20011 11030 20011 11028 20011 11031 20012 11029 20012 11033 20012 11035 20013 11031 20013 11033 20013 11033 20014 11032 20014 10923 20014 11035 20015 11034 20015 11031 20015 11035 20016 11033 20016 10923 20016 11036 20017 11030 20017 11034 20017 11037 20018 11034 20018 11035 20018 11037 20019 11035 20019 10923 20019 11037 20020 10923 20020 10921 20020 11036 20021 11034 20021 11037 20021 11038 20022 11037 20022 10921 20022 11039 20023 11037 20023 11038 20023 11039 20024 11036 20024 11037 20024 11040 20025 11038 20025 10921 20025 11041 20026 11038 20026 11040 20026 11041 20027 11039 20027 11038 20027 11041 20028 11040 20028 11042 20028 11043 20029 11036 20029 11039 20029 11044 20030 11039 20030 11041 20030 11043 20031 11039 20031 11044 20031 11045 20032 11042 20032 10918 20032 11045 20033 11041 20033 11042 20033 11044 20034 11041 20034 11045 20034 10917 20035 11045 20035 10918 20035 11046 20036 11044 20036 11045 20036 11047 20037 11045 20037 10917 20037 11043 20038 11044 20038 11046 20038 11048 20039 11045 20039 11047 20039 11048 20040 11046 20040 11045 20040 11047 20041 10917 20041 10915 20041 11049 20042 11046 20042 11048 20042 11049 20043 11043 20043 11046 20043 11052 20044 11043 20044 11049 20044 11050 20045 11047 20045 10915 20045 11051 20046 11047 20046 11050 20046 11051 20047 11048 20047 11047 20047 11050 20048 10915 20048 10913 20048 11051 20049 11049 20049 11048 20049 11052 20050 11049 20050 11051 20050 10912 20051 11050 20051 10913 20051 11053 20052 11050 20052 10912 20052 11053 20053 11051 20053 11050 20053 11054 20054 11051 20054 11053 20054 11052 20055 11051 20055 11054 20055 11055 20056 11053 20056 10912 20056 11056 20057 11052 20057 11054 20057 11057 20058 11053 20058 11055 20058 11054 20059 11053 20059 11057 20059 11057 20060 11055 20060 10911 20060 11058 20061 11056 20061 11054 20061 11058 20062 11054 20062 11057 20062 11060 20063 10911 20063 11059 20063 11060 20064 11057 20064 10911 20064 11061 20065 11056 20065 11058 20065 11058 20066 11057 20066 11060 20066 10908 20067 11060 20067 11059 20067 11062 20068 11058 20068 11060 20068 11063 20069 11060 20069 10908 20069 11061 20070 11058 20070 11062 20070 11062 20071 11060 20071 11063 20071 11064 20072 11062 20072 11063 20072 10907 20073 11063 20073 10908 20073 11065 20074 11062 20074 11064 20074 11065 20075 11061 20075 11062 20075 11064 20076 11063 20076 10907 20076 11067 20077 11061 20077 11065 20077 11066 20078 10907 20078 10905 20078 11066 20079 11064 20079 10907 20079 11065 20080 11064 20080 11066 20080 11068 20081 11066 20081 10905 20081 11068 20082 10966 20082 10967 20082 10968 20083 11065 20083 11066 20083 10968 20084 11067 20084 11065 20084 10967 20085 11066 20085 11068 20085 10968 20086 11066 20086 10967 20086 11067 20087 10968 20087 10969 20087 10145 20088 10143 20088 10981 20088 10143 20089 10975 20089 10981 20089 10145 20090 10981 20090 10988 20090 10142 20091 10975 20091 10143 20091 10148 20092 10145 20092 10988 20092 10142 20093 10971 20093 10975 20093 10140 20094 10971 20094 10142 20094 10148 20095 10988 20095 10991 20095 10149 20096 10148 20096 10991 20096 10138 20097 10971 20097 10140 20097 10138 20098 11067 20098 10971 20098 10151 20099 10149 20099 10991 20099 10151 20100 10991 20100 10998 20100 10136 20101 11067 20101 10138 20101 10153 20102 10151 20102 10998 20102 10153 20103 10998 20103 11001 20103 10136 20104 11061 20104 11067 20104 10134 20105 11061 20105 10136 20105 10155 20106 10153 20106 11001 20106 11056 20107 11061 20107 10134 20107 11007 20108 10155 20108 11001 20108 11056 20109 10134 20109 10132 20109 11007 20110 10157 20110 10155 20110 11052 20111 11056 20111 10132 20111 11007 20112 10160 20112 10157 20112 11052 20113 10132 20113 10130 20113 11017 20114 10160 20114 11007 20114 11043 20115 11052 20115 10130 20115 11017 20116 10119 20116 10160 20116 11043 20117 10130 20117 10128 20117 11020 20118 10119 20118 11017 20118 11043 20119 10128 20119 10126 20119 11020 20120 10120 20120 10119 20120 11036 20121 11043 20121 10126 20121 11024 20122 10120 20122 11020 20122 11036 20123 10126 20123 10124 20123 11024 20124 10122 20124 10120 20124 11030 20125 11036 20125 10124 20125 11030 20126 10124 20126 10122 20126 11030 20127 10122 20127 11024 20127 11069 20128 11070 20128 10833 20128 10835 20129 11069 20129 10833 20129 11075 20130 11164 20130 11071 20130 11072 20131 11069 20131 10835 20131 11073 20132 11069 20132 11072 20132 11073 20133 11071 20133 11069 20133 11075 20134 11071 20134 11073 20134 11073 20135 11072 20135 11074 20135 10837 20136 11074 20136 11072 20136 11076 20137 11073 20137 11074 20137 11077 20138 10837 20138 10839 20138 11076 20139 11075 20139 11073 20139 11077 20140 11074 20140 10837 20140 11076 20141 11074 20141 11077 20141 11078 20142 11075 20142 11076 20142 11079 20143 11076 20143 11077 20143 11077 20144 10839 20144 10840 20144 11079 20145 11078 20145 11076 20145 11080 20146 11077 20146 10840 20146 11080 20147 10840 20147 10842 20147 11079 20148 11077 20148 11080 20148 11081 20149 11078 20149 11079 20149 11082 20150 11079 20150 11080 20150 11082 20151 11081 20151 11079 20151 10843 20152 11080 20152 10842 20152 11083 20153 11080 20153 10843 20153 11083 20154 11082 20154 11080 20154 11084 20155 11082 20155 11083 20155 11084 20156 11081 20156 11082 20156 11085 20157 10843 20157 10844 20157 11085 20158 11083 20158 10843 20158 11086 20159 11083 20159 11085 20159 11086 20160 11084 20160 11083 20160 11087 20161 10844 20161 10846 20161 11087 20162 11085 20162 10844 20162 11089 20163 11084 20163 11086 20163 11087 20164 11086 20164 11085 20164 11088 20165 11084 20165 11089 20165 11089 20166 11086 20166 11087 20166 11090 20167 11087 20167 10846 20167 11090 20168 10846 20168 10848 20168 11091 20169 11087 20169 11090 20169 11091 20170 11089 20170 11087 20170 11088 20171 11089 20171 11091 20171 10849 20172 11090 20172 10848 20172 11092 20173 11090 20173 10849 20173 11092 20174 11091 20174 11090 20174 11093 20175 11088 20175 11091 20175 11094 20176 10849 20176 10851 20176 11094 20177 11092 20177 10849 20177 11093 20178 11091 20178 11092 20178 11094 20179 10851 20179 10852 20179 11095 20180 11092 20180 11094 20180 11093 20181 11092 20181 11095 20181 11096 20182 11093 20182 11095 20182 11097 20183 11094 20183 10852 20183 11097 20184 11095 20184 11094 20184 11100 20185 11093 20185 11096 20185 10853 20186 11097 20186 10852 20186 11098 20187 11095 20187 11097 20187 11098 20188 11096 20188 11095 20188 11099 20189 11097 20189 10853 20189 11100 20190 11096 20190 11098 20190 11098 20191 11097 20191 11099 20191 10855 20192 11099 20192 10853 20192 11101 20193 11098 20193 11099 20193 11101 20194 11100 20194 11098 20194 10856 20195 11099 20195 10855 20195 11102 20196 11100 20196 11101 20196 10856 20197 11101 20197 11099 20197 11104 20198 11100 20198 11102 20198 11103 20199 10856 20199 10858 20199 11103 20200 11101 20200 10856 20200 11103 20201 11102 20201 11101 20201 11104 20202 11102 20202 11103 20202 11105 20203 11103 20203 10858 20203 11105 20204 10858 20204 10859 20204 11106 20205 11103 20205 11105 20205 11106 20206 11104 20206 11103 20206 11106 20207 11105 20207 11107 20207 11107 20208 11105 20208 10859 20208 11109 20209 11104 20209 11106 20209 10861 20210 11107 20210 10859 20210 11109 20211 11106 20211 11107 20211 11110 20212 11104 20212 11109 20212 11108 20213 11107 20213 10861 20213 11109 20214 11107 20214 11108 20214 11111 20215 11109 20215 11108 20215 10862 20216 11108 20216 10861 20216 11110 20217 11109 20217 11111 20217 11111 20218 11108 20218 10862 20218 11112 20219 11110 20219 11111 20219 11113 20220 11111 20220 10862 20220 11113 20221 11112 20221 11111 20221 11113 20222 10862 20222 10864 20222 11114 20223 11113 20223 10864 20223 11115 20224 11113 20224 11114 20224 11115 20225 11112 20225 11113 20225 11116 20226 11110 20226 11112 20226 10866 20227 11114 20227 10864 20227 11116 20228 11112 20228 11115 20228 11117 20229 11115 20229 11114 20229 11117 20230 11114 20230 10866 20230 11118 20231 11116 20231 11115 20231 11119 20232 10866 20232 10867 20232 11119 20233 11117 20233 10866 20233 11118 20234 11115 20234 11117 20234 11120 20235 11117 20235 11119 20235 10868 20236 11119 20236 10867 20236 11120 20237 11119 20237 10868 20237 11121 20238 11117 20238 11120 20238 11121 20239 11118 20239 11117 20239 11122 20240 11121 20240 11120 20240 11122 20241 11120 20241 10868 20241 11123 20242 10868 20242 10870 20242 11123 20243 11122 20243 10868 20243 11124 20244 11118 20244 11121 20244 11125 20245 11123 20245 10870 20245 11124 20246 11121 20246 11122 20246 11122 20247 11123 20247 11125 20247 11126 20248 11122 20248 11125 20248 11125 20249 10870 20249 10872 20249 11126 20250 11124 20250 11122 20250 11127 20251 11125 20251 10872 20251 11128 20252 11125 20252 11127 20252 11128 20253 11126 20253 11125 20253 11129 20254 11124 20254 11126 20254 10873 20255 11127 20255 10872 20255 11129 20256 11126 20256 11128 20256 11130 20257 11128 20257 11127 20257 11129 20258 11128 20258 11130 20258 11131 20259 10873 20259 10875 20259 11131 20260 11127 20260 10873 20260 11130 20261 11127 20261 11131 20261 11132 20262 11129 20262 11130 20262 11133 20263 11130 20263 11131 20263 10877 20264 11131 20264 10875 20264 11133 20265 11132 20265 11130 20265 11133 20266 11131 20266 10877 20266 11134 20267 11129 20267 11132 20267 11134 20268 11132 20268 11133 20268 11133 20269 10877 20269 10878 20269 11135 20270 11133 20270 10878 20270 11134 20271 11133 20271 11135 20271 11136 20272 10878 20272 10879 20272 11136 20273 11135 20273 10878 20273 10881 20274 11136 20274 10879 20274 11137 20275 11134 20275 11135 20275 11138 20276 11136 20276 10881 20276 11138 20277 11135 20277 11136 20277 11139 20278 11135 20278 11138 20278 11139 20279 11137 20279 11135 20279 10882 20280 11138 20280 10881 20280 11140 20281 11137 20281 11139 20281 11141 20282 11138 20282 10882 20282 11139 20283 11138 20283 11141 20283 11141 20284 10882 20284 10883 20284 11142 20285 11141 20285 10883 20285 11143 20286 11141 20286 11142 20286 11143 20287 11139 20287 11141 20287 11143 20288 11140 20288 11139 20288 10885 20289 11142 20289 10883 20289 11144 20290 11143 20290 11142 20290 11140 20291 11143 20291 11144 20291 11145 20292 10885 20292 10886 20292 11145 20293 11142 20293 10885 20293 11148 20294 11140 20294 11144 20294 11145 20295 11144 20295 11142 20295 11146 20296 11145 20296 10886 20296 11146 20297 10886 20297 10888 20297 11146 20298 11144 20298 11145 20298 11147 20299 11144 20299 11146 20299 11148 20300 11144 20300 11147 20300 10889 20301 11146 20301 10888 20301 11147 20302 11146 20302 10889 20302 11150 20303 10889 20303 10890 20303 11148 20304 11147 20304 11149 20304 11150 20305 11147 20305 10889 20305 11150 20306 11149 20306 11147 20306 10892 20307 11150 20307 10890 20307 11151 20308 11150 20308 10892 20308 11149 20309 11150 20309 11151 20309 11151 20310 10892 20310 10893 20310 11152 20311 11148 20311 11149 20311 11153 20312 11149 20312 11151 20312 11154 20313 11151 20313 10893 20313 11152 20314 11149 20314 11153 20314 11153 20315 11151 20315 11154 20315 11154 20316 10893 20316 10894 20316 11153 20317 11154 20317 10894 20317 11155 20318 11153 20318 10894 20318 10896 20319 11155 20319 10894 20319 11156 20320 11153 20320 11155 20320 11156 20321 11152 20321 11153 20321 11157 20322 11155 20322 10896 20322 10897 20323 11157 20323 10896 20323 11156 20324 11155 20324 11157 20324 11158 20325 11156 20325 11157 20325 11158 20326 11157 20326 10897 20326 11159 20327 11152 20327 11156 20327 11159 20328 11156 20328 11158 20328 10899 20329 11158 20329 10897 20329 11160 20330 11159 20330 11158 20330 11160 20331 11158 20331 10899 20331 11161 20332 11159 20332 11160 20332 11162 20333 11161 20333 11160 20333 11162 20334 11160 20334 10899 20334 10902 20335 10899 20335 10900 20335 11162 20336 10899 20336 10902 20336 11163 20337 11162 20337 10902 20337 11163 20338 10902 20338 10903 20338 11163 20339 11161 20339 11162 20339 11164 20340 11161 20340 11163 20340 11070 20341 10903 20341 10833 20341 11070 20342 11163 20342 10903 20342 11163 20343 11070 20343 11069 20343 11163 20344 11069 20344 11071 20344 11164 20345 11163 20345 11071 20345 10177 20346 11129 20346 11134 20346 10179 20347 11129 20347 10177 20347 10176 20348 10177 20348 11134 20348 10176 20349 11134 20349 11137 20349 10179 20350 11124 20350 11129 20350 10181 20351 11124 20351 10179 20351 10174 20352 10176 20352 11137 20352 10181 20353 11118 20353 11124 20353 10174 20354 11137 20354 11140 20354 10174 20355 11140 20355 11148 20355 10172 20356 10174 20356 11148 20356 10184 20357 11118 20357 10181 20357 10184 20358 11116 20358 11118 20358 10170 20359 10172 20359 11148 20359 10184 20360 11110 20360 11116 20360 10186 20361 11110 20361 10184 20361 10169 20362 11148 20362 11152 20362 10169 20363 10170 20363 11148 20363 10188 20364 11110 20364 10186 20364 10166 20365 10169 20365 11152 20365 10189 20366 11110 20366 10188 20366 11104 20367 11110 20367 10189 20367 11159 20368 10166 20368 11152 20368 11159 20369 10165 20369 10166 20369 11104 20370 10189 20370 10191 20370 11100 20371 11104 20371 10191 20371 11161 20372 10165 20372 11159 20372 11161 20373 10162 20373 10165 20373 11100 20374 10191 20374 10193 20374 11164 20375 10162 20375 11161 20375 11093 20376 11100 20376 10193 20376 11093 20377 10193 20377 10195 20377 11075 20378 10162 20378 11164 20378 11088 20379 11093 20379 10195 20379 11075 20380 10202 20380 10162 20380 11088 20381 10195 20381 10197 20381 11078 20382 10202 20382 11075 20382 11084 20383 11088 20383 10197 20383 11078 20384 10201 20384 10202 20384 11084 20385 10197 20385 10199 20385 11081 20386 11084 20386 10199 20386 11078 20387 10199 20387 10201 20387 11081 20388 10199 20388 11078 20388 11165 20389 11238 20389 11166 20389 11167 20390 11165 20390 11166 20390 11167 20391 11166 20391 11168 20391 11169 20392 11167 20392 11168 20392 11170 20393 11168 20393 11171 20393 11170 20394 11169 20394 11168 20394 11172 20395 11170 20395 11171 20395 11173 20396 11172 20396 11171 20396 11174 20397 11173 20397 11171 20397 11174 20398 11171 20398 11175 20398 11176 20399 11174 20399 11175 20399 11177 20400 11176 20400 11175 20400 11177 20401 11175 20401 11178 20401 11179 20402 11177 20402 11178 20402 11180 20403 11179 20403 11178 20403 11181 20404 11180 20404 11178 20404 11181 20405 11178 20405 11182 20405 11183 20406 11181 20406 11182 20406 11184 20407 11183 20407 11182 20407 11185 20408 11184 20408 11182 20408 11185 20409 11182 20409 11186 20409 11187 20410 11185 20410 11186 20410 11188 20411 11187 20411 11186 20411 11189 20412 11188 20412 11186 20412 11189 20413 11186 20413 11190 20413 11191 20414 11189 20414 11190 20414 11192 20415 11191 20415 11190 20415 11192 20416 11190 20416 11193 20416 11194 20417 11192 20417 11193 20417 11194 20418 11193 20418 11195 20418 11196 20419 11194 20419 11195 20419 11197 20420 11196 20420 11195 20420 11197 20421 11195 20421 11198 20421 11199 20422 11197 20422 11198 20422 11200 20423 11198 20423 11201 20423 11200 20424 11199 20424 11198 20424 11202 20425 11200 20425 11201 20425 11203 20426 11202 20426 11201 20426 11204 20427 11201 20427 11205 20427 11204 20428 11203 20428 11201 20428 11472 20429 11204 20429 11205 20429 11474 20430 11472 20430 11205 20430 11206 20431 11474 20431 11205 20431 11206 20432 11205 20432 11207 20432 11208 20433 11206 20433 11207 20433 11208 20434 11207 20434 11209 20434 11210 20435 11208 20435 11209 20435 11211 20436 11210 20436 11209 20436 11212 20437 11211 20437 11209 20437 11212 20438 11209 20438 11213 20438 11214 20439 11212 20439 11213 20439 11215 20440 11214 20440 11213 20440 11215 20441 11213 20441 11216 20441 11217 20442 11215 20442 11216 20442 11218 20443 11217 20443 11216 20443 11218 20444 11216 20444 11219 20444 11220 20445 11218 20445 11219 20445 11221 20446 11220 20446 11219 20446 11221 20447 11219 20447 11222 20447 11223 20448 11221 20448 11222 20448 11224 20449 11223 20449 11222 20449 11224 20450 11222 20450 11225 20450 11226 20451 11224 20451 11225 20451 11227 20452 11226 20452 11225 20452 11227 20453 11225 20453 11228 20453 11229 20454 11227 20454 11228 20454 11230 20455 11229 20455 11228 20455 11230 20456 11228 20456 11231 20456 11232 20457 11230 20457 11231 20457 11233 20458 11232 20458 11231 20458 11234 20459 11233 20459 11231 20459 11234 20460 11231 20460 11235 20460 11236 20461 11234 20461 11235 20461 11237 20462 11236 20462 11235 20462 11237 20463 11235 20463 11238 20463 11239 20464 11237 20464 11238 20464 11240 20465 11239 20465 11238 20465 11165 20466 11240 20466 11238 20466 11241 20467 11242 20467 11419 20467 11243 20468 11241 20468 11419 20468 11243 20469 11419 20469 11244 20469 11243 20470 11244 20470 11416 20470 11245 20471 11416 20471 11246 20471 11245 20472 11243 20472 11416 20472 11245 20473 11246 20473 11409 20473 11245 20474 11409 20474 11247 20474 11248 20475 11245 20475 11247 20475 11248 20476 11247 20476 11406 20476 11249 20477 11406 20477 11250 20477 11249 20478 11248 20478 11406 20478 11249 20479 11250 20479 11251 20479 11252 20480 11251 20480 11253 20480 11252 20481 11249 20481 11251 20481 11252 20482 11253 20482 11254 20482 11252 20483 11254 20483 11255 20483 11256 20484 11252 20484 11255 20484 11256 20485 11255 20485 11394 20485 11257 20486 11256 20486 11394 20486 11257 20487 11394 20487 11392 20487 11257 20488 11392 20488 11258 20488 11259 20489 11257 20489 11258 20489 11259 20490 11258 20490 11260 20490 11259 20491 11260 20491 11261 20491 11262 20492 11259 20492 11261 20492 11262 20493 11261 20493 11263 20493 11262 20494 11263 20494 11264 20494 11265 20495 11262 20495 11264 20495 11265 20496 11264 20496 11266 20496 11265 20497 11266 20497 11376 20497 11267 20498 11265 20498 11376 20498 11267 20499 11376 20499 11268 20499 11267 20500 11268 20500 11269 20500 11270 20501 11269 20501 11271 20501 11270 20502 11267 20502 11269 20502 11270 20503 11271 20503 11272 20503 11270 20504 11272 20504 11273 20504 11274 20505 11270 20505 11273 20505 11274 20506 11273 20506 11275 20506 11274 20507 11275 20507 11276 20507 11274 20508 11276 20508 11277 20508 11278 20509 11274 20509 11277 20509 11278 20510 11277 20510 11279 20510 11278 20511 11279 20511 11280 20511 11281 20512 11278 20512 11280 20512 11281 20513 11280 20513 11282 20513 11281 20514 11282 20514 11283 20514 11281 20515 11283 20515 11284 20515 11285 20516 11281 20516 11284 20516 11285 20517 11284 20517 11286 20517 11285 20518 11286 20518 11287 20518 11288 20519 11285 20519 11287 20519 11288 20520 11287 20520 11289 20520 11288 20521 11289 20521 11290 20521 11288 20522 11290 20522 11291 20522 11292 20523 11288 20523 11291 20523 11292 20524 11291 20524 11293 20524 11294 20525 11292 20525 11293 20525 11294 20526 11293 20526 11295 20526 11294 20527 11295 20527 11296 20527 11297 20528 11296 20528 11298 20528 11297 20529 11294 20529 11296 20529 11297 20530 11298 20530 11329 20530 11297 20531 11329 20531 11299 20531 11297 20532 11299 20532 11300 20532 11301 20533 11297 20533 11300 20533 11301 20534 11300 20534 11302 20534 11303 20535 11301 20535 11302 20535 11303 20536 11302 20536 11304 20536 11303 20537 11304 20537 11305 20537 11306 20538 11303 20538 11305 20538 11306 20539 11305 20539 11307 20539 11308 20540 11307 20540 11309 20540 11308 20541 11306 20541 11307 20541 11308 20542 11309 20542 11310 20542 11241 20543 11308 20543 11310 20543 11241 20544 11310 20544 11242 20544 11311 20545 11242 20545 11310 20545 11311 20546 11312 20546 11242 20546 11311 20547 11420 20547 11312 20547 11313 20548 11420 20548 11311 20548 11313 20549 11421 20549 11420 20549 11314 20550 11310 20550 11309 20550 11314 20551 11311 20551 11310 20551 11316 20552 11421 20552 11313 20552 11315 20553 11311 20553 11314 20553 11313 20554 11311 20554 11315 20554 11316 20555 11313 20555 11315 20555 11315 20556 11314 20556 11309 20556 11307 20557 11315 20557 11309 20557 11317 20558 11315 20558 11307 20558 11318 20559 11307 20559 11305 20559 11317 20560 11316 20560 11315 20560 11318 20561 11317 20561 11307 20561 11320 20562 11316 20562 11317 20562 11319 20563 11318 20563 11305 20563 11323 20564 11316 20564 11320 20564 11320 20565 11317 20565 11318 20565 11319 20566 11305 20566 11304 20566 11319 20567 11320 20567 11318 20567 11321 20568 11320 20568 11319 20568 11322 20569 11319 20569 11304 20569 11323 20570 11320 20570 11321 20570 11321 20571 11319 20571 11322 20571 11322 20572 11304 20572 11302 20572 11324 20573 11321 20573 11322 20573 11300 20574 11322 20574 11302 20574 11323 20575 11321 20575 11324 20575 11325 20576 11322 20576 11300 20576 11326 20577 11322 20577 11325 20577 11326 20578 11324 20578 11322 20578 11327 20579 11323 20579 11324 20579 11299 20580 11325 20580 11300 20580 11327 20581 11324 20581 11326 20581 11328 20582 11325 20582 11299 20582 11328 20583 11326 20583 11325 20583 11330 20584 11326 20584 11328 20584 11329 20585 11328 20585 11299 20585 11330 20586 11327 20586 11326 20586 11331 20587 11328 20587 11329 20587 11331 20588 11330 20588 11328 20588 11298 20589 11331 20589 11329 20589 11332 20590 11331 20590 11298 20590 11332 20591 11330 20591 11331 20591 11333 20592 11327 20592 11330 20592 11333 20593 11330 20593 11332 20593 11334 20594 11298 20594 11296 20594 11334 20595 11332 20595 11298 20595 11333 20596 11332 20596 11334 20596 11295 20597 11334 20597 11296 20597 11336 20598 11334 20598 11295 20598 11333 20599 11334 20599 11336 20599 11336 20600 11295 20600 11293 20600 11337 20601 11333 20601 11336 20601 11337 20602 11335 20602 11333 20602 11338 20603 11336 20603 11293 20603 11338 20604 11337 20604 11336 20604 11339 20605 11338 20605 11293 20605 11340 20606 11335 20606 11337 20606 11339 20607 11337 20607 11338 20607 11340 20608 11337 20608 11339 20608 11291 20609 11339 20609 11293 20609 11341 20610 11339 20610 11291 20610 11342 20611 11335 20611 11340 20611 11343 20612 11339 20612 11341 20612 11343 20613 11340 20613 11339 20613 11290 20614 11341 20614 11291 20614 11344 20615 11341 20615 11290 20615 11342 20616 11340 20616 11343 20616 11343 20617 11341 20617 11344 20617 11344 20618 11290 20618 11289 20618 11345 20619 11343 20619 11344 20619 11287 20620 11344 20620 11289 20620 11346 20621 11343 20621 11345 20621 11346 20622 11342 20622 11343 20622 11347 20623 11344 20623 11287 20623 11345 20624 11344 20624 11347 20624 11348 20625 11345 20625 11347 20625 11349 20626 11342 20626 11346 20626 11286 20627 11347 20627 11287 20627 11348 20628 11346 20628 11345 20628 11349 20629 11346 20629 11348 20629 11348 20630 11347 20630 11286 20630 11350 20631 11348 20631 11286 20631 11351 20632 11348 20632 11350 20632 11350 20633 11286 20633 11284 20633 11352 20634 11350 20634 11284 20634 11349 20635 11348 20635 11351 20635 11352 20636 11351 20636 11350 20636 11283 20637 11352 20637 11284 20637 11353 20638 11349 20638 11351 20638 11354 20639 11352 20639 11283 20639 11355 20640 11352 20640 11354 20640 11355 20641 11351 20641 11352 20641 11355 20642 11353 20642 11351 20642 11354 20643 11283 20643 11282 20643 11357 20644 11353 20644 11355 20644 11356 20645 11354 20645 11282 20645 11357 20646 11354 20646 11356 20646 11357 20647 11355 20647 11354 20647 11280 20648 11356 20648 11282 20648 11358 20649 11356 20649 11280 20649 11359 20650 11353 20650 11357 20650 11358 20651 11357 20651 11356 20651 11360 20652 11280 20652 11279 20652 11360 20653 11358 20653 11280 20653 11361 20654 11357 20654 11358 20654 11361 20655 11359 20655 11357 20655 11361 20656 11358 20656 11360 20656 11277 20657 11360 20657 11279 20657 11362 20658 11360 20658 11277 20658 11362 20659 11361 20659 11360 20659 11363 20660 11359 20660 11361 20660 11276 20661 11362 20661 11277 20661 11364 20662 11361 20662 11362 20662 11364 20663 11363 20663 11361 20663 11364 20664 11362 20664 11276 20664 11365 20665 11276 20665 11275 20665 11365 20666 11364 20666 11276 20666 11366 20667 11364 20667 11365 20667 11365 20668 11275 20668 11273 20668 11367 20669 11365 20669 11273 20669 11363 20670 11364 20670 11366 20670 11366 20671 11365 20671 11367 20671 11368 20672 11363 20672 11366 20672 11367 20673 11273 20673 11272 20673 11369 20674 11366 20674 11367 20674 11370 20675 11367 20675 11272 20675 11368 20676 11366 20676 11369 20676 11369 20677 11367 20677 11370 20677 11370 20678 11272 20678 11271 20678 11371 20679 11368 20679 11369 20679 11371 20680 11369 20680 11370 20680 11269 20681 11370 20681 11271 20681 11372 20682 11370 20682 11269 20682 11373 20683 11368 20683 11371 20683 11372 20684 11371 20684 11370 20684 11374 20685 11269 20685 11268 20685 11373 20686 11371 20686 11372 20686 11374 20687 11372 20687 11269 20687 11373 20688 11372 20688 11374 20688 11375 20689 11373 20689 11374 20689 11376 20690 11374 20690 11268 20690 11375 20691 11374 20691 11376 20691 11378 20692 11373 20692 11375 20692 11377 20693 11375 20693 11376 20693 11379 20694 11375 20694 11377 20694 11377 20695 11376 20695 11266 20695 11378 20696 11375 20696 11379 20696 11380 20697 11377 20697 11266 20697 11379 20698 11377 20698 11380 20698 11380 20699 11266 20699 11264 20699 11381 20700 11379 20700 11380 20700 11382 20701 11264 20701 11263 20701 11382 20702 11380 20702 11264 20702 11381 20703 11378 20703 11379 20703 11381 20704 11380 20704 11382 20704 11383 20705 11378 20705 11381 20705 11382 20706 11263 20706 11261 20706 11384 20707 11381 20707 11382 20707 11385 20708 11382 20708 11261 20708 11384 20709 11383 20709 11381 20709 11385 20710 11384 20710 11382 20710 11386 20711 11383 20711 11384 20711 11385 20712 11261 20712 11260 20712 11387 20713 11385 20713 11260 20713 11387 20714 11384 20714 11385 20714 11388 20715 11383 20715 11386 20715 11387 20716 11386 20716 11384 20716 11388 20717 11386 20717 11387 20717 11387 20718 11260 20718 11389 20718 11389 20719 11260 20719 11258 20719 11390 20720 11387 20720 11389 20720 11391 20721 11387 20721 11390 20721 11391 20722 11388 20722 11387 20722 11390 20723 11389 20723 11258 20723 11392 20724 11390 20724 11258 20724 11393 20725 11390 20725 11392 20725 11391 20726 11390 20726 11393 20726 11393 20727 11392 20727 11394 20727 11391 20728 11397 20728 11388 20728 11395 20729 11393 20729 11394 20729 11395 20730 11391 20730 11393 20730 11397 20731 11391 20731 11395 20731 11396 20732 11395 20732 11394 20732 11255 20733 11396 20733 11394 20733 11398 20734 11395 20734 11396 20734 11398 20735 11397 20735 11395 20735 11254 20736 11396 20736 11255 20736 11399 20737 11397 20737 11398 20737 11400 20738 11396 20738 11254 20738 11400 20739 11398 20739 11396 20739 11401 20740 11398 20740 11400 20740 11401 20741 11399 20741 11398 20741 11253 20742 11400 20742 11254 20742 11402 20743 11400 20743 11253 20743 11401 20744 11400 20744 11402 20744 11403 20745 11399 20745 11401 20745 11403 20746 11397 20746 11399 20746 11403 20747 11401 20747 11402 20747 11402 20748 11253 20748 11251 20748 11403 20749 11402 20749 11404 20749 11404 20750 11402 20750 11251 20750 11405 20751 11403 20751 11404 20751 11250 20752 11404 20752 11251 20752 11405 20753 11404 20753 11250 20753 11407 20754 11403 20754 11405 20754 11406 20755 11405 20755 11250 20755 11408 20756 11405 20756 11406 20756 11408 20757 11407 20757 11405 20757 11408 20758 11406 20758 11247 20758 11409 20759 11408 20759 11247 20759 11410 20760 11407 20760 11408 20760 11411 20761 11408 20761 11409 20761 11410 20762 11408 20762 11411 20762 11412 20763 11407 20763 11410 20763 11413 20764 11409 20764 11246 20764 11411 20765 11409 20765 11413 20765 11412 20766 11415 20766 11407 20766 11414 20767 11410 20767 11411 20767 11412 20768 11410 20768 11414 20768 11414 20769 11411 20769 11413 20769 11416 20770 11413 20770 11246 20770 11416 20771 11414 20771 11413 20771 11415 20772 11412 20772 11414 20772 11417 20773 11416 20773 11244 20773 11417 20774 11414 20774 11416 20774 11418 20775 11414 20775 11417 20775 11415 20776 11414 20776 11418 20776 11419 20777 11417 20777 11244 20777 11418 20778 11417 20778 11419 20778 11420 20779 11415 20779 11418 20779 11421 20780 11415 20780 11420 20780 11312 20781 11418 20781 11419 20781 11420 20782 11418 20782 11312 20782 11242 20783 11312 20783 11419 20783 10959 20784 11323 20784 10957 20784 10954 20785 10957 20785 11323 20785 10954 20786 11323 20786 11327 20786 10954 20787 11327 20787 11333 20787 10962 20788 11323 20788 10959 20788 10962 20789 11316 20789 11323 20789 10952 20790 10954 20790 11333 20790 10952 20791 11333 20791 11335 20791 10964 20792 11316 20792 10962 20792 10950 20793 10952 20793 11335 20793 10964 20794 11421 20794 11316 20794 10904 20795 11421 20795 10964 20795 10950 20796 11335 20796 11342 20796 10947 20797 10950 20797 11342 20797 10906 20798 11421 20798 10904 20798 10906 20799 11415 20799 11421 20799 11349 20800 10947 20800 11342 20800 10945 20801 10947 20801 11349 20801 10909 20802 11415 20802 10906 20802 10909 20803 11407 20803 11415 20803 10943 20804 10945 20804 11349 20804 10910 20805 11407 20805 10909 20805 11353 20806 10943 20806 11349 20806 11353 20807 10940 20807 10943 20807 11403 20808 10910 20808 10914 20808 11403 20809 11407 20809 10910 20809 11353 20810 10937 20810 10940 20810 11359 20811 10937 20811 11353 20811 11397 20812 11403 20812 10914 20812 11397 20813 10914 20813 10916 20813 11363 20814 10937 20814 11359 20814 11397 20815 10916 20815 10919 20815 11363 20816 10933 20816 10937 20816 11368 20817 10933 20817 11363 20817 11388 20818 10919 20818 10920 20818 11388 20819 11397 20819 10919 20819 11368 20820 10930 20820 10933 20820 11388 20821 10920 20821 10922 20821 11373 20822 10930 20822 11368 20822 11373 20823 10927 20823 10930 20823 11383 20824 11388 20824 10922 20824 11383 20825 10922 20825 10924 20825 11378 20826 11383 20826 10924 20826 11378 20827 10927 20827 11373 20827 11378 20828 10924 20828 10927 20828 11425 20829 11165 20829 11167 20829 11425 20830 11422 20830 11165 20830 11425 20831 11423 20831 11422 20831 11426 20832 11423 20832 11425 20832 11424 20833 11423 20833 11426 20833 11426 20834 11425 20834 11167 20834 11428 20835 11426 20835 11427 20835 11428 20836 11424 20836 11426 20836 11169 20837 11426 20837 11167 20837 11427 20838 11426 20838 11169 20838 11429 20839 11427 20839 11169 20839 11430 20840 11427 20840 11429 20840 11429 20841 11169 20841 11170 20841 11430 20842 11428 20842 11427 20842 11431 20843 11429 20843 11170 20843 11431 20844 11430 20844 11429 20844 11432 20845 11428 20845 11430 20845 11433 20846 11430 20846 11431 20846 11431 20847 11170 20847 11172 20847 11432 20848 11430 20848 11433 20848 11173 20849 11431 20849 11172 20849 11433 20850 11431 20850 11173 20850 11432 20851 11433 20851 11434 20851 11174 20852 11433 20852 11173 20852 11435 20853 11432 20853 11434 20853 11436 20854 11433 20854 11174 20854 11434 20855 11433 20855 11436 20855 11436 20856 11174 20856 11176 20856 11437 20857 11434 20857 11436 20857 11437 20858 11435 20858 11434 20858 11438 20859 11436 20859 11176 20859 11437 20860 11436 20860 11438 20860 11438 20861 11176 20861 11177 20861 11439 20862 11437 20862 11438 20862 11440 20863 11177 20863 11179 20863 11440 20864 11438 20864 11177 20864 11435 20865 11437 20865 11439 20865 11440 20866 11439 20866 11438 20866 11180 20867 11440 20867 11179 20867 11441 20868 11435 20868 11439 20868 11441 20869 11439 20869 11440 20869 11442 20870 11440 20870 11180 20870 11442 20871 11441 20871 11440 20871 11442 20872 11180 20872 11181 20872 11444 20873 11441 20873 11442 20873 11443 20874 11442 20874 11181 20874 11444 20875 11442 20875 11443 20875 11441 20876 11447 20876 11435 20876 11443 20877 11181 20877 11183 20877 11445 20878 11444 20878 11443 20878 11446 20879 11183 20879 11184 20879 11446 20880 11443 20880 11183 20880 11445 20881 11443 20881 11446 20881 11445 20882 11441 20882 11444 20882 11447 20883 11441 20883 11445 20883 11448 20884 11445 20884 11446 20884 11446 20885 11184 20885 11185 20885 11448 20886 11447 20886 11445 20886 11449 20887 11446 20887 11185 20887 11449 20888 11448 20888 11446 20888 11187 20889 11449 20889 11185 20889 11450 20890 11447 20890 11448 20890 11450 20891 11448 20891 11449 20891 11451 20892 11449 20892 11187 20892 11452 20893 11449 20893 11451 20893 11452 20894 11450 20894 11449 20894 11451 20895 11187 20895 11188 20895 11189 20896 11451 20896 11188 20896 11453 20897 11450 20897 11452 20897 11454 20898 11451 20898 11189 20898 11454 20899 11452 20899 11451 20899 11453 20900 11452 20900 11454 20900 11455 20901 11189 20901 11191 20901 11455 20902 11454 20902 11189 20902 11456 20903 11454 20903 11455 20903 11456 20904 11453 20904 11454 20904 11192 20905 11455 20905 11191 20905 11457 20906 11453 20906 11456 20906 11458 20907 11456 20907 11455 20907 11459 20908 11455 20908 11192 20908 11457 20909 11456 20909 11458 20909 11459 20910 11458 20910 11455 20910 11460 20911 11458 20911 11459 20911 11194 20912 11459 20912 11192 20912 11460 20913 11457 20913 11458 20913 11461 20914 11459 20914 11194 20914 11462 20915 11457 20915 11460 20915 11461 20916 11460 20916 11459 20916 11461 20917 11194 20917 11196 20917 11197 20918 11461 20918 11196 20918 11463 20919 11460 20919 11461 20919 11463 20920 11462 20920 11460 20920 11463 20921 11461 20921 11197 20921 11464 20922 11462 20922 11463 20922 11465 20923 11197 20923 11199 20923 11465 20924 11463 20924 11197 20924 11464 20925 11463 20925 11465 20925 11466 20926 11465 20926 11199 20926 11466 20927 11199 20927 11200 20927 11465 20928 11466 20928 11200 20928 11467 20929 11464 20929 11465 20929 11467 20930 11465 20930 11200 20930 11467 20931 11200 20931 11202 20931 11468 20932 11464 20932 11467 20932 11203 20933 11467 20933 11202 20933 11469 20934 11464 20934 11468 20934 11468 20935 11467 20935 11470 20935 11470 20936 11467 20936 11203 20936 11471 20937 11203 20937 11204 20937 11471 20938 11470 20938 11203 20938 11468 20939 11470 20939 11471 20939 11472 20940 11471 20940 11204 20940 11473 20941 11468 20941 11471 20941 11473 20942 11471 20942 11472 20942 11469 20943 11468 20943 11473 20943 11473 20944 11472 20944 11474 20944 11475 20945 11469 20945 11473 20945 11476 20946 11473 20946 11474 20946 11476 20947 11475 20947 11473 20947 11476 20948 11474 20948 11206 20948 11478 20949 11469 20949 11475 20949 11208 20950 11476 20950 11206 20950 11477 20951 11476 20951 11208 20951 11477 20952 11475 20952 11476 20952 11478 20953 11475 20953 11477 20953 11478 20954 11482 20954 11469 20954 11479 20955 11477 20955 11208 20955 11210 20956 11479 20956 11208 20956 11480 20957 11478 20957 11477 20957 11482 20958 11478 20958 11480 20958 11480 20959 11477 20959 11479 20959 11481 20960 11210 20960 11211 20960 11481 20961 11479 20961 11210 20961 11483 20962 11479 20962 11481 20962 11483 20963 11480 20963 11479 20963 11482 20964 11480 20964 11483 20964 11484 20965 11211 20965 11212 20965 11484 20966 11481 20966 11211 20966 11485 20967 11482 20967 11483 20967 11486 20968 11481 20968 11484 20968 11486 20969 11483 20969 11481 20969 11485 20970 11483 20970 11486 20970 11488 20971 11482 20971 11485 20971 11214 20972 11484 20972 11212 20972 11487 20973 11484 20973 11214 20973 11487 20974 11486 20974 11484 20974 11487 20975 11485 20975 11486 20975 11488 20976 11485 20976 11487 20976 11489 20977 11214 20977 11215 20977 11489 20978 11487 20978 11214 20978 11490 20979 11487 20979 11489 20979 11488 20980 11487 20980 11490 20980 11491 20981 11215 20981 11217 20981 11491 20982 11489 20982 11215 20982 11492 20983 11488 20983 11490 20983 11491 20984 11490 20984 11489 20984 11492 20985 11490 20985 11491 20985 11493 20986 11491 20986 11217 20986 11494 20987 11488 20987 11492 20987 11492 20988 11491 20988 11493 20988 11495 20989 11492 20989 11493 20989 11218 20990 11493 20990 11217 20990 11494 20991 11492 20991 11495 20991 11218 20992 11495 20992 11493 20992 11496 20993 11495 20993 11218 20993 11496 20994 11494 20994 11495 20994 11220 20995 11496 20995 11218 20995 11497 20996 11494 20996 11496 20996 11498 20997 11220 20997 11221 20997 11498 20998 11496 20998 11220 20998 11497 20999 11496 20999 11498 20999 11499 21000 11221 21000 11223 21000 11499 21001 11498 21001 11221 21001 11500 21002 11498 21002 11499 21002 11500 21003 11497 21003 11498 21003 11501 21004 11223 21004 11224 21004 11501 21005 11499 21005 11223 21005 11501 21006 11500 21006 11499 21006 11502 21007 11500 21007 11501 21007 11503 21008 11224 21008 11226 21008 11503 21009 11501 21009 11224 21009 11504 21010 11500 21010 11502 21010 11503 21011 11502 21011 11501 21011 11504 21012 11497 21012 11500 21012 11505 21013 11502 21013 11503 21013 11506 21014 11226 21014 11227 21014 11506 21015 11503 21015 11226 21015 11505 21016 11503 21016 11506 21016 11505 21017 11504 21017 11502 21017 11229 21018 11506 21018 11227 21018 11507 21019 11506 21019 11229 21019 11504 21020 11505 21020 11508 21020 11507 21021 11505 21021 11506 21021 11508 21022 11505 21022 11507 21022 11509 21023 11504 21023 11508 21023 11230 21024 11507 21024 11229 21024 11510 21025 11507 21025 11230 21025 11510 21026 11508 21026 11507 21026 11511 21027 11508 21027 11510 21027 11232 21028 11510 21028 11230 21028 11512 21029 11510 21029 11232 21029 11509 21030 11508 21030 11511 21030 11511 21031 11510 21031 11512 21031 11233 21032 11512 21032 11232 21032 11513 21033 11509 21033 11511 21033 11514 21034 11511 21034 11512 21034 11515 21035 11512 21035 11233 21035 11513 21036 11511 21036 11514 21036 11514 21037 11512 21037 11515 21037 11234 21038 11515 21038 11233 21038 11517 21039 11515 21039 11234 21039 11516 21040 11513 21040 11514 21040 11517 21041 11514 21041 11515 21041 11516 21042 11514 21042 11517 21042 11236 21043 11517 21043 11234 21043 11518 21044 11517 21044 11236 21044 11518 21045 11516 21045 11517 21045 11519 21046 11513 21046 11516 21046 11519 21047 11516 21047 11518 21047 11237 21048 11518 21048 11236 21048 11520 21049 11518 21049 11237 21049 11521 21050 11518 21050 11520 21050 11521 21051 11519 21051 11518 21051 11239 21052 11520 21052 11237 21052 11522 21053 11520 21053 11239 21053 11522 21054 11521 21054 11520 21054 11240 21055 11522 21055 11239 21055 11240 21056 11165 21056 11422 21056 11423 21057 11240 21057 11422 21057 11423 21058 11522 21058 11240 21058 11424 21059 11519 21059 11521 21059 11423 21060 11521 21060 11522 21060 11521 21061 11423 21061 11424 21061 10876 21062 11482 21062 11488 21062 10874 21063 11482 21063 10876 21063 10871 21064 11482 21064 10874 21064 10876 21065 11488 21065 11494 21065 10880 21066 10876 21066 11494 21066 10871 21067 11469 21067 11482 21067 10869 21068 11469 21068 10871 21068 10884 21069 10880 21069 11494 21069 10865 21070 11469 21070 10869 21070 10884 21071 11494 21071 11497 21071 10887 21072 10884 21072 11497 21072 10863 21073 11469 21073 10865 21073 10863 21074 11464 21074 11469 21074 10887 21075 11497 21075 11504 21075 10891 21076 10887 21076 11504 21076 10860 21077 11464 21077 10863 21077 10891 21078 11504 21078 11509 21078 10860 21079 11462 21079 11464 21079 10895 21080 10891 21080 11509 21080 10857 21081 11462 21081 10860 21081 11457 21082 11462 21082 10857 21082 11513 21083 10895 21083 11509 21083 10854 21084 11457 21084 10857 21084 11513 21085 10898 21085 10895 21085 11453 21086 11457 21086 10854 21086 11519 21087 10898 21087 11513 21087 11450 21088 11453 21088 10854 21088 11450 21089 10854 21089 10850 21089 11519 21090 10901 21090 10898 21090 11519 21091 10834 21091 10901 21091 11424 21092 10834 21092 11519 21092 11447 21093 11450 21093 10850 21093 11447 21094 10850 21094 10847 21094 11424 21095 10836 21095 10834 21095 11447 21096 10847 21096 10845 21096 11428 21097 10836 21097 11424 21097 11435 21098 11447 21098 10845 21098 11428 21099 10838 21099 10836 21099 11432 21100 10838 21100 11428 21100 11435 21101 10845 21101 10841 21101 11435 21102 10838 21102 11432 21102 11435 21103 10841 21103 10838 21103 11523 21104 11524 21104 11525 21104 11526 21105 11523 21105 11525 21105 11527 21106 11526 21106 11525 21106 11528 21107 11525 21107 11529 21107 11528 21108 11527 21108 11525 21108 11805 21109 11528 21109 11529 21109 11530 21110 11805 21110 11529 21110 11530 21111 11529 21111 11531 21111 11532 21112 11530 21112 11531 21112 11533 21113 11532 21113 11531 21113 11534 21114 11533 21114 11531 21114 11534 21115 11531 21115 11535 21115 11536 21116 11534 21116 11535 21116 11536 21117 11535 21117 11537 21117 11538 21118 11536 21118 11537 21118 11538 21119 11537 21119 11539 21119 11540 21120 11538 21120 11539 21120 11541 21121 11540 21121 11539 21121 11541 21122 11539 21122 11542 21122 11543 21123 11541 21123 11542 21123 11544 21124 11543 21124 11542 21124 11544 21125 11542 21125 11545 21125 11546 21126 11544 21126 11545 21126 11547 21127 11546 21127 11545 21127 11547 21128 11545 21128 11548 21128 11549 21129 11547 21129 11548 21129 11550 21130 11549 21130 11548 21130 11550 21131 11548 21131 11551 21131 11552 21132 11550 21132 11551 21132 11553 21133 11552 21133 11551 21133 11554 21134 11553 21134 11551 21134 11554 21135 11551 21135 11555 21135 11556 21136 11554 21136 11555 21136 11557 21137 11555 21137 11558 21137 11557 21138 11556 21138 11555 21138 11559 21139 11557 21139 11558 21139 11560 21140 11559 21140 11558 21140 11561 21141 11558 21141 11562 21141 11561 21142 11560 21142 11558 21142 11563 21143 11561 21143 11562 21143 11564 21144 11562 21144 11565 21144 11564 21145 11563 21145 11562 21145 11566 21146 11564 21146 11565 21146 11567 21147 11566 21147 11565 21147 11568 21148 11567 21148 11565 21148 11568 21149 11565 21149 11569 21149 11570 21150 11568 21150 11569 21150 11853 21151 11570 21151 11569 21151 11853 21152 11569 21152 11571 21152 11572 21153 11853 21153 11571 21153 11573 21154 11572 21154 11571 21154 11573 21155 11571 21155 11574 21155 11575 21156 11573 21156 11574 21156 11576 21157 11575 21157 11574 21157 11576 21158 11574 21158 11577 21158 11578 21159 11576 21159 11577 21159 11579 21160 11578 21160 11577 21160 11579 21161 11577 21161 11580 21161 11581 21162 11579 21162 11580 21162 11582 21163 11580 21163 11583 21163 11582 21164 11581 21164 11580 21164 11584 21165 11582 21165 11583 21165 11584 21166 11583 21166 11585 21166 11586 21167 11584 21167 11585 21167 11587 21168 11585 21168 11588 21168 11587 21169 11586 21169 11585 21169 11589 21170 11587 21170 11588 21170 11589 21171 11588 21171 11590 21171 11591 21172 11589 21172 11590 21172 11592 21173 11591 21173 11590 21173 11592 21174 11590 21174 11593 21174 11594 21175 11592 21175 11593 21175 11595 21176 11593 21176 11596 21176 11595 21177 11594 21177 11593 21177 11597 21178 11595 21178 11596 21178 11597 21179 11596 21179 11598 21179 11599 21180 11597 21180 11598 21180 11600 21181 11599 21181 11598 21181 11601 21182 11600 21182 11598 21182 11601 21183 11598 21183 11602 21183 11603 21184 11601 21184 11602 21184 11603 21185 11602 21185 11604 21185 11605 21186 11603 21186 11604 21186 11606 21187 11605 21187 11604 21187 11606 21188 11604 21188 11524 21188 11607 21189 11606 21189 11524 21189 11523 21190 11607 21190 11524 21190 11608 21191 11609 21191 11794 21191 11610 21192 11608 21192 11794 21192 11610 21193 11794 21193 11611 21193 11610 21194 11611 21194 11790 21194 11610 21195 11790 21195 11612 21195 11613 21196 11610 21196 11612 21196 11613 21197 11612 21197 11786 21197 11613 21198 11786 21198 11614 21198 11615 21199 11613 21199 11614 21199 11615 21200 11614 21200 11616 21200 11615 21201 11616 21201 11617 21201 11618 21202 11615 21202 11617 21202 11618 21203 11617 21203 11619 21203 11618 21204 11619 21204 11620 21204 11621 21205 11618 21205 11620 21205 11621 21206 11620 21206 11622 21206 11621 21207 11622 21207 11774 21207 11621 21208 11774 21208 11623 21208 11624 21209 11621 21209 11623 21209 11624 21210 11623 21210 11770 21210 11624 21211 11770 21211 11625 21211 11626 21212 11624 21212 11625 21212 11626 21213 11625 21213 11765 21213 11626 21214 11765 21214 11627 21214 11628 21215 11626 21215 11627 21215 11628 21216 11627 21216 11629 21216 11628 21217 11629 21217 11630 21217 11631 21218 11628 21218 11630 21218 11631 21219 11630 21219 11632 21219 11633 21220 11631 21220 11632 21220 11633 21221 11632 21221 11634 21221 11633 21222 11634 21222 11635 21222 11636 21223 11633 21223 11635 21223 11636 21224 11635 21224 11637 21224 11636 21225 11637 21225 11638 21225 11639 21226 11636 21226 11638 21226 11639 21227 11638 21227 11640 21227 11641 21228 11640 21228 11642 21228 11641 21229 11639 21229 11640 21229 11641 21230 11642 21230 11743 21230 11643 21231 11641 21231 11743 21231 11643 21232 11743 21232 11741 21232 11643 21233 11741 21233 11644 21233 11645 21234 11643 21234 11644 21234 11645 21235 11644 21235 11646 21235 11645 21236 11646 21236 11647 21236 11648 21237 11645 21237 11647 21237 11648 21238 11647 21238 11649 21238 11650 21239 11648 21239 11649 21239 11650 21240 11649 21240 11730 21240 11650 21241 11730 21241 11651 21241 11652 21242 11650 21242 11651 21242 11652 21243 11651 21243 11653 21243 11654 21244 11653 21244 11723 21244 11654 21245 11652 21245 11653 21245 11654 21246 11723 21246 11655 21246 11656 21247 11654 21247 11655 21247 11656 21248 11655 21248 11657 21248 11656 21249 11657 21249 11658 21249 11659 21250 11656 21250 11658 21250 11659 21251 11658 21251 11714 21251 11659 21252 11714 21252 11712 21252 11660 21253 11659 21253 11712 21253 11660 21254 11712 21254 11661 21254 11660 21255 11661 21255 11707 21255 11662 21256 11660 21256 11707 21256 11662 21257 11707 21257 11663 21257 11664 21258 11663 21258 11665 21258 11664 21259 11662 21259 11663 21259 11664 21260 11665 21260 11666 21260 11664 21261 11666 21261 11667 21261 11668 21262 11667 21262 11669 21262 11668 21263 11664 21263 11667 21263 11668 21264 11669 21264 11670 21264 11668 21265 11670 21265 11671 21265 11672 21266 11668 21266 11671 21266 11672 21267 11671 21267 11673 21267 11674 21268 11672 21268 11673 21268 11674 21269 11673 21269 11688 21269 11674 21270 11688 21270 11675 21270 11676 21271 11674 21271 11675 21271 11676 21272 11675 21272 11677 21272 11676 21273 11677 21273 11678 21273 11676 21274 11678 21274 11679 21274 11608 21275 11679 21275 11609 21275 11608 21276 11676 21276 11679 21276 11681 21277 11796 21277 11680 21277 11679 21278 11680 21278 11609 21278 11682 21279 11796 21279 11681 21279 11683 21280 11680 21280 11679 21280 11681 21281 11680 21281 11683 21281 11678 21282 11683 21282 11679 21282 11684 21283 11683 21283 11678 21283 11685 21284 11683 21284 11684 21284 11685 21285 11681 21285 11683 21285 11682 21286 11681 21286 11685 21286 11684 21287 11678 21287 11677 21287 11686 21288 11685 21288 11684 21288 11686 21289 11682 21289 11685 21289 11675 21290 11684 21290 11677 21290 11687 21291 11684 21291 11675 21291 11686 21292 11684 21292 11687 21292 11688 21293 11687 21293 11675 21293 11690 21294 11687 21294 11688 21294 11689 21295 11682 21295 11686 21295 11690 21296 11686 21296 11687 21296 11691 21297 11686 21297 11690 21297 11689 21298 11686 21298 11691 21298 11692 21299 11688 21299 11673 21299 11692 21300 11690 21300 11688 21300 11691 21301 11690 21301 11692 21301 11671 21302 11692 21302 11673 21302 11693 21303 11692 21303 11671 21303 11694 21304 11692 21304 11693 21304 11694 21305 11691 21305 11692 21305 11694 21306 11689 21306 11691 21306 11695 21307 11693 21307 11671 21307 11694 21308 11693 21308 11695 21308 11670 21309 11695 21309 11671 21309 11696 21310 11689 21310 11694 21310 11698 21311 11689 21311 11696 21311 11696 21312 11694 21312 11695 21312 11669 21313 11695 21313 11670 21313 11697 21314 11695 21314 11669 21314 11697 21315 11696 21315 11695 21315 11698 21316 11696 21316 11697 21316 11667 21317 11697 21317 11669 21317 11699 21318 11698 21318 11697 21318 11700 21319 11697 21319 11667 21319 11700 21320 11699 21320 11697 21320 11666 21321 11700 21321 11667 21321 11701 21322 11698 21322 11699 21322 11702 21323 11700 21323 11666 21323 11699 21324 11700 21324 11702 21324 11702 21325 11666 21325 11665 21325 11703 21326 11699 21326 11702 21326 11703 21327 11701 21327 11699 21327 11704 21328 11702 21328 11665 21328 11704 21329 11665 21329 11663 21329 11704 21330 11703 21330 11702 21330 11705 21331 11704 21331 11663 21331 11706 21332 11701 21332 11703 21332 11703 21333 11704 21333 11705 21333 11707 21334 11705 21334 11663 21334 11708 21335 11703 21335 11705 21335 11706 21336 11703 21336 11708 21336 11708 21337 11705 21337 11707 21337 11709 21338 11707 21338 11661 21338 11709 21339 11708 21339 11707 21339 11711 21340 11701 21340 11706 21340 11710 21341 11708 21341 11709 21341 11710 21342 11706 21342 11708 21342 11711 21343 11706 21343 11710 21343 11712 21344 11709 21344 11661 21344 11713 21345 11710 21345 11709 21345 11711 21346 11710 21346 11713 21346 11713 21347 11709 21347 11712 21347 11715 21348 11712 21348 11714 21348 11715 21349 11713 21349 11712 21349 11716 21350 11711 21350 11713 21350 11718 21351 11713 21351 11715 21351 11717 21352 11714 21352 11658 21352 11716 21353 11713 21353 11718 21353 11717 21354 11715 21354 11714 21354 11718 21355 11715 21355 11717 21355 11657 21356 11717 21356 11658 21356 11719 21357 11716 21357 11718 21357 11720 21358 11717 21358 11657 21358 11720 21359 11718 21359 11717 21359 11719 21360 11718 21360 11720 21360 11720 21361 11657 21361 11655 21361 11721 21362 11719 21362 11720 21362 11722 21363 11720 21363 11655 21363 11721 21364 11720 21364 11722 21364 11723 21365 11722 21365 11655 21365 11726 21366 11721 21366 11722 21366 11724 21367 11721 21367 11726 21367 11724 21368 11719 21368 11721 21368 11725 21369 11722 21369 11723 21369 11726 21370 11722 21370 11725 21370 11653 21371 11725 21371 11723 21371 11727 21372 11725 21372 11653 21372 11728 21373 11726 21373 11725 21373 11727 21374 11653 21374 11651 21374 11728 21375 11724 21375 11726 21375 11729 21376 11724 21376 11728 21376 11728 21377 11725 21377 11727 21377 11730 21378 11727 21378 11651 21378 11731 21379 11727 21379 11730 21379 11731 21380 11728 21380 11727 21380 11729 21381 11728 21381 11731 21381 11732 21382 11729 21382 11731 21382 11733 21383 11730 21383 11649 21383 11733 21384 11731 21384 11730 21384 11732 21385 11731 21385 11733 21385 11734 21386 11729 21386 11732 21386 11733 21387 11649 21387 11647 21387 11735 21388 11732 21388 11733 21388 11736 21389 11733 21389 11647 21389 11735 21390 11733 21390 11736 21390 11646 21391 11736 21391 11647 21391 11734 21392 11732 21392 11735 21392 11734 21393 11735 21393 11738 21393 11737 21394 11736 21394 11646 21394 11738 21395 11736 21395 11737 21395 11738 21396 11735 21396 11736 21396 11644 21397 11737 21397 11646 21397 11740 21398 11738 21398 11737 21398 11739 21399 11738 21399 11740 21399 11740 21400 11737 21400 11644 21400 11739 21401 11734 21401 11738 21401 11741 21402 11740 21402 11644 21402 11742 21403 11739 21403 11740 21403 11744 21404 11739 21404 11742 21404 11742 21405 11740 21405 11741 21405 11743 21406 11742 21406 11741 21406 11745 21407 11742 21407 11743 21407 11745 21408 11744 21408 11742 21408 11746 21409 11743 21409 11642 21409 11746 21410 11745 21410 11743 21410 11747 21411 11745 21411 11746 21411 11747 21412 11744 21412 11745 21412 11640 21413 11746 21413 11642 21413 11748 21414 11747 21414 11746 21414 11749 21415 11747 21415 11748 21415 11750 21416 11746 21416 11640 21416 11749 21417 11744 21417 11747 21417 11748 21418 11746 21418 11750 21418 11750 21419 11640 21419 11638 21419 11637 21420 11750 21420 11638 21420 11751 21421 11748 21421 11750 21421 11749 21422 11748 21422 11751 21422 11751 21423 11750 21423 11637 21423 11752 21424 11637 21424 11635 21424 11753 21425 11749 21425 11751 21425 11752 21426 11751 21426 11637 21426 11753 21427 11751 21427 11752 21427 11752 21428 11635 21428 11634 21428 11754 21429 11753 21429 11752 21429 11755 21430 11752 21430 11634 21430 11755 21431 11754 21431 11752 21431 11756 21432 11749 21432 11753 21432 11755 21433 11634 21433 11632 21433 11756 21434 11753 21434 11754 21434 11757 21435 11754 21435 11755 21435 11758 21436 11754 21436 11757 21436 11758 21437 11756 21437 11754 21437 11757 21438 11755 21438 11632 21438 11759 21439 11632 21439 11630 21439 11759 21440 11757 21440 11632 21440 11759 21441 11758 21441 11757 21441 11760 21442 11758 21442 11759 21442 11629 21443 11759 21443 11630 21443 11760 21444 11756 21444 11758 21444 11761 21445 11760 21445 11759 21445 11761 21446 11759 21446 11629 21446 11762 21447 11756 21447 11760 21447 11762 21448 11760 21448 11761 21448 11763 21449 11629 21449 11627 21449 11763 21450 11761 21450 11629 21450 11762 21451 11761 21451 11763 21451 11764 21452 11762 21452 11763 21452 11765 21453 11763 21453 11627 21453 11766 21454 11764 21454 11763 21454 11767 21455 11763 21455 11765 21455 11768 21456 11762 21456 11764 21456 11766 21457 11763 21457 11767 21457 11767 21458 11765 21458 11625 21458 11768 21459 11764 21459 11766 21459 11769 21460 11766 21460 11767 21460 11770 21461 11767 21461 11625 21461 11768 21462 11766 21462 11769 21462 11771 21463 11767 21463 11770 21463 11771 21464 11769 21464 11767 21464 11772 21465 11770 21465 11623 21465 11772 21466 11771 21466 11770 21466 11773 21467 11769 21467 11771 21467 11773 21468 11768 21468 11769 21468 11774 21469 11772 21469 11623 21469 11777 21470 11768 21470 11773 21470 11775 21471 11771 21471 11772 21471 11775 21472 11773 21472 11771 21472 11776 21473 11772 21473 11774 21473 11775 21474 11772 21474 11776 21474 11777 21475 11773 21475 11775 21475 11776 21476 11774 21476 11622 21476 11620 21477 11776 21477 11622 21477 11778 21478 11776 21478 11620 21478 11778 21479 11775 21479 11776 21479 11777 21480 11775 21480 11778 21480 11619 21481 11778 21481 11620 21481 11779 21482 11777 21482 11778 21482 11781 21483 11777 21483 11779 21483 11779 21484 11778 21484 11619 21484 11780 21485 11619 21485 11617 21485 11780 21486 11779 21486 11619 21486 11782 21487 11779 21487 11780 21487 11781 21488 11779 21488 11782 21488 11616 21489 11780 21489 11617 21489 11783 21490 11780 21490 11616 21490 11782 21491 11780 21491 11783 21491 11784 21492 11782 21492 11783 21492 11781 21493 11782 21493 11784 21493 11614 21494 11783 21494 11616 21494 11785 21495 11783 21495 11614 21495 11785 21496 11784 21496 11783 21496 11786 21497 11785 21497 11614 21497 11787 21498 11784 21498 11785 21498 11788 21499 11785 21499 11786 21499 11787 21500 11781 21500 11784 21500 11788 21501 11787 21501 11785 21501 11788 21502 11786 21502 11612 21502 11789 21503 11787 21503 11788 21503 11790 21504 11788 21504 11612 21504 11791 21505 11788 21505 11790 21505 11791 21506 11789 21506 11788 21506 11793 21507 11787 21507 11789 21507 11611 21508 11791 21508 11790 21508 11792 21509 11791 21509 11611 21509 11792 21510 11789 21510 11791 21510 11793 21511 11789 21511 11792 21511 11795 21512 11611 21512 11794 21512 11795 21513 11792 21513 11611 21513 11796 21514 11792 21514 11795 21514 11793 21515 11792 21515 11796 21515 11795 21516 11794 21516 11609 21516 11795 21517 11609 21517 11680 21517 11796 21518 11795 21518 11680 21518 11793 21519 11796 21519 11682 21519 11301 21520 11689 21520 11698 21520 11303 21521 11689 21521 11301 21521 11297 21522 11301 21522 11698 21522 11306 21523 11689 21523 11303 21523 11297 21524 11698 21524 11701 21524 11306 21525 11682 21525 11689 21525 11294 21526 11297 21526 11701 21526 11308 21527 11682 21527 11306 21527 11294 21528 11701 21528 11711 21528 11241 21529 11682 21529 11308 21529 11292 21530 11294 21530 11711 21530 11241 21531 11793 21531 11682 21531 11243 21532 11793 21532 11241 21532 11288 21533 11292 21533 11711 21533 11716 21534 11288 21534 11711 21534 11245 21535 11793 21535 11243 21535 11245 21536 11787 21536 11793 21536 11719 21537 11288 21537 11716 21537 11285 21538 11288 21538 11719 21538 11724 21539 11285 21539 11719 21539 11248 21540 11781 21540 11787 21540 11248 21541 11787 21541 11245 21541 11281 21542 11285 21542 11724 21542 11729 21543 11281 21543 11724 21543 11781 21544 11248 21544 11249 21544 11777 21545 11249 21545 11252 21545 11777 21546 11781 21546 11249 21546 11734 21547 11278 21547 11281 21547 11734 21548 11281 21548 11729 21548 11734 21549 11274 21549 11278 21549 11777 21550 11252 21550 11256 21550 11739 21551 11274 21551 11734 21551 11768 21552 11777 21552 11256 21552 11768 21553 11256 21553 11257 21553 11739 21554 11270 21554 11274 21554 11744 21555 11270 21555 11739 21555 11762 21556 11768 21556 11257 21556 11762 21557 11257 21557 11259 21557 11749 21558 11267 21558 11270 21558 11749 21559 11270 21559 11744 21559 11756 21560 11259 21560 11262 21560 11756 21561 11762 21561 11259 21561 11749 21562 11265 21562 11267 21562 11756 21563 11262 21563 11265 21563 11756 21564 11265 21564 11749 21564 11797 21565 11798 21565 11523 21565 11799 21566 11798 21566 11797 21566 11799 21567 11903 21567 11798 21567 11797 21568 11523 21568 11526 21568 11800 21569 11799 21569 11797 21569 11800 21570 11797 21570 11526 21570 11527 21571 11800 21571 11526 21571 11801 21572 11799 21572 11800 21572 11802 21573 11800 21573 11527 21573 11802 21574 11801 21574 11800 21574 11802 21575 11527 21575 11528 21575 11803 21576 11799 21576 11801 21576 11804 21577 11801 21577 11802 21577 11805 21578 11802 21578 11528 21578 11804 21579 11803 21579 11801 21579 11806 21580 11802 21580 11805 21580 11806 21581 11804 21581 11802 21581 11530 21582 11806 21582 11805 21582 11807 21583 11803 21583 11804 21583 11808 21584 11806 21584 11530 21584 11809 21585 11806 21585 11808 21585 11809 21586 11804 21586 11806 21586 11808 21587 11530 21587 11532 21587 11807 21588 11804 21588 11809 21588 11808 21589 11532 21589 11533 21589 11810 21590 11809 21590 11808 21590 11810 21591 11807 21591 11809 21591 11811 21592 11808 21592 11533 21592 11810 21593 11808 21593 11811 21593 11811 21594 11533 21594 11534 21594 11812 21595 11807 21595 11810 21595 11813 21596 11811 21596 11534 21596 11813 21597 11810 21597 11811 21597 11812 21598 11810 21598 11813 21598 11536 21599 11813 21599 11534 21599 11814 21600 11813 21600 11536 21600 11815 21601 11812 21601 11813 21601 11815 21602 11813 21602 11814 21602 11816 21603 11536 21603 11538 21603 11816 21604 11814 21604 11536 21604 11817 21605 11814 21605 11816 21605 11817 21606 11815 21606 11814 21606 11818 21607 11815 21607 11817 21607 11540 21608 11816 21608 11538 21608 11819 21609 11816 21609 11540 21609 11819 21610 11817 21610 11816 21610 11820 21611 11817 21611 11819 21611 11820 21612 11818 21612 11817 21612 11819 21613 11540 21613 11541 21613 11821 21614 11819 21614 11541 21614 11821 21615 11820 21615 11819 21615 11821 21616 11541 21616 11543 21616 11822 21617 11818 21617 11820 21617 11823 21618 11821 21618 11543 21618 11824 21619 11821 21619 11823 21619 11824 21620 11820 21620 11821 21620 11822 21621 11820 21621 11824 21621 11823 21622 11543 21622 11544 21622 11825 21623 11818 21623 11822 21623 11546 21624 11823 21624 11544 21624 11825 21625 11822 21625 11824 21625 11826 21626 11823 21626 11546 21626 11826 21627 11824 21627 11823 21627 11827 21628 11824 21628 11826 21628 11826 21629 11546 21629 11547 21629 11827 21630 11825 21630 11824 21630 11828 21631 11826 21631 11547 21631 11828 21632 11547 21632 11549 21632 11829 21633 11826 21633 11828 21633 11829 21634 11827 21634 11826 21634 11829 21635 11828 21635 11549 21635 11830 21636 11827 21636 11829 21636 11550 21637 11829 21637 11549 21637 11831 21638 11829 21638 11550 21638 11825 21639 11827 21639 11830 21639 11831 21640 11830 21640 11829 21640 11833 21641 11825 21641 11830 21641 11832 21642 11550 21642 11552 21642 11832 21643 11831 21643 11550 21643 11830 21644 11831 21644 11832 21644 11834 21645 11830 21645 11832 21645 11833 21646 11830 21646 11834 21646 11553 21647 11832 21647 11552 21647 11835 21648 11832 21648 11553 21648 11834 21649 11832 21649 11835 21649 11835 21650 11553 21650 11554 21650 11836 21651 11834 21651 11835 21651 11837 21652 11834 21652 11836 21652 11837 21653 11833 21653 11834 21653 11838 21654 11833 21654 11837 21654 11556 21655 11835 21655 11554 21655 11836 21656 11835 21656 11556 21656 11839 21657 11836 21657 11556 21657 11839 21658 11837 21658 11836 21658 11839 21659 11556 21659 11557 21659 11838 21660 11837 21660 11839 21660 11840 21661 11839 21661 11557 21661 11840 21662 11838 21662 11839 21662 11840 21663 11557 21663 11559 21663 11842 21664 11840 21664 11559 21664 11842 21665 11838 21665 11840 21665 11843 21666 11559 21666 11560 21666 11841 21667 11838 21667 11842 21667 11843 21668 11842 21668 11559 21668 11843 21669 11560 21669 11561 21669 11561 21670 11842 21670 11843 21670 11844 21671 11842 21671 11561 21671 11844 21672 11841 21672 11842 21672 11846 21673 11561 21673 11563 21673 11846 21674 11844 21674 11561 21674 11564 21675 11846 21675 11563 21675 11845 21676 11841 21676 11844 21676 11845 21677 11844 21677 11846 21677 11566 21678 11846 21678 11564 21678 11847 21679 11846 21679 11566 21679 11847 21680 11845 21680 11846 21680 11848 21681 11845 21681 11847 21681 11849 21682 11566 21682 11567 21682 11849 21683 11847 21683 11566 21683 11850 21684 11848 21684 11847 21684 11849 21685 11567 21685 11568 21685 11850 21686 11847 21686 11849 21686 11851 21687 11849 21687 11568 21687 11852 21688 11848 21688 11850 21688 11851 21689 11850 21689 11849 21689 11570 21690 11851 21690 11568 21690 11852 21691 11850 21691 11851 21691 11853 21692 11851 21692 11570 21692 11854 21693 11851 21693 11853 21693 11854 21694 11852 21694 11851 21694 11855 21695 11852 21695 11854 21695 11854 21696 11853 21696 11572 21696 11856 21697 11572 21697 11573 21697 11856 21698 11854 21698 11572 21698 11857 21699 11854 21699 11856 21699 11857 21700 11855 21700 11854 21700 11858 21701 11855 21701 11857 21701 11575 21702 11856 21702 11573 21702 11859 21703 11856 21703 11575 21703 11860 21704 11855 21704 11858 21704 11859 21705 11857 21705 11856 21705 11859 21706 11858 21706 11857 21706 11860 21707 11858 21707 11859 21707 11861 21708 11859 21708 11575 21708 11861 21709 11575 21709 11576 21709 11862 21710 11861 21710 11576 21710 11862 21711 11859 21711 11861 21711 11863 21712 11859 21712 11862 21712 11863 21713 11860 21713 11859 21713 11862 21714 11576 21714 11578 21714 11864 21715 11860 21715 11863 21715 11865 21716 11863 21716 11862 21716 11864 21717 11863 21717 11865 21717 11579 21718 11862 21718 11578 21718 11865 21719 11862 21719 11579 21719 11868 21720 11860 21720 11864 21720 11866 21721 11579 21721 11581 21721 11866 21722 11865 21722 11579 21722 11867 21723 11865 21723 11866 21723 11867 21724 11864 21724 11865 21724 11868 21725 11864 21725 11867 21725 11582 21726 11866 21726 11581 21726 11869 21727 11867 21727 11866 21727 11868 21728 11867 21728 11869 21728 11870 21729 11866 21729 11582 21729 11869 21730 11866 21730 11870 21730 11584 21731 11870 21731 11582 21731 11871 21732 11870 21732 11584 21732 11872 21733 11868 21733 11869 21733 11871 21734 11869 21734 11870 21734 11872 21735 11869 21735 11871 21735 11873 21736 11871 21736 11584 21736 11874 21737 11871 21737 11873 21737 11874 21738 11872 21738 11871 21738 11586 21739 11873 21739 11584 21739 11875 21740 11872 21740 11874 21740 11876 21741 11586 21741 11587 21741 11876 21742 11873 21742 11586 21742 11876 21743 11874 21743 11873 21743 11877 21744 11874 21744 11876 21744 11875 21745 11874 21745 11877 21745 11589 21746 11876 21746 11587 21746 11877 21747 11876 21747 11589 21747 11880 21748 11875 21748 11877 21748 11879 21749 11875 21749 11880 21749 11878 21750 11877 21750 11589 21750 11880 21751 11877 21751 11878 21751 11881 21752 11879 21752 11880 21752 11591 21753 11878 21753 11589 21753 11881 21754 11880 21754 11878 21754 11592 21755 11878 21755 11591 21755 11882 21756 11878 21756 11592 21756 11882 21757 11881 21757 11878 21757 11879 21758 11881 21758 11883 21758 11883 21759 11881 21759 11882 21759 11884 21760 11882 21760 11592 21760 11883 21761 11882 21761 11884 21761 11594 21762 11884 21762 11592 21762 11887 21763 11879 21763 11883 21763 11885 21764 11883 21764 11884 21764 11885 21765 11884 21765 11594 21765 11886 21766 11594 21766 11595 21766 11887 21767 11883 21767 11885 21767 11885 21768 11594 21768 11886 21768 11887 21769 11885 21769 11886 21769 11888 21770 11886 21770 11595 21770 11597 21771 11888 21771 11595 21771 11889 21772 11886 21772 11888 21772 11889 21773 11887 21773 11886 21773 11599 21774 11888 21774 11597 21774 11890 21775 11887 21775 11889 21775 11891 21776 11888 21776 11599 21776 11891 21777 11889 21777 11888 21777 11600 21778 11891 21778 11599 21778 11892 21779 11891 21779 11600 21779 11892 21780 11889 21780 11891 21780 11892 21781 11890 21781 11889 21781 11893 21782 11892 21782 11600 21782 11894 21783 11892 21783 11893 21783 11895 21784 11887 21784 11890 21784 11893 21785 11600 21785 11601 21785 11895 21786 11890 21786 11892 21786 11894 21787 11895 21787 11892 21787 11896 21788 11894 21788 11893 21788 11895 21789 11894 21789 11896 21789 11896 21790 11601 21790 11603 21790 11896 21791 11893 21791 11601 21791 11898 21792 11896 21792 11603 21792 11898 21793 11895 21793 11896 21793 11897 21794 11895 21794 11898 21794 11605 21795 11898 21795 11603 21795 11900 21796 11895 21796 11897 21796 11899 21797 11898 21797 11605 21797 11897 21798 11898 21798 11899 21798 11899 21799 11605 21799 11606 21799 11900 21800 11897 21800 11899 21800 11901 21801 11899 21801 11606 21801 11902 21802 11899 21802 11901 21802 11902 21803 11900 21803 11899 21803 11607 21804 11901 21804 11606 21804 11904 21805 11901 21805 11607 21805 11904 21806 11902 21806 11901 21806 11798 21807 11902 21807 11904 21807 11798 21808 11900 21808 11902 21808 11904 21809 11607 21809 11523 21809 11903 21810 11900 21810 11798 21810 11904 21811 11523 21811 11798 21811 11213 21812 11209 21812 11860 21812 11213 21813 11860 21813 11868 21813 11209 21814 11855 21814 11860 21814 11216 21815 11213 21815 11868 21815 11207 21816 11855 21816 11209 21816 11216 21817 11868 21817 11872 21817 11207 21818 11852 21818 11855 21818 11205 21819 11852 21819 11207 21819 11219 21820 11216 21820 11872 21820 11219 21821 11872 21821 11875 21821 11222 21822 11219 21822 11875 21822 11201 21823 11848 21823 11852 21823 11201 21824 11852 21824 11205 21824 11222 21825 11875 21825 11879 21825 11201 21826 11845 21826 11848 21826 11225 21827 11222 21827 11879 21827 11225 21828 11879 21828 11887 21828 11198 21829 11845 21829 11201 21829 11198 21830 11841 21830 11845 21830 11228 21831 11225 21831 11887 21831 11195 21832 11838 21832 11841 21832 11195 21833 11841 21833 11198 21833 11193 21834 11838 21834 11195 21834 11887 21835 11231 21835 11228 21835 11895 21836 11231 21836 11887 21836 11190 21837 11838 21837 11193 21837 11833 21838 11838 21838 11190 21838 11235 21839 11231 21839 11895 21839 11825 21840 11833 21840 11190 21840 11900 21841 11235 21841 11895 21841 11186 21842 11825 21842 11190 21842 11903 21843 11235 21843 11900 21843 11903 21844 11238 21844 11235 21844 11825 21845 11186 21845 11182 21845 11799 21846 11238 21846 11903 21846 11818 21847 11825 21847 11182 21847 11799 21848 11166 21848 11238 21848 11818 21849 11182 21849 11178 21849 11799 21850 11168 21850 11166 21850 11803 21851 11168 21851 11799 21851 11815 21852 11818 21852 11178 21852 11807 21853 11168 21853 11803 21853 11807 21854 11171 21854 11168 21854 11815 21855 11178 21855 11175 21855 11812 21856 11815 21856 11175 21856 11812 21857 11171 21857 11807 21857 11812 21858 11175 21858 11171 21858 11905 21859 11907 21859 11906 21859 11908 21860 11907 21860 11905 21860 11909 21861 11907 21861 11908 21861 11911 21862 11909 21862 11908 21862 11912 21863 11905 21863 11910 21863 11912 21864 11908 21864 11905 21864 11913 21865 11908 21865 11912 21865 11913 21866 11911 21866 11908 21866 11914 21867 11912 21867 11910 21867 11913 21868 11912 21868 11914 21868 11915 21869 11914 21869 11910 21869 11917 21870 11911 21870 11913 21870 11916 21871 11913 21871 11914 21871 11917 21872 11913 21872 11916 21872 11918 21873 11914 21873 11915 21873 11916 21874 11914 21874 11918 21874 11919 21875 11916 21875 11918 21875 11919 21876 11917 21876 11916 21876 11919 21877 11918 21877 11920 21877 11921 21878 11920 21878 11918 21878 11923 21879 11917 21879 11919 21879 11922 21880 11919 21880 11920 21880 11923 21881 11919 21881 11922 21881 11924 21882 11920 21882 11921 21882 11922 21883 11920 21883 11924 21883 11924 21884 11921 21884 11925 21884 11926 21885 11924 21885 11925 21885 11927 21886 11923 21886 11922 21886 11928 21887 11924 21887 11926 21887 11928 21888 11922 21888 11924 21888 11927 21889 11922 21889 11928 21889 11930 21890 11926 21890 11929 21890 11930 21891 11928 21891 11926 21891 11930 21892 11927 21892 11928 21892 11931 21893 11930 21893 11929 21893 11932 21894 11930 21894 11931 21894 11933 21895 11930 21895 11932 21895 11933 21896 11927 21896 11930 21896 11935 21897 11931 21897 11934 21897 11935 21898 11932 21898 11931 21898 11933 21899 11932 21899 11935 21899 11938 21900 11933 21900 11935 21900 11937 21901 11933 21901 11938 21901 11938 21902 11934 21902 11936 21902 11938 21903 11935 21903 11934 21903 11937 21904 11927 21904 11933 21904 11939 21905 11938 21905 11936 21905 11937 21906 11938 21906 11939 21906 11940 21907 11939 21907 11936 21907 11941 21908 11937 21908 11939 21908 11944 21909 11940 21909 11943 21909 11942 21910 11937 21910 11941 21910 11944 21911 11939 21911 11940 21911 11941 21912 11939 21912 11944 21912 11946 21913 11943 21913 11945 21913 11946 21914 11944 21914 11943 21914 11946 21915 11941 21915 11944 21915 11947 21916 11941 21916 11946 21916 11947 21917 11942 21917 11941 21917 11949 21918 11946 21918 11945 21918 11949 21919 11945 21919 11948 21919 11950 21920 11942 21920 11947 21920 11951 21921 11946 21921 11949 21921 11951 21922 11947 21922 11946 21922 11950 21923 11947 21923 11951 21923 11952 21924 11949 21924 11948 21924 11951 21925 11949 21925 11952 21925 11953 21926 11951 21926 11952 21926 11955 21927 11951 21927 11953 21927 11955 21928 11950 21928 11951 21928 11953 21929 11952 21929 11954 21929 11956 21930 11953 21930 11954 21930 11956 21931 11955 21931 11953 21931 11959 21932 11955 21932 11956 21932 11958 21933 11954 21933 11957 21933 11959 21934 11950 21934 11955 21934 11958 21935 11956 21935 11954 21935 11961 21936 11958 21936 11957 21936 11960 21937 11950 21937 11959 21937 11962 21938 11958 21938 11961 21938 11962 21939 11956 21939 11958 21939 11959 21940 11956 21940 11962 21940 11963 21941 11962 21941 11961 21941 11964 21942 11962 21942 11963 21942 11965 21943 11962 21943 11964 21943 11965 21944 11959 21944 11962 21944 11960 21945 11959 21945 11965 21945 11964 21946 11963 21946 11966 21946 11967 21947 11965 21947 11964 21947 11968 21948 11965 21948 11967 21948 11968 21949 11960 21949 11965 21949 11967 21950 11964 21950 11966 21950 11970 21951 11960 21951 11968 21951 11971 21952 11966 21952 11969 21952 11971 21953 11967 21953 11966 21953 11968 21954 11967 21954 11971 21954 11972 21955 11968 21955 11971 21955 11972 21956 11970 21956 11968 21956 11973 21957 11971 21957 11969 21957 11972 21958 11971 21958 11973 21958 11974 21959 11972 21959 11973 21959 11976 21960 11970 21960 11972 21960 11974 21961 11973 21961 11975 21961 11982 21962 11970 21962 11976 21962 11976 21963 11972 21963 11974 21963 11977 21964 11974 21964 11975 21964 11976 21965 11974 21965 11977 21965 11977 21966 11975 21966 11978 21966 11979 21967 11976 21967 11977 21967 11982 21968 11976 21968 11979 21968 11980 21969 11977 21969 11978 21969 11979 21970 11977 21970 11980 21970 11980 21971 11978 21971 11981 21971 11983 21972 11980 21972 11981 21972 11984 21973 11982 21973 11979 21973 11985 21974 11980 21974 11983 21974 11985 21975 11979 21975 11980 21975 11984 21976 11979 21976 11985 21976 11986 21977 11985 21977 11983 21977 11987 21978 11985 21978 11986 21978 11987 21979 11984 21979 11985 21979 11988 21980 11986 21980 11983 21980 11989 21981 11986 21981 11988 21981 11989 21982 11987 21982 11986 21982 11990 21983 11987 21983 11989 21983 11990 21984 11984 21984 11987 21984 11996 21985 11984 21985 11990 21985 11991 21986 11989 21986 11988 21986 11992 21987 11989 21987 11991 21987 11992 21988 11990 21988 11989 21988 11993 21989 11990 21989 11992 21989 11994 21990 11992 21990 11991 21990 11993 21991 11992 21991 11994 21991 11996 21992 11990 21992 11993 21992 11995 21993 11994 21993 11991 21993 11997 21994 11993 21994 11994 21994 11999 21995 11993 21995 11997 21995 11999 21996 11996 21996 11993 21996 11998 21997 11994 21997 11995 21997 12000 21998 11994 21998 11998 21998 11997 21999 11994 21999 12000 21999 12000 22000 11998 22000 12001 22000 12002 22001 12000 22001 12001 22001 12004 22002 11996 22002 11999 22002 12002 22003 11997 22003 12000 22003 12005 22004 11997 22004 12002 22004 12002 22005 12001 22005 12003 22005 12004 22006 11997 22006 12005 22006 12004 22007 11999 22007 11997 22007 12006 22008 12002 22008 12003 22008 12006 22009 12005 22009 12002 22009 12004 22010 12005 22010 12006 22010 12006 22011 12003 22011 12007 22011 12008 22012 12004 22012 12006 22012 12009 22013 12006 22013 12007 22013 12009 22014 12008 22014 12006 22014 12009 22015 12007 22015 12011 22015 12010 22016 12008 22016 12009 22016 12010 22017 12004 22017 12008 22017 12012 22018 12009 22018 12011 22018 12013 22019 12009 22019 12012 22019 12013 22020 12010 22020 12009 22020 12014 22021 12012 22021 12011 22021 12015 22022 12010 22022 12013 22022 12016 22023 12013 22023 12012 22023 12015 22024 12013 22024 12016 22024 12017 22025 12012 22025 12014 22025 12018 22026 12012 22026 12017 22026 12016 22027 12012 22027 12018 22027 12019 22028 12018 22028 12017 22028 12020 22029 12018 22029 12019 22029 12020 22030 12016 22030 12018 22030 12021 22031 12016 22031 12020 22031 12021 22032 12015 22032 12016 22032 12020 22033 12019 22033 12022 22033 12023 22034 12020 22034 12022 22034 12025 22035 12021 22035 12020 22035 12023 22036 12022 22036 12024 22036 12026 22037 12020 22037 12023 22037 12025 22038 12020 22038 12026 22038 12027 22039 12023 22039 12024 22039 12027 22040 12026 22040 12023 22040 12029 22041 12026 22041 12027 22041 12025 22042 12026 22042 12029 22042 12027 22043 12024 22043 12028 22043 12030 22044 12025 22044 12029 22044 12031 22045 12027 22045 12028 22045 12029 22046 12027 22046 12031 22046 12033 22047 12028 22047 12032 22047 12033 22048 12031 22048 12028 22048 12034 22049 12031 22049 12033 22049 12034 22050 12029 22050 12031 22050 12035 22051 12029 22051 12034 22051 12035 22052 12030 22052 12029 22052 12036 22053 12033 22053 12032 22053 12036 22054 12034 22054 12033 22054 12035 22055 12034 22055 12036 22055 12036 22056 12032 22056 12037 22056 12038 22057 12030 22057 12035 22057 12039 22058 12035 22058 12036 22058 12038 22059 12035 22059 12039 22059 12040 22060 12036 22060 12037 22060 12039 22061 12036 22061 12040 22061 12041 22062 12040 22062 12037 22062 12042 22063 12040 22063 12041 22063 12042 22064 12039 22064 12040 22064 12043 22065 12042 22065 12041 22065 12045 22066 12038 22066 12039 22066 12044 22067 12039 22067 12042 22067 12045 22068 12039 22068 12044 22068 12046 22069 12042 22069 12043 22069 12046 22070 12044 22070 12042 22070 12048 22071 12043 22071 12047 22071 12048 22072 12046 22072 12043 22072 12048 22073 12044 22073 12046 22073 12049 22074 12045 22074 12044 22074 12049 22075 12044 22075 12048 22075 12050 22076 12048 22076 12047 22076 12051 22077 12048 22077 12050 22077 12049 22078 12048 22078 12051 22078 12052 22079 12049 22079 12051 22079 12054 22080 12050 22080 12053 22080 12054 22081 12051 22081 12050 22081 12052 22082 12051 22082 12054 22082 12055 22083 12049 22083 12052 22083 12056 22084 12054 22084 12053 22084 12057 22085 12054 22085 12056 22085 12057 22086 12052 22086 12054 22086 12055 22087 12052 22087 12057 22087 12057 22088 12056 22088 12058 22088 12059 22089 12057 22089 12058 22089 12059 22090 12055 22090 12057 22090 12060 22091 12055 22091 12059 22091 12061 22092 12059 22092 12058 22092 12062 22093 12059 22093 12061 22093 12062 22094 12060 22094 12059 22094 12063 22095 12062 22095 12061 22095 12065 22096 12062 22096 12063 22096 12065 22097 12060 22097 12062 22097 12064 22098 12060 22098 12065 22098 12067 22099 12063 22099 12066 22099 12069 22100 12060 22100 12064 22100 12067 22101 12065 22101 12063 22101 12064 22102 12065 22102 12067 22102 12068 22103 12067 22103 12066 22103 12071 22104 12064 22104 12067 22104 12069 22105 12064 22105 12071 22105 12072 22106 12068 22106 12070 22106 12072 22107 12067 22107 12068 22107 12071 22108 12067 22108 12072 22108 12073 22109 12072 22109 12070 22109 12074 22110 12072 22110 12073 22110 12074 22111 12071 22111 12072 22111 11906 22112 12073 22112 12070 22112 12074 22113 12069 22113 12071 22113 11909 22114 12069 22114 12074 22114 11907 22115 12073 22115 11906 22115 11907 22116 12074 22116 12073 22116 12074 22117 11907 22117 11909 22117 12076 22118 11906 22118 12070 22118 12076 22119 12075 22119 11906 22119 12134 22120 12076 22120 12070 22120 12077 22121 12070 22121 12068 22121 12077 22122 12134 22122 12070 22122 12078 22123 12068 22123 12066 22123 12078 22124 12077 22124 12068 22124 12078 22125 12066 22125 12063 22125 12138 22126 12063 22126 12061 22126 12138 22127 12078 22127 12063 22127 12079 22128 12138 22128 12061 22128 12079 22129 12061 22129 12058 22129 12080 22130 12079 22130 12058 22130 12080 22131 12058 22131 12056 22131 12081 22132 12080 22132 12056 22132 12081 22133 12056 22133 12053 22133 12082 22134 12053 22134 12050 22134 12082 22135 12081 22135 12053 22135 12083 22136 12050 22136 12047 22136 12083 22137 12082 22137 12050 22137 12084 22138 12047 22138 12043 22138 12084 22139 12083 22139 12047 22139 12085 22140 12084 22140 12043 22140 12085 22141 12043 22141 12041 22141 12086 22142 12041 22142 12037 22142 12086 22143 12085 22143 12041 22143 12087 22144 12037 22144 12032 22144 12087 22145 12086 22145 12037 22145 12088 22146 12032 22146 12028 22146 12088 22147 12087 22147 12032 22147 12089 22148 12088 22148 12028 22148 12089 22149 12028 22149 12024 22149 12090 22150 12089 22150 12024 22150 12091 22151 12024 22151 12022 22151 12091 22152 12090 22152 12024 22152 12092 22153 12022 22153 12019 22153 12092 22154 12091 22154 12022 22154 12093 22155 12019 22155 12017 22155 12093 22156 12092 22156 12019 22156 12093 22157 12017 22157 12014 22157 12094 22158 12093 22158 12014 22158 12094 22159 12014 22159 12011 22159 12095 22160 12094 22160 12011 22160 12095 22161 12011 22161 12007 22161 12096 22162 12007 22162 12003 22162 12096 22163 12095 22163 12007 22163 12097 22164 12096 22164 12003 22164 12097 22165 12003 22165 12001 22165 12098 22166 12097 22166 12001 22166 12098 22167 12001 22167 11998 22167 12099 22168 12098 22168 11998 22168 12099 22169 11998 22169 11995 22169 12100 22170 11995 22170 11991 22170 12100 22171 12099 22171 11995 22171 12101 22172 12100 22172 11991 22172 12101 22173 11991 22173 11988 22173 12102 22174 12101 22174 11988 22174 12103 22175 12102 22175 11988 22175 12103 22176 11988 22176 11983 22176 12104 22177 12103 22177 11983 22177 12104 22178 11983 22178 11981 22178 12105 22179 12104 22179 11981 22179 12105 22180 11981 22180 11978 22180 12106 22181 12105 22181 11978 22181 12106 22182 11978 22182 11975 22182 12107 22183 12106 22183 11975 22183 12107 22184 11975 22184 11973 22184 12108 22185 12107 22185 11973 22185 12108 22186 11973 22186 11969 22186 12109 22187 11969 22187 11966 22187 12109 22188 12108 22188 11969 22188 12110 22189 12109 22189 11966 22189 12110 22190 11966 22190 11963 22190 12111 22191 12110 22191 11963 22191 12111 22192 11963 22192 11961 22192 12112 22193 12111 22193 11961 22193 12112 22194 11961 22194 11957 22194 12113 22195 12112 22195 11957 22195 12114 22196 12113 22196 11957 22196 12114 22197 11957 22197 11954 22197 12114 22198 11954 22198 11952 22198 12115 22199 12114 22199 11952 22199 12115 22200 11952 22200 11948 22200 12116 22201 12115 22201 11948 22201 12116 22202 11948 22202 11945 22202 12117 22203 12116 22203 11945 22203 12117 22204 11945 22204 11943 22204 12117 22205 11943 22205 11940 22205 12118 22206 12117 22206 11940 22206 12118 22207 11940 22207 11936 22207 12119 22208 12118 22208 11936 22208 12120 22209 12119 22209 11936 22209 12120 22210 11936 22210 11934 22210 12121 22211 11934 22211 11931 22211 12121 22212 12120 22212 11934 22212 12122 22213 12121 22213 11931 22213 12122 22214 11931 22214 11929 22214 12123 22215 11929 22215 11926 22215 12123 22216 12122 22216 11929 22216 12124 22217 12123 22217 11926 22217 12124 22218 11926 22218 11925 22218 12125 22219 12124 22219 11925 22219 12125 22220 11925 22220 11921 22220 12126 22221 12125 22221 11921 22221 12126 22222 11921 22222 11918 22222 12127 22223 12126 22223 11918 22223 12127 22224 11918 22224 11915 22224 12128 22225 11915 22225 11910 22225 12128 22226 12127 22226 11915 22226 12129 22227 12128 22227 11910 22227 12129 22228 11910 22228 11905 22228 12130 22229 12129 22229 11905 22229 12075 22230 11905 22230 11906 22230 12075 22231 12130 22231 11905 22231 11668 22232 11672 22232 11927 22232 11672 22233 11923 22233 11927 22233 11674 22234 11923 22234 11672 22234 11668 22235 11927 22235 11937 22235 11664 22236 11668 22236 11937 22236 11676 22237 11923 22237 11674 22237 11664 22238 11937 22238 11942 22238 11676 22239 11917 22239 11923 22239 11662 22240 11664 22240 11942 22240 11676 22241 11911 22241 11917 22241 11608 22242 11911 22242 11676 22242 11662 22243 11942 22243 11950 22243 11608 22244 11909 22244 11911 22244 11660 22245 11662 22245 11950 22245 11610 22246 11909 22246 11608 22246 11659 22247 11660 22247 11950 22247 11610 22248 12069 22248 11909 22248 11960 22249 11659 22249 11950 22249 11656 22250 11659 22250 11960 22250 11613 22251 12069 22251 11610 22251 11613 22252 12060 22252 12069 22252 11654 22253 11656 22253 11960 22253 11615 22254 12060 22254 11613 22254 11970 22255 11654 22255 11960 22255 12055 22256 12060 22256 11615 22256 11618 22257 12055 22257 11615 22257 11970 22258 11652 22258 11654 22258 11982 22259 11652 22259 11970 22259 12049 22260 12055 22260 11618 22260 11982 22261 11650 22261 11652 22261 11621 22262 12049 22262 11618 22262 11982 22263 11648 22263 11650 22263 12045 22264 12049 22264 11621 22264 11984 22265 11648 22265 11982 22265 11624 22266 12045 22266 11621 22266 11984 22267 11645 22267 11648 22267 12038 22268 12045 22268 11624 22268 11996 22269 11645 22269 11984 22269 12038 22270 11624 22270 11626 22270 11996 22271 11643 22271 11645 22271 12030 22272 12038 22272 11626 22272 11996 22273 11641 22273 11643 22273 12030 22274 11626 22274 11628 22274 12025 22275 12030 22275 11628 22275 12004 22276 11641 22276 11996 22276 12004 22277 11639 22277 11641 22277 12021 22278 11628 22278 11631 22278 12021 22279 12025 22279 11628 22279 12010 22280 11639 22280 12004 22280 12010 22281 11636 22281 11639 22281 12015 22282 11631 22282 11633 22282 12015 22283 12021 22283 11631 22283 12010 22284 12015 22284 11633 22284 12010 22285 11633 22285 11636 22285 12132 22286 12239 22286 12131 22286 12131 22287 12075 22287 12076 22287 12133 22288 12132 22288 12131 22288 12134 22289 12131 22289 12076 22289 12135 22290 12131 22290 12134 22290 12133 22291 12131 22291 12135 22291 12135 22292 12134 22292 12077 22292 12136 22293 12132 22293 12133 22293 12136 22294 12133 22294 12135 22294 12078 22295 12135 22295 12077 22295 12137 22296 12135 22296 12078 22296 12136 22297 12135 22297 12137 22297 12138 22298 12137 22298 12078 22298 12140 22299 12137 22299 12138 22299 12140 22300 12136 22300 12137 22300 12139 22301 12136 22301 12140 22301 12140 22302 12138 22302 12079 22302 12141 22303 12140 22303 12079 22303 12142 22304 12139 22304 12140 22304 12142 22305 12140 22305 12141 22305 12143 22306 12079 22306 12080 22306 12143 22307 12141 22307 12079 22307 12146 22308 12139 22308 12142 22308 12144 22309 12141 22309 12143 22309 12144 22310 12142 22310 12141 22310 12146 22311 12142 22311 12144 22311 12143 22312 12080 22312 12081 22312 12145 22313 12144 22313 12143 22313 12146 22314 12144 22314 12145 22314 12145 22315 12143 22315 12081 22315 12147 22316 12145 22316 12081 22316 12148 22317 12145 22317 12147 22317 12148 22318 12146 22318 12145 22318 12147 22319 12081 22319 12082 22319 12149 22320 12148 22320 12147 22320 12083 22321 12147 22321 12082 22321 12151 22322 12146 22322 12148 22322 12149 22323 12147 22323 12083 22323 12150 22324 12149 22324 12083 22324 12151 22325 12148 22325 12149 22325 12150 22326 12083 22326 12084 22326 12152 22327 12149 22327 12150 22327 12152 22328 12151 22328 12149 22328 12153 22329 12150 22329 12084 22329 12152 22330 12150 22330 12153 22330 12153 22331 12084 22331 12085 22331 12154 22332 12153 22332 12085 22332 12154 22333 12152 22333 12153 22333 12156 22334 12151 22334 12152 22334 12156 22335 12154 22335 12155 22335 12156 22336 12152 22336 12154 22336 12086 22337 12154 22337 12085 22337 12155 22338 12154 22338 12086 22338 12157 22339 12156 22339 12155 22339 12158 22340 12086 22340 12087 22340 12158 22341 12155 22341 12086 22341 12157 22342 12155 22342 12158 22342 12159 22343 12157 22343 12158 22343 12159 22344 12158 22344 12087 22344 12088 22345 12159 22345 12087 22345 12160 22346 12156 22346 12157 22346 12160 22347 12159 22347 12161 22347 12160 22348 12157 22348 12159 22348 12161 22349 12159 22349 12088 22349 12162 22350 12088 22350 12089 22350 12162 22351 12161 22351 12088 22351 12163 22352 12161 22352 12162 22352 12163 22353 12160 22353 12161 22353 12090 22354 12162 22354 12089 22354 12164 22355 12162 22355 12090 22355 12164 22356 12163 22356 12162 22356 12165 22357 12090 22357 12091 22357 12165 22358 12164 22358 12090 22358 12092 22359 12165 22359 12091 22359 12166 22360 12163 22360 12164 22360 12167 22361 12164 22361 12165 22361 12166 22362 12164 22362 12167 22362 12168 22363 12165 22363 12092 22363 12169 22364 12163 22364 12166 22364 12167 22365 12165 22365 12168 22365 12093 22366 12168 22366 12092 22366 12170 22367 12166 22367 12167 22367 12169 22368 12166 22368 12170 22368 12167 22369 12168 22369 12093 22369 12171 22370 12167 22370 12093 22370 12172 22371 12167 22371 12171 22371 12172 22372 12170 22372 12167 22372 12171 22373 12093 22373 12094 22373 12169 22374 12170 22374 12172 22374 12094 22375 12172 22375 12171 22375 12174 22376 12172 22376 12094 22376 12174 22377 12169 22377 12172 22377 12174 22378 12094 22378 12095 22378 12173 22379 12169 22379 12174 22379 12175 22380 12174 22380 12095 22380 12096 22381 12175 22381 12095 22381 12176 22382 12174 22382 12175 22382 12173 22383 12174 22383 12176 22383 12177 22384 12175 22384 12096 22384 12178 22385 12173 22385 12176 22385 12179 22386 12175 22386 12177 22386 12179 22387 12176 22387 12175 22387 12177 22388 12096 22388 12097 22388 12178 22389 12176 22389 12179 22389 12180 22390 12177 22390 12097 22390 12179 22391 12177 22391 12180 22391 12098 22392 12180 22392 12097 22392 12181 22393 12179 22393 12180 22393 12181 22394 12178 22394 12179 22394 12182 22395 12180 22395 12098 22395 12182 22396 12181 22396 12180 22396 12182 22397 12098 22397 12099 22397 12183 22398 12182 22398 12099 22398 12184 22399 12181 22399 12182 22399 12183 22400 12099 22400 12100 22400 12185 22401 12178 22401 12181 22401 12184 22402 12182 22402 12183 22402 12185 22403 12181 22403 12184 22403 12186 22404 12100 22404 12101 22404 12186 22405 12183 22405 12100 22405 12186 22406 12184 22406 12183 22406 12185 22407 12184 22407 12186 22407 12102 22408 12186 22408 12101 22408 12187 22409 12186 22409 12102 22409 12188 22410 12186 22410 12187 22410 12188 22411 12185 22411 12186 22411 12189 22412 12185 22412 12188 22412 12190 22413 12102 22413 12103 22413 12190 22414 12187 22414 12102 22414 12190 22415 12188 22415 12187 22415 12104 22416 12190 22416 12103 22416 12191 22417 12190 22417 12104 22417 12191 22418 12188 22418 12190 22418 12191 22419 12189 22419 12188 22419 12192 22420 12189 22420 12191 22420 12193 22421 12104 22421 12105 22421 12193 22422 12191 22422 12104 22422 12194 22423 12191 22423 12193 22423 12192 22424 12191 22424 12194 22424 12106 22425 12193 22425 12105 22425 12194 22426 12193 22426 12106 22426 12195 22427 12192 22427 12194 22427 12196 22428 12106 22428 12107 22428 12196 22429 12194 22429 12106 22429 12195 22430 12194 22430 12196 22430 12197 22431 12192 22431 12195 22431 12198 22432 12107 22432 12108 22432 12198 22433 12196 22433 12107 22433 12195 22434 12196 22434 12198 22434 12197 22435 12195 22435 12198 22435 12199 22436 12198 22436 12108 22436 12199 22437 12108 22437 12109 22437 12200 22438 12198 22438 12199 22438 12200 22439 12197 22439 12198 22439 12202 22440 12197 22440 12200 22440 12110 22441 12199 22441 12109 22441 12201 22442 12199 22442 12110 22442 12201 22443 12200 22443 12199 22443 12203 22444 12201 22444 12110 22444 12204 22445 12201 22445 12203 22445 12204 22446 12200 22446 12201 22446 12202 22447 12200 22447 12204 22447 12111 22448 12203 22448 12110 22448 12205 22449 12204 22449 12203 22449 12206 22450 12204 22450 12205 22450 12206 22451 12202 22451 12204 22451 12112 22452 12203 22452 12111 22452 12207 22453 12202 22453 12206 22453 12205 22454 12203 22454 12112 22454 12208 22455 12205 22455 12112 22455 12208 22456 12206 22456 12205 22456 12113 22457 12208 22457 12112 22457 12209 22458 12206 22458 12208 22458 12210 22459 12113 22459 12114 22459 12210 22460 12208 22460 12113 22460 12207 22461 12206 22461 12209 22461 12209 22462 12208 22462 12210 22462 12212 22463 12207 22463 12209 22463 12211 22464 12210 22464 12114 22464 12213 22465 12209 22465 12210 22465 12213 22466 12210 22466 12211 22466 12212 22467 12209 22467 12213 22467 12115 22468 12211 22468 12114 22468 12214 22469 12211 22469 12115 22469 12214 22470 12213 22470 12211 22470 12215 22471 12212 22471 12213 22471 12116 22472 12214 22472 12115 22472 12216 22473 12213 22473 12214 22473 12215 22474 12213 22474 12216 22474 12217 22475 12214 22475 12116 22475 12216 22476 12214 22476 12217 22476 12217 22477 12116 22477 12117 22477 12218 22478 12217 22478 12117 22478 12219 22479 12217 22479 12218 22479 12219 22480 12216 22480 12217 22480 12220 22481 12216 22481 12219 22481 12220 22482 12215 22482 12216 22482 12118 22483 12218 22483 12117 22483 12219 22484 12218 22484 12118 22484 12221 22485 12219 22485 12118 22485 12221 22486 12118 22486 12119 22486 12222 22487 12215 22487 12220 22487 12220 22488 12219 22488 12221 22488 12223 22489 12221 22489 12119 22489 12223 22490 12220 22490 12221 22490 12222 22491 12220 22491 12223 22491 12223 22492 12119 22492 12120 22492 12224 22493 12223 22493 12120 22493 12224 22494 12120 22494 12121 22494 12225 22495 12222 22495 12223 22495 12226 22496 12223 22496 12224 22496 12122 22497 12224 22497 12121 22497 12226 22498 12225 22498 12223 22498 12227 22499 12224 22499 12122 22499 12227 22500 12226 22500 12224 22500 12225 22501 12226 22501 12227 22501 12227 22502 12122 22502 12123 22502 12229 22503 12225 22503 12227 22503 12228 22504 12227 22504 12123 22504 12229 22505 12227 22505 12228 22505 12228 22506 12123 22506 12124 22506 12230 22507 12225 22507 12229 22507 12228 22508 12124 22508 12125 22508 12230 22509 12229 22509 12228 22509 12231 22510 12228 22510 12125 22510 12230 22511 12228 22511 12231 22511 12126 22512 12231 22512 12125 22512 12232 22513 12230 22513 12231 22513 12233 22514 12231 22514 12126 22514 12232 22515 12231 22515 12233 22515 12234 22516 12126 22516 12127 22516 12234 22517 12233 22517 12126 22517 12235 22518 12232 22518 12233 22518 12235 22519 12233 22519 12234 22519 12128 22520 12234 22520 12127 22520 12236 22521 12232 22521 12235 22521 12237 22522 12234 22522 12128 22522 12237 22523 12235 22523 12234 22523 12237 22524 12128 22524 12129 22524 12238 22525 12235 22525 12237 22525 12238 22526 12236 22526 12235 22526 12239 22527 12236 22527 12238 22527 12130 22528 12237 22528 12129 22528 12238 22529 12237 22529 12130 22529 12130 22530 12075 22530 12131 22530 12238 22531 12130 22531 12131 22531 12239 22532 12238 22532 12131 22532 11574 22533 12197 22533 12202 22533 11574 22534 12202 22534 11577 22534 11580 22535 12202 22535 12207 22535 11580 22536 11577 22536 12202 22536 11571 22537 12197 22537 11574 22537 11571 22538 12192 22538 12197 22538 11583 22539 11580 22539 12207 22539 11583 22540 12207 22540 12212 22540 11569 22541 12192 22541 11571 22541 11585 22542 11583 22542 12212 22542 11569 22543 12189 22543 12192 22543 11565 22544 12189 22544 11569 22544 11588 22545 11585 22545 12212 22545 11565 22546 12185 22546 12189 22546 11588 22547 12212 22547 12215 22547 11565 22548 12178 22548 12185 22548 11590 22549 11588 22549 12215 22549 11562 22550 12178 22550 11565 22550 11593 22551 11590 22551 12215 22551 11593 22552 12215 22552 12222 22552 11558 22553 12178 22553 11562 22553 11596 22554 11593 22554 12222 22554 11596 22555 12222 22555 12225 22555 11558 22556 12173 22556 12178 22556 11555 22557 12173 22557 11558 22557 11598 22558 11596 22558 12225 22558 12230 22559 11598 22559 12225 22559 11551 22560 12173 22560 11555 22560 12169 22561 12173 22561 11551 22561 11602 22562 11598 22562 12230 22562 12232 22563 11602 22563 12230 22563 11548 22564 12169 22564 11551 22564 12163 22565 12169 22565 11548 22565 12232 22566 11604 22566 11602 22566 12236 22567 11604 22567 12232 22567 12160 22568 12163 22568 11548 22568 11545 22569 12160 22569 11548 22569 12239 22570 11604 22570 12236 22570 12132 22571 11604 22571 12239 22571 12132 22572 11524 22572 11604 22572 12160 22573 11545 22573 11542 22573 12156 22574 12160 22574 11542 22574 12132 22575 11525 22575 11524 22575 12156 22576 11542 22576 11539 22576 12151 22577 12156 22577 11539 22577 12136 22578 11525 22578 12132 22578 12151 22579 11539 22579 11537 22579 12139 22580 11525 22580 12136 22580 12139 22581 11529 22581 11525 22581 12151 22582 11537 22582 11535 22582 12146 22583 12151 22583 11535 22583 12139 22584 11531 22584 11529 22584 12146 22585 11531 22585 12139 22585 12146 22586 11535 22586 11531 22586

+
+ + + +

12241 22587 12240 22587 12242 22587 12242 22588 12240 22588 12244 22588 12245 22589 12243 22589 12241 22589 12245 22590 12241 22590 12242 22590 12247 22591 12242 22591 12244 22591 12245 22592 12242 22592 12247 22592 12247 22593 12244 22593 12246 22593 12248 22594 12245 22594 12247 22594 12247 22595 12246 22595 12249 22595 12252 22596 12245 22596 12248 22596 12249 22597 12248 22597 12247 22597 12250 22598 12248 22598 12249 22598 12250 22599 12249 22599 12251 22599 12252 22600 12248 22600 12250 22600 12255 22601 12251 22601 12253 22601 12255 22602 12250 22602 12251 22602 12256 22603 12252 22603 12250 22603 12256 22604 12250 22604 12255 22604 12254 22605 12255 22605 12253 22605 12257 22606 12255 22606 12254 22606 12256 22607 12255 22607 12257 22607 12256 22608 12257 22608 12259 22608 12258 22609 12259 22609 12257 22609 12260 22610 12256 22610 12259 22610 12261 22611 12259 22611 12258 22611 12262 22612 12259 22612 12261 22612 12260 22613 12259 22613 12262 22613 12263 22614 12262 22614 12261 22614 12264 22615 12260 22615 12262 22615 12262 22616 12263 22616 12265 22616 12266 22617 12262 22617 12265 22617 12267 22618 12262 22618 12266 22618 12267 22619 12264 22619 12262 22619 12268 22620 12266 22620 12265 22620 12267 22621 12266 22621 12268 22621 12270 22622 12264 22622 12267 22622 12269 22623 12267 22623 12268 22623 12270 22624 12267 22624 12269 22624 12269 22625 12268 22625 12271 22625 12273 22626 12269 22626 12271 22626 12273 22627 12270 22627 12269 22627 12272 22628 12270 22628 12273 22628 12273 22629 12271 22629 12274 22629 12275 22630 12273 22630 12274 22630 12275 22631 12272 22631 12273 22631 12276 22632 12272 22632 12275 22632 12275 22633 12274 22633 12277 22633 12278 22634 12275 22634 12277 22634 12278 22635 12276 22635 12275 22635 12279 22636 12276 22636 12278 22636 12278 22637 12277 22637 12280 22637 12279 22638 12278 22638 12281 22638 12281 22639 12278 22639 12280 22639 12283 22640 12279 22640 12281 22640 12282 22641 12281 22641 12280 22641 12284 22642 12281 22642 12282 22642 12284 22643 12283 22643 12281 22643 12284 22644 12282 22644 12285 22644 12286 22645 12284 22645 12285 22645 12286 22646 12283 22646 12284 22646 12288 22647 12285 22647 12287 22647 12288 22648 12286 22648 12285 22648 12289 22649 12288 22649 12287 22649 12291 22650 12288 22650 12289 22650 12291 22651 12286 22651 12288 22651 12290 22652 12289 22652 12287 22652 12289 22653 12290 22653 12292 22653 12293 22654 12291 22654 12289 22654 12293 22655 12289 22655 12292 22655 12295 22656 12291 22656 12293 22656 12293 22657 12292 22657 12294 22657 12297 22658 12294 22658 12296 22658 12297 22659 12293 22659 12294 22659 12295 22660 12293 22660 12297 22660 12298 22661 12297 22661 12296 22661 12300 22662 12297 22662 12298 22662 12300 22663 12295 22663 12297 22663 12299 22664 12295 22664 12300 22664 12301 22665 12300 22665 12298 22665 12302 22666 12300 22666 12301 22666 12303 22667 12302 22667 12301 22667 12299 22668 12300 22668 12302 22668 12305 22669 12303 22669 12304 22669 12305 22670 12302 22670 12303 22670 12299 22671 12302 22671 12305 22671 12307 22672 12299 22672 12305 22672 12305 22673 12304 22673 12306 22673 12308 22674 12305 22674 12306 22674 12307 22675 12305 22675 12308 22675 12309 22676 12307 22676 12308 22676 12311 22677 12308 22677 12310 22677 12309 22678 12308 22678 12311 22678 12312 22679 12311 22679 12310 22679 12313 22680 12309 22680 12311 22680 12315 22681 12312 22681 12314 22681 12315 22682 12311 22682 12312 22682 12315 22683 12313 22683 12311 22683 12315 22684 12314 22684 12316 22684 12317 22685 12315 22685 12316 22685 12318 22686 12315 22686 12317 22686 12318 22687 12313 22687 12315 22687 12320 22688 12317 22688 12319 22688 12320 22689 12318 22689 12317 22689 12321 22690 12320 22690 12319 22690 12322 22691 12313 22691 12318 22691 12322 22692 12318 22692 12320 22692 12323 22693 12321 22693 12319 22693 12323 22694 12320 22694 12321 22694 12323 22695 12322 22695 12320 22695 12323 22696 12319 22696 12324 22696 12326 22697 12324 22697 12325 22697 12326 22698 12323 22698 12324 22698 12322 22699 12323 22699 12326 22699 12328 22700 12326 22700 12325 22700 12327 22701 12322 22701 12326 22701 12329 22702 12326 22702 12328 22702 12329 22703 12327 22703 12326 22703 12330 22704 12329 22704 12328 22704 12331 22705 12329 22705 12330 22705 12332 22706 12329 22706 12331 22706 12332 22707 12327 22707 12329 22707 12334 22708 12331 22708 12333 22708 12334 22709 12332 22709 12331 22709 12335 22710 12334 22710 12333 22710 12243 22711 12332 22711 12334 22711 12336 22712 12334 22712 12335 22712 12241 22713 12334 22713 12336 22713 12243 22714 12334 22714 12241 22714 12336 22715 12240 22715 12241 22715 12290 22716 12287 22716 12337 22716 12337 22717 12287 22717 12383 22717 12287 22718 12285 22718 12383 22718 12383 22719 12285 22719 12338 22719 12338 22720 12285 22720 12339 22720 12285 22721 12282 22721 12339 22721 12282 22722 12280 22722 12339 22722 12339 22723 12280 22723 12340 22723 12340 22724 12277 22724 12341 22724 12280 22725 12277 22725 12340 22725 12341 22726 12277 22726 12342 22726 12277 22727 12274 22727 12342 22727 12342 22728 12274 22728 12343 22728 12343 22729 12274 22729 12344 22729 12274 22730 12271 22730 12344 22730 12344 22731 12271 22731 12345 22731 12271 22732 12268 22732 12345 22732 12345 22733 12268 22733 12346 22733 12346 22734 12265 22734 12347 22734 12268 22735 12265 22735 12346 22735 12347 22736 12265 22736 12398 22736 12265 22737 12263 22737 12398 22737 12398 22738 12263 22738 12348 22738 12263 22739 12261 22739 12348 22739 12261 22740 12258 22740 12348 22740 12348 22741 12258 22741 12349 22741 12349 22742 12258 22742 12350 22742 12258 22743 12257 22743 12350 22743 12350 22744 12257 22744 12351 22744 12257 22745 12254 22745 12351 22745 12351 22746 12254 22746 12404 22746 12254 22747 12253 22747 12404 22747 12404 22748 12253 22748 12352 22748 12253 22749 12251 22749 12352 22749 12352 22750 12251 22750 12353 22750 12251 22751 12249 22751 12353 22751 12353 22752 12246 22752 12354 22752 12249 22753 12246 22753 12353 22753 12354 22754 12246 22754 12355 22754 12246 22755 12244 22755 12355 22755 12355 22756 12244 22756 12356 22756 12244 22757 12240 22757 12356 22757 12356 22758 12240 22758 12357 22758 12240 22759 12336 22759 12357 22759 12336 22760 12335 22760 12357 22760 12357 22761 12335 22761 12358 22761 12335 22762 12333 22762 12358 22762 12358 22763 12333 22763 12359 22763 12333 22764 12331 22764 12359 22764 12359 22765 12331 22765 12360 22765 12331 22766 12330 22766 12360 22766 12330 22767 12328 22767 12360 22767 12360 22768 12328 22768 12361 22768 12328 22769 12325 22769 12361 22769 12361 22770 12325 22770 12362 22770 12325 22771 12324 22771 12362 22771 12362 22772 12324 22772 12363 22772 12363 22773 12324 22773 12364 22773 12324 22774 12319 22774 12364 22774 12364 22775 12319 22775 12365 22775 12365 22776 12319 22776 12366 22776 12319 22777 12317 22777 12366 22777 12317 22778 12316 22778 12366 22778 12366 22779 12316 22779 12367 22779 12316 22780 12314 22780 12367 22780 12367 22781 12314 22781 12368 22781 12314 22782 12312 22782 12368 22782 12368 22783 12312 22783 12369 22783 12312 22784 12310 22784 12369 22784 12369 22785 12310 22785 12370 22785 12310 22786 12308 22786 12370 22786 12370 22787 12308 22787 12371 22787 12308 22788 12306 22788 12371 22788 12371 22789 12306 22789 12372 22789 12306 22790 12304 22790 12372 22790 12372 22791 12304 22791 12373 22791 12304 22792 12303 22792 12373 22792 12373 22793 12301 22793 12374 22793 12303 22794 12301 22794 12373 22794 12301 22795 12298 22795 12374 22795 12374 22796 12298 22796 12375 22796 12375 22797 12296 22797 12376 22797 12298 22798 12296 22798 12375 22798 12376 22799 12296 22799 12377 22799 12296 22800 12294 22800 12377 22800 12377 22801 12294 22801 12378 22801 12294 22802 12292 22802 12378 22802 12378 22803 12292 22803 12379 22803 12292 22804 12290 22804 12379 22804 12379 22805 12290 22805 12337 22805 12252 22806 12861 22806 12867 22806 12252 22807 12256 22807 12861 22807 12252 22808 12867 22808 12877 22808 12256 22809 12856 22809 12861 22809 12260 22810 12856 22810 12256 22810 12260 22811 12850 22811 12856 22811 12245 22812 12252 22812 12877 22812 12260 22813 12845 22813 12850 22813 12245 22814 12877 22814 12879 22814 12264 22815 12845 22815 12260 22815 12243 22816 12245 22816 12879 22816 12243 22817 12879 22817 12886 22817 12270 22818 12845 22818 12264 22818 12270 22819 12993 22819 12845 22819 12243 22820 12886 22820 12890 22820 12332 22821 12243 22821 12890 22821 12272 22822 12993 22822 12270 22822 12332 22823 12890 22823 12897 22823 12327 22824 12332 22824 12897 22824 12272 22825 12986 22825 12993 22825 12276 22826 12986 22826 12272 22826 12327 22827 12897 22827 12903 22827 12279 22828 12986 22828 12276 22828 12903 22829 12322 22829 12327 22829 12978 22830 12986 22830 12279 22830 12911 22831 12322 22831 12903 22831 12972 22832 12978 22832 12279 22832 12972 22833 12279 22833 12283 22833 12972 22834 12283 22834 12286 22834 12919 22835 12322 22835 12911 22835 12919 22836 12313 22836 12322 22836 12966 22837 12972 22837 12286 22837 12966 22838 12286 22838 12291 22838 12961 22839 12966 22839 12291 22839 12953 22840 12291 22840 12295 22840 12953 22841 12961 22841 12291 22841 12927 22842 12313 22842 12919 22842 12927 22843 12309 22843 12313 22843 12932 22844 12309 22844 12927 22844 12953 22845 12295 22845 12299 22845 12932 22846 12307 22846 12309 22846 12947 22847 12953 22847 12299 22847 12941 22848 12307 22848 12932 22848 12941 22849 12299 22849 12307 22849 12941 22850 12947 22850 12299 22850 12380 22851 12381 22851 12337 22851 12382 22852 12381 22852 12380 22852 12383 22853 12380 22853 12337 22853 12384 22854 12380 22854 12383 22854 12384 22855 12382 22855 12380 22855 12385 22856 12382 22856 12384 22856 12338 22857 12384 22857 12383 22857 12386 22858 12338 22858 12339 22858 12386 22859 12384 22859 12338 22859 12386 22860 12385 22860 12384 22860 12387 22861 12386 22861 12339 22861 12387 22862 12339 22862 12340 22862 12388 22863 12387 22863 12340 22863 12388 22864 12386 22864 12387 22864 12389 22865 12385 22865 12386 22865 12389 22866 12386 22866 12388 22866 12390 22867 12389 22867 12388 22867 12341 22868 12388 22868 12340 22868 12390 22869 12388 22869 12341 22869 12342 22870 12390 22870 12341 22870 12391 22871 12390 22871 12342 22871 12389 22872 12390 22872 12391 22872 12343 22873 12391 22873 12342 22873 12393 22874 12391 22874 12343 22874 12392 22875 12389 22875 12391 22875 12392 22876 12391 22876 12393 22876 12393 22877 12343 22877 12344 22877 12345 22878 12393 22878 12344 22878 12394 22879 12393 22879 12345 22879 12394 22880 12392 22880 12393 22880 12395 22881 12394 22881 12345 22881 12395 22882 12345 22882 12346 22882 12396 22883 12395 22883 12346 22883 12396 22884 12346 22884 12347 22884 12397 22885 12394 22885 12395 22885 12398 22886 12396 22886 12347 22886 12397 22887 12396 22887 12398 22887 12397 22888 12395 22888 12396 22888 12399 22889 12397 22889 12398 22889 12400 22890 12398 22890 12348 22890 12400 22891 12399 22891 12398 22891 12401 22892 12399 22892 12400 22892 12401 22893 12348 22893 12349 22893 12401 22894 12400 22894 12348 22894 12402 22895 12399 22895 12401 22895 12403 22896 12401 22896 12349 22896 12402 22897 12401 22897 12403 22897 12403 22898 12349 22898 12350 22898 12351 22899 12403 22899 12350 22899 12405 22900 12402 22900 12403 22900 12405 22901 12351 22901 12404 22901 12405 22902 12403 22902 12351 22902 12406 22903 12405 22903 12404 22903 12406 22904 12404 22904 12352 22904 12408 22905 12405 22905 12406 22905 12407 22906 12352 22906 12353 22906 12407 22907 12406 22907 12352 22907 12408 22908 12406 22908 12407 22908 12354 22909 12407 22909 12353 22909 12409 22910 12407 22910 12354 22910 12409 22911 12354 22911 12355 22911 12408 22912 12407 22912 12409 22912 12409 22913 12355 22913 12356 22913 12410 22914 12356 22914 12357 22914 12411 22915 12408 22915 12409 22915 12410 22916 12409 22916 12356 22916 12411 22917 12409 22917 12410 22917 12412 22918 12410 22918 12357 22918 12358 22919 12412 22919 12357 22919 12411 22920 12410 22920 12412 22920 12413 22921 12411 22921 12412 22921 12414 22922 12358 22922 12359 22922 12414 22923 12412 22923 12358 22923 12413 22924 12412 22924 12414 22924 12360 22925 12414 22925 12359 22925 12415 22926 12414 22926 12360 22926 12413 22927 12414 22927 12415 22927 12416 22928 12360 22928 12361 22928 12416 22929 12415 22929 12360 22929 12362 22930 12416 22930 12361 22930 12417 22931 12416 22931 12362 22931 12417 22932 12415 22932 12416 22932 12418 22933 12415 22933 12417 22933 12417 22934 12362 22934 12363 22934 12417 22935 12363 22935 12364 22935 12418 22936 12417 22936 12419 22936 12419 22937 12417 22937 12364 22937 12365 22938 12419 22938 12364 22938 12420 22939 12419 22939 12365 22939 12420 22940 12418 22940 12419 22940 12421 22941 12418 22941 12420 22941 12420 22942 12365 22942 12366 22942 12422 22943 12420 22943 12366 22943 12421 22944 12420 22944 12422 22944 12367 22945 12422 22945 12366 22945 12423 22946 12421 22946 12422 22946 12423 22947 12422 22947 12367 22947 12425 22948 12367 22948 12368 22948 12424 22949 12421 22949 12423 22949 12425 22950 12423 22950 12367 22950 12424 22951 12423 22951 12425 22951 12369 22952 12425 22952 12368 22952 12424 22953 12425 22953 12369 22953 12426 22954 12369 22954 12370 22954 12424 22955 12369 22955 12426 22955 12371 22956 12426 22956 12370 22956 12427 22957 12424 22957 12426 22957 12428 22958 12424 22958 12427 22958 12427 22959 12426 22959 12371 22959 12428 22960 12371 22960 12372 22960 12428 22961 12427 22961 12371 22961 12373 22962 12428 22962 12372 22962 12429 22963 12428 22963 12373 22963 12430 22964 12428 22964 12429 22964 12374 22965 12429 22965 12373 22965 12431 22966 12429 22966 12374 22966 12430 22967 12429 22967 12431 22967 12375 22968 12431 22968 12374 22968 12376 22969 12431 22969 12375 22969 12432 22970 12430 22970 12431 22970 12433 22971 12376 22971 12377 22971 12433 22972 12431 22972 12376 22972 12432 22973 12431 22973 12433 22973 12378 22974 12433 22974 12377 22974 12381 22975 12378 22975 12379 22975 12433 22976 12378 22976 12381 22976 12381 22977 12379 22977 12337 22977 12432 22978 12433 22978 12381 22978 12432 22979 12381 22979 12382 22979 12415 22980 12418 22980 12625 22980 12418 22981 12617 22981 12625 22981 12415 22982 12625 22982 12630 22982 12421 22983 12608 22983 12617 22983 12421 22984 12617 22984 12418 22984 12413 22985 12415 22985 12630 22985 12413 22986 12630 22986 12639 22986 12411 22987 12413 22987 12639 22987 12421 22988 12601 22988 12608 22988 12408 22989 12411 22989 12639 22989 12424 22990 12601 22990 12421 22990 12408 22991 12639 22991 12649 22991 12424 22992 12593 22992 12601 22992 12424 22993 12584 22993 12593 22993 12408 22994 12649 22994 12659 22994 12428 22995 12584 22995 12424 22995 12405 22996 12408 22996 12659 22996 12428 22997 12576 22997 12584 22997 12666 22998 12405 22998 12659 22998 12402 22999 12405 22999 12666 22999 12430 23000 12576 23000 12428 23000 12671 23001 12402 23001 12666 23001 12671 23002 12399 23002 12402 23002 12568 23003 12576 23003 12430 23003 12568 23004 12430 23004 12432 23004 12680 23005 12399 23005 12671 23005 12680 23006 12397 23006 12399 23006 12561 23007 12568 23007 12432 23007 12561 23008 12432 23008 12382 23008 12680 23009 12394 23009 12397 23009 12555 23010 12561 23010 12382 23010 12526 23011 12394 23011 12680 23011 12526 23012 12392 23012 12394 23012 12555 23013 12382 23013 12385 23013 12548 23014 12555 23014 12385 23014 12533 23015 12392 23015 12526 23015 12541 23016 12548 23016 12385 23016 12541 23017 12385 23017 12389 23017 12533 23018 12389 23018 12392 23018 12541 23019 12389 23019 12533 23019 12434 23020 12435 23020 12436 23020 12434 23021 12436 23021 12437 23021 12438 23022 12434 23022 12437 23022 12438 23023 12437 23023 12439 23023 12440 23024 12438 23024 12439 23024 12440 23025 12439 23025 12441 23025 12442 23026 12440 23026 12441 23026 12442 23027 12441 23027 12443 23027 12444 23028 12442 23028 12443 23028 12444 23029 12443 23029 12445 23029 12446 23030 12444 23030 12445 23030 12446 23031 12445 23031 12447 23031 12448 23032 12446 23032 12447 23032 12448 23033 12447 23033 12449 23033 12450 23034 12448 23034 12449 23034 12450 23035 12449 23035 12451 23035 12452 23036 12450 23036 12451 23036 12452 23037 12451 23037 12453 23037 12454 23038 12452 23038 12453 23038 12454 23039 12453 23039 12455 23039 12456 23040 12454 23040 12455 23040 12456 23041 12455 23041 12457 23041 12458 23042 12456 23042 12457 23042 12458 23043 12457 23043 12459 23043 12460 23044 12458 23044 12459 23044 12461 23045 12459 23045 12462 23045 12461 23046 12460 23046 12459 23046 12461 23047 12462 23047 12463 23047 12464 23048 12461 23048 12463 23048 12464 23049 12463 23049 12465 23049 12466 23050 12464 23050 12465 23050 12466 23051 12465 23051 12467 23051 12466 23052 12467 23052 12468 23052 12469 23053 12466 23053 12468 23053 12469 23054 12468 23054 12470 23054 12471 23055 12469 23055 12470 23055 12471 23056 12470 23056 12472 23056 12473 23057 12471 23057 12472 23057 12473 23058 12472 23058 12474 23058 12475 23059 12473 23059 12474 23059 12475 23060 12474 23060 12435 23060 12434 23061 12475 23061 12435 23061 12476 23062 12477 23062 12478 23062 12479 23063 12476 23063 12478 23063 12479 23064 12478 23064 12480 23064 12481 23065 12479 23065 12480 23065 12481 23066 12480 23066 12482 23066 12483 23067 12481 23067 12482 23067 12483 23068 12482 23068 12484 23068 12485 23069 12483 23069 12484 23069 12485 23070 12484 23070 12486 23070 12487 23071 12485 23071 12486 23071 12487 23072 12486 23072 12488 23072 12489 23073 12487 23073 12488 23073 12489 23074 12488 23074 12490 23074 12491 23075 12489 23075 12490 23075 12491 23076 12490 23076 12492 23076 12491 23077 12492 23077 12493 23077 12494 23078 12491 23078 12493 23078 12494 23079 12493 23079 12495 23079 12496 23080 12494 23080 12495 23080 12496 23081 12495 23081 12497 23081 12498 23082 12496 23082 12497 23082 12498 23083 12497 23083 12499 23083 12500 23084 12498 23084 12499 23084 12500 23085 12499 23085 12501 23085 12502 23086 12500 23086 12501 23086 12502 23087 12501 23087 12503 23087 12504 23088 12502 23088 12503 23088 12504 23089 12503 23089 12505 23089 12506 23090 12504 23090 12505 23090 12506 23091 12505 23091 12507 23091 12508 23092 12506 23092 12507 23092 12508 23093 12507 23093 12509 23093 12510 23094 12508 23094 12509 23094 12510 23095 12509 23095 12511 23095 12512 23096 12510 23096 12511 23096 12513 23097 12511 23097 12514 23097 12513 23098 12512 23098 12511 23098 12515 23099 12513 23099 12514 23099 12515 23100 12514 23100 12516 23100 12517 23101 12516 23101 12518 23101 12517 23102 12515 23102 12516 23102 12517 23103 12518 23103 12477 23103 12476 23104 12517 23104 12477 23104 12520 23105 12683 23105 12519 23105 12522 23106 12682 23106 12520 23106 12521 23107 12520 23107 12519 23107 12522 23108 12680 23108 12682 23108 12523 23109 12520 23109 12521 23109 12522 23110 12520 23110 12523 23110 12526 23111 12680 23111 12522 23111 12525 23112 12522 23112 12523 23112 12524 23113 12523 23113 12521 23113 12526 23114 12522 23114 12525 23114 12527 23115 12523 23115 12524 23115 12525 23116 12523 23116 12527 23116 12526 23117 12525 23117 12527 23117 12528 23118 12527 23118 12524 23118 12529 23119 12527 23119 12528 23119 12530 23120 12527 23120 12529 23120 12530 23121 12526 23121 12527 23121 12531 23122 12529 23122 12528 23122 12531 23123 12530 23123 12529 23123 12532 23124 12531 23124 12528 23124 12533 23125 12526 23125 12530 23125 12533 23126 12530 23126 12531 23126 12534 23127 12531 23127 12532 23127 12535 23128 12531 23128 12534 23128 12535 23129 12533 23129 12531 23129 12536 23130 12534 23130 12532 23130 12537 23131 12534 23131 12536 23131 12535 23132 12534 23132 12537 23132 12538 23133 12533 23133 12535 23133 12539 23134 12535 23134 12537 23134 12538 23135 12535 23135 12539 23135 12540 23136 12537 23136 12536 23136 12539 23137 12537 23137 12540 23137 12541 23138 12533 23138 12538 23138 12543 23139 12540 23139 12542 23139 12543 23140 12539 23140 12540 23140 12544 23141 12539 23141 12543 23141 12544 23142 12538 23142 12539 23142 12541 23143 12538 23143 12544 23143 12546 23144 12542 23144 12545 23144 12546 23145 12543 23145 12542 23145 12546 23146 12544 23146 12543 23146 12547 23147 12544 23147 12546 23147 12547 23148 12541 23148 12544 23148 12548 23149 12541 23149 12547 23149 12549 23150 12546 23150 12545 23150 12550 23151 12547 23151 12546 23151 12551 23152 12546 23152 12549 23152 12550 23153 12546 23153 12551 23153 12548 23154 12547 23154 12550 23154 12553 23155 12549 23155 12552 23155 12553 23156 12551 23156 12549 23156 12553 23157 12550 23157 12551 23157 12554 23158 12550 23158 12553 23158 12555 23159 12550 23159 12554 23159 12555 23160 12548 23160 12550 23160 12556 23161 12553 23161 12552 23161 12556 23162 12554 23162 12553 23162 12556 23163 12552 23163 12557 23163 12558 23164 12554 23164 12556 23164 12558 23165 12555 23165 12554 23165 12559 23166 12556 23166 12557 23166 12559 23167 12558 23167 12556 23167 12559 23168 12557 23168 12560 23168 12561 23169 12555 23169 12558 23169 12561 23170 12558 23170 12559 23170 12562 23171 12559 23171 12560 23171 12562 23172 12561 23172 12559 23172 12564 23173 12561 23173 12562 23173 12563 23174 12562 23174 12560 23174 12565 23175 12562 23175 12563 23175 12564 23176 12562 23176 12565 23176 12567 23177 12563 23177 12566 23177 12567 23178 12565 23178 12563 23178 12568 23179 12561 23179 12564 23179 12567 23180 12564 23180 12565 23180 12569 23181 12564 23181 12567 23181 12570 23182 12567 23182 12566 23182 12571 23183 12567 23183 12570 23183 12568 23184 12564 23184 12569 23184 12569 23185 12567 23185 12571 23185 12572 23186 12571 23186 12570 23186 12573 23187 12571 23187 12572 23187 12573 23188 12569 23188 12571 23188 12575 23189 12572 23189 12574 23189 12576 23190 12568 23190 12569 23190 12576 23191 12569 23191 12573 23191 12575 23192 12573 23192 12572 23192 12579 23193 12574 23193 12577 23193 12578 23194 12576 23194 12573 23194 12579 23195 12575 23195 12574 23195 12579 23196 12573 23196 12575 23196 12578 23197 12573 23197 12579 23197 12580 23198 12579 23198 12577 23198 12581 23199 12579 23199 12580 23199 12578 23200 12579 23200 12581 23200 12583 23201 12580 23201 12582 23201 12584 23202 12578 23202 12581 23202 12584 23203 12576 23203 12578 23203 12583 23204 12581 23204 12580 23204 12585 23205 12581 23205 12583 23205 12586 23206 12583 23206 12582 23206 12587 23207 12583 23207 12586 23207 12584 23208 12581 23208 12585 23208 12587 23209 12585 23209 12583 23209 12587 23210 12586 23210 12588 23210 12589 23211 12584 23211 12585 23211 12589 23212 12587 23212 12590 23212 12589 23213 12585 23213 12587 23213 12590 23214 12587 23214 12588 23214 12590 23215 12588 23215 12591 23215 12593 23216 12584 23216 12589 23216 12592 23217 12589 23217 12590 23217 12593 23218 12589 23218 12592 23218 12594 23219 12590 23219 12591 23219 12592 23220 12590 23220 12594 23220 12594 23221 12591 23221 12595 23221 12596 23222 12593 23222 12592 23222 12596 23223 12592 23223 12594 23223 12597 23224 12594 23224 12595 23224 12598 23225 12596 23225 12594 23225 12599 23226 12594 23226 12597 23226 12599 23227 12598 23227 12594 23227 12600 23228 12599 23228 12597 23228 12601 23229 12593 23229 12596 23229 12602 23230 12596 23230 12598 23230 12601 23231 12596 23231 12602 23231 12603 23232 12599 23232 12600 23232 12603 23233 12598 23233 12599 23233 12604 23234 12598 23234 12603 23234 12604 23235 12602 23235 12598 23235 12601 23236 12602 23236 12604 23236 12606 23237 12603 23237 12605 23237 12604 23238 12603 23238 12606 23238 12601 23239 12604 23239 12606 23239 12608 23240 12601 23240 12606 23240 12607 23241 12606 23241 12605 23241 12609 23242 12606 23242 12607 23242 12609 23243 12608 23243 12606 23243 12611 23244 12609 23244 12607 23244 12611 23245 12607 23245 12610 23245 12611 23246 12608 23246 12609 23246 12613 23247 12608 23247 12611 23247 12614 23248 12610 23248 12612 23248 12614 23249 12611 23249 12610 23249 12613 23250 12611 23250 12614 23250 12615 23251 12614 23251 12612 23251 12617 23252 12608 23252 12613 23252 12615 23253 12612 23253 12616 23253 12618 23254 12614 23254 12615 23254 12618 23255 12613 23255 12614 23255 12617 23256 12613 23256 12618 23256 12620 23257 12616 23257 12619 23257 12620 23258 12615 23258 12616 23258 12620 23259 12618 23259 12615 23259 12622 23260 12619 23260 12621 23260 12622 23261 12620 23261 12619 23261 12622 23262 12618 23262 12620 23262 12623 23263 12618 23263 12622 23263 12624 23264 12622 23264 12621 23264 12623 23265 12617 23265 12618 23265 12625 23266 12617 23266 12623 23266 12626 23267 12622 23267 12624 23267 12626 23268 12623 23268 12622 23268 12626 23269 12624 23269 12627 23269 12625 23270 12623 23270 12626 23270 12629 23271 12626 23271 12627 23271 12625 23272 12626 23272 12629 23272 12629 23273 12627 23273 12628 23273 12630 23274 12625 23274 12629 23274 12631 23275 12629 23275 12628 23275 12632 23276 12629 23276 12631 23276 12630 23277 12629 23277 12632 23277 12633 23278 12631 23278 12628 23278 12634 23279 12631 23279 12633 23279 12634 23280 12632 23280 12631 23280 12635 23281 12634 23281 12633 23281 12636 23282 12630 23282 12632 23282 12637 23283 12632 23283 12634 23283 12636 23284 12632 23284 12637 23284 12637 23285 12634 23285 12635 23285 12637 23286 12635 23286 12638 23286 12639 23287 12630 23287 12636 23287 12640 23288 12636 23288 12637 23288 12640 23289 12639 23289 12636 23289 12641 23290 12637 23290 12638 23290 12640 23291 12637 23291 12641 23291 12641 23292 12638 23292 12642 23292 12643 23293 12639 23293 12640 23293 12643 23294 12640 23294 12641 23294 12644 23295 12641 23295 12642 23295 12645 23296 12641 23296 12644 23296 12645 23297 12643 23297 12641 23297 12647 23298 12643 23298 12645 23298 12646 23299 12645 23299 12644 23299 12648 23300 12645 23300 12646 23300 12649 23301 12639 23301 12643 23301 12647 23302 12645 23302 12648 23302 12649 23303 12643 23303 12647 23303 12650 23304 12648 23304 12646 23304 12651 23305 12648 23305 12650 23305 12651 23306 12647 23306 12648 23306 12653 23307 12650 23307 12652 23307 12649 23308 12647 23308 12651 23308 12651 23309 12650 23309 12653 23309 12654 23310 12651 23310 12653 23310 12649 23311 12651 23311 12654 23311 12653 23312 12652 23312 12655 23312 12657 23313 12653 23313 12655 23313 12657 23314 12654 23314 12653 23314 12656 23315 12657 23315 12655 23315 12658 23316 12654 23316 12657 23316 12659 23317 12649 23317 12654 23317 12659 23318 12654 23318 12658 23318 12658 23319 12657 23319 12656 23319 12661 23320 12658 23320 12656 23320 12661 23321 12656 23321 12660 23321 12663 23322 12658 23322 12661 23322 12662 23323 12661 23323 12660 23323 12663 23324 12659 23324 12658 23324 12663 23325 12661 23325 12664 23325 12664 23326 12661 23326 12662 23326 12664 23327 12662 23327 12665 23327 12666 23328 12659 23328 12663 23328 12667 23329 12664 23329 12665 23329 12669 23330 12664 23330 12667 23330 12669 23331 12663 23331 12664 23331 12667 23332 12665 23332 12668 23332 12666 23333 12663 23333 12669 23333 12670 23334 12667 23334 12668 23334 12670 23335 12669 23335 12667 23335 12671 23336 12666 23336 12669 23336 12672 23337 12670 23337 12668 23337 12673 23338 12670 23338 12672 23338 12674 23339 12670 23339 12673 23339 12674 23340 12669 23340 12670 23340 12671 23341 12669 23341 12674 23341 12675 23342 12673 23342 12672 23342 12676 23343 12673 23343 12675 23343 12674 23344 12673 23344 12676 23344 12677 23345 12676 23345 12675 23345 12679 23346 12674 23346 12676 23346 12678 23347 12674 23347 12679 23347 12678 23348 12671 23348 12674 23348 12679 23349 12676 23349 12677 23349 12680 23350 12671 23350 12678 23350 12681 23351 12679 23351 12677 23351 12682 23352 12678 23352 12679 23352 12683 23353 12679 23353 12681 23353 12680 23354 12678 23354 12682 23354 12682 23355 12679 23355 12683 23355 12681 23356 12519 23356 12683 23356 12682 23357 12683 23357 12520 23357 12521 23358 12684 23358 12685 23358 12521 23359 12519 23359 12684 23359 12521 23360 12685 23360 12686 23360 12524 23361 12521 23361 12686 23361 12524 23362 12686 23362 12835 23362 12524 23363 12835 23363 12687 23363 12528 23364 12524 23364 12687 23364 12528 23365 12687 23365 12688 23365 12532 23366 12528 23366 12688 23366 12532 23367 12688 23367 12689 23367 12536 23368 12689 23368 12690 23368 12536 23369 12532 23369 12689 23369 12540 23370 12690 23370 12691 23370 12540 23371 12536 23371 12690 23371 12542 23372 12691 23372 12692 23372 12542 23373 12540 23373 12691 23373 12542 23374 12692 23374 12693 23374 12545 23375 12542 23375 12693 23375 12549 23376 12693 23376 12694 23376 12549 23377 12545 23377 12693 23377 12552 23378 12549 23378 12694 23378 12552 23379 12694 23379 12695 23379 12552 23380 12695 23380 12818 23380 12557 23381 12552 23381 12818 23381 12557 23382 12818 23382 12816 23382 12560 23383 12557 23383 12816 23383 12560 23384 12816 23384 12696 23384 12563 23385 12696 23385 12810 23385 12563 23386 12560 23386 12696 23386 12566 23387 12563 23387 12810 23387 12566 23388 12810 23388 12697 23388 12570 23389 12566 23389 12697 23389 12570 23390 12697 23390 12698 23390 12572 23391 12570 23391 12698 23391 12572 23392 12698 23392 12699 23392 12574 23393 12572 23393 12699 23393 12574 23394 12699 23394 12700 23394 12577 23395 12574 23395 12700 23395 12577 23396 12700 23396 12701 23396 12580 23397 12577 23397 12701 23397 12580 23398 12701 23398 12702 23398 12582 23399 12580 23399 12702 23399 12582 23400 12702 23400 12703 23400 12586 23401 12582 23401 12703 23401 12586 23402 12703 23402 12797 23402 12588 23403 12586 23403 12797 23403 12588 23404 12797 23404 12704 23404 12591 23405 12588 23405 12704 23405 12591 23406 12704 23406 12705 23406 12595 23407 12591 23407 12705 23407 12595 23408 12705 23408 12791 23408 12597 23409 12595 23409 12791 23409 12597 23410 12791 23410 12706 23410 12600 23411 12597 23411 12706 23411 12603 23412 12600 23412 12706 23412 12603 23413 12706 23413 12707 23413 12605 23414 12603 23414 12707 23414 12605 23415 12707 23415 12708 23415 12607 23416 12605 23416 12708 23416 12610 23417 12607 23417 12708 23417 12610 23418 12708 23418 12709 23418 12612 23419 12610 23419 12709 23419 12612 23420 12709 23420 12710 23420 12612 23421 12710 23421 12775 23421 12616 23422 12612 23422 12775 23422 12616 23423 12775 23423 12711 23423 12619 23424 12616 23424 12711 23424 12619 23425 12711 23425 12712 23425 12621 23426 12619 23426 12712 23426 12621 23427 12712 23427 12769 23427 12624 23428 12621 23428 12769 23428 12627 23429 12769 23429 12713 23429 12627 23430 12624 23430 12769 23430 12628 23431 12713 23431 12714 23431 12628 23432 12627 23432 12713 23432 12628 23433 12714 23433 12764 23433 12633 23434 12628 23434 12764 23434 12633 23435 12764 23435 12715 23435 12635 23436 12633 23436 12715 23436 12635 23437 12715 23437 12716 23437 12638 23438 12635 23438 12716 23438 12642 23439 12638 23439 12716 23439 12642 23440 12716 23440 12717 23440 12644 23441 12642 23441 12717 23441 12644 23442 12717 23442 12718 23442 12646 23443 12718 23443 12719 23443 12646 23444 12644 23444 12718 23444 12650 23445 12646 23445 12719 23445 12650 23446 12719 23446 12720 23446 12652 23447 12650 23447 12720 23447 12652 23448 12720 23448 12721 23448 12655 23449 12652 23449 12721 23449 12655 23450 12721 23450 12722 23450 12656 23451 12655 23451 12722 23451 12660 23452 12722 23452 12723 23452 12660 23453 12656 23453 12722 23453 12660 23454 12723 23454 12724 23454 12662 23455 12660 23455 12724 23455 12665 23456 12724 23456 12725 23456 12665 23457 12662 23457 12724 23457 12665 23458 12725 23458 12726 23458 12668 23459 12665 23459 12726 23459 12668 23460 12726 23460 12727 23460 12672 23461 12727 23461 12728 23461 12672 23462 12668 23462 12727 23462 12675 23463 12672 23463 12728 23463 12677 23464 12728 23464 12729 23464 12677 23465 12675 23465 12728 23465 12677 23466 12729 23466 12730 23466 12681 23467 12730 23467 12731 23467 12681 23468 12677 23468 12730 23468 12519 23469 12731 23469 12684 23469 12519 23470 12681 23470 12731 23470 12731 23471 12732 23471 12684 23471 12733 23472 12732 23472 12731 23472 12733 23473 12734 23473 12732 23473 12733 23474 12735 23474 12734 23474 12730 23475 12733 23475 12731 23475 12736 23476 12733 23476 12730 23476 12735 23477 12733 23477 12736 23477 12736 23478 12730 23478 12729 23478 12737 23479 12735 23479 12736 23479 12728 23480 12736 23480 12729 23480 12738 23481 12736 23481 12728 23481 12737 23482 12736 23482 12738 23482 12738 23483 12728 23483 12727 23483 12740 23484 12737 23484 12738 23484 12739 23485 12738 23485 12727 23485 12740 23486 12738 23486 12739 23486 12739 23487 12727 23487 12726 23487 12743 23488 12737 23488 12740 23488 12741 23489 12740 23489 12739 23489 12725 23490 12739 23490 12726 23490 12742 23491 12739 23491 12725 23491 12741 23492 12739 23492 12742 23492 12743 23493 12740 23493 12741 23493 12742 23494 12725 23494 12724 23494 12744 23495 12742 23495 12724 23495 12744 23496 12741 23496 12742 23496 12743 23497 12741 23497 12744 23497 12723 23498 12744 23498 12724 23498 12745 23499 12744 23499 12723 23499 12745 23500 12743 23500 12744 23500 12746 23501 12743 23501 12745 23501 12747 23502 12723 23502 12722 23502 12747 23503 12745 23503 12723 23503 12748 23504 12746 23504 12745 23504 12748 23505 12745 23505 12747 23505 12749 23506 12747 23506 12722 23506 12749 23507 12722 23507 12721 23507 12749 23508 12748 23508 12747 23508 12750 23509 12748 23509 12749 23509 12720 23510 12749 23510 12721 23510 12751 23511 12749 23511 12720 23511 12752 23512 12746 23512 12748 23512 12751 23513 12750 23513 12749 23513 12751 23514 12720 23514 12719 23514 12752 23515 12748 23515 12750 23515 12752 23516 12750 23516 12751 23516 12753 23517 12751 23517 12719 23517 12753 23518 12752 23518 12751 23518 12754 23519 12752 23519 12753 23519 12718 23520 12753 23520 12719 23520 12755 23521 12753 23521 12718 23521 12755 23522 12754 23522 12753 23522 12756 23523 12752 23523 12754 23523 12717 23524 12755 23524 12718 23524 12757 23525 12755 23525 12717 23525 12758 23526 12755 23526 12757 23526 12758 23527 12754 23527 12755 23527 12756 23528 12754 23528 12758 23528 12716 23529 12757 23529 12717 23529 12759 23530 12756 23530 12758 23530 12760 23531 12758 23531 12757 23531 12759 23532 12758 23532 12760 23532 12760 23533 12757 23533 12716 23533 12761 23534 12716 23534 12715 23534 12761 23535 12760 23535 12716 23535 12762 23536 12756 23536 12759 23536 12763 23537 12759 23537 12760 23537 12762 23538 12759 23538 12763 23538 12763 23539 12760 23539 12761 23539 12764 23540 12761 23540 12715 23540 12765 23541 12761 23541 12764 23541 12765 23542 12763 23542 12761 23542 12714 23543 12765 23543 12764 23543 12766 23544 12765 23544 12714 23544 12766 23545 12763 23545 12765 23545 12767 23546 12763 23546 12766 23546 12767 23547 12762 23547 12763 23547 12768 23548 12767 23548 12766 23548 12713 23549 12766 23549 12714 23549 12768 23550 12766 23550 12713 23550 12770 23551 12713 23551 12769 23551 12770 23552 12768 23552 12713 23552 12771 23553 12768 23553 12770 23553 12772 23554 12769 23554 12712 23554 12771 23555 12767 23555 12768 23555 12772 23556 12770 23556 12769 23556 12771 23557 12770 23557 12772 23557 12778 23558 12767 23558 12771 23558 12711 23559 12772 23559 12712 23559 12773 23560 12772 23560 12711 23560 12774 23561 12771 23561 12772 23561 12774 23562 12772 23562 12773 23562 12778 23563 12771 23563 12774 23563 12775 23564 12773 23564 12711 23564 12778 23565 12774 23565 12776 23565 12773 23566 12775 23566 12777 23566 12776 23567 12774 23567 12773 23567 12777 23568 12775 23568 12710 23568 12777 23569 12776 23569 12773 23569 12779 23570 12778 23570 12776 23570 12780 23571 12710 23571 12709 23571 12780 23572 12777 23572 12710 23572 12779 23573 12776 23573 12777 23573 12779 23574 12777 23574 12780 23574 12781 23575 12778 23575 12779 23575 12782 23576 12779 23576 12780 23576 12708 23577 12780 23577 12709 23577 12783 23578 12780 23578 12708 23578 12781 23579 12779 23579 12782 23579 12783 23580 12782 23580 12780 23580 12784 23581 12708 23581 12707 23581 12784 23582 12783 23582 12708 23582 12784 23583 12782 23583 12783 23583 12785 23584 12781 23584 12782 23584 12785 23585 12782 23585 12784 23585 12786 23586 12784 23586 12707 23586 12786 23587 12707 23587 12706 23587 12787 23588 12784 23588 12786 23588 12787 23589 12785 23589 12784 23589 12788 23590 12786 23590 12706 23590 12787 23591 12786 23591 12788 23591 12789 23592 12785 23592 12787 23592 12790 23593 12785 23593 12789 23593 12790 23594 12781 23594 12785 23594 12789 23595 12787 23595 12788 23595 12791 23596 12788 23596 12706 23596 12792 23597 12788 23597 12791 23597 12792 23598 12789 23598 12788 23598 12793 23599 12789 23599 12792 23599 12792 23600 12791 23600 12705 23600 12794 23601 12789 23601 12793 23601 12794 23602 12790 23602 12789 23602 12793 23603 12792 23603 12705 23603 12795 23604 12793 23604 12705 23604 12795 23605 12705 23605 12704 23605 12796 23606 12793 23606 12795 23606 12796 23607 12794 23607 12793 23607 12797 23608 12795 23608 12704 23608 12796 23609 12795 23609 12797 23609 12798 23610 12794 23610 12796 23610 12799 23611 12796 23611 12797 23611 12800 23612 12797 23612 12703 23612 12799 23613 12798 23613 12796 23613 12800 23614 12799 23614 12797 23614 12801 23615 12799 23615 12800 23615 12702 23616 12800 23616 12703 23616 12798 23617 12799 23617 12801 23617 12801 23618 12800 23618 12702 23618 12802 23619 12702 23619 12701 23619 12803 23620 12798 23620 12801 23620 12802 23621 12801 23621 12702 23621 12804 23622 12801 23622 12802 23622 12804 23623 12803 23623 12801 23623 12700 23624 12802 23624 12701 23624 12804 23625 12802 23625 12700 23625 12805 23626 12700 23626 12699 23626 12806 23627 12803 23627 12804 23627 12805 23628 12804 23628 12700 23628 12808 23629 12803 23629 12806 23629 12806 23630 12804 23630 12805 23630 12698 23631 12805 23631 12699 23631 12807 23632 12805 23632 12698 23632 12809 23633 12806 23633 12805 23633 12808 23634 12806 23634 12809 23634 12809 23635 12805 23635 12807 23635 12697 23636 12807 23636 12698 23636 12810 23637 12807 23637 12697 23637 12811 23638 12807 23638 12810 23638 12811 23639 12809 23639 12807 23639 12808 23640 12809 23640 12811 23640 12812 23641 12811 23641 12810 23641 12812 23642 12808 23642 12811 23642 12813 23643 12810 23643 12696 23643 12812 23644 12810 23644 12813 23644 12814 23645 12808 23645 12812 23645 12816 23646 12813 23646 12696 23646 12814 23647 12812 23647 12815 23647 12816 23648 12812 23648 12813 23648 12815 23649 12812 23649 12816 23649 12817 23650 12814 23650 12815 23650 12819 23651 12815 23651 12816 23651 12819 23652 12816 23652 12818 23652 12817 23653 12815 23653 12819 23653 12820 23654 12819 23654 12818 23654 12820 23655 12817 23655 12819 23655 12820 23656 12818 23656 12695 23656 12694 23657 12820 23657 12695 23657 12821 23658 12820 23658 12694 23658 12822 23659 12820 23659 12821 23659 12822 23660 12817 23660 12820 23660 12823 23661 12817 23661 12822 23661 12823 23662 12822 23662 12821 23662 12821 23663 12694 23663 12693 23663 12824 23664 12821 23664 12693 23664 12824 23665 12823 23665 12821 23665 12825 23666 12823 23666 12824 23666 12826 23667 12823 23667 12825 23667 12692 23668 12824 23668 12693 23668 12827 23669 12824 23669 12692 23669 12827 23670 12825 23670 12824 23670 12826 23671 12825 23671 12827 23671 12828 23672 12692 23672 12691 23672 12827 23673 12692 23673 12828 23673 12690 23674 12828 23674 12691 23674 12829 23675 12826 23675 12827 23675 12830 23676 12827 23676 12828 23676 12829 23677 12827 23677 12830 23677 12831 23678 12826 23678 12829 23678 12689 23679 12828 23679 12690 23679 12830 23680 12828 23680 12689 23680 12831 23681 12829 23681 12830 23681 12832 23682 12830 23682 12689 23682 12832 23683 12689 23683 12688 23683 12831 23684 12830 23684 12832 23684 12833 23685 12832 23685 12688 23685 12833 23686 12688 23686 12687 23686 12834 23687 12832 23687 12833 23687 12834 23688 12831 23688 12832 23688 12836 23689 12687 23689 12835 23689 12836 23690 12833 23690 12687 23690 12836 23691 12834 23691 12833 23691 12686 23692 12836 23692 12835 23692 12837 23693 12834 23693 12836 23693 12838 23694 12836 23694 12686 23694 12837 23695 12836 23695 12838 23695 12838 23696 12686 23696 12685 23696 12839 23697 12834 23697 12837 23697 12840 23698 12838 23698 12685 23698 12840 23699 12837 23699 12838 23699 12839 23700 12837 23700 12840 23700 12840 23701 12685 23701 12684 23701 12732 23702 12840 23702 12684 23702 12734 23703 12840 23703 12732 23703 12734 23704 12839 23704 12840 23704 12839 23705 12734 23705 12735 23705 12482 23706 12480 23706 12743 23706 12482 23707 12743 23707 12746 23707 12484 23708 12482 23708 12746 23708 12484 23709 12746 23709 12752 23709 12478 23710 12737 23710 12743 23710 12478 23711 12743 23711 12480 23711 12477 23712 12735 23712 12737 23712 12477 23713 12737 23713 12478 23713 12484 23714 12752 23714 12756 23714 12486 23715 12484 23715 12756 23715 12518 23716 12735 23716 12477 23716 12518 23717 12839 23717 12735 23717 12486 23718 12756 23718 12762 23718 12488 23719 12486 23719 12762 23719 12516 23720 12834 23720 12839 23720 12516 23721 12839 23721 12518 23721 12490 23722 12488 23722 12762 23722 12490 23723 12762 23723 12767 23723 12514 23724 12834 23724 12516 23724 12514 23725 12831 23725 12834 23725 12492 23726 12490 23726 12767 23726 12492 23727 12767 23727 12778 23727 12826 23728 12514 23728 12511 23728 12826 23729 12831 23729 12514 23729 12778 23730 12493 23730 12492 23730 12826 23731 12511 23731 12509 23731 12778 23732 12495 23732 12493 23732 12823 23733 12826 23733 12509 23733 12781 23734 12495 23734 12778 23734 12781 23735 12497 23735 12495 23735 12817 23736 12823 23736 12509 23736 12817 23737 12509 23737 12507 23737 12790 23738 12497 23738 12781 23738 12790 23739 12499 23739 12497 23739 12814 23740 12817 23740 12507 23740 12814 23741 12507 23741 12505 23741 12794 23742 12499 23742 12790 23742 12794 23743 12501 23743 12499 23743 12808 23744 12814 23744 12505 23744 12798 23745 12501 23745 12794 23745 12808 23746 12505 23746 12503 23746 12803 23747 12808 23747 12503 23747 12798 23748 12803 23748 12503 23748 12798 23749 12503 23749 12501 23749 12844 23750 12842 23750 12841 23750 12846 23751 12842 23751 12844 23751 12846 23752 12843 23752 12842 23752 12847 23753 12843 23753 12846 23753 12847 23754 12845 23754 12843 23754 12848 23755 12846 23755 12844 23755 12849 23756 12846 23756 12848 23756 12849 23757 12847 23757 12846 23757 12850 23758 12845 23758 12847 23758 12849 23759 12850 23759 12847 23759 12851 23760 12849 23760 12848 23760 12853 23761 12849 23761 12851 23761 12854 23762 12851 23762 12852 23762 12850 23763 12849 23763 12853 23763 12854 23764 12853 23764 12851 23764 12855 23765 12854 23765 12852 23765 12856 23766 12850 23766 12853 23766 12857 23767 12854 23767 12855 23767 12857 23768 12853 23768 12854 23768 12856 23769 12853 23769 12857 23769 12858 23770 12857 23770 12855 23770 12858 23771 12855 23771 12859 23771 12860 23772 12857 23772 12858 23772 12860 23773 12856 23773 12857 23773 12861 23774 12856 23774 12860 23774 12862 23775 12858 23775 12859 23775 12863 23776 12858 23776 12862 23776 12863 23777 12860 23777 12858 23777 12861 23778 12860 23778 12863 23778 12863 23779 12862 23779 12864 23779 12866 23780 12864 23780 12865 23780 12866 23781 12863 23781 12864 23781 12868 23782 12863 23782 12866 23782 12868 23783 12861 23783 12863 23783 12867 23784 12861 23784 12868 23784 12869 23785 12866 23785 12865 23785 12869 23786 12868 23786 12866 23786 12869 23787 12865 23787 12870 23787 12871 23788 12867 23788 12868 23788 12872 23789 12869 23789 12870 23789 12872 23790 12868 23790 12869 23790 12877 23791 12867 23791 12871 23791 12871 23792 12868 23792 12872 23792 12873 23793 12872 23793 12870 23793 12874 23794 12872 23794 12873 23794 12874 23795 12871 23795 12872 23795 12875 23796 12873 23796 12870 23796 12877 23797 12871 23797 12874 23797 12876 23798 12873 23798 12875 23798 12874 23799 12873 23799 12876 23799 12878 23800 12876 23800 12875 23800 12880 23801 12876 23801 12878 23801 12880 23802 12874 23802 12876 23802 12880 23803 12877 23803 12874 23803 12879 23804 12877 23804 12880 23804 12882 23805 12880 23805 12878 23805 12882 23806 12878 23806 12881 23806 12879 23807 12880 23807 12882 23807 12884 23808 12881 23808 12883 23808 12884 23809 12882 23809 12881 23809 12885 23810 12879 23810 12882 23810 12886 23811 12879 23811 12885 23811 12885 23812 12882 23812 12884 23812 12887 23813 12884 23813 12883 23813 12888 23814 12884 23814 12887 23814 12885 23815 12884 23815 12888 23815 12889 23816 12885 23816 12888 23816 12889 23817 12886 23817 12885 23817 12890 23818 12886 23818 12889 23818 12892 23819 12888 23819 12887 23819 12892 23820 12887 23820 12891 23820 12892 23821 12889 23821 12888 23821 12894 23822 12891 23822 12893 23822 12894 23823 12892 23823 12891 23823 12895 23824 12889 23824 12892 23824 12895 23825 12890 23825 12889 23825 12894 23826 12895 23826 12892 23826 12896 23827 12894 23827 12893 23827 12897 23828 12890 23828 12895 23828 12898 23829 12894 23829 12896 23829 12895 23830 12894 23830 12898 23830 12898 23831 12896 23831 12899 23831 12900 23832 12895 23832 12898 23832 12900 23833 12897 23833 12895 23833 12901 23834 12898 23834 12899 23834 12900 23835 12898 23835 12901 23835 12902 23836 12901 23836 12899 23836 12903 23837 12897 23837 12900 23837 12903 23838 12900 23838 12901 23838 12905 23839 12901 23839 12902 23839 12905 23840 12902 23840 12904 23840 12905 23841 12903 23841 12901 23841 12906 23842 12905 23842 12904 23842 12907 23843 12903 23843 12905 23843 12908 23844 12905 23844 12906 23844 12907 23845 12905 23845 12908 23845 12909 23846 12908 23846 12906 23846 12910 23847 12908 23847 12909 23847 12911 23848 12903 23848 12907 23848 12912 23849 12908 23849 12910 23849 12912 23850 12907 23850 12908 23850 12913 23851 12910 23851 12909 23851 12911 23852 12907 23852 12912 23852 12914 23853 12910 23853 12913 23853 12914 23854 12912 23854 12910 23854 12915 23855 12911 23855 12912 23855 12915 23856 12912 23856 12914 23856 12916 23857 12914 23857 12913 23857 12918 23858 12916 23858 12917 23858 12918 23859 12914 23859 12916 23859 12919 23860 12911 23860 12915 23860 12920 23861 12914 23861 12918 23861 12920 23862 12915 23862 12914 23862 12919 23863 12915 23863 12920 23863 12921 23864 12918 23864 12917 23864 12920 23865 12918 23865 12921 23865 12922 23866 12920 23866 12921 23866 12923 23867 12920 23867 12922 23867 12923 23868 12919 23868 12920 23868 12925 23869 12922 23869 12924 23869 12927 23870 12919 23870 12923 23870 12926 23871 12922 23871 12925 23871 12926 23872 12923 23872 12922 23872 12927 23873 12923 23873 12926 23873 12929 23874 12927 23874 12926 23874 12928 23875 12925 23875 12924 23875 12928 23876 12926 23876 12925 23876 12929 23877 12926 23877 12928 23877 12930 23878 12928 23878 12924 23878 12931 23879 12928 23879 12930 23879 12932 23880 12927 23880 12929 23880 12933 23881 12928 23881 12931 23881 12933 23882 12929 23882 12928 23882 12932 23883 12929 23883 12933 23883 12933 23884 12931 23884 12934 23884 12934 23885 12931 23885 12935 23885 12936 23886 12933 23886 12934 23886 12937 23887 12934 23887 12935 23887 12932 23888 12933 23888 12936 23888 12938 23889 12937 23889 12935 23889 12936 23890 12934 23890 12937 23890 12939 23891 12937 23891 12938 23891 12940 23892 12937 23892 12939 23892 12940 23893 12936 23893 12937 23893 12941 23894 12936 23894 12940 23894 12941 23895 12932 23895 12936 23895 12939 23896 12938 23896 12942 23896 12943 23897 12940 23897 12939 23897 12944 23898 12940 23898 12943 23898 12943 23899 12939 23899 12942 23899 12944 23900 12941 23900 12940 23900 12946 23901 12942 23901 12945 23901 12946 23902 12943 23902 12942 23902 12947 23903 12944 23903 12943 23903 12947 23904 12941 23904 12944 23904 12948 23905 12943 23905 12946 23905 12947 23906 12943 23906 12948 23906 12949 23907 12946 23907 12945 23907 12948 23908 12946 23908 12949 23908 12950 23909 12947 23909 12948 23909 12951 23910 12948 23910 12949 23910 12951 23911 12950 23911 12948 23911 12952 23912 12951 23912 12949 23912 12953 23913 12947 23913 12950 23913 12954 23914 12951 23914 12952 23914 12955 23915 12954 23915 12952 23915 12956 23916 12951 23916 12954 23916 12956 23917 12950 23917 12951 23917 12953 23918 12950 23918 12956 23918 12957 23919 12954 23919 12955 23919 12956 23920 12954 23920 12957 23920 12958 23921 12956 23921 12957 23921 12958 23922 12953 23922 12956 23922 12960 23923 12957 23923 12959 23923 12960 23924 12958 23924 12957 23924 12961 23925 12953 23925 12958 23925 12961 23926 12958 23926 12960 23926 12962 23927 12960 23927 12959 23927 12963 23928 12960 23928 12962 23928 12963 23929 12961 23929 12960 23929 12965 23930 12961 23930 12963 23930 12964 23931 12963 23931 12962 23931 12965 23932 12963 23932 12964 23932 12966 23933 12961 23933 12965 23933 12968 23934 12965 23934 12964 23934 12969 23935 12965 23935 12968 23935 12968 23936 12964 23936 12967 23936 12966 23937 12965 23937 12969 23937 12970 23938 12968 23938 12967 23938 12971 23939 12968 23939 12970 23939 12972 23940 12966 23940 12969 23940 12969 23941 12968 23941 12971 23941 12973 23942 12971 23942 12970 23942 12974 23943 12971 23943 12973 23943 12974 23944 12969 23944 12971 23944 12976 23945 12969 23945 12974 23945 12975 23946 12974 23946 12973 23946 12972 23947 12969 23947 12976 23947 12977 23948 12974 23948 12975 23948 12978 23949 12972 23949 12976 23949 12977 23950 12976 23950 12974 23950 12979 23951 12977 23951 12975 23951 12979 23952 12975 23952 12980 23952 12978 23953 12976 23953 12977 23953 12981 23954 12977 23954 12979 23954 12981 23955 12978 23955 12977 23955 12982 23956 12979 23956 12980 23956 12982 23957 12981 23957 12979 23957 12984 23958 12981 23958 12982 23958 12982 23959 12980 23959 12983 23959 12984 23960 12978 23960 12981 23960 12985 23961 12982 23961 12983 23961 12986 23962 12978 23962 12984 23962 12984 23963 12982 23963 12985 23963 12985 23964 12983 23964 12987 23964 12988 23965 12984 23965 12985 23965 12986 23966 12984 23966 12988 23966 12989 23967 12985 23967 12987 23967 12989 23968 12988 23968 12985 23968 12990 23969 12986 23969 12988 23969 12992 23970 12989 23970 12991 23970 12993 23971 12986 23971 12990 23971 12992 23972 12988 23972 12989 23972 12990 23973 12988 23973 12992 23973 12995 23974 12991 23974 12994 23974 12995 23975 12992 23975 12991 23975 12997 23976 12992 23976 12995 23976 12997 23977 12990 23977 12992 23977 12993 23978 12990 23978 12997 23978 12995 23979 12994 23979 12996 23979 12999 23980 12997 23980 12995 23980 12998 23981 12997 23981 12999 23981 12999 23982 12995 23982 12996 23982 12998 23983 12993 23983 12997 23983 13000 23984 12999 23984 12996 23984 12843 23985 12999 23985 13000 23985 12843 23986 12998 23986 12999 23986 12845 23987 12998 23987 12843 23987 13000 23988 12841 23988 12842 23988 12845 23989 12993 23989 12998 23989 12843 23990 13000 23990 12842 23990 13001 23991 12841 23991 13000 23991 13002 23992 13001 23992 13000 23992 13002 23993 13000 23993 12996 23993 13003 23994 13002 23994 12996 23994 13003 23995 12996 23995 12994 23995 13004 23996 13003 23996 12994 23996 13004 23997 12994 23997 12991 23997 13005 23998 13004 23998 12991 23998 13005 23999 12991 23999 12989 23999 13006 24000 13005 24000 12989 24000 13006 24001 12989 24001 12987 24001 13007 24002 13006 24002 12987 24002 13007 24003 12987 24003 12983 24003 13008 24004 13007 24004 12983 24004 13008 24005 12983 24005 12980 24005 13009 24006 13008 24006 12980 24006 13009 24007 12980 24007 12975 24007 13010 24008 13009 24008 12975 24008 13010 24009 12975 24009 12973 24009 13011 24010 13010 24010 12973 24010 13011 24011 12973 24011 12970 24011 13012 24012 13011 24012 12970 24012 13012 24013 12970 24013 12967 24013 13013 24014 12967 24014 12964 24014 13013 24015 13012 24015 12967 24015 13013 24016 12964 24016 12962 24016 13014 24017 13013 24017 12962 24017 13014 24018 12962 24018 12959 24018 13015 24019 13014 24019 12959 24019 13016 24020 12959 24020 12957 24020 13016 24021 13015 24021 12959 24021 13016 24022 12957 24022 12955 24022 13017 24023 13016 24023 12955 24023 13018 24024 12955 24024 12952 24024 13018 24025 13017 24025 12955 24025 13019 24026 12952 24026 12949 24026 13019 24027 13018 24027 12952 24027 13019 24028 12949 24028 12945 24028 13020 24029 13019 24029 12945 24029 13020 24030 12945 24030 12942 24030 13021 24031 13020 24031 12942 24031 13022 24032 12942 24032 12938 24032 13022 24033 13021 24033 12942 24033 13023 24034 13022 24034 12938 24034 13023 24035 12938 24035 12935 24035 13024 24036 13023 24036 12935 24036 13024 24037 12935 24037 12931 24037 13025 24038 13024 24038 12931 24038 13025 24039 12931 24039 12930 24039 13026 24040 13025 24040 12930 24040 13026 24041 12930 24041 12924 24041 13027 24042 13026 24042 12924 24042 13027 24043 12924 24043 12922 24043 13028 24044 13027 24044 12922 24044 13028 24045 12922 24045 12921 24045 13029 24046 13028 24046 12921 24046 13029 24047 12921 24047 12917 24047 13029 24048 12917 24048 12916 24048 13030 24049 13029 24049 12916 24049 13030 24050 12916 24050 12913 24050 13031 24051 13030 24051 12913 24051 13031 24052 12913 24052 12909 24052 13032 24053 13031 24053 12909 24053 13033 24054 13032 24054 12909 24054 13033 24055 12909 24055 12906 24055 13034 24056 13033 24056 12906 24056 13034 24057 12906 24057 12904 24057 13035 24058 13034 24058 12904 24058 13035 24059 12904 24059 12902 24059 13036 24060 12902 24060 12899 24060 13036 24061 13035 24061 12902 24061 13037 24062 13036 24062 12899 24062 13037 24063 12899 24063 12896 24063 13038 24064 13037 24064 12896 24064 13038 24065 12896 24065 12893 24065 13039 24066 13038 24066 12893 24066 13039 24067 12893 24067 12891 24067 13040 24068 13039 24068 12891 24068 13041 24069 13040 24069 12891 24069 13041 24070 12891 24070 12887 24070 13042 24071 13041 24071 12887 24071 13042 24072 12887 24072 12883 24072 13043 24073 13042 24073 12883 24073 13043 24074 12883 24074 12881 24074 13043 24075 12881 24075 12878 24075 13044 24076 13043 24076 12878 24076 13044 24077 12878 24077 12875 24077 13045 24078 12875 24078 12870 24078 13045 24079 13044 24079 12875 24079 13046 24080 13045 24080 12870 24080 13047 24081 13046 24081 12870 24081 13047 24082 12870 24082 12865 24082 13048 24083 12865 24083 12864 24083 13048 24084 13047 24084 12865 24084 13049 24085 13048 24085 12864 24085 13049 24086 12864 24086 12862 24086 13050 24087 12862 24087 12859 24087 13050 24088 13049 24088 12862 24088 13051 24089 13050 24089 12859 24089 13051 24090 12859 24090 12855 24090 13052 24091 13051 24091 12855 24091 13052 24092 12855 24092 12852 24092 13053 24093 13052 24093 12852 24093 13053 24094 12852 24094 12851 24094 13054 24095 13053 24095 12851 24095 13054 24096 12851 24096 12848 24096 13055 24097 12848 24097 12844 24097 13055 24098 13054 24098 12848 24098 13001 24099 12844 24099 12841 24099 13001 24100 13055 24100 12844 24100 13056 24101 13001 24101 13002 24101 13059 24102 13057 24102 13056 24102 13003 24103 13056 24103 13002 24103 13059 24104 13056 24104 13003 24104 13060 24105 13058 24105 13057 24105 13061 24106 13057 24106 13059 24106 13060 24107 13057 24107 13061 24107 13062 24108 13059 24108 13003 24108 13063 24109 13059 24109 13062 24109 13063 24110 13061 24110 13059 24110 13004 24111 13062 24111 13003 24111 13063 24112 13060 24112 13061 24112 13005 24113 13062 24113 13004 24113 13064 24114 13062 24114 13005 24114 13064 24115 13063 24115 13062 24115 13065 24116 13060 24116 13063 24116 13065 24117 13063 24117 13064 24117 13066 24118 13005 24118 13006 24118 13066 24119 13064 24119 13005 24119 13067 24120 13064 24120 13066 24120 13067 24121 13065 24121 13064 24121 13068 24122 13006 24122 13007 24122 13068 24123 13066 24123 13006 24123 13068 24124 13067 24124 13066 24124 13069 24125 13060 24125 13065 24125 13069 24126 13065 24126 13067 24126 13070 24127 13067 24127 13068 24127 13071 24128 13068 24128 13007 24128 13069 24129 13067 24129 13070 24129 13070 24130 13068 24130 13071 24130 13008 24131 13071 24131 13007 24131 13072 24132 13069 24132 13070 24132 13073 24133 13071 24133 13008 24133 13073 24134 13070 24134 13071 24134 13072 24135 13070 24135 13073 24135 13074 24136 13008 24136 13009 24136 13074 24137 13073 24137 13008 24137 13074 24138 13072 24138 13073 24138 13075 24139 13069 24139 13072 24139 13076 24140 13009 24140 13010 24140 13076 24141 13074 24141 13009 24141 13075 24142 13072 24142 13074 24142 13077 24143 13074 24143 13076 24143 13011 24144 13076 24144 13010 24144 13077 24145 13075 24145 13074 24145 13078 24146 13076 24146 13011 24146 13078 24147 13077 24147 13076 24147 13080 24148 13011 24148 13012 24148 13080 24149 13078 24149 13011 24149 13079 24150 13075 24150 13077 24150 13081 24151 13077 24151 13078 24151 13081 24152 13078 24152 13080 24152 13080 24153 13012 24153 13013 24153 13079 24154 13077 24154 13081 24154 13082 24155 13081 24155 13080 24155 13079 24156 13081 24156 13082 24156 13083 24157 13080 24157 13013 24157 13083 24158 13082 24158 13080 24158 13083 24159 13013 24159 13014 24159 13084 24160 13079 24160 13082 24160 13085 24161 13082 24161 13083 24161 13084 24162 13082 24162 13085 24162 13085 24163 13083 24163 13014 24163 13015 24164 13085 24164 13014 24164 13084 24165 13085 24165 13086 24165 13086 24166 13085 24166 13015 24166 13087 24167 13015 24167 13016 24167 13088 24168 13084 24168 13086 24168 13087 24169 13086 24169 13015 24169 13089 24170 13086 24170 13087 24170 13087 24171 13016 24171 13017 24171 13089 24172 13088 24172 13086 24172 13090 24173 13089 24173 13087 24173 13090 24174 13087 24174 13017 24174 13090 24175 13017 24175 13018 24175 13092 24176 13088 24176 13089 24176 13089 24177 13090 24177 13091 24177 13091 24178 13018 24178 13019 24178 13091 24179 13090 24179 13018 24179 13092 24180 13089 24180 13091 24180 13093 24181 13091 24181 13019 24181 13092 24182 13091 24182 13093 24182 13094 24183 13092 24183 13093 24183 13095 24184 13019 24184 13020 24184 13095 24185 13093 24185 13019 24185 13094 24186 13093 24186 13095 24186 13021 24187 13095 24187 13020 24187 13097 24188 13092 24188 13094 24188 13096 24189 13095 24189 13021 24189 13096 24190 13094 24190 13095 24190 13097 24191 13094 24191 13096 24191 13096 24192 13021 24192 13022 24192 13098 24193 13096 24193 13022 24193 13098 24194 13022 24194 13023 24194 13099 24195 13098 24195 13023 24195 13100 24196 13098 24196 13099 24196 13100 24197 13096 24197 13098 24197 13099 24198 13023 24198 13024 24198 13101 24199 13096 24199 13100 24199 13101 24200 13097 24200 13096 24200 13102 24201 13100 24201 13099 24201 13103 24202 13100 24202 13102 24202 13103 24203 13101 24203 13100 24203 13025 24204 13099 24204 13024 24204 13102 24205 13099 24205 13025 24205 13104 24206 13025 24206 13026 24206 13104 24207 13102 24207 13025 24207 13105 24208 13101 24208 13103 24208 13104 24209 13103 24209 13102 24209 13105 24210 13103 24210 13104 24210 13027 24211 13104 24211 13026 24211 13106 24212 13104 24212 13027 24212 13106 24213 13105 24213 13104 24213 13107 24214 13106 24214 13027 24214 13107 24215 13027 24215 13028 24215 13108 24216 13105 24216 13106 24216 13108 24217 13106 24217 13107 24217 13109 24218 13107 24218 13028 24218 13110 24219 13105 24219 13108 24219 13109 24220 13108 24220 13107 24220 13109 24221 13028 24221 13029 24221 13111 24222 13108 24222 13109 24222 13110 24223 13108 24223 13111 24223 13112 24224 13109 24224 13029 24224 13112 24225 13111 24225 13109 24225 13113 24226 13110 24226 13111 24226 13030 24227 13112 24227 13029 24227 13114 24228 13112 24228 13030 24228 13114 24229 13111 24229 13112 24229 13113 24230 13111 24230 13114 24230 13031 24231 13114 24231 13030 24231 13115 24232 13114 24232 13031 24232 13115 24233 13113 24233 13114 24233 13116 24234 13113 24234 13115 24234 13117 24235 13031 24235 13032 24235 13117 24236 13115 24236 13031 24236 13117 24237 13032 24237 13033 24237 13118 24238 13115 24238 13117 24238 13118 24239 13116 24239 13115 24239 13120 24240 13113 24240 13116 24240 13034 24241 13117 24241 13033 24241 13119 24242 13117 24242 13034 24242 13120 24243 13116 24243 13118 24243 13119 24244 13118 24244 13117 24244 13121 24245 13118 24245 13119 24245 13122 24246 13034 24246 13035 24246 13120 24247 13118 24247 13121 24247 13122 24248 13119 24248 13034 24248 13121 24249 13119 24249 13122 24249 13036 24250 13122 24250 13035 24250 13121 24251 13122 24251 13036 24251 13123 24252 13121 24252 13036 24252 13124 24253 13121 24253 13123 24253 13124 24254 13120 24254 13121 24254 13123 24255 13036 24255 13037 24255 13126 24256 13120 24256 13124 24256 13125 24257 13037 24257 13038 24257 13125 24258 13123 24258 13037 24258 13125 24259 13124 24259 13123 24259 13126 24260 13124 24260 13125 24260 13125 24261 13038 24261 13039 24261 13127 24262 13126 24262 13125 24262 13128 24263 13125 24263 13039 24263 13127 24264 13125 24264 13128 24264 13040 24265 13128 24265 13039 24265 13129 24266 13126 24266 13127 24266 13128 24267 13040 24267 13041 24267 13131 24268 13127 24268 13128 24268 13131 24269 13129 24269 13127 24269 13131 24270 13128 24270 13041 24270 13132 24271 13131 24271 13041 24271 13132 24272 13041 24272 13042 24272 13130 24273 13129 24273 13131 24273 13133 24274 13132 24274 13042 24274 13134 24275 13131 24275 13132 24275 13134 24276 13132 24276 13133 24276 13134 24277 13130 24277 13131 24277 13135 24278 13042 24278 13043 24278 13135 24279 13133 24279 13042 24279 13135 24280 13134 24280 13133 24280 13136 24281 13134 24281 13135 24281 13137 24282 13134 24282 13136 24282 13137 24283 13130 24283 13134 24283 13044 24284 13135 24284 13043 24284 13136 24285 13135 24285 13044 24285 13138 24286 13137 24286 13136 24286 13139 24287 13136 24287 13044 24287 13138 24288 13136 24288 13139 24288 13045 24289 13139 24289 13044 24289 13140 24290 13139 24290 13045 24290 13141 24291 13137 24291 13138 24291 13142 24292 13139 24292 13140 24292 13142 24293 13138 24293 13139 24293 13046 24294 13140 24294 13045 24294 13141 24295 13138 24295 13142 24295 13143 24296 13140 24296 13046 24296 13142 24297 13140 24297 13143 24297 13047 24298 13143 24298 13046 24298 13144 24299 13141 24299 13142 24299 13145 24300 13142 24300 13143 24300 13146 24301 13143 24301 13047 24301 13144 24302 13142 24302 13145 24302 13145 24303 13143 24303 13146 24303 13146 24304 13047 24304 13048 24304 13049 24305 13146 24305 13048 24305 13147 24306 13146 24306 13049 24306 13147 24307 13145 24307 13146 24307 13148 24308 13145 24308 13147 24308 13148 24309 13144 24309 13145 24309 13147 24310 13049 24310 13050 24310 13051 24311 13147 24311 13050 24311 13149 24312 13147 24312 13051 24312 13150 24313 13144 24313 13148 24313 13149 24314 13148 24314 13147 24314 13150 24315 13148 24315 13149 24315 13052 24316 13149 24316 13051 24316 13151 24317 13149 24317 13052 24317 13151 24318 13150 24318 13149 24318 13153 24319 13052 24319 13053 24319 13153 24320 13151 24320 13052 24320 13152 24321 13150 24321 13151 24321 13153 24322 13053 24322 13054 24322 13154 24323 13152 24323 13151 24323 13154 24324 13151 24324 13153 24324 13155 24325 13153 24325 13054 24325 13154 24326 13153 24326 13155 24326 13155 24327 13054 24327 13055 24327 13152 24328 13154 24328 13156 24328 13156 24329 13154 24329 13155 24329 13001 24330 13155 24330 13055 24330 13157 24331 13156 24331 13155 24331 13058 24332 13152 24332 13156 24332 13157 24333 13155 24333 13001 24333 13157 24334 13001 24334 13056 24334 13157 24335 13056 24335 13057 24335 13058 24336 13157 24336 13057 24336 13058 24337 13156 24337 13157 24337 12469 24338 12471 24338 13120 24338 12469 24339 13120 24339 13126 24339 12471 24340 13113 24340 13120 24340 12473 24341 13113 24341 12471 24341 12469 24342 13126 24342 13129 24342 12466 24343 12469 24343 13129 24343 12466 24344 13129 24344 13130 24344 12475 24345 13113 24345 12473 24345 12475 24346 13110 24346 13113 24346 12434 24347 13110 24347 12475 24347 12464 24348 12466 24348 13130 24348 12464 24349 13130 24349 13137 24349 12434 24350 13105 24350 13110 24350 12464 24351 13137 24351 13141 24351 12434 24352 13101 24352 13105 24352 12461 24353 12464 24353 13141 24353 12438 24354 13101 24354 12434 24354 12461 24355 13141 24355 13144 24355 12440 24356 13101 24356 12438 24356 12440 24357 13097 24357 13101 24357 12460 24358 12461 24358 13144 24358 13150 24359 12460 24359 13144 24359 12442 24360 13097 24360 12440 24360 12458 24361 12460 24361 13150 24361 13092 24362 13097 24362 12442 24362 13152 24363 12458 24363 13150 24363 13152 24364 12456 24364 12458 24364 13092 24365 12442 24365 12444 24365 13088 24366 13092 24366 12444 24366 13084 24367 13088 24367 12444 24367 13058 24368 12456 24368 13152 24368 13058 24369 12454 24369 12456 24369 13084 24370 12444 24370 12446 24370 13060 24371 12454 24371 13058 24371 13079 24372 13084 24372 12446 24372 13079 24373 12446 24373 12448 24373 13060 24374 12452 24374 12454 24374 13075 24375 13079 24375 12448 24375 13069 24376 12452 24376 13060 24376 13069 24377 12450 24377 12452 24377 13075 24378 12448 24378 12450 24378 13069 24379 13075 24379 12450 24379 13160 24380 13158 24380 13159 24380 13160 24381 13159 24381 13161 24381 13162 24382 13160 24382 13161 24382 13163 24383 13162 24383 13161 24383 13163 24384 13161 24384 13164 24384 13165 24385 13163 24385 13164 24385 13166 24386 13165 24386 13164 24386 13167 24387 13166 24387 13164 24387 13167 24388 13164 24388 13168 24388 13169 24389 13167 24389 13168 24389 13170 24390 13169 24390 13168 24390 13170 24391 13168 24391 13171 24391 13409 24392 13170 24392 13171 24392 13172 24393 13409 24393 13171 24393 13412 24394 13172 24394 13171 24394 13412 24395 13171 24395 13173 24395 13174 24396 13412 24396 13173 24396 13175 24397 13174 24397 13173 24397 13176 24398 13175 24398 13173 24398 13177 24399 13176 24399 13173 24399 13177 24400 13173 24400 13178 24400 13179 24401 13177 24401 13178 24401 13180 24402 13179 24402 13178 24402 13180 24403 13178 24403 13181 24403 13182 24404 13180 24404 13181 24404 13183 24405 13182 24405 13181 24405 13184 24406 13183 24406 13181 24406 13184 24407 13181 24407 13185 24407 13186 24408 13184 24408 13185 24408 13187 24409 13186 24409 13185 24409 13187 24410 13185 24410 13188 24410 13189 24411 13187 24411 13188 24411 13190 24412 13189 24412 13188 24412 13191 24413 13188 24413 13192 24413 13191 24414 13190 24414 13188 24414 13193 24415 13191 24415 13192 24415 13193 24416 13192 24416 13194 24416 13195 24417 13193 24417 13194 24417 13196 24418 13195 24418 13194 24418 13196 24419 13194 24419 13197 24419 13198 24420 13196 24420 13197 24420 13199 24421 13197 24421 13200 24421 13199 24422 13198 24422 13197 24422 13201 24423 13199 24423 13200 24423 13202 24424 13201 24424 13200 24424 13202 24425 13200 24425 13203 24425 13204 24426 13202 24426 13203 24426 13205 24427 13204 24427 13203 24427 13205 24428 13203 24428 13206 24428 13207 24429 13205 24429 13206 24429 13207 24430 13206 24430 13208 24430 13209 24431 13207 24431 13208 24431 13210 24432 13209 24432 13208 24432 13210 24433 13208 24433 13211 24433 13212 24434 13210 24434 13211 24434 13213 24435 13212 24435 13211 24435 13214 24436 13213 24436 13211 24436 13214 24437 13211 24437 13215 24437 13216 24438 13214 24438 13215 24438 13216 24439 13215 24439 13217 24439 13218 24440 13216 24440 13217 24440 13219 24441 13218 24441 13217 24441 13220 24442 13219 24442 13217 24442 13220 24443 13217 24443 13221 24443 13481 24444 13220 24444 13221 24444 13222 24445 13481 24445 13221 24445 13222 24446 13221 24446 13223 24446 13224 24447 13222 24447 13223 24447 13225 24448 13224 24448 13223 24448 13225 24449 13223 24449 13159 24449 13158 24450 13225 24450 13159 24450 13226 24451 13227 24451 13228 24451 13226 24452 13228 24452 13388 24452 13229 24453 13226 24453 13388 24453 13229 24454 13388 24454 13230 24454 13231 24455 13230 24455 13232 24455 13231 24456 13229 24456 13230 24456 13231 24457 13232 24457 13381 24457 13231 24458 13381 24458 13379 24458 13231 24459 13379 24459 13233 24459 13234 24460 13231 24460 13233 24460 13234 24461 13233 24461 13235 24461 13236 24462 13235 24462 13237 24462 13236 24463 13234 24463 13235 24463 13236 24464 13237 24464 13238 24464 13236 24465 13238 24465 13371 24465 13239 24466 13236 24466 13371 24466 13239 24467 13371 24467 13240 24467 13239 24468 13240 24468 13241 24468 13239 24469 13241 24469 13242 24469 13243 24470 13239 24470 13242 24470 13243 24471 13242 24471 13363 24471 13243 24472 13363 24472 13360 24472 13244 24473 13243 24473 13360 24473 13244 24474 13360 24474 13358 24474 13245 24475 13244 24475 13358 24475 13245 24476 13358 24476 13355 24476 13245 24477 13355 24477 13246 24477 13247 24478 13245 24478 13246 24478 13247 24479 13246 24479 13248 24479 13247 24480 13248 24480 13249 24480 13250 24481 13247 24481 13249 24481 13250 24482 13249 24482 13251 24482 13252 24483 13250 24483 13251 24483 13252 24484 13251 24484 13342 24484 13252 24485 13342 24485 13253 24485 13252 24486 13253 24486 13254 24486 13255 24487 13252 24487 13254 24487 13255 24488 13254 24488 13256 24488 13255 24489 13256 24489 13257 24489 13258 24490 13255 24490 13257 24490 13258 24491 13257 24491 13259 24491 13258 24492 13259 24492 13260 24492 13261 24493 13258 24493 13260 24493 13261 24494 13260 24494 13262 24494 13263 24495 13262 24495 13264 24495 13263 24496 13261 24496 13262 24496 13263 24497 13264 24497 13265 24497 13266 24498 13263 24498 13265 24498 13266 24499 13265 24499 13267 24499 13266 24500 13267 24500 13268 24500 13269 24501 13266 24501 13268 24501 13269 24502 13268 24502 13315 24502 13270 24503 13269 24503 13315 24503 13270 24504 13315 24504 13271 24504 13270 24505 13271 24505 13313 24505 13270 24506 13313 24506 13272 24506 13273 24507 13270 24507 13272 24507 13273 24508 13272 24508 13274 24508 13273 24509 13274 24509 13275 24509 13276 24510 13273 24510 13275 24510 13276 24511 13275 24511 13306 24511 13276 24512 13306 24512 13304 24512 13276 24513 13304 24513 13277 24513 13278 24514 13276 24514 13277 24514 13278 24515 13277 24515 13279 24515 13280 24516 13279 24516 13281 24516 13280 24517 13278 24517 13279 24517 13280 24518 13281 24518 13282 24518 13280 24519 13282 24519 13283 24519 13284 24520 13280 24520 13283 24520 13284 24521 13283 24521 13285 24521 13286 24522 13284 24522 13285 24522 13286 24523 13285 24523 13227 24523 13226 24524 13286 24524 13227 24524 13287 24525 13391 24525 13227 24525 13287 24526 13288 24526 13391 24526 13290 24527 13227 24527 13285 24527 13290 24528 13287 24528 13227 24528 13291 24529 13287 24529 13290 24529 13291 24530 13288 24530 13287 24530 13289 24531 13288 24531 13291 24531 13292 24532 13290 24532 13285 24532 13292 24533 13291 24533 13290 24533 13283 24534 13292 24534 13285 24534 13293 24535 13289 24535 13291 24535 13294 24536 13291 24536 13292 24536 13295 24537 13292 24537 13283 24537 13293 24538 13291 24538 13294 24538 13294 24539 13292 24539 13295 24539 13282 24540 13295 24540 13283 24540 13296 24541 13295 24541 13282 24541 13297 24542 13294 24542 13295 24542 13297 24543 13295 24543 13296 24543 13297 24544 13293 24544 13294 24544 13298 24545 13296 24545 13282 24545 13299 24546 13293 24546 13297 24546 13297 24547 13296 24547 13298 24547 13281 24548 13298 24548 13282 24548 13300 24549 13297 24549 13298 24549 13299 24550 13297 24550 13300 24550 13279 24551 13298 24551 13281 24551 13300 24552 13298 24552 13279 24552 13302 24553 13279 24553 13277 24553 13302 24554 13300 24554 13279 24554 13303 24555 13300 24555 13302 24555 13303 24556 13299 24556 13300 24556 13301 24557 13299 24557 13303 24557 13304 24558 13302 24558 13277 24558 13305 24559 13302 24559 13304 24559 13303 24560 13302 24560 13305 24560 13306 24561 13305 24561 13304 24561 13307 24562 13301 24562 13303 24562 13307 24563 13303 24563 13305 24563 13308 24564 13305 24564 13306 24564 13307 24565 13305 24565 13308 24565 13308 24566 13306 24566 13275 24566 13310 24567 13307 24567 13308 24567 13309 24568 13308 24568 13275 24568 13310 24569 13301 24569 13307 24569 13274 24570 13309 24570 13275 24570 13309 24571 13310 24571 13308 24571 13311 24572 13309 24572 13274 24572 13311 24573 13310 24573 13309 24573 13272 24574 13311 24574 13274 24574 13312 24575 13310 24575 13311 24575 13313 24576 13311 24576 13272 24576 13314 24577 13311 24577 13313 24577 13312 24578 13311 24578 13314 24578 13314 24579 13313 24579 13271 24579 13315 24580 13314 24580 13271 24580 13316 24581 13312 24581 13314 24581 13319 24582 13312 24582 13316 24582 13317 24583 13314 24583 13315 24583 13317 24584 13316 24584 13314 24584 13318 24585 13317 24585 13315 24585 13318 24586 13315 24586 13268 24586 13320 24587 13316 24587 13317 24587 13320 24588 13319 24588 13316 24588 13321 24589 13317 24589 13318 24589 13321 24590 13320 24590 13317 24590 13321 24591 13318 24591 13268 24591 13267 24592 13321 24592 13268 24592 13320 24593 13321 24593 13322 24593 13322 24594 13321 24594 13267 24594 13324 24595 13319 24595 13320 24595 13323 24596 13267 24596 13265 24596 13324 24597 13320 24597 13322 24597 13323 24598 13322 24598 13267 24598 13323 24599 13265 24599 13264 24599 13325 24600 13322 24600 13323 24600 13326 24601 13323 24601 13264 24601 13325 24602 13324 24602 13322 24602 13325 24603 13323 24603 13326 24603 13327 24604 13324 24604 13325 24604 13328 24605 13326 24605 13264 24605 13325 24606 13326 24606 13328 24606 13328 24607 13264 24607 13262 24607 13329 24608 13325 24608 13328 24608 13330 24609 13325 24609 13329 24609 13330 24610 13327 24610 13325 24610 13332 24611 13262 24611 13260 24611 13332 24612 13328 24612 13262 24612 13332 24613 13329 24613 13328 24613 13331 24614 13327 24614 13330 24614 13330 24615 13329 24615 13332 24615 13334 24616 13330 24616 13332 24616 13333 24617 13332 24617 13260 24617 13334 24618 13331 24618 13330 24618 13334 24619 13332 24619 13333 24619 13333 24620 13260 24620 13259 24620 13335 24621 13333 24621 13259 24621 13335 24622 13334 24622 13333 24622 13336 24623 13334 24623 13335 24623 13336 24624 13331 24624 13334 24624 13335 24625 13259 24625 13257 24625 13337 24626 13336 24626 13335 24626 13256 24627 13335 24627 13257 24627 13337 24628 13335 24628 13256 24628 13340 24629 13331 24629 13336 24629 13338 24630 13336 24630 13337 24630 13339 24631 13337 24631 13256 24631 13338 24632 13337 24632 13339 24632 13339 24633 13256 24633 13254 24633 13340 24634 13336 24634 13338 24634 13253 24635 13339 24635 13254 24635 13341 24636 13339 24636 13253 24636 13338 24637 13339 24637 13341 24637 13342 24638 13341 24638 13253 24638 13340 24639 13338 24639 13341 24639 13343 24640 13340 24640 13341 24640 13344 24641 13341 24641 13342 24641 13343 24642 13341 24642 13344 24642 13344 24643 13342 24643 13251 24643 13345 24644 13343 24644 13344 24644 13346 24645 13344 24645 13251 24645 13345 24646 13344 24646 13346 24646 13347 24647 13345 24647 13346 24647 13249 24648 13346 24648 13251 24648 13347 24649 13346 24649 13249 24649 13348 24650 13343 24650 13345 24650 13348 24651 13345 24651 13347 24651 13349 24652 13347 24652 13249 24652 13248 24653 13349 24653 13249 24653 13350 24654 13347 24654 13349 24654 13351 24655 13347 24655 13350 24655 13351 24656 13348 24656 13347 24656 13352 24657 13349 24657 13248 24657 13352 24658 13350 24658 13349 24658 13246 24659 13352 24659 13248 24659 13353 24660 13350 24660 13352 24660 13353 24661 13351 24661 13350 24661 13353 24662 13352 24662 13246 24662 13356 24663 13348 24663 13351 24663 13354 24664 13353 24664 13246 24664 13355 24665 13354 24665 13246 24665 13356 24666 13351 24666 13353 24666 13357 24667 13353 24667 13354 24667 13356 24668 13353 24668 13357 24668 13358 24669 13354 24669 13355 24669 13357 24670 13354 24670 13358 24670 13359 24671 13356 24671 13357 24671 13359 24672 13357 24672 13358 24672 13361 24673 13358 24673 13360 24673 13361 24674 13359 24674 13358 24674 13362 24675 13356 24675 13359 24675 13362 24676 13359 24676 13361 24676 13363 24677 13361 24677 13360 24677 13364 24678 13356 24678 13362 24678 13242 24679 13361 24679 13363 24679 13365 24680 13361 24680 13242 24680 13365 24681 13362 24681 13361 24681 13364 24682 13362 24682 13365 24682 13366 24683 13242 24683 13241 24683 13366 24684 13365 24684 13242 24684 13367 24685 13241 24685 13240 24685 13367 24686 13366 24686 13241 24686 13368 24687 13364 24687 13365 24687 13369 24688 13366 24688 13367 24688 13369 24689 13365 24689 13366 24689 13368 24690 13365 24690 13369 24690 13370 24691 13369 24691 13367 24691 13371 24692 13367 24692 13240 24692 13370 24693 13367 24693 13371 24693 13372 24694 13371 24694 13238 24694 13372 24695 13370 24695 13371 24695 13374 24696 13369 24696 13370 24696 13374 24697 13370 24697 13372 24697 13374 24698 13368 24698 13369 24698 13375 24699 13372 24699 13238 24699 13374 24700 13372 24700 13375 24700 13375 24701 13238 24701 13237 24701 13373 24702 13368 24702 13374 24702 13376 24703 13375 24703 13237 24703 13376 24704 13374 24704 13375 24704 13373 24705 13374 24705 13376 24705 13376 24706 13237 24706 13235 24706 13377 24707 13373 24707 13376 24707 13378 24708 13373 24708 13377 24708 13376 24709 13235 24709 13233 24709 13380 24710 13376 24710 13233 24710 13380 24711 13377 24711 13376 24711 13380 24712 13233 24712 13379 24712 13378 24713 13377 24713 13380 24713 13381 24714 13380 24714 13379 24714 13382 24715 13380 24715 13381 24715 13382 24716 13378 24716 13380 24716 13384 24717 13381 24717 13232 24717 13384 24718 13382 24718 13381 24718 13383 24719 13378 24719 13382 24719 13384 24720 13232 24720 13230 24720 13385 24721 13382 24721 13384 24721 13385 24722 13383 24722 13382 24722 13386 24723 13383 24723 13385 24723 13387 24724 13384 24724 13230 24724 13385 24725 13384 24725 13387 24725 13388 24726 13387 24726 13230 24726 13390 24727 13387 24727 13388 24727 13389 24728 13386 24728 13385 24728 13390 24729 13385 24729 13387 24729 13390 24730 13389 24730 13385 24730 13228 24731 13390 24731 13388 24731 13391 24732 13390 24732 13228 24732 13389 24733 13390 24733 13391 24733 13289 24734 13386 24734 13389 24734 13391 24735 13228 24735 13227 24735 13288 24736 13389 24736 13391 24736 13289 24737 13389 24737 13288 24737 12459 24738 13299 24738 13301 24738 12462 24739 12459 24739 13301 24739 12459 24740 13293 24740 13299 24740 12457 24741 13293 24741 12459 24741 12463 24742 13301 24742 13310 24742 12463 24743 12462 24743 13301 24743 12457 24744 13289 24744 13293 24744 12465 24745 12463 24745 13310 24745 12455 24746 13289 24746 12457 24746 12465 24747 13310 24747 13312 24747 12455 24748 13386 24748 13289 24748 12465 24749 13312 24749 13319 24749 12453 24750 13386 24750 12455 24750 12467 24751 12465 24751 13319 24751 12468 24752 12467 24752 13319 24752 12451 24753 13383 24753 13386 24753 12451 24754 13386 24754 12453 24754 12468 24755 13319 24755 13324 24755 12470 24756 12468 24756 13324 24756 13327 24757 12470 24757 13324 24757 13383 24758 12451 24758 12449 24758 13378 24759 13383 24759 12449 24759 13331 24760 12470 24760 13327 24760 13331 24761 12472 24761 12470 24761 13373 24762 12449 24762 12447 24762 13373 24763 13378 24763 12449 24763 13331 24764 12474 24764 12472 24764 13373 24765 12447 24765 12445 24765 13368 24766 13373 24766 12445 24766 13340 24767 12474 24767 13331 24767 13340 24768 12435 24768 12474 24768 13364 24769 13368 24769 12445 24769 13364 24770 12445 24770 12443 24770 13340 24771 12436 24771 12435 24771 13343 24772 12436 24772 13340 24772 13343 24773 12437 24773 12436 24773 13364 24774 12443 24774 12441 24774 13348 24775 12437 24775 13343 24775 13356 24776 13364 24776 12441 24776 13348 24777 12439 24777 12437 24777 13356 24778 12441 24778 12439 24778 13348 24779 13356 24779 12439 24779 13160 24780 13392 24780 13158 24780 13393 24781 13488 24781 13490 24781 13393 24782 13392 24782 13160 24782 13393 24783 13490 24783 13392 24783 13396 24784 13488 24784 13393 24784 13394 24785 13160 24785 13162 24785 13395 24786 13160 24786 13394 24786 13395 24787 13393 24787 13160 24787 13396 24788 13393 24788 13395 24788 13397 24789 13394 24789 13162 24789 13397 24790 13162 24790 13163 24790 13397 24791 13395 24791 13394 24791 13398 24792 13395 24792 13397 24792 13399 24793 13397 24793 13163 24793 13398 24794 13396 24794 13395 24794 13400 24795 13397 24795 13399 24795 13400 24796 13398 24796 13397 24796 13399 24797 13163 24797 13165 24797 13401 24798 13399 24798 13165 24798 13401 24799 13400 24799 13399 24799 13166 24800 13401 24800 13165 24800 13402 24801 13398 24801 13400 24801 13403 24802 13401 24802 13166 24802 13404 24803 13401 24803 13403 24803 13405 24804 13398 24804 13402 24804 13404 24805 13400 24805 13401 24805 13402 24806 13400 24806 13404 24806 13403 24807 13166 24807 13167 24807 13406 24808 13403 24808 13167 24808 13406 24809 13167 24809 13169 24809 13405 24810 13402 24810 13404 24810 13406 24811 13404 24811 13403 24811 13407 24812 13404 24812 13406 24812 13405 24813 13404 24813 13407 24813 13407 24814 13406 24814 13169 24814 13170 24815 13407 24815 13169 24815 13409 24816 13407 24816 13170 24816 13408 24817 13405 24817 13407 24817 13408 24818 13407 24818 13409 24818 13410 24819 13405 24819 13408 24819 13411 24820 13408 24820 13409 24820 13411 24821 13409 24821 13172 24821 13411 24822 13410 24822 13408 24822 13415 24823 13405 24823 13410 24823 13413 24824 13410 24824 13411 24824 13414 24825 13172 24825 13412 24825 13414 24826 13411 24826 13172 24826 13413 24827 13411 24827 13414 24827 13174 24828 13414 24828 13412 24828 13415 24829 13410 24829 13413 24829 13416 24830 13413 24830 13414 24830 13415 24831 13413 24831 13416 24831 13417 24832 13174 24832 13175 24832 13417 24833 13414 24833 13174 24833 13416 24834 13414 24834 13417 24834 13417 24835 13175 24835 13176 24835 13418 24836 13416 24836 13417 24836 13419 24837 13416 24837 13418 24837 13418 24838 13417 24838 13176 24838 13419 24839 13415 24839 13416 24839 13418 24840 13176 24840 13177 24840 13420 24841 13419 24841 13418 24841 13421 24842 13418 24842 13177 24842 13421 24843 13420 24843 13418 24843 13422 24844 13415 24844 13419 24844 13422 24845 13419 24845 13420 24845 13421 24846 13177 24846 13179 24846 13423 24847 13422 24847 13420 24847 13423 24848 13420 24848 13421 24848 13180 24849 13421 24849 13179 24849 13424 24850 13421 24850 13180 24850 13423 24851 13421 24851 13424 24851 13182 24852 13424 24852 13180 24852 13425 24853 13423 24853 13424 24853 13425 24854 13424 24854 13182 24854 13426 24855 13422 24855 13423 24855 13427 24856 13182 24856 13183 24856 13427 24857 13425 24857 13182 24857 13426 24858 13423 24858 13425 24858 13184 24859 13427 24859 13183 24859 13428 24860 13425 24860 13427 24860 13428 24861 13426 24861 13425 24861 13428 24862 13427 24862 13429 24862 13429 24863 13184 24863 13186 24863 13429 24864 13427 24864 13184 24864 13431 24865 13186 24865 13187 24865 13430 24866 13428 24866 13429 24866 13431 24867 13429 24867 13186 24867 13430 24868 13429 24868 13431 24868 13431 24869 13187 24869 13189 24869 13433 24870 13426 24870 13428 24870 13432 24871 13430 24871 13431 24871 13432 24872 13431 24872 13189 24872 13433 24873 13428 24873 13430 24873 13434 24874 13430 24874 13432 24874 13433 24875 13430 24875 13434 24875 13190 24876 13432 24876 13189 24876 13435 24877 13432 24877 13190 24877 13434 24878 13432 24878 13435 24878 13436 24879 13190 24879 13191 24879 13436 24880 13435 24880 13190 24880 13437 24881 13435 24881 13436 24881 13437 24882 13434 24882 13435 24882 13433 24883 13434 24883 13437 24883 13438 24884 13437 24884 13436 24884 13193 24885 13436 24885 13191 24885 13439 24886 13436 24886 13193 24886 13440 24887 13437 24887 13438 24887 13439 24888 13438 24888 13436 24888 13440 24889 13433 24889 13437 24889 13441 24890 13438 24890 13439 24890 13195 24891 13439 24891 13193 24891 13440 24892 13438 24892 13441 24892 13442 24893 13439 24893 13195 24893 13442 24894 13441 24894 13439 24894 13442 24895 13195 24895 13196 24895 13444 24896 13440 24896 13441 24896 13443 24897 13440 24897 13444 24897 13444 24898 13441 24898 13442 24898 13445 24899 13442 24899 13196 24899 13445 24900 13444 24900 13442 24900 13445 24901 13196 24901 13198 24901 13446 24902 13444 24902 13445 24902 13199 24903 13445 24903 13198 24903 13447 24904 13445 24904 13199 24904 13443 24905 13444 24905 13446 24905 13446 24906 13445 24906 13447 24906 13447 24907 13199 24907 13201 24907 13448 24908 13447 24908 13201 24908 13449 24909 13447 24909 13448 24909 13449 24910 13446 24910 13447 24910 13450 24911 13443 24911 13446 24911 13450 24912 13446 24912 13449 24912 13202 24913 13448 24913 13201 24913 13451 24914 13448 24914 13202 24914 13451 24915 13449 24915 13448 24915 13452 24916 13202 24916 13204 24916 13452 24917 13451 24917 13202 24917 13453 24918 13449 24918 13451 24918 13453 24919 13450 24919 13449 24919 13454 24920 13451 24920 13452 24920 13456 24921 13452 24921 13204 24921 13454 24922 13453 24922 13451 24922 13454 24923 13452 24923 13456 24923 13456 24924 13204 24924 13205 24924 13455 24925 13450 24925 13453 24925 13457 24926 13456 24926 13205 24926 13453 24927 13454 24927 13458 24927 13457 24928 13454 24928 13456 24928 13455 24929 13453 24929 13458 24929 13458 24930 13454 24930 13457 24930 13207 24931 13457 24931 13205 24931 13459 24932 13457 24932 13207 24932 13460 24933 13457 24933 13459 24933 13460 24934 13458 24934 13457 24934 13455 24935 13458 24935 13460 24935 13461 24936 13207 24936 13209 24936 13461 24937 13459 24937 13207 24937 13462 24938 13459 24938 13461 24938 13462 24939 13460 24939 13459 24939 13463 24940 13460 24940 13462 24940 13463 24941 13455 24941 13460 24941 13461 24942 13209 24942 13210 24942 13464 24943 13462 24943 13461 24943 13464 24944 13461 24944 13210 24944 13465 24945 13462 24945 13464 24945 13463 24946 13462 24946 13465 24946 13466 24947 13210 24947 13212 24947 13466 24948 13464 24948 13210 24948 13467 24949 13464 24949 13466 24949 13465 24950 13464 24950 13467 24950 13213 24951 13466 24951 13212 24951 13213 24952 13467 24952 13466 24952 13468 24953 13467 24953 13213 24953 13469 24954 13465 24954 13467 24954 13470 24955 13213 24955 13214 24955 13469 24956 13467 24956 13468 24956 13468 24957 13213 24957 13470 24957 13471 24958 13468 24958 13470 24958 13470 24959 13214 24959 13216 24959 13473 24960 13465 24960 13469 24960 13471 24961 13469 24961 13468 24961 13472 24962 13470 24962 13216 24962 13473 24963 13469 24963 13471 24963 13474 24964 13470 24964 13472 24964 13474 24965 13471 24965 13470 24965 13473 24966 13471 24966 13474 24966 13218 24967 13472 24967 13216 24967 13475 24968 13472 24968 13218 24968 13475 24969 13474 24969 13472 24969 13476 24970 13473 24970 13474 24970 13476 24971 13474 24971 13475 24971 13219 24972 13475 24972 13218 24972 13477 24973 13475 24973 13219 24973 13479 24974 13473 24974 13476 24974 13477 24975 13476 24975 13475 24975 13478 24976 13219 24976 13220 24976 13478 24977 13477 24977 13219 24977 13480 24978 13476 24978 13477 24978 13479 24979 13476 24979 13480 24979 13480 24980 13477 24980 13478 24980 13481 24981 13478 24981 13220 24981 13482 24982 13478 24982 13481 24982 13483 24983 13479 24983 13480 24983 13482 24984 13480 24984 13478 24984 13484 24985 13482 24985 13481 24985 13485 24986 13482 24986 13484 24986 13222 24987 13484 24987 13481 24987 13485 24988 13480 24988 13482 24988 13483 24989 13480 24989 13485 24989 13486 24990 13484 24990 13222 24990 13486 24991 13485 24991 13484 24991 13487 24992 13485 24992 13486 24992 13486 24993 13222 24993 13224 24993 13483 24994 13485 24994 13487 24994 13488 24995 13483 24995 13487 24995 13489 24996 13224 24996 13225 24996 13489 24997 13486 24997 13224 24997 13489 24998 13487 24998 13486 24998 13490 24999 13487 24999 13489 24999 13488 25000 13487 25000 13490 25000 13392 25001 13489 25001 13225 25001 13392 25002 13225 25002 13158 25002 13490 25003 13489 25003 13392 25003 12491 25004 13450 25004 13455 25004 12494 25005 13450 25005 12491 25005 12489 25006 12491 25006 13455 25006 12494 25007 13443 25007 13450 25007 12487 25008 12489 25008 13455 25008 12496 25009 13443 25009 12494 25009 12487 25010 13455 25010 13463 25010 12496 25011 13440 25011 13443 25011 12487 25012 13463 25012 13465 25012 12498 25013 13440 25013 12496 25013 12485 25014 12487 25014 13465 25014 12498 25015 13433 25015 13440 25015 12485 25016 13465 25016 13473 25016 12500 25017 13433 25017 12498 25017 12483 25018 12485 25018 13473 25018 12502 25019 13433 25019 12500 25019 12502 25020 13426 25020 13433 25020 12481 25021 13473 25021 13479 25021 12481 25022 12483 25022 13473 25022 12504 25023 13426 25023 12502 25023 13483 25024 12481 25024 13479 25024 12479 25025 12481 25025 13483 25025 13422 25026 13426 25026 12504 25026 13483 25027 12476 25027 12479 25027 13422 25028 12504 25028 12506 25028 13488 25029 12476 25029 13483 25029 13422 25030 12506 25030 12508 25030 13415 25031 13422 25031 12508 25031 13396 25032 12476 25032 13488 25032 13396 25033 12517 25033 12476 25033 13415 25034 12508 25034 12510 25034 13396 25035 12515 25035 12517 25035 13398 25036 12515 25036 13396 25036 13405 25037 13415 25037 12510 25037 13405 25038 12510 25038 12512 25038 13405 25039 12515 25039 13398 25039 13405 25040 12513 25040 12515 25040 13405 25041 12512 25041 12513 25041 13492 25042 13567 25042 13491 25042 13493 25043 13492 25043 13491 25043 13493 25044 13491 25044 13494 25044 13495 25045 13493 25045 13494 25045 13496 25046 13495 25046 13494 25046 13496 25047 13494 25047 13497 25047 13498 25048 13496 25048 13497 25048 13499 25049 13498 25049 13497 25049 13499 25050 13497 25050 13500 25050 13501 25051 13499 25051 13500 25051 13502 25052 13501 25052 13500 25052 13760 25053 13502 25053 13500 25053 13760 25054 13500 25054 13503 25054 13504 25055 13760 25055 13503 25055 13505 25056 13504 25056 13503 25056 13506 25057 13505 25057 13503 25057 13506 25058 13503 25058 13507 25058 13508 25059 13506 25059 13507 25059 13509 25060 13507 25060 13510 25060 13509 25061 13508 25061 13507 25061 13511 25062 13509 25062 13510 25062 13512 25063 13510 25063 13513 25063 13512 25064 13511 25064 13510 25064 13514 25065 13512 25065 13513 25065 13774 25066 13514 25066 13513 25066 13774 25067 13513 25067 13515 25067 13516 25068 13774 25068 13515 25068 13517 25069 13516 25069 13515 25069 13517 25070 13515 25070 13518 25070 13519 25071 13517 25071 13518 25071 13520 25072 13519 25072 13518 25072 13520 25073 13518 25073 13521 25073 13522 25074 13520 25074 13521 25074 13523 25075 13522 25075 13521 25075 13524 25076 13523 25076 13521 25076 13525 25077 13521 25077 13526 25077 13525 25078 13524 25078 13521 25078 13527 25079 13525 25079 13526 25079 13788 25080 13526 25080 13528 25080 13788 25081 13527 25081 13526 25081 13529 25082 13788 25082 13528 25082 13530 25083 13529 25083 13528 25083 13530 25084 13528 25084 13531 25084 13532 25085 13530 25085 13531 25085 13533 25086 13532 25086 13531 25086 13534 25087 13533 25087 13531 25087 13534 25088 13531 25088 13535 25088 13536 25089 13534 25089 13535 25089 13536 25090 13535 25090 13537 25090 13538 25091 13536 25091 13537 25091 13539 25092 13537 25092 13540 25092 13539 25093 13538 25093 13537 25093 13541 25094 13539 25094 13540 25094 13542 25095 13541 25095 13540 25095 13543 25096 13540 25096 13544 25096 13543 25097 13542 25097 13540 25097 13545 25098 13543 25098 13544 25098 13546 25099 13545 25099 13544 25099 13546 25100 13544 25100 13547 25100 13548 25101 13546 25101 13547 25101 13549 25102 13548 25102 13547 25102 13550 25103 13547 25103 13551 25103 13550 25104 13549 25104 13547 25104 13552 25105 13550 25105 13551 25105 13553 25106 13552 25106 13551 25106 13553 25107 13551 25107 13554 25107 13555 25108 13553 25108 13554 25108 13556 25109 13555 25109 13554 25109 13556 25110 13554 25110 13557 25110 13558 25111 13556 25111 13557 25111 13559 25112 13558 25112 13557 25112 13559 25113 13557 25113 13560 25113 13561 25114 13559 25114 13560 25114 13562 25115 13561 25115 13560 25115 13563 25116 13562 25116 13560 25116 13563 25117 13560 25117 13564 25117 13565 25118 13563 25118 13564 25118 13566 25119 13565 25119 13564 25119 13566 25120 13564 25120 13491 25120 13567 25121 13566 25121 13491 25121 13568 25122 13569 25122 13570 25122 13568 25123 13570 25123 13571 25123 13568 25124 13571 25124 13572 25124 13573 25125 13568 25125 13572 25125 13573 25126 13572 25126 13574 25126 13575 25127 13574 25127 13576 25127 13575 25128 13573 25128 13574 25128 13575 25129 13576 25129 13577 25129 13578 25130 13575 25130 13577 25130 13578 25131 13577 25131 13731 25131 13578 25132 13731 25132 13579 25132 13580 25133 13579 25133 13581 25133 13580 25134 13578 25134 13579 25134 13580 25135 13581 25135 13582 25135 13580 25136 13582 25136 13583 25136 13584 25137 13583 25137 13585 25137 13584 25138 13580 25138 13583 25138 13584 25139 13585 25139 13586 25139 13584 25140 13586 25140 13587 25140 13588 25141 13584 25141 13587 25141 13588 25142 13587 25142 13589 25142 13588 25143 13589 25143 13590 25143 13588 25144 13590 25144 13591 25144 13592 25145 13588 25145 13591 25145 13592 25146 13591 25146 13593 25146 13592 25147 13593 25147 13712 25147 13594 25148 13592 25148 13712 25148 13594 25149 13712 25149 13710 25149 13594 25150 13710 25150 13595 25150 13594 25151 13595 25151 13596 25151 13597 25152 13594 25152 13596 25152 13597 25153 13596 25153 13598 25153 13597 25154 13598 25154 13599 25154 13597 25155 13599 25155 13600 25155 13601 25156 13600 25156 13602 25156 13601 25157 13597 25157 13600 25157 13601 25158 13602 25158 13603 25158 13604 25159 13603 25159 13605 25159 13604 25160 13601 25160 13603 25160 13604 25161 13605 25161 13606 25161 13604 25162 13606 25162 13607 25162 13608 25163 13604 25163 13607 25163 13608 25164 13607 25164 13609 25164 13608 25165 13609 25165 13610 25165 13608 25166 13610 25166 13611 25166 13612 25167 13608 25167 13611 25167 13612 25168 13611 25168 13613 25168 13612 25169 13613 25169 13615 25169 13614 25170 13612 25170 13615 25170 13614 25171 13615 25171 13681 25171 13614 25172 13681 25172 13616 25172 13617 25173 13614 25173 13616 25173 13617 25174 13616 25174 13618 25174 13617 25175 13618 25175 13675 25175 13619 25176 13675 25176 13620 25176 13619 25177 13617 25177 13675 25177 13619 25178 13620 25178 13621 25178 13619 25179 13621 25179 13622 25179 13623 25180 13619 25180 13622 25180 13623 25181 13622 25181 13667 25181 13623 25182 13667 25182 13624 25182 13625 25183 13623 25183 13624 25183 13625 25184 13624 25184 13626 25184 13625 25185 13626 25185 13627 25185 13628 25186 13627 25186 13629 25186 13628 25187 13625 25187 13627 25187 13630 25188 13629 25188 13631 25188 13630 25189 13628 25189 13629 25189 13630 25190 13631 25190 13655 25190 13630 25191 13655 25191 13632 25191 13633 25192 13630 25192 13632 25192 13633 25193 13632 25193 13651 25193 13634 25194 13633 25194 13651 25194 13634 25195 13651 25195 13649 25195 13634 25196 13646 25196 13643 25196 13634 25197 13649 25197 13646 25197 13635 25198 13634 25198 13643 25198 13635 25199 13643 25199 13642 25199 13636 25200 13635 25200 13642 25200 13636 25201 13642 25201 13637 25201 13636 25202 13637 25202 13569 25202 13568 25203 13636 25203 13569 25203 13637 25204 13638 25204 13569 25204 13640 25205 13744 25205 13639 25205 13637 25206 13639 25206 13638 25206 13641 25207 13639 25207 13637 25207 13640 25208 13639 25208 13641 25208 13641 25209 13637 25209 13642 25209 13645 25210 13640 25210 13641 25210 13644 25211 13640 25211 13645 25211 13643 25212 13641 25212 13642 25212 13645 25213 13641 25213 13643 25213 13647 25214 13644 25214 13645 25214 13648 25215 13643 25215 13646 25215 13648 25216 13645 25216 13643 25216 13647 25217 13645 25217 13648 25217 13649 25218 13648 25218 13646 25218 13650 25219 13648 25219 13649 25219 13650 25220 13647 25220 13648 25220 13647 25221 13653 25221 13644 25221 13650 25222 13649 25222 13651 25222 13652 25223 13651 25223 13632 25223 13653 25224 13647 25224 13650 25224 13652 25225 13650 25225 13651 25225 13654 25226 13650 25226 13652 25226 13653 25227 13650 25227 13654 25227 13655 25228 13652 25228 13632 25228 13655 25229 13654 25229 13652 25229 13656 25230 13653 25230 13654 25230 13657 25231 13654 25231 13655 25231 13658 25232 13655 25232 13631 25232 13656 25233 13654 25233 13657 25233 13657 25234 13655 25234 13658 25234 13659 25235 13653 25235 13656 25235 13629 25236 13658 25236 13631 25236 13660 25237 13656 25237 13657 25237 13659 25238 13656 25238 13660 25238 13660 25239 13657 25239 13658 25239 13661 25240 13658 25240 13629 25240 13661 25241 13660 25241 13658 25241 13627 25242 13661 25242 13629 25242 13662 25243 13661 25243 13627 25243 13662 25244 13660 25244 13661 25244 13663 25245 13660 25245 13662 25245 13659 25246 13660 25246 13663 25246 13626 25247 13662 25247 13627 25247 13664 25248 13662 25248 13626 25248 13664 25249 13663 25249 13662 25249 13665 25250 13659 25250 13663 25250 13665 25251 13663 25251 13664 25251 13666 25252 13626 25252 13624 25252 13666 25253 13664 25253 13626 25253 13669 25254 13659 25254 13665 25254 13667 25255 13666 25255 13624 25255 13668 25256 13666 25256 13667 25256 13668 25257 13664 25257 13666 25257 13668 25258 13665 25258 13664 25258 13669 25259 13665 25259 13668 25259 13670 25260 13668 25260 13667 25260 13670 25261 13667 25261 13622 25261 13669 25262 13668 25262 13670 25262 13672 25263 13669 25263 13670 25263 13671 25264 13669 25264 13672 25264 13672 25265 13670 25265 13622 25265 13673 25266 13622 25266 13621 25266 13673 25267 13672 25267 13622 25267 13673 25268 13621 25268 13620 25268 13674 25269 13672 25269 13673 25269 13675 25270 13673 25270 13620 25270 13676 25271 13672 25271 13674 25271 13676 25272 13671 25272 13672 25272 13674 25273 13673 25273 13675 25273 13677 25274 13671 25274 13676 25274 13678 25275 13675 25275 13618 25275 13678 25276 13674 25276 13675 25276 13676 25277 13674 25277 13678 25277 13679 25278 13678 25278 13618 25278 13679 25279 13618 25279 13616 25279 13676 25280 13678 25280 13679 25280 13680 25281 13676 25281 13679 25281 13681 25282 13679 25282 13616 25282 13677 25283 13676 25283 13680 25283 13680 25284 13679 25284 13681 25284 13683 25285 13677 25285 13680 25285 13682 25286 13680 25286 13681 25286 13682 25287 13681 25287 13615 25287 13683 25288 13680 25288 13682 25288 13684 25289 13683 25289 13682 25289 13685 25290 13682 25290 13615 25290 13685 25291 13684 25291 13682 25291 13685 25292 13615 25292 13613 25292 13686 25293 13685 25293 13613 25293 13687 25294 13684 25294 13685 25294 13687 25295 13683 25295 13684 25295 13688 25296 13685 25296 13686 25296 13611 25297 13686 25297 13613 25297 13687 25298 13685 25298 13688 25298 13610 25299 13686 25299 13611 25299 13689 25300 13686 25300 13610 25300 13689 25301 13688 25301 13686 25301 13690 25302 13688 25302 13689 25302 13690 25303 13687 25303 13688 25303 13691 25304 13687 25304 13690 25304 13692 25305 13610 25305 13609 25305 13692 25306 13689 25306 13610 25306 13690 25307 13689 25307 13692 25307 13692 25308 13609 25308 13607 25308 13693 25309 13690 25309 13692 25309 13694 25310 13692 25310 13607 25310 13694 25311 13693 25311 13692 25311 13694 25312 13607 25312 13606 25312 13691 25313 13690 25313 13693 25313 13695 25314 13694 25314 13606 25314 13695 25315 13693 25315 13694 25315 13695 25316 13606 25316 13605 25316 13696 25317 13693 25317 13695 25317 13696 25318 13691 25318 13693 25318 13697 25319 13605 25319 13603 25319 13697 25320 13695 25320 13605 25320 13698 25321 13691 25321 13696 25321 13696 25322 13695 25322 13697 25322 13700 25323 13696 25323 13697 25323 13602 25324 13697 25324 13603 25324 13700 25325 13698 25325 13696 25325 13701 25326 13697 25326 13602 25326 13699 25327 13698 25327 13700 25327 13701 25328 13700 25328 13697 25328 13701 25329 13602 25329 13600 25329 13702 25330 13701 25330 13600 25330 13702 25331 13700 25331 13701 25331 13703 25332 13700 25332 13702 25332 13702 25333 13600 25333 13599 25333 13703 25334 13699 25334 13700 25334 13704 25335 13702 25335 13599 25335 13706 25336 13699 25336 13703 25336 13704 25337 13703 25337 13702 25337 13705 25338 13599 25338 13598 25338 13705 25339 13704 25339 13599 25339 13705 25340 13703 25340 13704 25340 13706 25341 13703 25341 13705 25341 13596 25342 13705 25342 13598 25342 13707 25343 13705 25343 13596 25343 13707 25344 13596 25344 13595 25344 13708 25345 13705 25345 13707 25345 13709 25346 13705 25346 13708 25346 13709 25347 13706 25347 13705 25347 13710 25348 13707 25348 13595 25348 13708 25349 13707 25349 13710 25349 13713 25350 13706 25350 13709 25350 13711 25351 13708 25351 13710 25351 13711 25352 13709 25352 13708 25352 13711 25353 13710 25353 13712 25353 13713 25354 13709 25354 13711 25354 13714 25355 13711 25355 13712 25355 13715 25356 13711 25356 13714 25356 13715 25357 13713 25357 13711 25357 13593 25358 13714 25358 13712 25358 13716 25359 13714 25359 13593 25359 13717 25360 13713 25360 13715 25360 13716 25361 13715 25361 13714 25361 13718 25362 13715 25362 13716 25362 13591 25363 13716 25363 13593 25363 13717 25364 13715 25364 13718 25364 13719 25365 13716 25365 13591 25365 13719 25366 13718 25366 13716 25366 13719 25367 13591 25367 13590 25367 13721 25368 13717 25368 13718 25368 13589 25369 13719 25369 13590 25369 13720 25370 13718 25370 13719 25370 13721 25371 13718 25371 13720 25371 13722 25372 13719 25372 13589 25372 13722 25373 13720 25373 13719 25373 13722 25374 13589 25374 13587 25374 13723 25375 13722 25375 13587 25375 13724 25376 13722 25376 13723 25376 13724 25377 13720 25377 13722 25377 13724 25378 13721 25378 13720 25378 13723 25379 13587 25379 13586 25379 13585 25380 13723 25380 13586 25380 13725 25381 13723 25381 13585 25381 13724 25382 13723 25382 13725 25382 13725 25383 13585 25383 13583 25383 13726 25384 13725 25384 13583 25384 13727 25385 13721 25385 13724 25385 13726 25386 13583 25386 13582 25386 13727 25387 13724 25387 13725 25387 13728 25388 13726 25388 13582 25388 13729 25389 13726 25389 13728 25389 13729 25390 13725 25390 13726 25390 13728 25391 13582 25391 13581 25391 13727 25392 13725 25392 13729 25392 13579 25393 13728 25393 13581 25393 13732 25394 13727 25394 13729 25394 13730 25395 13728 25395 13579 25395 13730 25396 13729 25396 13728 25396 13730 25397 13579 25397 13731 25397 13732 25398 13729 25398 13730 25398 13733 25399 13730 25399 13731 25399 13733 25400 13731 25400 13577 25400 13734 25401 13730 25401 13733 25401 13734 25402 13732 25402 13730 25402 13735 25403 13577 25403 13576 25403 13735 25404 13733 25404 13577 25404 13735 25405 13734 25405 13733 25405 13736 25406 13734 25406 13735 25406 13737 25407 13735 25407 13576 25407 13738 25408 13734 25408 13736 25408 13738 25409 13732 25409 13734 25409 13737 25410 13736 25410 13735 25410 13574 25411 13737 25411 13576 25411 13739 25412 13736 25412 13737 25412 13739 25413 13738 25413 13736 25413 13740 25414 13737 25414 13574 25414 13739 25415 13737 25415 13740 25415 13740 25416 13574 25416 13572 25416 13741 25417 13738 25417 13739 25417 13742 25418 13740 25418 13572 25418 13741 25419 13740 25419 13742 25419 13741 25420 13739 25420 13740 25420 13742 25421 13572 25421 13571 25421 13743 25422 13738 25422 13741 25422 13570 25423 13742 25423 13571 25423 13744 25424 13743 25424 13741 25424 13745 25425 13741 25425 13742 25425 13638 25426 13742 25426 13570 25426 13744 25427 13741 25427 13745 25427 13638 25428 13745 25428 13742 25428 13638 25429 13570 25429 13569 25429 13745 25430 13638 25430 13639 25430 13744 25431 13745 25431 13639 25431 13640 25432 13743 25432 13744 25432 13280 25433 13653 25433 13278 25433 13278 25434 13653 25434 13659 25434 13276 25435 13278 25435 13659 25435 13284 25436 13644 25436 13653 25436 13284 25437 13653 25437 13280 25437 13273 25438 13276 25438 13659 25438 13286 25439 13644 25439 13284 25439 13273 25440 13659 25440 13669 25440 13286 25441 13640 25441 13644 25441 13270 25442 13273 25442 13669 25442 13226 25443 13640 25443 13286 25443 13226 25444 13743 25444 13640 25444 13270 25445 13669 25445 13671 25445 13229 25446 13743 25446 13226 25446 13269 25447 13270 25447 13671 25447 13677 25448 13269 25448 13671 25448 13738 25449 13743 25449 13229 25449 13231 25450 13738 25450 13229 25450 13266 25451 13269 25451 13677 25451 13732 25452 13738 25452 13231 25452 13263 25453 13266 25453 13677 25453 13732 25454 13231 25454 13234 25454 13683 25455 13263 25455 13677 25455 13683 25456 13261 25456 13263 25456 13727 25457 13234 25457 13236 25457 13727 25458 13732 25458 13234 25458 13687 25459 13261 25459 13683 25459 13687 25460 13258 25460 13261 25460 13691 25461 13258 25461 13687 25461 13239 25462 13727 25462 13236 25462 13721 25463 13727 25463 13239 25463 13691 25464 13255 25464 13258 25464 13698 25465 13255 25465 13691 25465 13698 25466 13252 25466 13255 25466 13721 25467 13239 25467 13243 25467 13717 25468 13721 25468 13243 25468 13699 25469 13252 25469 13698 25469 13717 25470 13243 25470 13244 25470 13706 25471 13252 25471 13699 25471 13706 25472 13250 25472 13252 25472 13717 25473 13244 25473 13245 25473 13713 25474 13717 25474 13245 25474 13706 25475 13247 25475 13250 25475 13706 25476 13245 25476 13247 25476 13706 25477 13713 25477 13245 25477 13492 25478 13746 25478 13567 25478 13748 25479 13747 25479 13746 25479 13748 25480 13746 25480 13492 25480 13750 25481 13747 25481 13748 25481 13748 25482 13492 25482 13493 25482 13750 25483 13749 25483 13747 25483 13751 25484 13748 25484 13493 25484 13751 25485 13750 25485 13748 25485 13752 25486 13750 25486 13751 25486 13495 25487 13751 25487 13493 25487 13751 25488 13495 25488 13496 25488 13753 25489 13750 25489 13752 25489 13755 25490 13496 25490 13498 25490 13755 25491 13751 25491 13496 25491 13754 25492 13753 25492 13752 25492 13755 25493 13752 25493 13751 25493 13754 25494 13752 25494 13755 25494 13756 25495 13755 25495 13498 25495 13499 25496 13756 25496 13498 25496 13758 25497 13753 25497 13754 25497 13756 25498 13754 25498 13755 25498 13758 25499 13754 25499 13756 25499 13757 25500 13756 25500 13499 25500 13757 25501 13499 25501 13501 25501 13758 25502 13756 25502 13757 25502 13502 25503 13757 25503 13501 25503 13759 25504 13758 25504 13757 25504 13759 25505 13757 25505 13502 25505 13759 25506 13502 25506 13760 25506 13761 25507 13759 25507 13760 25507 13762 25508 13759 25508 13761 25508 13762 25509 13758 25509 13759 25509 13504 25510 13761 25510 13760 25510 13764 25511 13758 25511 13762 25511 13761 25512 13504 25512 13505 25512 13763 25513 13761 25513 13505 25513 13763 25514 13762 25514 13761 25514 13764 25515 13762 25515 13763 25515 13763 25516 13505 25516 13506 25516 13765 25517 13763 25517 13506 25517 13765 25518 13764 25518 13763 25518 13767 25519 13764 25519 13765 25519 13765 25520 13506 25520 13766 25520 13766 25521 13506 25521 13508 25521 13768 25522 13765 25522 13766 25522 13767 25523 13765 25523 13768 25523 13509 25524 13766 25524 13508 25524 13769 25525 13766 25525 13509 25525 13769 25526 13768 25526 13766 25526 13770 25527 13768 25527 13769 25527 13770 25528 13767 25528 13768 25528 13511 25529 13769 25529 13509 25529 13770 25530 13769 25530 13511 25530 13771 25531 13770 25531 13511 25531 13771 25532 13511 25532 13512 25532 13772 25533 13770 25533 13771 25533 13772 25534 13767 25534 13770 25534 13514 25535 13771 25535 13512 25535 13773 25536 13772 25536 13771 25536 13774 25537 13771 25537 13514 25537 13773 25538 13771 25538 13774 25538 13776 25539 13772 25539 13773 25539 13775 25540 13773 25540 13774 25540 13777 25541 13773 25541 13775 25541 13775 25542 13774 25542 13516 25542 13776 25543 13773 25543 13777 25543 13517 25544 13775 25544 13516 25544 13779 25545 13777 25545 13775 25545 13778 25546 13772 25546 13776 25546 13778 25547 13777 25547 13779 25547 13778 25548 13776 25548 13777 25548 13779 25549 13775 25549 13517 25549 13519 25550 13779 25550 13517 25550 13780 25551 13779 25551 13519 25551 13780 25552 13778 25552 13779 25552 13781 25553 13778 25553 13780 25553 13780 25554 13519 25554 13520 25554 13782 25555 13780 25555 13520 25555 13783 25556 13781 25556 13780 25556 13782 25557 13520 25557 13522 25557 13783 25558 13780 25558 13782 25558 13782 25559 13522 25559 13523 25559 13784 25560 13782 25560 13523 25560 13784 25561 13783 25561 13782 25561 13785 25562 13781 25562 13783 25562 13784 25563 13523 25563 13524 25563 13525 25564 13784 25564 13524 25564 13785 25565 13783 25565 13784 25565 13786 25566 13784 25566 13525 25566 13787 25567 13784 25567 13786 25567 13787 25568 13785 25568 13784 25568 13527 25569 13786 25569 13525 25569 13790 25570 13785 25570 13787 25570 13788 25571 13786 25571 13527 25571 13789 25572 13787 25572 13786 25572 13790 25573 13787 25573 13789 25573 13789 25574 13786 25574 13788 25574 13789 25575 13788 25575 13791 25575 13791 25576 13788 25576 13529 25576 13792 25577 13789 25577 13791 25577 13790 25578 13789 25578 13792 25578 13530 25579 13791 25579 13529 25579 13792 25580 13791 25580 13530 25580 13794 25581 13530 25581 13532 25581 13795 25582 13790 25582 13792 25582 13793 25583 13790 25583 13795 25583 13794 25584 13792 25584 13530 25584 13795 25585 13792 25585 13794 25585 13533 25586 13794 25586 13532 25586 13796 25587 13794 25587 13533 25587 13796 25588 13795 25588 13794 25588 13798 25589 13795 25589 13796 25589 13798 25590 13793 25590 13795 25590 13797 25591 13793 25591 13798 25591 13534 25592 13796 25592 13533 25592 13797 25593 13798 25593 13796 25593 13799 25594 13796 25594 13534 25594 13799 25595 13797 25595 13796 25595 13536 25596 13799 25596 13534 25596 13800 25597 13797 25597 13799 25597 13802 25598 13797 25598 13800 25598 13801 25599 13799 25599 13536 25599 13800 25600 13799 25600 13801 25600 13801 25601 13536 25601 13538 25601 13801 25602 13802 25602 13800 25602 13804 25603 13538 25603 13539 25603 13803 25604 13802 25604 13801 25604 13804 25605 13801 25605 13538 25605 13803 25606 13801 25606 13804 25606 13805 25607 13539 25607 13541 25607 13805 25608 13804 25608 13539 25608 13806 25609 13804 25609 13805 25609 13806 25610 13803 25610 13804 25610 13806 25611 13802 25611 13803 25611 13807 25612 13805 25612 13541 25612 13808 25613 13802 25613 13806 25613 13807 25614 13806 25614 13805 25614 13807 25615 13541 25615 13542 25615 13809 25616 13806 25616 13807 25616 13810 25617 13807 25617 13542 25617 13810 25618 13542 25618 13543 25618 13811 25619 13806 25619 13809 25619 13811 25620 13808 25620 13806 25620 13810 25621 13809 25621 13807 25621 13812 25622 13809 25622 13810 25622 13811 25623 13809 25623 13812 25623 13812 25624 13810 25624 13543 25624 13813 25625 13543 25625 13545 25625 13813 25626 13812 25626 13543 25626 13814 25627 13812 25627 13813 25627 13815 25628 13813 25628 13545 25628 13815 25629 13545 25629 13546 25629 13811 25630 13812 25630 13814 25630 13815 25631 13814 25631 13813 25631 13817 25632 13808 25632 13811 25632 13817 25633 13811 25633 13814 25633 13548 25634 13815 25634 13546 25634 13816 25635 13815 25635 13548 25635 13818 25636 13815 25636 13816 25636 13818 25637 13814 25637 13815 25637 13817 25638 13814 25638 13818 25638 13549 25639 13816 25639 13548 25639 13819 25640 13818 25640 13816 25640 13820 25641 13816 25641 13549 25641 13819 25642 13816 25642 13820 25642 13820 25643 13549 25643 13550 25643 13821 25644 13817 25644 13818 25644 13822 25645 13818 25645 13819 25645 13822 25646 13821 25646 13818 25646 13822 25647 13819 25647 13820 25647 13822 25648 13820 25648 13550 25648 13823 25649 13822 25649 13550 25649 13824 25650 13822 25650 13823 25650 13552 25651 13823 25651 13550 25651 13824 25652 13821 25652 13822 25652 13826 25653 13824 25653 13823 25653 13553 25654 13823 25654 13552 25654 13825 25655 13824 25655 13826 25655 13825 25656 13821 25656 13824 25656 13826 25657 13823 25657 13553 25657 13827 25658 13553 25658 13555 25658 13827 25659 13826 25659 13553 25659 13827 25660 13555 25660 13556 25660 13828 25661 13825 25661 13826 25661 13825 25662 13830 25662 13821 25662 13828 25663 13826 25663 13827 25663 13829 25664 13827 25664 13556 25664 13830 25665 13825 25665 13828 25665 13829 25666 13828 25666 13827 25666 13829 25667 13556 25667 13558 25667 13831 25668 13828 25668 13829 25668 13832 25669 13829 25669 13558 25669 13830 25670 13828 25670 13831 25670 13832 25671 13831 25671 13829 25671 13832 25672 13558 25672 13559 25672 13834 25673 13832 25673 13559 25673 13833 25674 13830 25674 13831 25674 13834 25675 13831 25675 13832 25675 13561 25676 13834 25676 13559 25676 13833 25677 13831 25677 13834 25677 13835 25678 13561 25678 13562 25678 13835 25679 13834 25679 13561 25679 13836 25680 13834 25680 13835 25680 13833 25681 13834 25681 13836 25681 13837 25682 13833 25682 13836 25682 13563 25683 13835 25683 13562 25683 13838 25684 13835 25684 13563 25684 13836 25685 13835 25685 13838 25685 13839 25686 13837 25686 13836 25686 13839 25687 13836 25687 13838 25687 13840 25688 13839 25688 13838 25688 13840 25689 13563 25689 13565 25689 13840 25690 13838 25690 13563 25690 13841 25691 13840 25691 13565 25691 13841 25692 13839 25692 13840 25692 13843 25693 13839 25693 13841 25693 13843 25694 13837 25694 13839 25694 13749 25695 13837 25695 13843 25695 13842 25696 13565 25696 13566 25696 13842 25697 13841 25697 13565 25697 13843 25698 13841 25698 13842 25698 13842 25699 13566 25699 13567 25699 13747 25700 13842 25700 13567 25700 13747 25701 13567 25701 13746 25701 13747 25702 13843 25702 13842 25702 13749 25703 13843 25703 13747 25703 13203 25704 13200 25704 13808 25704 13200 25705 13802 25705 13808 25705 13206 25706 13203 25706 13808 25706 13197 25707 13802 25707 13200 25707 13197 25708 13797 25708 13802 25708 13206 25709 13808 25709 13817 25709 13208 25710 13206 25710 13817 25710 13194 25711 13797 25711 13197 25711 13194 25712 13793 25712 13797 25712 13211 25713 13208 25713 13817 25713 13192 25714 13793 25714 13194 25714 13192 25715 13790 25715 13793 25715 13211 25716 13817 25716 13821 25716 13188 25717 13790 25717 13192 25717 13215 25718 13211 25718 13821 25718 13215 25719 13821 25719 13830 25719 13188 25720 13785 25720 13790 25720 13217 25721 13215 25721 13830 25721 13185 25722 13785 25722 13188 25722 13185 25723 13781 25723 13785 25723 13217 25724 13830 25724 13833 25724 13181 25725 13781 25725 13185 25725 13833 25726 13221 25726 13217 25726 13778 25727 13781 25727 13181 25727 13837 25728 13221 25728 13833 25728 13178 25729 13778 25729 13181 25729 13837 25730 13223 25730 13221 25730 13772 25731 13778 25731 13178 25731 13749 25732 13223 25732 13837 25732 13772 25733 13178 25733 13173 25733 13749 25734 13159 25734 13223 25734 13767 25735 13772 25735 13173 25735 13750 25736 13159 25736 13749 25736 13767 25737 13173 25737 13171 25737 13750 25738 13161 25738 13159 25738 13753 25739 13161 25739 13750 25739 13764 25740 13767 25740 13171 25740 13764 25741 13171 25741 13168 25741 13753 25742 13164 25742 13161 25742 13758 25743 13764 25743 13168 25743 13758 25744 13164 25744 13753 25744 13758 25745 13168 25745 13164 25745 13846 25746 13844 25746 13845 25746 13847 25747 13846 25747 13845 25747 13847 25748 13845 25748 13848 25748 13849 25749 13847 25749 13848 25749 13849 25750 13848 25750 13850 25750 13851 25751 13849 25751 13850 25751 13852 25752 13851 25752 13850 25752 13852 25753 13850 25753 13853 25753 13854 25754 13852 25754 13853 25754 13855 25755 13854 25755 13853 25755 13855 25756 13853 25756 13856 25756 13857 25757 13855 25757 13856 25757 14144 25758 13857 25758 13856 25758 13858 25759 14144 25759 13856 25759 13858 25760 13856 25760 13859 25760 13860 25761 13858 25761 13859 25761 13861 25762 13860 25762 13859 25762 13861 25763 13859 25763 13862 25763 13863 25764 13861 25764 13862 25764 13864 25765 13862 25765 13865 25765 13864 25766 13863 25766 13862 25766 13866 25767 13864 25767 13865 25767 13866 25768 13865 25768 13867 25768 13868 25769 13866 25769 13867 25769 13869 25770 13868 25770 13867 25770 13870 25771 13869 25771 13867 25771 13870 25772 13867 25772 13871 25772 13872 25773 13870 25773 13871 25773 13873 25774 13872 25774 13871 25774 13873 25775 13871 25775 13874 25775 13875 25776 13873 25776 13874 25776 13876 25777 13875 25777 13874 25777 13877 25778 13874 25778 13878 25778 13877 25779 13876 25779 13874 25779 13879 25780 13877 25780 13878 25780 13879 25781 13878 25781 13880 25781 13881 25782 13879 25782 13880 25782 13882 25783 13880 25783 13883 25783 13882 25784 13881 25784 13880 25784 13884 25785 13882 25785 13883 25785 13884 25786 13883 25786 13885 25786 13886 25787 13884 25787 13885 25787 13887 25788 13886 25788 13885 25788 13887 25789 13885 25789 13888 25789 13889 25790 13887 25790 13888 25790 13889 25791 13888 25791 13890 25791 13891 25792 13889 25792 13890 25792 13892 25793 13891 25793 13890 25793 13893 25794 13892 25794 13890 25794 13893 25795 13890 25795 13894 25795 13895 25796 13893 25796 13894 25796 13896 25797 13895 25797 13894 25797 13896 25798 13894 25798 13897 25798 13898 25799 13896 25799 13897 25799 13899 25800 13898 25800 13897 25800 13899 25801 13897 25801 13900 25801 13901 25802 13899 25802 13900 25802 13902 25803 13901 25803 13900 25803 13903 25804 13902 25804 13900 25804 13903 25805 13900 25805 13904 25805 13905 25806 13903 25806 13904 25806 13906 25807 13904 25807 13907 25807 13906 25808 13905 25808 13904 25808 13908 25809 13906 25809 13907 25809 13909 25810 13908 25810 13907 25810 13909 25811 13907 25811 13910 25811 13911 25812 13909 25812 13910 25812 13912 25813 13911 25813 13910 25813 13912 25814 13910 25814 13913 25814 13914 25815 13912 25815 13913 25815 13915 25816 13913 25816 13916 25816 13915 25817 13914 25817 13913 25817 13917 25818 13915 25818 13916 25818 13918 25819 13917 25819 13916 25819 13918 25820 13916 25820 13919 25820 13920 25821 13918 25821 13919 25821 13921 25822 13920 25822 13919 25822 13921 25823 13919 25823 13922 25823 13923 25824 13921 25824 13922 25824 13924 25825 13923 25825 13922 25825 13925 25826 13924 25826 13922 25826 13925 25827 13922 25827 13926 25827 13927 25828 13925 25828 13926 25828 13927 25829 13926 25829 13928 25829 13929 25830 13927 25830 13928 25830 13844 25831 13929 25831 13928 25831 13844 25832 13928 25832 13845 25832 13930 25833 13931 25833 13932 25833 13930 25834 13932 25834 13933 25834 13934 25835 13930 25835 13933 25835 13934 25836 13933 25836 13935 25836 13936 25837 13935 25837 13937 25837 13936 25838 13934 25838 13935 25838 13936 25839 13937 25839 13938 25839 13936 25840 13938 25840 13939 25840 13940 25841 13936 25841 13939 25841 13940 25842 13939 25842 13941 25842 13940 25843 13941 25843 13942 25843 13940 25844 13942 25844 13943 25844 13944 25845 13940 25845 13943 25845 13944 25846 13943 25846 13945 25846 13946 25847 13945 25847 13947 25847 13946 25848 13944 25848 13945 25848 13946 25849 13947 25849 13948 25849 13949 25850 13946 25850 13948 25850 13949 25851 13948 25851 13950 25851 13949 25852 13950 25852 13951 25852 13952 25853 13949 25853 13951 25853 13952 25854 13951 25854 13953 25854 13952 25855 13953 25855 13954 25855 13955 25856 13952 25856 13954 25856 13955 25857 13954 25857 13956 25857 13955 25858 13956 25858 13957 25858 13958 25859 13955 25859 13957 25859 13958 25860 13957 25860 13959 25860 13958 25861 13959 25861 13960 25861 13961 25862 13958 25862 13960 25862 13961 25863 13960 25863 13962 25863 13961 25864 13962 25864 13963 25864 13961 25865 13963 25865 13964 25865 13965 25866 13961 25866 13964 25866 13965 25867 13964 25867 13966 25867 13965 25868 13966 25868 13967 25868 13968 25869 13967 25869 13969 25869 13968 25870 13965 25870 13967 25870 13968 25871 13969 25871 13970 25871 13971 25872 13968 25872 13970 25872 13971 25873 13970 25873 13972 25873 13971 25874 13972 25874 13973 25874 13974 25875 13971 25875 13973 25875 13974 25876 13973 25876 13975 25876 13974 25877 13975 25877 13976 25877 13974 25878 13976 25878 13977 25878 13978 25879 13974 25879 13977 25879 13978 25880 13977 25880 13979 25880 13978 25881 13979 25881 13980 25881 13981 25882 13978 25882 13980 25882 13981 25883 13980 25883 13982 25883 13981 25884 13982 25884 13983 25884 13984 25885 13983 25885 13985 25885 13984 25886 13981 25886 13983 25886 13984 25887 13985 25887 13986 25887 13984 25888 13986 25888 13987 25888 13988 25889 13987 25889 13989 25889 13988 25890 13984 25890 13987 25890 13988 25891 13989 25891 13990 25891 13991 25892 13988 25892 13990 25892 13991 25893 13990 25893 13992 25893 13991 25894 13992 25894 13993 25894 13991 25895 13993 25895 14043 25895 13991 25896 14043 25896 13994 25896 13995 25897 13991 25897 13994 25897 13995 25898 13994 25898 13996 25898 13997 25899 13996 25899 14038 25899 13997 25900 13995 25900 13996 25900 13997 25901 14038 25901 13998 25901 13997 25902 13998 25902 13999 25902 14000 25903 13999 25903 14001 25903 14000 25904 13997 25904 13999 25904 14002 25905 14000 25905 14001 25905 14002 25906 14001 25906 14003 25906 14002 25907 14029 25907 14004 25907 14002 25908 14003 25908 14029 25908 14005 25909 14002 25909 14004 25909 14005 25910 14004 25910 14006 25910 14005 25911 14006 25911 14007 25911 14008 25912 14005 25912 14007 25912 14008 25913 14007 25913 14009 25913 14010 25914 14009 25914 14011 25914 14010 25915 14008 25915 14009 25915 14010 25916 14011 25916 13931 25916 13930 25917 14010 25917 13931 25917 14013 25918 14014 25918 14012 25918 14015 25919 14012 25919 13931 25919 14016 25920 14014 25920 14013 25920 14015 25921 14013 25921 14012 25921 14019 25922 14122 25922 14016 25922 14015 25923 13931 25923 14011 25923 14017 25924 14016 25924 14013 25924 14018 25925 14013 25925 14015 25925 14017 25926 14013 25926 14018 25926 14018 25927 14015 25927 14011 25927 14019 25928 14016 25928 14017 25928 14018 25929 14011 25929 14009 25929 14020 25930 14017 25930 14018 25930 14019 25931 14017 25931 14020 25931 14021 25932 14018 25932 14009 25932 14020 25933 14018 25933 14021 25933 14021 25934 14009 25934 14007 25934 14022 25935 14020 25935 14021 25935 14019 25936 14020 25936 14022 25936 14023 25937 14021 25937 14007 25937 14023 25938 14022 25938 14021 25938 14023 25939 14007 25939 14006 25939 14024 25940 14019 25940 14022 25940 14026 25941 14022 25941 14023 25941 14024 25942 14022 25942 14026 25942 14027 25943 14023 25943 14006 25943 14026 25944 14023 25944 14027 25944 14027 25945 14006 25945 14004 25945 14025 25946 14019 25946 14024 25946 14028 25947 14024 25947 14026 25947 14029 25948 14027 25948 14004 25948 14030 25949 14027 25949 14029 25949 14025 25950 14024 25950 14028 25950 14030 25951 14026 25951 14027 25951 14028 25952 14026 25952 14030 25952 14003 25953 14030 25953 14029 25953 14031 25954 14030 25954 14003 25954 14028 25955 14030 25955 14031 25955 14032 25956 14003 25956 14001 25956 14032 25957 14031 25957 14003 25957 14033 25958 14028 25958 14031 25958 14034 25959 14028 25959 14033 25959 14034 25960 14025 25960 14028 25960 14033 25961 14031 25961 14032 25961 13999 25962 14032 25962 14001 25962 13999 25963 14033 25963 14032 25963 14035 25964 14033 25964 13999 25964 14035 25965 14034 25965 14033 25965 14036 25966 13999 25966 13998 25966 14036 25967 14035 25967 13999 25967 14038 25968 14036 25968 13998 25968 14039 25969 14034 25969 14035 25969 14037 25970 14034 25970 14039 25970 14039 25971 14035 25971 14036 25971 14040 25972 14036 25972 14038 25972 14040 25973 14039 25973 14036 25973 14041 25974 14038 25974 13996 25974 14041 25975 14040 25975 14038 25975 14042 25976 14040 25976 14041 25976 14042 25977 14039 25977 14040 25977 13994 25978 14041 25978 13996 25978 14042 25979 14037 25979 14039 25979 14043 25980 14041 25980 13994 25980 14042 25981 14041 25981 14043 25981 14044 25982 14037 25982 14042 25982 14045 25983 14042 25983 14043 25983 14045 25984 14044 25984 14042 25984 14046 25985 14043 25985 13993 25985 14046 25986 14045 25986 14043 25986 14047 25987 14045 25987 14046 25987 14047 25988 14044 25988 14045 25988 14046 25989 13993 25989 13992 25989 14049 25990 14046 25990 13992 25990 14048 25991 14044 25991 14047 25991 14049 25992 14047 25992 14046 25992 14049 25993 13992 25993 13990 25993 14048 25994 14047 25994 14049 25994 14050 25995 14049 25995 13990 25995 14051 25996 14049 25996 14050 25996 14051 25997 14048 25997 14049 25997 13989 25998 14050 25998 13990 25998 14052 25999 14048 25999 14051 25999 13987 26000 14050 26000 13989 26000 14053 26001 14050 26001 13987 26001 14053 26002 14051 26002 14050 26002 14053 26003 14052 26003 14051 26003 13986 26004 14053 26004 13987 26004 14052 26005 14053 26005 14055 26005 14055 26006 14053 26006 13986 26006 14056 26007 13986 26007 13985 26007 14056 26008 14055 26008 13986 26008 14054 26009 14052 26009 14055 26009 13983 26010 14056 26010 13985 26010 14057 26011 14056 26011 13983 26011 14057 26012 14055 26012 14056 26012 14058 26013 14057 26013 13983 26013 14059 26014 14055 26014 14057 26014 14058 26015 13983 26015 13982 26015 14054 26016 14055 26016 14059 26016 14059 26017 14057 26017 14058 26017 14060 26018 13982 26018 13980 26018 14060 26019 14058 26019 13982 26019 14060 26020 14059 26020 14058 26020 14061 26021 14059 26021 14060 26021 14061 26022 14054 26022 14059 26022 14062 26023 14060 26023 13980 26023 14061 26024 14060 26024 14062 26024 14062 26025 13980 26025 13979 26025 14064 26026 14054 26026 14061 26026 14063 26027 14061 26027 14062 26027 14064 26028 14061 26028 14063 26028 14065 26029 13979 26029 13977 26029 14065 26030 14062 26030 13979 26030 14065 26031 14063 26031 14062 26031 14064 26032 14063 26032 14065 26032 14066 26033 14065 26033 13977 26033 14066 26034 13977 26034 13976 26034 14067 26035 14065 26035 14066 26035 14067 26036 14064 26036 14065 26036 13975 26037 14066 26037 13976 26037 14068 26038 14064 26038 14067 26038 13975 26039 14067 26039 14066 26039 14068 26040 14067 26040 13975 26040 14069 26041 13975 26041 13973 26041 14069 26042 14068 26042 13975 26042 14070 26043 14064 26043 14068 26043 14071 26044 14068 26044 14069 26044 14070 26045 14068 26045 14071 26045 14072 26046 13973 26046 13972 26046 14072 26047 14069 26047 13973 26047 14072 26048 14071 26048 14069 26048 14073 26049 14071 26049 14072 26049 13970 26050 14072 26050 13972 26050 14070 26051 14071 26051 14073 26051 14073 26052 14072 26052 13970 26052 14074 26053 14070 26053 14073 26053 14075 26054 14073 26054 13970 26054 14074 26055 14073 26055 14075 26055 13969 26056 14075 26056 13970 26056 13967 26057 14075 26057 13969 26057 14077 26058 14075 26058 13967 26058 14076 26059 14070 26059 14074 26059 14078 26060 14075 26060 14077 26060 14078 26061 14074 26061 14075 26061 14076 26062 14074 26062 14078 26062 14077 26063 13967 26063 13966 26063 14079 26064 14077 26064 13966 26064 14079 26065 14078 26065 14077 26065 14080 26066 14078 26066 14079 26066 14080 26067 14076 26067 14078 26067 14081 26068 14076 26068 14080 26068 14079 26069 13966 26069 13964 26069 14082 26070 14079 26070 13964 26070 14080 26071 14079 26071 14082 26071 13963 26072 14082 26072 13964 26072 14084 26073 14080 26073 14082 26073 14084 26074 14081 26074 14080 26074 14083 26075 14082 26075 13963 26075 14084 26076 14082 26076 14083 26076 14083 26077 13963 26077 13962 26077 14086 26078 14081 26078 14084 26078 14086 26079 14084 26079 14083 26079 13960 26080 14083 26080 13962 26080 14087 26081 14083 26081 13960 26081 14085 26082 14081 26082 14086 26082 14087 26083 14086 26083 14083 26083 14088 26084 13960 26084 13959 26084 14088 26085 14087 26085 13960 26085 14088 26086 14086 26086 14087 26086 14085 26087 14086 26087 14088 26087 14089 26088 13959 26088 13957 26088 14089 26089 14088 26089 13959 26089 14090 26090 14088 26090 14089 26090 14090 26091 14085 26091 14088 26091 13956 26092 14089 26092 13957 26092 14091 26093 14089 26093 13956 26093 14093 26094 14085 26094 14090 26094 14092 26095 14089 26095 14091 26095 14092 26096 14090 26096 14089 26096 14093 26097 14090 26097 14092 26097 13954 26098 14091 26098 13956 26098 13953 26099 14091 26099 13954 26099 14094 26100 14091 26100 13953 26100 14096 26101 14091 26101 14094 26101 14096 26102 14092 26102 14091 26102 14096 26103 14093 26103 14092 26103 14095 26104 14093 26104 14096 26104 13951 26105 14094 26105 13953 26105 14097 26106 14094 26106 13951 26106 14097 26107 14096 26107 14094 26107 14099 26108 14093 26108 14095 26108 14098 26109 14095 26109 14096 26109 14098 26110 14096 26110 14097 26110 14097 26111 13951 26111 13950 26111 14099 26112 14095 26112 14098 26112 14101 26113 14097 26113 13950 26113 14100 26114 14099 26114 14098 26114 14100 26115 14097 26115 14101 26115 14100 26116 14098 26116 14097 26116 14101 26117 13950 26117 13948 26117 14102 26118 14101 26118 13948 26118 14102 26119 14100 26119 14101 26119 14103 26120 14100 26120 14102 26120 13947 26121 14102 26121 13948 26121 14103 26122 14099 26122 14100 26122 14104 26123 14102 26123 13947 26123 14106 26124 14099 26124 14103 26124 14105 26125 14102 26125 14104 26125 14105 26126 14103 26126 14102 26126 14106 26127 14103 26127 14105 26127 13945 26128 14104 26128 13947 26128 14105 26129 14104 26129 13945 26129 14107 26130 14105 26130 13945 26130 14108 26131 14106 26131 14105 26131 14107 26132 13945 26132 13943 26132 14109 26133 14106 26133 14108 26133 14108 26134 14105 26134 14107 26134 13942 26135 14107 26135 13943 26135 14110 26136 14108 26136 14107 26136 14110 26137 14109 26137 14108 26137 14110 26138 14107 26138 13942 26138 14111 26139 13942 26139 13941 26139 14111 26140 14110 26140 13942 26140 14112 26141 14110 26141 14111 26141 14113 26142 14110 26142 14112 26142 14113 26143 14109 26143 14110 26143 14111 26144 13941 26144 13939 26144 14114 26145 14111 26145 13939 26145 14114 26146 14112 26146 14111 26146 14115 26147 14112 26147 14114 26147 14116 26148 14114 26148 13939 26148 14116 26149 13939 26149 13938 26149 14113 26150 14112 26150 14115 26150 14115 26151 14114 26151 14116 26151 14117 26152 14116 26152 13938 26152 14115 26153 14116 26153 14117 26153 14117 26154 13938 26154 13937 26154 14118 26155 14115 26155 14117 26155 14119 26156 14117 26156 13937 26156 14118 26157 14113 26157 14115 26157 14119 26158 13937 26158 13935 26158 14120 26159 14117 26159 14119 26159 14120 26160 14118 26160 14117 26160 14121 26161 14119 26161 13935 26161 14120 26162 14119 26162 14121 26162 13933 26163 14121 26163 13935 26163 14122 26164 14118 26164 14120 26164 14120 26165 14121 26165 13933 26165 14123 26166 14120 26166 13933 26166 14123 26167 14122 26167 14120 26167 14124 26168 14123 26168 13933 26168 13932 26169 14124 26169 13933 26169 14016 26170 14122 26170 14123 26170 14014 26171 14123 26171 14124 26171 14124 26172 13932 26172 13931 26172 14124 26173 13931 26173 14012 26173 14124 26174 14012 26174 14014 26174 14014 26175 14016 26175 14123 26175 13630 26176 14025 26176 14034 26176 13630 26177 13633 26177 14025 26177 13634 26178 14025 26178 13633 26178 13630 26179 14034 26179 14037 26179 13628 26180 13630 26180 14037 26180 13635 26181 14025 26181 13634 26181 13635 26182 14019 26182 14025 26182 13625 26183 13628 26183 14037 26183 13636 26184 14019 26184 13635 26184 13625 26185 14037 26185 14044 26185 13623 26186 13625 26186 14044 26186 13568 26187 14122 26187 14019 26187 13568 26188 14019 26188 13636 26188 13623 26189 14044 26189 14048 26189 13619 26190 13623 26190 14048 26190 14052 26191 13619 26191 14048 26191 13573 26192 14122 26192 13568 26192 13573 26193 14118 26193 14122 26193 13575 26194 14118 26194 13573 26194 13617 26195 13619 26195 14052 26195 14054 26196 13617 26196 14052 26196 14113 26197 14118 26197 13575 26197 13578 26198 14113 26198 13575 26198 13614 26199 13617 26199 14054 26199 14109 26200 14113 26200 13578 26200 13580 26201 14109 26201 13578 26201 14054 26202 13612 26202 13614 26202 14064 26203 13612 26203 14054 26203 14106 26204 14109 26204 13580 26204 14064 26205 13608 26205 13612 26205 14106 26206 13580 26206 13584 26206 14099 26207 14106 26207 13584 26207 14099 26208 13584 26208 13588 26208 14070 26209 13608 26209 14064 26209 14070 26210 13604 26210 13608 26210 14093 26211 14099 26211 13588 26211 14070 26212 13601 26212 13604 26212 14093 26213 13588 26213 13592 26213 14085 26214 14093 26214 13592 26214 14076 26215 13601 26215 14070 26215 14076 26216 13597 26216 13601 26216 14081 26217 13597 26217 14076 26217 14085 26218 13592 26218 13594 26218 14081 26219 13594 26219 13597 26219 14081 26220 14085 26220 13594 26220 14126 26221 14125 26221 13844 26221 14126 26222 13844 26222 13846 26222 14130 26223 14228 26223 14127 26223 14128 26224 14125 26224 14126 26224 14128 26225 14127 26225 14125 26225 14129 26226 14126 26226 13846 26226 14130 26227 14127 26227 14128 26227 13847 26228 14129 26228 13846 26228 14128 26229 14126 26229 14129 26229 14131 26230 14129 26230 13847 26230 14131 26231 14128 26231 14129 26231 14132 26232 14128 26232 14131 26232 13849 26233 14131 26233 13847 26233 14132 26234 14130 26234 14128 26234 14133 26235 14131 26235 13849 26235 14132 26236 14131 26236 14133 26236 14134 26237 14130 26237 14132 26237 14135 26238 14132 26238 14133 26238 14134 26239 14132 26239 14135 26239 14136 26240 13849 26240 13851 26240 14136 26241 14133 26241 13849 26241 14136 26242 14135 26242 14133 26242 14137 26243 13851 26243 13852 26243 14137 26244 14136 26244 13851 26244 14138 26245 14136 26245 14137 26245 14138 26246 14135 26246 14136 26246 14139 26247 14135 26247 14138 26247 14139 26248 14134 26248 14135 26248 13854 26249 14137 26249 13852 26249 14142 26250 14134 26250 14139 26250 14139 26251 14138 26251 14137 26251 14140 26252 14137 26252 13854 26252 14140 26253 14139 26253 14137 26253 14141 26254 13854 26254 13855 26254 14140 26255 13854 26255 14141 26255 14142 26256 14139 26256 14140 26256 14143 26257 14140 26257 14141 26257 14141 26258 13855 26258 13857 26258 14143 26259 14142 26259 14140 26259 14144 26260 14141 26260 13857 26260 14145 26261 14141 26261 14144 26261 14145 26262 14143 26262 14141 26262 14146 26263 14142 26263 14143 26263 14147 26264 14143 26264 14145 26264 14148 26265 14144 26265 13858 26265 14147 26266 14146 26266 14143 26266 14148 26267 14145 26267 14144 26267 14147 26268 14145 26268 14148 26268 14148 26269 13858 26269 13860 26269 14147 26270 14148 26270 13860 26270 14146 26271 14147 26271 14149 26271 14150 26272 14147 26272 13860 26272 14150 26273 14149 26273 14147 26273 14150 26274 13860 26274 13861 26274 14151 26275 13861 26275 13863 26275 14151 26276 14150 26276 13861 26276 14153 26277 14146 26277 14149 26277 14151 26278 14149 26278 14150 26278 14152 26279 14149 26279 14151 26279 13864 26280 14151 26280 13863 26280 14153 26281 14149 26281 14152 26281 14154 26282 14151 26282 13864 26282 14152 26283 14151 26283 14154 26283 13866 26284 14154 26284 13864 26284 14155 26285 14154 26285 13866 26285 14155 26286 14152 26286 14154 26286 14156 26287 14152 26287 14155 26287 14156 26288 14153 26288 14152 26288 14157 26289 14155 26289 13866 26289 14158 26290 14155 26290 14157 26290 14158 26291 14156 26291 14155 26291 14157 26292 13866 26292 13868 26292 14160 26293 14156 26293 14158 26293 14159 26294 14157 26294 13868 26294 14159 26295 14158 26295 14157 26295 14160 26296 14158 26296 14159 26296 14159 26297 13868 26297 13869 26297 14161 26298 14159 26298 13869 26298 14162 26299 14159 26299 14161 26299 14162 26300 14160 26300 14159 26300 13870 26301 14161 26301 13869 26301 14163 26302 14161 26302 13870 26302 14163 26303 14162 26303 14161 26303 14164 26304 14162 26304 14163 26304 13872 26305 14163 26305 13870 26305 14164 26306 14160 26306 14162 26306 14165 26307 14163 26307 13872 26307 14164 26308 14163 26308 14165 26308 14166 26309 13872 26309 13873 26309 14166 26310 14165 26310 13872 26310 13875 26311 14166 26311 13873 26311 14167 26312 14164 26312 14165 26312 14168 26313 14166 26313 13875 26313 14168 26314 14165 26314 14166 26314 14168 26315 14167 26315 14165 26315 14169 26316 14167 26316 14168 26316 13876 26317 14168 26317 13875 26317 14170 26318 14168 26318 13876 26318 14169 26319 14168 26319 14170 26319 14171 26320 13876 26320 13877 26320 14171 26321 14170 26321 13876 26321 14172 26322 14167 26322 14169 26322 14171 26323 14169 26323 14170 26323 13879 26324 14171 26324 13877 26324 14174 26325 14171 26325 14173 26325 14174 26326 14169 26326 14171 26326 14173 26327 14171 26327 13879 26327 14172 26328 14169 26328 14174 26328 13881 26329 14173 26329 13879 26329 14175 26330 14173 26330 13881 26330 14175 26331 14174 26331 14173 26331 14176 26332 14174 26332 14175 26332 14175 26333 13881 26333 13882 26333 14176 26334 14172 26334 14174 26334 14177 26335 14175 26335 13882 26335 14176 26336 14175 26336 14177 26336 13884 26337 14177 26337 13882 26337 14178 26338 14177 26338 13884 26338 14180 26339 14172 26339 14176 26339 14179 26340 14177 26340 14178 26340 14179 26341 14176 26341 14177 26341 13886 26342 14178 26342 13884 26342 14180 26343 14176 26343 14179 26343 14181 26344 13886 26344 13887 26344 14181 26345 14178 26345 13886 26345 14182 26346 14179 26346 14178 26346 14180 26347 14179 26347 14182 26347 14182 26348 14178 26348 14181 26348 13889 26349 14181 26349 13887 26349 13889 26350 14182 26350 14181 26350 14183 26351 14180 26351 14182 26351 14184 26352 14182 26352 13889 26352 14183 26353 14182 26353 14184 26353 14184 26354 13889 26354 13891 26354 14185 26355 14180 26355 14183 26355 13892 26356 14184 26356 13891 26356 14186 26357 14184 26357 13892 26357 14186 26358 14183 26358 14184 26358 14185 26359 14183 26359 14186 26359 14187 26360 13892 26360 13893 26360 14187 26361 14186 26361 13892 26361 14188 26362 14186 26362 14187 26362 14189 26363 14186 26363 14188 26363 14189 26364 14185 26364 14186 26364 14187 26365 13893 26365 13895 26365 14190 26366 14187 26366 13895 26366 14190 26367 14188 26367 14187 26367 13896 26368 14190 26368 13895 26368 14191 26369 14189 26369 14188 26369 14191 26370 14188 26370 14190 26370 13898 26371 14190 26371 13896 26371 14192 26372 14189 26372 14191 26372 14193 26373 14190 26373 13898 26373 14193 26374 14191 26374 14190 26374 14192 26375 14191 26375 14193 26375 14194 26376 13898 26376 13899 26376 14194 26377 14193 26377 13898 26377 14195 26378 14193 26378 14194 26378 14192 26379 14193 26379 14195 26379 14196 26380 13899 26380 13901 26380 14197 26381 14192 26381 14195 26381 14196 26382 14194 26382 13899 26382 14195 26383 14194 26383 14196 26383 14198 26384 14195 26384 14196 26384 14197 26385 14195 26385 14198 26385 13902 26386 14196 26386 13901 26386 14198 26387 14196 26387 13902 26387 14199 26388 14197 26388 14198 26388 14200 26389 13902 26389 13903 26389 14200 26390 14198 26390 13902 26390 14199 26391 14198 26391 14200 26391 14201 26392 14197 26392 14199 26392 14202 26393 14199 26393 14200 26393 13905 26394 14200 26394 13903 26394 14202 26395 14200 26395 13905 26395 14201 26396 14199 26396 14202 26396 14203 26397 14201 26397 14202 26397 14204 26398 13905 26398 13906 26398 14204 26399 14202 26399 13905 26399 14204 26400 14203 26400 14202 26400 14205 26401 14203 26401 14204 26401 13908 26402 14204 26402 13906 26402 14206 26403 14204 26403 13908 26403 14201 26404 14203 26404 14205 26404 14206 26405 14205 26405 14204 26405 14206 26406 13908 26406 13909 26406 14201 26407 14205 26407 14208 26407 14207 26408 14205 26408 14206 26408 14208 26409 14205 26409 14207 26409 14207 26410 14206 26410 13909 26410 13911 26411 14207 26411 13909 26411 14209 26412 14208 26412 14207 26412 14210 26413 14207 26413 13911 26413 14209 26414 14207 26414 14210 26414 14210 26415 13911 26415 13912 26415 14211 26416 14208 26416 14209 26416 14211 26417 14209 26417 14210 26417 14212 26418 14210 26418 13912 26418 14211 26419 14210 26419 14212 26419 14212 26420 13912 26420 13914 26420 14215 26421 14211 26421 14212 26421 14213 26422 14212 26422 13914 26422 14214 26423 14212 26423 14213 26423 14214 26424 14215 26424 14212 26424 14213 26425 13914 26425 13915 26425 14216 26426 14215 26426 14214 26426 13917 26427 14213 26427 13915 26427 14216 26428 14213 26428 13917 26428 14217 26429 14211 26429 14215 26429 14216 26430 14214 26430 14213 26430 14217 26431 14215 26431 14216 26431 13918 26432 14216 26432 13917 26432 14218 26433 14216 26433 13918 26433 14219 26434 14211 26434 14217 26434 14217 26435 14216 26435 14218 26435 13920 26436 14218 26436 13918 26436 14220 26437 14218 26437 13920 26437 14221 26438 14218 26438 14220 26438 14221 26439 14217 26439 14218 26439 13921 26440 14220 26440 13920 26440 14219 26441 14217 26441 14221 26441 14222 26442 14220 26442 13921 26442 14222 26443 14221 26443 14220 26443 14222 26444 13921 26444 13923 26444 14223 26445 14221 26445 14222 26445 14219 26446 14221 26446 14223 26446 13924 26447 14222 26447 13923 26447 14225 26448 14219 26448 14223 26448 14224 26449 14223 26449 14222 26449 14226 26450 14222 26450 13924 26450 14226 26451 14224 26451 14222 26451 14226 26452 13924 26452 13925 26452 14224 26453 14225 26453 14223 26453 14227 26454 14226 26454 13925 26454 13927 26455 14227 26455 13925 26455 14225 26456 14224 26456 14228 26456 14229 26457 14226 26457 14227 26457 14229 26458 14224 26458 14226 26458 14228 26459 14224 26459 14229 26459 13929 26460 14227 26460 13927 26460 14229 26461 14227 26461 13929 26461 14125 26462 13929 26462 13844 26462 14125 26463 14229 26463 13929 26463 14127 26464 14229 26464 14125 26464 14127 26465 14228 26465 14229 26465 13540 26466 14189 26466 14192 26466 13537 26467 14189 26467 13540 26467 13540 26468 14192 26468 14197 26468 13537 26469 14185 26469 14189 26469 13544 26470 13540 26470 14197 26470 13535 26471 14185 26471 13537 26471 13544 26472 14197 26472 14201 26472 13535 26473 14180 26473 14185 26473 13547 26474 13544 26474 14201 26474 13531 26475 14180 26475 13535 26475 13528 26476 14180 26476 13531 26476 13551 26477 14201 26477 14208 26477 13551 26478 13547 26478 14201 26478 13528 26479 14172 26479 14180 26479 13526 26480 14172 26480 13528 26480 13554 26481 13551 26481 14208 26481 14211 26482 13554 26482 14208 26482 13521 26483 14172 26483 13526 26483 13557 26484 13554 26484 14211 26484 13521 26485 14167 26485 14172 26485 13557 26486 14211 26486 14219 26486 13560 26487 13557 26487 14219 26487 13518 26488 14167 26488 13521 26488 14164 26489 14167 26489 13518 26489 13515 26490 14164 26490 13518 26490 14225 26491 13560 26491 14219 26491 14160 26492 14164 26492 13515 26492 14225 26493 13564 26493 13560 26493 13513 26494 14160 26494 13515 26494 14156 26495 14160 26495 13513 26495 14156 26496 13513 26496 13510 26496 14228 26497 13564 26497 14225 26497 14228 26498 13491 26498 13564 26498 14130 26499 13491 26499 14228 26499 14156 26500 13510 26500 13507 26500 14153 26501 14156 26501 13507 26501 14130 26502 13494 26502 13491 26502 14146 26503 13507 26503 13503 26503 14146 26504 14153 26504 13507 26504 14134 26505 13494 26505 14130 26505 14134 26506 13497 26506 13494 26506 14142 26507 14146 26507 13503 26507 14142 26508 13497 26508 14134 26508 14142 26509 13503 26509 13500 26509 14142 26510 13500 26510 13497 26510 14230 26511 14231 26511 14398 26511 14232 26512 14399 26512 14231 26512 14233 26513 14399 26513 14232 26513 14234 26514 14231 26514 14230 26514 14234 26515 14232 26515 14231 26515 14235 26516 14232 26516 14234 26516 14236 26517 14234 26517 14230 26517 14237 26518 14233 26518 14232 26518 14235 26519 14234 26519 14236 26519 14238 26520 14232 26520 14235 26520 14238 26521 14237 26521 14232 26521 14240 26522 14236 26522 14239 26522 14240 26523 14235 26523 14236 26523 14238 26524 14235 26524 14240 26524 14241 26525 14240 26525 14239 26525 14242 26526 14238 26526 14240 26526 14242 26527 14237 26527 14238 26527 14243 26528 14240 26528 14241 26528 14242 26529 14240 26529 14243 26529 14243 26530 14241 26530 14244 26530 14245 26531 14242 26531 14243 26531 14246 26532 14243 26532 14244 26532 14248 26533 14237 26533 14242 26533 14245 26534 14243 26534 14246 26534 14247 26535 14242 26535 14245 26535 14248 26536 14242 26536 14247 26536 14247 26537 14245 26537 14246 26537 14250 26538 14246 26538 14249 26538 14250 26539 14247 26539 14246 26539 14251 26540 14248 26540 14247 26540 14251 26541 14247 26541 14250 26541 14253 26542 14249 26542 14252 26542 14254 26543 14248 26543 14251 26543 14253 26544 14250 26544 14249 26544 14251 26545 14250 26545 14253 26545 14255 26546 14251 26546 14253 26546 14254 26547 14251 26547 14255 26547 14256 26548 14253 26548 14252 26548 14255 26549 14253 26549 14256 26549 14257 26550 14255 26550 14256 26550 14259 26551 14255 26551 14257 26551 14259 26552 14254 26552 14255 26552 14258 26553 14254 26553 14259 26553 14261 26554 14257 26554 14260 26554 14261 26555 14259 26555 14257 26555 14262 26556 14259 26556 14261 26556 14262 26557 14258 26557 14259 26557 14261 26558 14260 26558 14263 26558 14262 26559 14261 26559 14264 26559 14264 26560 14261 26560 14263 26560 14265 26561 14258 26561 14262 26561 14265 26562 14262 26562 14264 26562 14266 26563 14264 26563 14263 26563 14267 26564 14264 26564 14266 26564 14267 26565 14265 26565 14264 26565 14269 26566 14265 26566 14267 26566 14270 26567 14266 26567 14268 26567 14270 26568 14267 26568 14266 26568 14271 26569 14267 26569 14270 26569 14271 26570 14269 26570 14267 26570 14272 26571 14270 26571 14268 26571 14271 26572 14270 26572 14272 26572 14274 26573 14269 26573 14271 26573 14275 26574 14271 26574 14272 26574 14274 26575 14271 26575 14275 26575 14275 26576 14272 26576 14273 26576 14277 26577 14273 26577 14276 26577 14277 26578 14275 26578 14273 26578 14274 26579 14275 26579 14277 26579 14279 26580 14274 26580 14277 26580 14278 26581 14277 26581 14276 26581 14280 26582 14277 26582 14278 26582 14279 26583 14277 26583 14280 26583 14281 26584 14274 26584 14279 26584 14282 26585 14280 26585 14278 26585 14283 26586 14280 26586 14282 26586 14283 26587 14279 26587 14280 26587 14281 26588 14279 26588 14283 26588 14284 26589 14281 26589 14283 26589 14286 26590 14282 26590 14285 26590 14286 26591 14283 26591 14282 26591 14287 26592 14281 26592 14284 26592 14284 26593 14283 26593 14286 26593 14288 26594 14284 26594 14286 26594 14287 26595 14284 26595 14288 26595 14288 26596 14286 26596 14285 26596 14290 26597 14285 26597 14289 26597 14290 26598 14288 26598 14285 26598 14292 26599 14288 26599 14290 26599 14292 26600 14287 26600 14288 26600 14293 26601 14289 26601 14291 26601 14293 26602 14290 26602 14289 26602 14296 26603 14287 26603 14292 26603 14294 26604 14290 26604 14293 26604 14294 26605 14292 26605 14290 26605 14296 26606 14292 26606 14294 26606 14293 26607 14291 26607 14295 26607 14297 26608 14293 26608 14295 26608 14297 26609 14294 26609 14293 26609 14297 26610 14296 26610 14294 26610 14298 26611 14297 26611 14295 26611 14299 26612 14297 26612 14298 26612 14300 26613 14296 26613 14297 26613 14300 26614 14297 26614 14299 26614 14302 26615 14298 26615 14301 26615 14302 26616 14299 26616 14298 26616 14300 26617 14299 26617 14302 26617 14303 26618 14302 26618 14301 26618 14304 26619 14302 26619 14303 26619 14304 26620 14300 26620 14302 26620 14304 26621 14303 26621 14305 26621 14307 26622 14304 26622 14305 26622 14309 26623 14304 26623 14307 26623 14309 26624 14300 26624 14304 26624 14310 26625 14305 26625 14308 26625 14306 26626 14300 26626 14309 26626 14310 26627 14307 26627 14305 26627 14309 26628 14307 26628 14310 26628 14310 26629 14308 26629 14311 26629 14312 26630 14309 26630 14310 26630 14306 26631 14309 26631 14312 26631 14312 26632 14310 26632 14311 26632 14314 26633 14306 26633 14312 26633 14313 26634 14312 26634 14311 26634 14316 26635 14312 26635 14313 26635 14314 26636 14312 26636 14316 26636 14316 26637 14313 26637 14315 26637 14317 26638 14306 26638 14314 26638 14319 26639 14315 26639 14318 26639 14319 26640 14316 26640 14315 26640 14317 26641 14314 26641 14316 26641 14320 26642 14316 26642 14319 26642 14317 26643 14316 26643 14320 26643 14321 26644 14319 26644 14318 26644 14322 26645 14319 26645 14321 26645 14323 26646 14319 26646 14322 26646 14323 26647 14320 26647 14319 26647 14324 26648 14317 26648 14320 26648 14325 26649 14322 26649 14321 26649 14324 26650 14320 26650 14323 26650 14326 26651 14322 26651 14325 26651 14326 26652 14323 26652 14322 26652 14328 26653 14323 26653 14326 26653 14328 26654 14324 26654 14323 26654 14329 26655 14325 26655 14327 26655 14329 26656 14326 26656 14325 26656 14328 26657 14326 26657 14329 26657 14331 26658 14324 26658 14328 26658 14330 26659 14329 26659 14327 26659 14332 26660 14329 26660 14330 26660 14332 26661 14328 26661 14329 26661 14331 26662 14328 26662 14332 26662 14334 26663 14330 26663 14333 26663 14334 26664 14332 26664 14330 26664 14335 26665 14331 26665 14332 26665 14335 26666 14332 26666 14334 26666 14336 26667 14334 26667 14333 26667 14337 26668 14331 26668 14335 26668 14338 26669 14334 26669 14336 26669 14335 26670 14334 26670 14338 26670 14339 26671 14338 26671 14336 26671 14340 26672 14335 26672 14338 26672 14340 26673 14337 26673 14335 26673 14341 26674 14338 26674 14339 26674 14340 26675 14338 26675 14341 26675 14342 26676 14337 26676 14340 26676 14343 26677 14341 26677 14339 26677 14344 26678 14341 26678 14343 26678 14344 26679 14340 26679 14341 26679 14345 26680 14340 26680 14344 26680 14342 26681 14340 26681 14345 26681 14347 26682 14343 26682 14346 26682 14347 26683 14344 26683 14343 26683 14347 26684 14345 26684 14344 26684 14348 26685 14347 26685 14346 26685 14349 26686 14347 26686 14348 26686 14350 26687 14342 26687 14345 26687 14351 26688 14347 26688 14349 26688 14351 26689 14345 26689 14347 26689 14352 26690 14349 26690 14348 26690 14353 26691 14349 26691 14352 26691 14350 26692 14345 26692 14351 26692 14353 26693 14351 26693 14349 26693 14354 26694 14351 26694 14353 26694 14355 26695 14353 26695 14352 26695 14350 26696 14351 26696 14354 26696 14356 26697 14353 26697 14355 26697 14356 26698 14354 26698 14353 26698 14357 26699 14350 26699 14354 26699 14359 26700 14357 26700 14354 26700 14358 26701 14356 26701 14355 26701 14359 26702 14356 26702 14358 26702 14359 26703 14354 26703 14356 26703 14358 26704 14355 26704 14360 26704 14361 26705 14358 26705 14360 26705 14361 26706 14359 26706 14358 26706 14364 26707 14357 26707 14359 26707 14362 26708 14359 26708 14361 26708 14364 26709 14359 26709 14362 26709 14361 26710 14360 26710 14363 26710 14365 26711 14361 26711 14363 26711 14365 26712 14362 26712 14361 26712 14367 26713 14362 26713 14365 26713 14367 26714 14364 26714 14362 26714 14365 26715 14363 26715 14366 26715 14368 26716 14365 26716 14366 26716 14368 26717 14367 26717 14365 26717 14369 26718 14368 26718 14366 26718 14370 26719 14367 26719 14368 26719 14372 26720 14367 26720 14370 26720 14373 26721 14369 26721 14371 26721 14372 26722 14364 26722 14367 26722 14373 26723 14368 26723 14369 26723 14373 26724 14370 26724 14368 26724 14374 26725 14370 26725 14373 26725 14372 26726 14370 26726 14374 26726 14375 26727 14373 26727 14371 26727 14374 26728 14373 26728 14375 26728 14375 26729 14371 26729 14376 26729 14377 26730 14372 26730 14374 26730 14378 26731 14374 26731 14375 26731 14378 26732 14377 26732 14374 26732 14378 26733 14375 26733 14376 26733 14378 26734 14376 26734 14379 26734 14380 26735 14377 26735 14378 26735 14381 26736 14378 26736 14379 26736 14380 26737 14378 26737 14381 26737 14382 26738 14381 26738 14379 26738 14387 26739 14377 26739 14380 26739 14381 26740 14382 26740 14383 26740 14384 26741 14380 26741 14381 26741 14384 26742 14381 26742 14383 26742 14385 26743 14380 26743 14384 26743 14387 26744 14380 26744 14385 26744 14386 26745 14384 26745 14383 26745 14385 26746 14384 26746 14386 26746 14388 26747 14386 26747 14383 26747 14390 26748 14387 26748 14385 26748 14391 26749 14386 26749 14388 26749 14391 26750 14388 26750 14389 26750 14391 26751 14385 26751 14386 26751 14390 26752 14385 26752 14391 26752 14392 26753 14391 26753 14389 26753 14393 26754 14391 26754 14392 26754 14394 26755 14391 26755 14393 26755 14394 26756 14390 26756 14391 26756 14396 26757 14392 26757 14395 26757 14396 26758 14393 26758 14392 26758 14397 26759 14394 26759 14393 26759 14397 26760 14390 26760 14394 26760 14397 26761 14393 26761 14396 26761 14398 26762 14396 26762 14395 26762 14399 26763 14396 26763 14398 26763 14233 26764 14397 26764 14396 26764 14399 26765 14398 26765 14231 26765 14233 26766 14396 26766 14399 26766 14401 26767 14398 26767 14395 26767 14401 26768 14400 26768 14398 26768 14401 26769 14395 26769 14392 26769 14402 26770 14401 26770 14392 26770 14402 26771 14392 26771 14389 26771 14403 26772 14402 26772 14389 26772 14403 26773 14389 26773 14388 26773 14404 26774 14388 26774 14383 26774 14404 26775 14403 26775 14388 26775 14405 26776 14404 26776 14383 26776 14405 26777 14383 26777 14382 26777 14406 26778 14405 26778 14382 26778 14406 26779 14382 26779 14379 26779 14407 26780 14406 26780 14379 26780 14407 26781 14379 26781 14376 26781 14408 26782 14407 26782 14376 26782 14408 26783 14376 26783 14371 26783 14409 26784 14408 26784 14371 26784 14409 26785 14371 26785 14369 26785 14410 26786 14409 26786 14369 26786 14410 26787 14369 26787 14366 26787 14411 26788 14366 26788 14363 26788 14411 26789 14410 26789 14366 26789 14412 26790 14363 26790 14360 26790 14412 26791 14411 26791 14363 26791 14413 26792 14412 26792 14360 26792 14413 26793 14360 26793 14355 26793 14414 26794 14413 26794 14355 26794 14486 26795 14355 26795 14352 26795 14486 26796 14414 26796 14355 26796 14415 26797 14486 26797 14352 26797 14415 26798 14352 26798 14348 26798 14416 26799 14415 26799 14348 26799 14416 26800 14348 26800 14346 26800 14417 26801 14416 26801 14346 26801 14417 26802 14346 26802 14343 26802 14418 26803 14417 26803 14343 26803 14418 26804 14343 26804 14339 26804 14419 26805 14418 26805 14339 26805 14420 26806 14339 26806 14336 26806 14420 26807 14419 26807 14339 26807 14421 26808 14336 26808 14333 26808 14421 26809 14420 26809 14336 26809 14422 26810 14333 26810 14330 26810 14422 26811 14421 26811 14333 26811 14423 26812 14330 26812 14327 26812 14423 26813 14422 26813 14330 26813 14423 26814 14327 26814 14325 26814 14424 26815 14423 26815 14325 26815 14424 26816 14325 26816 14321 26816 14425 26817 14424 26817 14321 26817 14426 26818 14425 26818 14321 26818 14426 26819 14321 26819 14318 26819 14427 26820 14318 26820 14315 26820 14427 26821 14426 26821 14318 26821 14428 26822 14315 26822 14313 26822 14428 26823 14427 26823 14315 26823 14428 26824 14313 26824 14311 26824 14429 26825 14428 26825 14311 26825 14429 26826 14311 26826 14308 26826 14430 26827 14429 26827 14308 26827 14430 26828 14308 26828 14305 26828 14431 26829 14430 26829 14305 26829 14431 26830 14305 26830 14303 26830 14431 26831 14303 26831 14301 26831 14432 26832 14431 26832 14301 26832 14432 26833 14301 26833 14298 26833 14433 26834 14432 26834 14298 26834 14433 26835 14298 26835 14295 26835 14434 26836 14433 26836 14295 26836 14434 26837 14295 26837 14291 26837 14435 26838 14434 26838 14291 26838 14435 26839 14291 26839 14289 26839 14436 26840 14289 26840 14285 26840 14436 26841 14435 26841 14289 26841 14437 26842 14436 26842 14285 26842 14437 26843 14285 26843 14282 26843 14438 26844 14437 26844 14282 26844 14438 26845 14282 26845 14278 26845 14537 26846 14438 26846 14278 26846 14439 26847 14537 26847 14278 26847 14439 26848 14278 26848 14276 26848 14440 26849 14439 26849 14276 26849 14440 26850 14276 26850 14273 26850 14441 26851 14440 26851 14273 26851 14441 26852 14273 26852 14272 26852 14546 26853 14441 26853 14272 26853 14546 26854 14272 26854 14268 26854 14442 26855 14546 26855 14268 26855 14442 26856 14268 26856 14266 26856 14443 26857 14442 26857 14266 26857 14443 26858 14266 26858 14263 26858 14444 26859 14443 26859 14263 26859 14445 26860 14263 26860 14260 26860 14445 26861 14444 26861 14263 26861 14446 26862 14445 26862 14260 26862 14447 26863 14260 26863 14257 26863 14447 26864 14446 26864 14260 26864 14447 26865 14257 26865 14256 26865 14448 26866 14447 26866 14256 26866 14449 26867 14256 26867 14252 26867 14449 26868 14448 26868 14256 26868 14449 26869 14252 26869 14249 26869 14450 26870 14449 26870 14249 26870 14450 26871 14249 26871 14246 26871 14451 26872 14450 26872 14246 26872 14451 26873 14246 26873 14244 26873 14452 26874 14451 26874 14244 26874 14452 26875 14244 26875 14241 26875 14453 26876 14452 26876 14241 26876 14453 26877 14241 26877 14239 26877 14454 26878 14239 26878 14236 26878 14454 26879 14453 26879 14239 26879 14455 26880 14236 26880 14230 26880 14455 26881 14454 26881 14236 26881 14400 26882 14455 26882 14230 26882 14400 26883 14230 26883 14398 26883 14002 26884 14248 26884 14254 26884 14005 26885 14248 26885 14002 26885 14002 26886 14254 26886 14258 26886 14000 26887 14002 26887 14258 26887 14005 26888 14237 26888 14248 26888 13997 26889 14258 26889 14265 26889 13997 26890 14000 26890 14258 26890 14008 26891 14237 26891 14005 26891 13995 26892 13997 26892 14265 26892 13995 26893 14265 26893 14269 26893 14010 26894 14237 26894 14008 26894 13995 26895 14269 26895 14274 26895 14010 26896 14233 26896 14237 26896 13991 26897 13995 26897 14274 26897 13930 26898 14233 26898 14010 26898 13930 26899 14397 26899 14233 26899 14281 26900 13991 26900 14274 26900 13934 26901 14397 26901 13930 26901 14390 26902 14397 26902 13934 26902 13988 26903 13991 26903 14281 26903 13936 26904 14390 26904 13934 26904 14287 26905 13988 26905 14281 26905 13984 26906 13988 26906 14287 26906 13936 26907 14387 26907 14390 26907 13940 26908 14387 26908 13936 26908 13940 26909 14377 26909 14387 26909 14296 26910 13984 26910 14287 26910 14296 26911 13981 26911 13984 26911 14372 26912 13940 26912 13944 26912 14372 26913 14377 26913 13940 26913 14300 26914 13981 26914 14296 26914 14300 26915 13978 26915 13981 26915 14372 26916 13944 26916 13946 26916 14364 26917 14372 26917 13946 26917 14306 26918 13978 26918 14300 26918 14306 26919 13974 26919 13978 26919 14364 26920 13946 26920 13949 26920 14364 26921 13949 26921 13952 26921 14357 26922 14364 26922 13952 26922 14306 26923 13971 26923 13974 26923 14317 26924 13971 26924 14306 26924 14350 26925 14357 26925 13952 26925 14324 26926 13968 26926 13971 26926 14324 26927 13971 26927 14317 26927 14350 26928 13952 26928 13955 26928 14324 26929 13965 26929 13968 26929 14342 26930 14350 26930 13955 26930 14331 26931 13965 26931 14324 26931 14342 26932 13955 26932 13958 26932 14342 26933 13958 26933 13961 26933 14337 26934 13965 26934 14331 26934 14337 26935 14342 26935 13961 26935 14337 26936 13961 26936 13965 26936 14456 26937 14457 26937 14569 26937 14458 26938 14400 26938 14401 26938 14458 26939 14456 26939 14400 26939 14459 26940 14457 26940 14456 26940 14461 26941 14457 26941 14459 26941 14460 26942 14456 26942 14458 26942 14460 26943 14459 26943 14456 26943 14460 26944 14458 26944 14401 26944 14461 26945 14459 26945 14460 26945 14462 26946 14401 26946 14402 26946 14462 26947 14460 26947 14401 26947 14463 26948 14460 26948 14462 26948 14461 26949 14460 26949 14463 26949 14403 26950 14462 26950 14402 26950 14464 26951 14462 26951 14403 26951 14464 26952 14463 26952 14462 26952 14465 26953 14461 26953 14463 26953 14465 26954 14463 26954 14464 26954 14404 26955 14464 26955 14403 26955 14466 26956 14464 26956 14404 26956 14467 26957 14464 26957 14466 26957 14467 26958 14465 26958 14464 26958 14405 26959 14466 26959 14404 26959 14467 26960 14466 26960 14405 26960 14469 26961 14465 26961 14467 26961 14470 26962 14405 26962 14406 26962 14468 26963 14465 26963 14469 26963 14470 26964 14467 26964 14405 26964 14469 26965 14467 26965 14470 26965 14407 26966 14470 26966 14406 26966 14471 26967 14470 26967 14407 26967 14472 26968 14470 26968 14471 26968 14472 26969 14469 26969 14470 26969 14468 26970 14469 26970 14472 26970 14408 26971 14471 26971 14407 26971 14473 26972 14471 26972 14408 26972 14473 26973 14472 26973 14471 26973 14474 26974 14408 26974 14409 26974 14474 26975 14473 26975 14408 26975 14475 26976 14472 26976 14473 26976 14475 26977 14468 26977 14472 26977 14476 26978 14473 26978 14474 26978 14475 26979 14473 26979 14476 26979 14476 26980 14474 26980 14409 26980 14480 26981 14468 26981 14475 26981 14477 26982 14409 26982 14410 26982 14477 26983 14476 26983 14409 26983 14478 26984 14476 26984 14477 26984 14478 26985 14475 26985 14476 26985 14480 26986 14475 26986 14478 26986 14479 26987 14477 26987 14410 26987 14479 26988 14478 26988 14477 26988 14480 26989 14478 26989 14479 26989 14411 26990 14479 26990 14410 26990 14482 26991 14479 26991 14411 26991 14482 26992 14411 26992 14412 26992 14482 26993 14480 26993 14479 26993 14481 26994 14480 26994 14482 26994 14483 26995 14412 26995 14413 26995 14483 26996 14482 26996 14412 26996 14484 26997 14480 26997 14481 26997 14485 26998 14482 26998 14483 26998 14485 26999 14481 26999 14482 26999 14484 27000 14481 27000 14485 27000 14483 27001 14413 27001 14414 27001 14486 27002 14483 27002 14414 27002 14485 27003 14483 27003 14486 27003 14487 27004 14484 27004 14485 27004 14487 27005 14485 27005 14486 27005 14488 27006 14486 27006 14415 27006 14489 27007 14484 27007 14487 27007 14488 27008 14487 27008 14486 27008 14490 27009 14487 27009 14488 27009 14488 27010 14415 27010 14416 27010 14489 27011 14487 27011 14490 27011 14491 27012 14488 27012 14416 27012 14491 27013 14490 27013 14488 27013 14491 27014 14416 27014 14417 27014 14492 27015 14490 27015 14491 27015 14489 27016 14490 27016 14492 27016 14493 27017 14491 27017 14417 27017 14493 27018 14492 27018 14491 27018 14494 27019 14489 27019 14492 27019 14418 27020 14493 27020 14417 27020 14494 27021 14492 27021 14493 27021 14495 27022 14493 27022 14418 27022 14496 27023 14493 27023 14495 27023 14496 27024 14494 27024 14493 27024 14419 27025 14495 27025 14418 27025 14497 27026 14494 27026 14496 27026 14498 27027 14419 27027 14420 27027 14498 27028 14495 27028 14419 27028 14498 27029 14496 27029 14495 27029 14499 27030 14496 27030 14498 27030 14499 27031 14497 27031 14496 27031 14421 27032 14498 27032 14420 27032 14500 27033 14498 27033 14421 27033 14501 27034 14497 27034 14499 27034 14500 27035 14499 27035 14498 27035 14502 27036 14499 27036 14500 27036 14501 27037 14499 27037 14502 27037 14422 27038 14500 27038 14421 27038 14502 27039 14500 27039 14422 27039 14503 27040 14422 27040 14423 27040 14503 27041 14502 27041 14422 27041 14504 27042 14502 27042 14503 27042 14504 27043 14501 27043 14502 27043 14504 27044 14503 27044 14505 27044 14505 27045 14503 27045 14423 27045 14506 27046 14504 27046 14505 27046 14424 27047 14505 27047 14423 27047 14506 27048 14501 27048 14504 27048 14507 27049 14505 27049 14424 27049 14508 27050 14505 27050 14507 27050 14509 27051 14505 27051 14508 27051 14509 27052 14506 27052 14505 27052 14507 27053 14424 27053 14425 27053 14510 27054 14508 27054 14507 27054 14510 27055 14509 27055 14508 27055 14426 27056 14507 27056 14425 27056 14510 27057 14507 27057 14426 27057 14511 27058 14506 27058 14509 27058 14512 27059 14509 27059 14510 27059 14511 27060 14509 27060 14512 27060 14513 27061 14426 27061 14427 27061 14513 27062 14510 27062 14426 27062 14513 27063 14512 27063 14510 27063 14428 27064 14513 27064 14427 27064 14514 27065 14513 27065 14428 27065 14512 27066 14513 27066 14514 27066 14515 27067 14511 27067 14512 27067 14515 27068 14512 27068 14514 27068 14429 27069 14514 27069 14428 27069 14516 27070 14514 27070 14429 27070 14517 27071 14514 27071 14516 27071 14517 27072 14515 27072 14514 27072 14430 27073 14516 27073 14429 27073 14518 27074 14511 27074 14515 27074 14518 27075 14515 27075 14517 27075 14519 27076 14516 27076 14430 27076 14519 27077 14517 27077 14516 27077 14518 27078 14517 27078 14519 27078 14520 27079 14518 27079 14519 27079 14521 27080 14430 27080 14431 27080 14521 27081 14519 27081 14430 27081 14521 27082 14520 27082 14519 27082 14522 27083 14521 27083 14431 27083 14523 27084 14518 27084 14520 27084 14520 27085 14521 27085 14522 27085 14432 27086 14522 27086 14431 27086 14524 27087 14520 27087 14522 27087 14524 27088 14523 27088 14520 27088 14524 27089 14522 27089 14432 27089 14525 27090 14432 27090 14433 27090 14525 27091 14524 27091 14432 27091 14526 27092 14524 27092 14525 27092 14527 27093 14433 27093 14434 27093 14528 27094 14524 27094 14526 27094 14527 27095 14525 27095 14433 27095 14528 27096 14523 27096 14524 27096 14526 27097 14525 27097 14527 27097 14529 27098 14526 27098 14527 27098 14530 27099 14434 27099 14435 27099 14528 27100 14526 27100 14529 27100 14530 27101 14527 27101 14434 27101 14529 27102 14527 27102 14530 27102 14531 27103 14528 27103 14529 27103 14532 27104 14530 27104 14435 27104 14532 27105 14529 27105 14530 27105 14533 27106 14529 27106 14532 27106 14531 27107 14529 27107 14533 27107 14532 27108 14435 27108 14436 27108 14535 27109 14528 27109 14531 27109 14533 27110 14532 27110 14436 27110 14534 27111 14533 27111 14436 27111 14534 27112 14531 27112 14533 27112 14535 27113 14531 27113 14534 27113 14437 27114 14534 27114 14436 27114 14536 27115 14535 27115 14534 27115 14438 27116 14534 27116 14437 27116 14536 27117 14534 27117 14438 27117 14539 27118 14535 27118 14536 27118 14538 27119 14438 27119 14537 27119 14538 27120 14536 27120 14438 27120 14539 27121 14536 27121 14538 27121 14542 27122 14535 27122 14539 27122 14439 27123 14538 27123 14537 27123 14540 27124 14538 27124 14439 27124 14540 27125 14539 27125 14538 27125 14541 27126 14439 27126 14440 27126 14542 27127 14539 27127 14540 27127 14541 27128 14540 27128 14439 27128 14543 27129 14540 27129 14541 27129 14544 27130 14540 27130 14543 27130 14544 27131 14542 27131 14540 27131 14541 27132 14440 27132 14441 27132 14545 27133 14543 27133 14541 27133 14545 27134 14544 27134 14543 27134 14546 27135 14541 27135 14441 27135 14545 27136 14541 27136 14546 27136 14547 27137 14542 27137 14544 27137 14548 27138 14545 27138 14546 27138 14548 27139 14546 27139 14442 27139 14547 27140 14544 27140 14545 27140 14547 27141 14545 27141 14548 27141 14443 27142 14548 27142 14442 27142 14549 27143 14548 27143 14443 27143 14549 27144 14547 27144 14548 27144 14550 27145 14547 27145 14549 27145 14549 27146 14443 27146 14444 27146 14551 27147 14444 27147 14445 27147 14551 27148 14549 27148 14444 27148 14551 27149 14550 27149 14549 27149 14552 27150 14550 27150 14551 27150 14553 27151 14445 27151 14446 27151 14553 27152 14551 27152 14445 27152 14552 27153 14551 27153 14553 27153 14447 27154 14553 27154 14446 27154 14554 27155 14553 27155 14447 27155 14556 27156 14550 27156 14552 27156 14555 27157 14552 27157 14553 27157 14555 27158 14553 27158 14554 27158 14448 27159 14554 27159 14447 27159 14556 27160 14552 27160 14555 27160 14556 27161 14555 27161 14558 27161 14557 27162 14554 27162 14448 27162 14557 27163 14555 27163 14554 27163 14558 27164 14555 27164 14557 27164 14557 27165 14448 27165 14449 27165 14558 27166 14557 27166 14559 27166 14559 27167 14557 27167 14449 27167 14450 27168 14559 27168 14449 27168 14561 27169 14556 27169 14558 27169 14560 27170 14558 27170 14559 27170 14561 27171 14558 27171 14560 27171 14562 27172 14559 27172 14450 27172 14560 27173 14559 27173 14562 27173 14562 27174 14450 27174 14451 27174 14452 27175 14562 27175 14451 27175 14563 27176 14562 27176 14452 27176 14563 27177 14560 27177 14562 27177 14561 27178 14560 27178 14563 27178 14564 27179 14561 27179 14563 27179 14565 27180 14452 27180 14453 27180 14565 27181 14563 27181 14452 27181 14454 27182 14565 27182 14453 27182 14566 27183 14565 27183 14454 27183 14566 27184 14563 27184 14565 27184 14567 27185 14563 27185 14566 27185 14567 27186 14564 27186 14563 27186 14455 27187 14566 27187 14454 27187 14568 27188 14566 27188 14455 27188 14568 27189 14567 27189 14566 27189 14569 27190 14564 27190 14567 27190 14570 27191 14567 27191 14568 27191 14569 27192 14567 27192 14570 27192 14570 27193 14568 27193 14455 27193 14457 27194 14564 27194 14569 27194 14570 27195 14455 27195 14400 27195 14570 27196 14400 27196 14456 27196 14569 27197 14570 27197 14456 27197 13894 27198 14528 27198 13897 27198 13897 27199 14528 27199 14535 27199 13894 27200 14523 27200 14528 27200 13900 27201 13897 27201 14535 27201 13890 27202 14523 27202 13894 27202 13900 27203 14535 27203 14542 27203 13904 27204 13900 27204 14542 27204 13888 27205 14523 27205 13890 27205 13888 27206 14518 27206 14523 27206 13885 27207 14518 27207 13888 27207 13907 27208 13904 27208 14542 27208 13885 27209 14511 27209 14518 27209 13907 27210 14542 27210 14547 27210 13883 27211 14511 27211 13885 27211 13910 27212 14547 27212 14550 27212 13910 27213 13907 27213 14547 27213 13880 27214 14511 27214 13883 27214 13913 27215 13910 27215 14550 27215 13880 27216 14506 27216 14511 27216 13878 27217 14506 27217 13880 27217 14556 27218 13913 27218 14550 27218 13878 27219 14501 27219 14506 27219 13916 27220 13913 27220 14556 27220 13874 27221 14501 27221 13878 27221 14497 27222 14501 27222 13874 27222 14556 27223 13919 27223 13916 27223 14561 27224 13919 27224 14556 27224 13871 27225 14497 27225 13874 27225 13922 27226 13919 27226 14561 27226 14494 27227 14497 27227 13871 27227 13867 27228 14494 27228 13871 27228 14564 27229 13922 27229 14561 27229 14564 27230 13926 27230 13922 27230 14489 27231 14494 27231 13867 27231 13928 27232 13926 27232 14564 27232 13865 27233 14489 27233 13867 27233 14457 27234 13928 27234 14564 27234 14484 27235 14489 27235 13865 27235 14457 27236 13845 27236 13928 27236 14484 27237 13865 27237 13862 27237 14461 27238 13845 27238 14457 27238 14480 27239 14484 27239 13862 27239 14461 27240 13848 27240 13845 27240 14480 27241 13862 27241 13859 27241 14480 27242 13859 27242 13856 27242 14465 27243 13848 27243 14461 27243 14465 27244 13850 27244 13848 27244 14468 27245 14480 27245 13856 27245 14468 27246 13850 27246 14465 27246 14468 27247 13853 27247 13850 27247 14468 27248 13856 27248 13853 27248

+
+ + + +

14572 27249 14571 27249 14574 27249 14576 27250 14663 27250 14573 27250 14575 27251 14572 27251 14574 27251 14575 27252 14573 27252 14572 27252 14576 27253 14573 27253 14575 27253 14577 27254 14575 27254 14574 27254 14579 27255 14575 27255 14577 27255 14579 27256 14576 27256 14575 27256 14577 27257 14574 27257 14578 27257 14580 27258 14577 27258 14578 27258 14579 27259 14577 27259 14580 27259 14581 27260 14580 27260 14578 27260 14582 27261 14579 27261 14580 27261 14583 27262 14580 27262 14581 27262 14583 27263 14581 27263 14584 27263 14585 27264 14580 27264 14583 27264 14582 27265 14580 27265 14585 27265 14585 27266 14583 27266 14584 27266 14588 27267 14582 27267 14585 27267 14585 27268 14584 27268 14587 27268 14588 27269 14585 27269 14586 27269 14586 27270 14585 27270 14587 27270 14589 27271 14588 27271 14586 27271 14589 27272 14586 27272 14587 27272 14590 27273 14589 27273 14587 27273 14592 27274 14589 27274 14590 27274 14591 27275 14588 27275 14589 27275 14592 27276 14591 27276 14589 27276 14594 27277 14590 27277 14593 27277 14594 27278 14592 27278 14590 27278 14595 27279 14594 27279 14593 27279 14596 27280 14592 27280 14594 27280 14596 27281 14591 27281 14592 27281 14597 27282 14594 27282 14595 27282 14597 27283 14596 27283 14594 27283 14598 27284 14597 27284 14595 27284 14599 27285 14597 27285 14598 27285 14600 27286 14597 27286 14599 27286 14600 27287 14596 27287 14597 27287 14601 27288 14599 27288 14598 27288 14601 27289 14600 27289 14599 27289 14602 27290 14596 27290 14600 27290 14600 27291 14601 27291 14603 27291 14602 27292 14600 27292 14604 27292 14604 27293 14600 27293 14603 27293 14606 27294 14603 27294 14605 27294 14604 27295 14603 27295 14606 27295 14607 27296 14604 27296 14606 27296 14607 27297 14602 27297 14604 27297 14609 27298 14606 27298 14608 27298 14609 27299 14607 27299 14606 27299 14609 27300 14608 27300 14610 27300 14611 27301 14609 27301 14610 27301 14611 27302 14610 27302 14612 27302 14607 27303 14609 27303 14611 27303 14614 27304 14607 27304 14611 27304 14611 27305 14612 27305 14613 27305 14615 27306 14611 27306 14613 27306 14614 27307 14611 27307 14615 27307 14616 27308 14615 27308 14613 27308 14617 27309 14615 27309 14616 27309 14614 27310 14615 27310 14617 27310 14617 27311 14616 27311 14618 27311 14619 27312 14614 27312 14617 27312 14620 27313 14617 27313 14618 27313 14621 27314 14620 27314 14618 27314 14619 27315 14617 27315 14620 27315 14622 27316 14620 27316 14621 27316 14623 27317 14620 27317 14622 27317 14619 27318 14620 27318 14623 27318 14625 27319 14619 27319 14623 27319 14626 27320 14622 27320 14624 27320 14623 27321 14622 27321 14626 27321 14627 27322 14626 27322 14624 27322 14625 27323 14623 27323 14626 27323 14628 27324 14626 27324 14627 27324 14630 27325 14626 27325 14628 27325 14625 27326 14626 27326 14630 27326 14631 27327 14628 27327 14629 27327 14631 27328 14630 27328 14628 27328 14633 27329 14631 27329 14629 27329 14633 27330 14629 27330 14632 27330 14634 27331 14631 27331 14633 27331 14634 27332 14630 27332 14631 27332 14635 27333 14633 27333 14632 27333 14636 27334 14633 27334 14635 27334 14634 27335 14633 27335 14636 27335 14636 27336 14635 27336 14637 27336 14638 27337 14636 27337 14637 27337 14639 27338 14636 27338 14638 27338 14639 27339 14634 27339 14636 27339 14638 27340 14637 27340 14640 27340 14641 27341 14639 27341 14638 27341 14642 27342 14638 27342 14640 27342 14641 27343 14638 27343 14642 27343 14643 27344 14639 27344 14641 27344 14641 27345 14642 27345 14644 27345 14645 27346 14641 27346 14644 27346 14645 27347 14643 27347 14641 27347 14647 27348 14645 27348 14644 27348 14647 27349 14644 27349 14646 27349 14647 27350 14643 27350 14645 27350 14648 27351 14647 27351 14646 27351 14649 27352 14643 27352 14647 27352 14650 27353 14647 27353 14648 27353 14649 27354 14647 27354 14650 27354 14652 27355 14649 27355 14650 27355 14653 27356 14650 27356 14651 27356 14652 27357 14650 27357 14653 27357 14653 27358 14651 27358 14654 27358 14655 27359 14652 27359 14653 27359 14657 27360 14653 27360 14654 27360 14655 27361 14653 27361 14657 27361 14656 27362 14652 27362 14655 27362 14658 27363 14655 27363 14657 27363 14659 27364 14655 27364 14658 27364 14659 27365 14656 27365 14655 27365 14659 27366 14658 27366 14660 27366 14660 27367 14658 27367 14661 27367 14663 27368 14659 27368 14660 27368 14660 27369 14661 27369 14662 27369 14663 27370 14656 27370 14659 27370 14663 27371 14660 27371 14662 27371 14572 27372 14662 27372 14571 27372 14572 27373 14663 27373 14662 27373 14573 27374 14663 27374 14572 27374 14701 27375 14618 27375 14664 27375 14618 27376 14616 27376 14664 27376 14664 27377 14616 27377 14665 27377 14616 27378 14613 27378 14665 27378 14665 27379 14613 27379 14666 27379 14613 27380 14612 27380 14666 27380 14612 27381 14610 27381 14666 27381 14666 27382 14610 27382 14667 27382 14610 27383 14608 27383 14667 27383 14667 27384 14608 27384 14668 27384 14608 27385 14606 27385 14668 27385 14668 27386 14606 27386 14669 27386 14606 27387 14605 27387 14669 27387 14669 27388 14605 27388 14670 27388 14605 27389 14603 27389 14670 27389 14670 27390 14601 27390 14712 27390 14603 27391 14601 27391 14670 27391 14712 27392 14598 27392 14671 27392 14601 27393 14598 27393 14712 27393 14671 27394 14598 27394 14672 27394 14598 27395 14595 27395 14672 27395 14672 27396 14595 27396 14673 27396 14595 27397 14593 27397 14673 27397 14673 27398 14593 27398 14674 27398 14593 27399 14590 27399 14674 27399 14674 27400 14590 27400 14675 27400 14590 27401 14587 27401 14675 27401 14675 27402 14587 27402 14676 27402 14587 27403 14584 27403 14676 27403 14676 27404 14584 27404 14677 27404 14677 27405 14584 27405 14678 27405 14584 27406 14581 27406 14678 27406 14678 27407 14578 27407 14726 27407 14581 27408 14578 27408 14678 27408 14726 27409 14578 27409 14679 27409 14679 27410 14578 27410 14680 27410 14578 27411 14574 27411 14680 27411 14680 27412 14574 27412 14681 27412 14574 27413 14571 27413 14681 27413 14681 27414 14571 27414 14682 27414 14571 27415 14662 27415 14682 27415 14682 27416 14662 27416 14683 27416 14662 27417 14661 27417 14683 27417 14683 27418 14661 27418 14684 27418 14661 27419 14658 27419 14684 27419 14658 27420 14657 27420 14684 27420 14684 27421 14657 27421 14685 27421 14657 27422 14654 27422 14685 27422 14685 27423 14654 27423 14686 27423 14686 27424 14654 27424 14687 27424 14654 27425 14651 27425 14687 27425 14651 27426 14650 27426 14687 27426 14687 27427 14650 27427 14688 27427 14688 27428 14648 27428 14689 27428 14650 27429 14648 27429 14688 27429 14648 27430 14646 27430 14689 27430 14689 27431 14646 27431 14690 27431 14646 27432 14644 27432 14690 27432 14644 27433 14642 27433 14690 27433 14690 27434 14642 27434 14691 27434 14642 27435 14640 27435 14691 27435 14691 27436 14640 27436 14692 27436 14640 27437 14637 27437 14692 27437 14692 27438 14637 27438 14693 27438 14637 27439 14635 27439 14693 27439 14693 27440 14635 27440 14694 27440 14635 27441 14632 27441 14694 27441 14694 27442 14632 27442 14695 27442 14695 27443 14629 27443 14696 27443 14632 27444 14629 27444 14695 27444 14696 27445 14629 27445 14697 27445 14697 27446 14628 27446 14698 27446 14629 27447 14628 27447 14697 27447 14628 27448 14627 27448 14698 27448 14627 27449 14624 27449 14698 27449 14698 27450 14624 27450 14699 27450 14624 27451 14622 27451 14699 27451 14699 27452 14622 27452 14700 27452 14622 27453 14621 27453 14700 27453 14700 27454 14621 27454 14701 27454 14621 27455 14618 27455 14701 27455 14588 27456 15172 27456 15183 27456 14582 27457 14588 27457 15183 27457 14579 27458 14582 27458 15183 27458 14579 27459 15183 27459 15192 27459 14588 27460 15163 27460 15172 27460 14591 27461 15163 27461 14588 27461 14576 27462 14579 27462 15192 27462 14576 27463 15192 27463 15200 27463 14591 27464 15312 27464 15163 27464 14663 27465 14576 27465 15200 27465 14596 27466 15312 27466 14591 27466 14663 27467 15200 27467 15205 27467 14596 27468 15306 27468 15312 27468 14602 27469 15306 27469 14596 27469 14656 27470 14663 27470 15205 27470 14656 27471 15205 27471 15212 27471 14602 27472 15300 27472 15306 27472 14602 27473 15293 27473 15300 27473 14652 27474 14656 27474 15212 27474 14652 27475 15212 27475 15218 27475 14607 27476 15293 27476 14602 27476 15291 27477 15293 27477 14607 27477 15224 27478 14652 27478 15218 27478 15224 27479 14649 27479 14652 27479 15229 27480 14649 27480 15224 27480 15286 27481 15291 27481 14607 27481 15286 27482 14607 27482 14614 27482 15229 27483 14643 27483 14649 27483 15278 27484 15286 27484 14614 27484 15236 27485 14643 27485 15229 27485 15236 27486 14639 27486 14643 27486 15241 27487 14639 27487 15236 27487 15278 27488 14614 27488 14619 27488 15272 27489 15278 27489 14619 27489 15241 27490 14634 27490 14639 27490 15272 27491 14619 27491 14625 27491 15266 27492 15272 27492 14625 27492 15247 27493 14634 27493 15241 27493 15260 27494 14634 27494 15247 27494 15260 27495 14630 27495 14634 27495 15260 27496 15266 27496 14625 27496 15260 27497 14625 27497 14630 27497 14704 27498 14758 27498 14702 27498 14703 27499 14701 27499 14664 27499 14702 27500 14701 27500 14703 27500 14665 27501 14703 27501 14664 27501 14705 27502 14703 27502 14665 27502 14707 27503 14704 27503 14702 27503 14705 27504 14702 27504 14703 27504 14705 27505 14665 27505 14666 27505 14707 27506 14702 27506 14705 27506 14706 27507 14705 27507 14666 27507 14706 27508 14666 27508 14667 27508 14707 27509 14705 27509 14706 27509 14709 27510 14706 27510 14667 27510 14708 27511 14707 27511 14706 27511 14708 27512 14706 27512 14709 27512 14668 27513 14709 27513 14667 27513 14669 27514 14709 27514 14668 27514 14710 27515 14709 27515 14669 27515 14710 27516 14708 27516 14709 27516 14711 27517 14708 27517 14710 27517 14710 27518 14669 27518 14670 27518 14711 27519 14713 27519 14708 27519 14712 27520 14710 27520 14670 27520 14711 27521 14710 27521 14712 27521 14713 27522 14711 27522 14712 27522 14714 27523 14712 27523 14671 27523 14714 27524 14713 27524 14712 27524 14672 27525 14714 27525 14671 27525 14715 27526 14714 27526 14672 27526 14716 27527 14713 27527 14714 27527 14716 27528 14714 27528 14715 27528 14717 27529 14715 27529 14672 27529 14717 27530 14672 27530 14673 27530 14716 27531 14715 27531 14717 27531 14718 27532 14716 27532 14717 27532 14719 27533 14673 27533 14674 27533 14719 27534 14717 27534 14673 27534 14719 27535 14718 27535 14717 27535 14675 27536 14719 27536 14674 27536 14718 27537 14719 27537 14720 27537 14720 27538 14719 27538 14675 27538 14720 27539 14675 27539 14676 27539 14721 27540 14720 27540 14676 27540 14718 27541 14720 27541 14721 27541 14722 27542 14718 27542 14721 27542 14677 27543 14721 27543 14676 27543 14723 27544 14721 27544 14677 27544 14722 27545 14721 27545 14723 27545 14678 27546 14723 27546 14677 27546 14724 27547 14723 27547 14678 27547 14725 27548 14722 27548 14723 27548 14725 27549 14723 27549 14724 27549 14726 27550 14724 27550 14678 27550 14727 27551 14724 27551 14726 27551 14727 27552 14725 27552 14724 27552 14727 27553 14726 27553 14679 27553 14728 27554 14725 27554 14727 27554 14729 27555 14679 27555 14680 27555 14729 27556 14727 27556 14679 27556 14729 27557 14728 27557 14727 27557 14730 27558 14729 27558 14680 27558 14681 27559 14730 27559 14680 27559 14728 27560 14729 27560 14730 27560 14731 27561 14728 27561 14730 27561 14732 27562 14681 27562 14682 27562 14732 27563 14730 27563 14681 27563 14733 27564 14730 27564 14732 27564 14733 27565 14731 27565 14730 27565 14732 27566 14682 27566 14683 27566 14734 27567 14732 27567 14683 27567 14733 27568 14732 27568 14734 27568 14735 27569 14731 27569 14733 27569 14735 27570 14733 27570 14734 27570 14734 27571 14683 27571 14684 27571 14736 27572 14734 27572 14684 27572 14736 27573 14735 27573 14734 27573 14685 27574 14736 27574 14684 27574 14737 27575 14735 27575 14736 27575 14737 27576 14736 27576 14685 27576 14738 27577 14685 27577 14686 27577 14738 27578 14737 27578 14685 27578 14739 27579 14738 27579 14686 27579 14739 27580 14686 27580 14687 27580 14739 27581 14687 27581 14688 27581 14740 27582 14739 27582 14688 27582 14741 27583 14739 27583 14740 27583 14741 27584 14738 27584 14739 27584 14740 27585 14688 27585 14689 27585 14742 27586 14740 27586 14689 27586 14742 27587 14741 27587 14740 27587 14742 27588 14689 27588 14690 27588 14743 27589 14741 27589 14742 27589 14744 27590 14742 27590 14690 27590 14744 27591 14743 27591 14742 27591 14691 27592 14744 27592 14690 27592 14745 27593 14744 27593 14691 27593 14743 27594 14744 27594 14745 27594 14746 27595 14743 27595 14745 27595 14692 27596 14745 27596 14691 27596 14747 27597 14745 27597 14692 27597 14746 27598 14745 27598 14747 27598 14747 27599 14692 27599 14693 27599 14748 27600 14747 27600 14693 27600 14748 27601 14746 27601 14747 27601 14749 27602 14693 27602 14694 27602 14750 27603 14746 27603 14748 27603 14749 27604 14748 27604 14693 27604 14750 27605 14748 27605 14749 27605 14695 27606 14749 27606 14694 27606 14751 27607 14749 27607 14695 27607 14750 27608 14749 27608 14751 27608 14751 27609 14695 27609 14696 27609 14752 27610 14750 27610 14751 27610 14753 27611 14751 27611 14696 27611 14752 27612 14751 27612 14753 27612 14697 27613 14753 27613 14696 27613 14754 27614 14753 27614 14697 27614 14754 27615 14697 27615 14698 27615 14754 27616 14752 27616 14753 27616 14756 27617 14754 27617 14698 27617 14755 27618 14752 27618 14754 27618 14699 27619 14756 27619 14698 27619 14756 27620 14755 27620 14754 27620 14757 27621 14755 27621 14756 27621 14700 27622 14756 27622 14699 27622 14700 27623 14757 27623 14756 27623 14758 27624 14757 27624 14700 27624 14758 27625 14700 27625 14701 27625 14704 27626 14757 27626 14758 27626 14758 27627 14701 27627 14702 27627 14737 27628 14738 27628 14945 27628 14738 27629 14938 27629 14945 27629 14741 27630 14938 27630 14738 27630 14737 27631 14945 27631 14953 27631 14741 27632 14933 27632 14938 27632 14743 27633 14933 27633 14741 27633 14735 27634 14737 27634 14953 27634 14735 27635 14953 27635 14960 27635 14743 27636 14922 27636 14933 27636 14731 27637 14735 27637 14960 27637 14746 27638 14922 27638 14743 27638 14728 27639 14960 27639 14970 27639 14728 27640 14731 27640 14960 27640 14746 27641 14912 27641 14922 27641 14750 27642 14912 27642 14746 27642 14750 27643 14905 27643 14912 27643 14725 27644 14728 27644 14970 27644 14752 27645 14905 27645 14750 27645 14725 27646 14970 27646 14981 27646 14722 27647 14725 27647 14981 27647 14900 27648 14905 27648 14752 27648 14900 27649 14752 27649 14755 27649 14989 27650 14722 27650 14981 27650 14900 27651 14755 27651 14757 27651 14989 27652 14718 27652 14722 27652 14998 27653 14718 27653 14989 27653 14883 27654 14900 27654 14757 27654 14847 27655 14716 27655 14718 27655 14847 27656 14718 27656 14998 27656 14883 27657 14757 27657 14704 27657 14876 27658 14883 27658 14704 27658 14876 27659 14704 27659 14707 27659 14847 27660 14713 27660 14716 27660 14855 27661 14713 27661 14847 27661 14869 27662 14876 27662 14707 27662 14869 27663 14707 27663 14708 27663 14864 27664 14713 27664 14855 27664 14864 27665 14869 27665 14708 27665 14864 27666 14708 27666 14713 27666 14759 27667 14760 27667 14761 27667 14762 27668 14759 27668 14761 27668 14762 27669 14761 27669 14763 27669 14764 27670 14762 27670 14763 27670 14764 27671 14763 27671 14765 27671 14766 27672 14764 27672 14765 27672 14766 27673 14765 27673 14767 27673 14768 27674 14766 27674 14767 27674 14768 27675 14767 27675 14769 27675 14768 27676 14769 27676 14770 27676 14771 13760 14768 13760 14770 13760 14771 27677 14770 27677 14772 27677 14773 27678 14771 27678 14772 27678 14773 27679 14772 27679 14774 27679 14775 27680 14773 27680 14774 27680 14775 27681 14774 27681 14776 27681 14777 27682 14775 27682 14776 27682 14777 27683 14776 27683 14778 27683 14779 27684 14777 27684 14778 27684 14779 27685 14778 27685 14780 27685 14781 27686 14779 27686 14780 27686 14781 27687 14780 27687 14782 27687 14783 27688 14781 27688 14782 27688 14784 27689 14783 27689 14782 27689 14784 27690 14782 27690 14785 27690 14786 27691 14784 27691 14785 27691 14786 27692 14785 27692 14787 27692 14788 27693 14786 27693 14787 27693 14788 27694 14787 27694 14789 27694 14790 27695 14788 27695 14789 27695 14790 27696 14789 27696 14791 27696 14792 27697 14790 27697 14791 27697 14792 27698 14791 27698 14793 27698 14794 27699 14792 27699 14793 27699 14794 27700 14793 27700 14795 27700 14796 27701 14794 27701 14795 27701 14796 27702 14795 27702 14797 27702 14798 27703 14796 27703 14797 27703 14799 27704 14797 27704 14800 27704 14799 27705 14798 27705 14797 27705 14801 27706 14799 27706 14800 27706 14801 27707 14800 27707 14760 27707 14759 27708 14801 27708 14760 27708 14802 27709 14803 27709 14804 27709 14805 27710 14802 27710 14804 27710 14805 27711 14804 27711 14806 27711 14807 27712 14805 27712 14806 27712 14807 27713 14806 27713 14808 27713 14809 27714 14807 27714 14808 27714 14809 27715 14808 27715 14810 27715 14811 27716 14809 27716 14810 27716 14811 27717 14810 27717 14812 27717 14813 27718 14811 27718 14812 27718 14813 27719 14812 27719 14814 27719 14815 27720 14813 27720 14814 27720 14815 27721 14814 27721 14816 27721 14817 27722 14815 27722 14816 27722 14817 27723 14816 27723 14818 27723 14819 27724 14817 27724 14818 27724 14819 27725 14818 27725 14820 27725 14821 27726 14819 27726 14820 27726 14822 27727 14820 27727 14823 27727 14822 27728 14821 27728 14820 27728 14822 27729 14823 27729 14824 27729 14825 27730 14822 27730 14824 27730 14825 27731 14824 27731 14826 27731 14827 27732 14825 27732 14826 27732 14827 27733 14826 27733 14828 27733 14829 27734 14827 27734 14828 27734 14829 27735 14828 27735 14830 27735 14831 27736 14829 27736 14830 27736 14831 13825 14830 13825 14832 13825 14833 27737 14831 27737 14832 27737 14833 27738 14832 27738 14834 27738 14835 27739 14833 27739 14834 27739 14835 27740 14834 27740 14836 27740 14837 27741 14835 27741 14836 27741 14838 27742 14836 27742 14839 27742 14838 27743 14837 27743 14836 27743 14840 27744 14838 27744 14839 27744 14840 27745 14839 27745 14841 27745 14842 27746 14840 27746 14841 27746 14842 27747 14841 27747 14803 27747 14802 27748 14842 27748 14803 27748 14844 27749 14845 27749 14843 27749 14846 27750 14845 27750 14844 27750 14846 27751 14847 27751 15000 27751 14848 27752 14846 27752 14844 27752 14849 27753 14844 27753 14843 27753 14848 27754 14844 27754 14849 27754 14850 27755 14846 27755 14848 27755 14851 27756 14848 27756 14849 27756 14854 27757 14846 27757 14850 27757 14854 27758 14847 27758 14846 27758 14850 27759 14848 27759 14851 27759 14852 27760 14850 27760 14851 27760 14854 27761 14850 27761 14852 27761 14852 27762 14851 27762 14853 27762 14855 27763 14847 27763 14854 27763 14856 27764 14852 27764 14853 27764 14856 27765 14854 27765 14852 27765 14855 27766 14854 27766 14856 27766 14857 27767 14856 27767 14853 27767 14859 27768 14857 27768 14858 27768 14859 27769 14856 27769 14857 27769 14861 27770 14856 27770 14859 27770 14855 27771 14856 27771 14861 27771 14859 27772 14858 27772 14860 27772 14863 27773 14859 27773 14860 27773 14863 27774 14860 27774 14862 27774 14864 27775 14855 27775 14861 27775 14865 27776 14859 27776 14863 27776 14865 27777 14861 27777 14859 27777 14864 27778 14861 27778 14865 27778 14866 27779 14863 27779 14862 27779 14867 27780 14863 27780 14866 27780 14867 27781 14865 27781 14863 27781 14867 27782 14864 27782 14865 27782 14870 27783 14866 27783 14868 27783 14869 27784 14864 27784 14867 27784 14870 27785 14867 27785 14866 27785 14869 27786 14867 27786 14870 27786 14872 27787 14868 27787 14871 27787 14872 27788 14870 27788 14868 27788 14873 27789 14870 27789 14872 27789 14873 27790 14869 27790 14870 27790 14874 27791 14872 27791 14871 27791 14875 27792 14872 27792 14874 27792 14875 27793 14873 27793 14872 27793 14876 27794 14869 27794 14873 27794 14876 27795 14873 27795 14875 27795 14875 27796 14874 27796 14877 27796 14878 27797 14876 27797 14875 27797 14878 27798 14875 27798 14877 27798 14879 27799 14878 27799 14877 27799 14882 27800 14876 27800 14878 27800 14880 27801 14878 27801 14879 27801 14882 27802 14878 27802 14880 27802 14880 27803 14879 27803 14881 27803 14883 27804 14876 27804 14882 27804 14885 27805 14882 27805 14880 27805 14884 27806 14880 27806 14881 27806 14883 27807 14882 27807 14885 27807 14887 27808 14880 27808 14884 27808 14887 27809 14885 27809 14880 27809 14887 27810 14884 27810 14886 27810 14889 27811 14885 27811 14887 27811 14890 27812 14886 27812 14888 27812 14883 27813 14885 27813 14889 27813 14890 27814 14887 27814 14886 27814 14890 27815 14889 27815 14887 27815 14891 27816 14890 27816 14888 27816 14892 27817 14890 27817 14891 27817 14893 27818 14890 27818 14892 27818 14893 27819 14889 27819 14890 27819 14893 27820 14883 27820 14889 27820 14894 27821 14892 27821 14891 27821 14900 27822 14883 27822 14893 27822 14894 27823 14893 27823 14892 27823 14895 27824 14894 27824 14891 27824 14896 27825 14893 27825 14894 27825 14897 27826 14894 27826 14895 27826 14900 27827 14893 27827 14896 27827 14896 27828 14894 27828 14897 27828 14898 27829 14897 27829 14895 27829 14899 27830 14896 27830 14897 27830 14899 27831 14897 27831 14898 27831 14899 27832 14898 27832 14901 27832 14903 27833 14896 27833 14899 27833 14902 27834 14899 27834 14901 27834 14904 27835 14899 27835 14902 27835 14903 27836 14900 27836 14896 27836 14903 27837 14899 27837 14904 27837 14905 27838 14900 27838 14903 27838 14904 27839 14902 27839 14906 27839 14907 27840 14903 27840 14904 27840 14907 27841 14904 27841 14906 27841 14905 27842 14903 27842 14907 27842 14908 27843 14907 27843 14906 27843 14909 27844 14907 27844 14908 27844 14911 27845 14907 27845 14909 27845 14911 27846 14905 27846 14907 27846 14909 27847 14908 27847 14910 27847 14912 27848 14905 27848 14911 27848 14913 27849 14911 27849 14909 27849 14914 27850 14909 27850 14910 27850 14915 27851 14909 27851 14914 27851 14915 27852 14913 27852 14909 27852 14912 27853 14911 27853 14913 27853 14915 27854 14914 27854 14916 27854 14917 27855 14913 27855 14915 27855 14918 27856 14913 27856 14917 27856 14918 27857 14912 27857 14913 27857 14917 27858 14915 27858 14916 27858 14922 27859 14912 27859 14918 27859 14917 27860 14916 27860 14919 27860 14922 27861 14918 27861 14917 27861 14921 27862 14917 27862 14919 27862 14922 27863 14917 27863 14921 27863 14923 27864 14919 27864 14920 27864 14923 27865 14921 27865 14919 27865 14923 27866 14920 27866 14924 27866 14925 27867 14921 27867 14923 27867 14925 27868 14922 27868 14921 27868 14926 27869 14923 27869 14924 27869 14927 27870 14923 27870 14926 27870 14928 27871 14923 27871 14927 27871 14928 27872 14925 27872 14923 27872 14929 27873 14927 27873 14926 27873 14932 27874 14925 27874 14928 27874 14932 27875 14922 27875 14925 27875 14930 27876 14927 27876 14929 27876 14930 27877 14928 27877 14927 27877 14931 27878 14930 27878 14929 27878 14933 27879 14922 27879 14932 27879 14932 27880 14928 27880 14930 27880 14935 27881 14931 27881 14934 27881 14935 27882 14930 27882 14931 27882 14935 27883 14932 27883 14930 27883 14936 27884 14932 27884 14935 27884 14937 27885 14935 27885 14934 27885 14933 27886 14932 27886 14936 27886 14936 27887 14935 27887 14937 27887 14938 27888 14933 27888 14936 27888 14939 27889 14936 27889 14937 27889 14940 27890 14939 27890 14937 27890 14941 27891 14936 27891 14939 27891 14938 27892 14936 27892 14941 27892 14941 27893 14939 27893 14940 27893 14943 27894 14940 27894 14942 27894 14943 27895 14941 27895 14940 27895 14945 27896 14938 27896 14941 27896 14945 27897 14941 27897 14943 27897 14944 27898 14943 27898 14942 27898 14946 27899 14943 27899 14944 27899 14945 27900 14943 27900 14946 27900 14949 27901 14944 27901 14948 27901 14947 27902 14945 27902 14946 27902 14949 27903 14946 27903 14944 27903 14947 27904 14946 27904 14949 27904 14953 27905 14945 27905 14947 27905 14951 27906 14947 27906 14949 27906 14952 27907 14948 27907 14950 27907 14952 27908 14949 27908 14948 27908 14951 27909 14949 27909 14952 27909 14953 27910 14947 27910 14951 27910 14955 27911 14951 27911 14952 27911 14953 27912 14951 27912 14955 27912 14955 27913 14952 27913 14950 27913 14955 27914 14950 27914 14954 27914 14956 27915 14955 27915 14954 27915 14957 27916 14953 27916 14955 27916 14957 27917 14955 27917 14956 27917 14958 27918 14957 27918 14956 27918 14958 27919 14956 27919 14959 27919 14960 27920 14953 27920 14957 27920 14961 27921 14957 27921 14958 27921 14960 27922 14957 27922 14961 27922 14961 27923 14958 27923 14959 27923 14964 27924 14959 27924 14962 27924 14964 27925 14961 27925 14959 27925 14963 27926 14960 27926 14961 27926 14963 27927 14961 27927 14964 27927 14965 27928 14964 27928 14962 27928 14966 27929 14964 27929 14965 27929 14963 27930 14964 27930 14966 27930 14968 27931 14960 27931 14963 27931 14967 27932 14966 27932 14965 27932 14968 27933 14963 27933 14966 27933 14969 27934 14966 27934 14967 27934 14970 27935 14960 27935 14968 27935 14968 27936 14966 27936 14969 27936 14971 27937 14969 27937 14967 27937 14972 27938 14968 27938 14969 27938 14973 27939 14969 27939 14971 27939 14972 27940 14969 27940 14973 27940 14970 27941 14968 27941 14972 27941 14974 27942 14973 27942 14971 27942 14975 27943 14972 27943 14973 27943 14975 27944 14970 27944 14972 27944 14976 27945 14973 27945 14974 27945 14977 27946 14973 27946 14976 27946 14977 27947 14975 27947 14973 27947 14980 27948 14970 27948 14975 27948 14978 27949 14977 27949 14976 27949 14979 27950 14977 27950 14978 27950 14979 27951 14975 27951 14977 27951 14980 27952 14975 27952 14979 27952 14981 27953 14970 27953 14980 27953 14983 27954 14980 27954 14979 27954 14984 27955 14978 27955 14982 27955 14984 27956 14979 27956 14978 27956 14983 27957 14979 27957 14984 27957 14983 27958 14981 27958 14980 27958 14986 27959 14983 27959 14984 27959 14985 27960 14984 27960 14982 27960 14987 27961 14984 27961 14985 27961 14981 27962 14983 27962 14986 27962 14987 27963 14986 27963 14984 27963 14987 27964 14985 27964 14988 27964 14989 27965 14981 27965 14986 27965 14990 27966 14987 27966 14988 27966 14991 27967 14987 27967 14990 27967 14991 27968 14986 27968 14987 27968 14989 27969 14986 27969 14991 27969 14992 27970 14990 27970 14988 27970 14993 27971 14990 27971 14992 27971 14993 27972 14991 27972 14990 27972 14995 27973 14991 27973 14993 27973 14995 27974 14989 27974 14991 27974 14996 27975 14992 27975 14994 27975 14996 27976 14993 27976 14992 27976 14995 27977 14993 27977 14996 27977 14997 27978 14996 27978 14994 27978 14998 27979 14989 27979 14995 27979 15000 27980 14995 27980 14996 27980 14998 27981 14995 27981 15000 27981 14999 27982 14996 27982 14997 27982 15000 27983 14996 27983 14999 27983 14845 27984 14999 27984 14843 27984 14845 27985 15000 27985 14999 27985 15000 27986 14845 27986 14846 27986 14998 27987 15000 27987 14847 27987 14843 27988 15001 27988 15002 27988 14849 27989 14843 27989 15002 27989 14851 27990 15002 27990 15003 27990 14851 27991 14849 27991 15002 27991 14853 27992 15003 27992 15004 27992 14853 27993 14851 27993 15003 27993 14857 27994 14853 27994 15004 27994 14857 27995 15004 27995 15005 27995 14858 27996 14857 27996 15005 27996 14858 27997 15005 27997 15146 27997 14860 27998 14858 27998 15146 27998 14860 27999 15146 27999 15006 27999 14862 28000 14860 28000 15006 28000 14862 28001 15006 28001 15007 28001 14866 28002 14862 28002 15007 28002 14866 28003 15007 28003 15140 28003 14868 28004 14866 28004 15140 28004 14868 28005 15140 28005 15008 28005 14871 28006 14868 28006 15008 28006 14871 28007 15008 28007 15009 28007 14874 28008 14871 28008 15009 28008 14874 28009 15009 28009 15010 28009 14877 28010 14874 28010 15010 28010 14877 28011 15010 28011 15011 28011 14879 28012 14877 28012 15011 28012 14879 28013 15011 28013 15132 28013 14879 28014 15132 28014 15012 28014 14881 28015 14879 28015 15012 28015 14884 28016 14881 28016 15012 28016 14884 28017 15012 28017 15013 28017 14886 28018 14884 28018 15013 28018 14886 28019 15013 28019 15014 28019 14888 28020 14886 28020 15014 28020 14888 28021 15014 28021 15015 28021 14891 28022 14888 28022 15015 28022 14891 28023 15015 28023 15016 28023 14895 28024 14891 28024 15016 28024 14895 28025 15016 28025 15017 28025 14898 28026 14895 28026 15017 28026 14898 28027 15017 28027 15018 28027 14901 28028 14898 28028 15018 28028 14901 28029 15018 28029 15019 28029 14902 28030 14901 28030 15019 28030 14902 28031 15019 28031 15020 28031 14906 28032 14902 28032 15020 28032 14906 28033 15020 28033 15021 28033 14908 28034 14906 28034 15021 28034 14908 28035 15021 28035 15022 28035 14910 28036 14908 28036 15022 28036 14910 28037 15022 28037 15023 28037 14914 28038 14910 28038 15023 28038 14914 28039 15023 28039 15024 28039 14916 28040 14914 28040 15024 28040 14916 28041 15024 28041 15025 28041 14919 28042 14916 28042 15025 28042 14920 28043 15025 28043 15026 28043 14920 28044 14919 28044 15025 28044 14924 28045 14920 28045 15026 28045 14924 28046 15026 28046 15027 28046 14926 28047 14924 28047 15027 28047 14926 28048 15027 28048 15028 28048 14929 28049 14926 28049 15028 28049 14931 28050 14929 28050 15028 28050 14931 28051 15028 28051 15029 28051 14931 28052 15029 28052 15030 28052 14934 28053 14931 28053 15030 28053 14934 28054 15030 28054 15031 28054 14937 28055 15031 28055 15032 28055 14937 28056 14934 28056 15031 28056 14940 28057 15032 28057 15033 28057 14940 28058 14937 28058 15032 28058 14942 28059 14940 28059 15033 28059 14942 28060 15033 28060 15034 28060 14942 28061 15034 28061 15035 28061 14944 28062 14942 28062 15035 28062 14948 28063 15035 28063 15036 28063 14948 28064 14944 28064 15035 28064 14950 28065 14948 28065 15036 28065 14950 28066 15036 28066 15037 28066 14954 28067 14950 28067 15037 28067 14954 28068 15037 28068 15038 28068 14956 28069 14954 28069 15038 28069 14956 28070 15038 28070 15039 28070 14959 28071 14956 28071 15039 28071 14959 28072 15039 28072 15040 28072 14962 28073 14959 28073 15040 28073 14962 28074 15040 28074 15041 28074 14965 28075 14962 28075 15041 28075 14967 28076 15041 28076 15042 28076 14967 28077 14965 28077 15041 28077 14971 28078 15042 28078 15043 28078 14971 28079 14967 28079 15042 28079 14974 28080 14971 28080 15043 28080 14976 28081 15043 28081 15044 28081 14976 28082 14974 28082 15043 28082 14976 28083 15044 28083 15045 28083 14978 28084 14976 28084 15045 28084 14978 28085 15045 28085 15046 28085 14982 28086 14978 28086 15046 28086 14982 28087 15046 28087 15047 28087 14985 28088 14982 28088 15047 28088 14985 28089 15047 28089 15048 28089 14988 28090 14985 28090 15048 28090 14988 28091 15048 28091 15061 28091 14988 28092 15061 28092 15059 28092 14992 28093 14988 28093 15059 28093 14992 28094 15059 28094 15049 28094 14994 28095 14992 28095 15049 28095 14997 28096 15049 28096 15050 28096 14997 28097 14994 28097 15049 28097 14997 28098 15050 28098 15051 28098 14999 28099 14997 28099 15051 28099 14843 28100 15051 28100 15001 28100 14843 28101 14999 28101 15051 28101 15052 28102 15001 28102 15051 28102 15052 28103 15053 28103 15001 28103 15054 28104 15053 28104 15052 28104 15055 28105 15054 28105 15052 28105 15050 28106 15052 28106 15051 28106 15055 28107 15052 28107 15050 28107 15056 28108 15054 28108 15055 28108 15057 28109 15050 28109 15049 28109 15057 28110 15055 28110 15050 28110 15056 28111 15156 28111 15054 28111 15056 28112 15055 28112 15057 28112 15058 28113 15156 28113 15056 28113 15059 28114 15057 28114 15049 28114 15060 28115 15056 28115 15057 28115 15058 28116 15056 28116 15060 28116 15060 28117 15057 28117 15059 28117 15060 28118 15059 28118 15061 28118 15062 28119 15058 28119 15060 28119 15048 28120 15060 28120 15061 28120 15063 28121 15060 28121 15048 28121 15062 28122 15060 28122 15063 28122 15063 28123 15048 28123 15047 28123 15064 28124 15063 28124 15047 28124 15064 28125 15062 28125 15063 28125 15064 28126 15047 28126 15046 28126 15065 28127 15062 28127 15064 28127 15066 28128 15064 28128 15046 28128 15067 28129 15062 28129 15065 28129 15066 28130 15065 28130 15064 28130 15045 28131 15066 28131 15046 28131 15067 28132 15065 28132 15066 28132 15068 28133 15062 28133 15067 28133 15069 28134 15045 28134 15044 28134 15069 28135 15066 28135 15045 28135 15069 28136 15067 28136 15066 28136 15068 28137 15067 28137 15069 28137 15070 28138 15044 28138 15043 28138 15070 28139 15069 28139 15044 28139 15071 28140 15068 28140 15069 28140 15072 28141 15069 28141 15070 28141 15071 28142 15069 28142 15072 28142 15072 28143 15070 28143 15043 28143 15072 28144 15043 28144 15042 28144 15073 28145 15068 28145 15071 28145 15071 28146 15072 28146 15074 28146 15075 28147 15072 28147 15042 28147 15075 28148 15074 28148 15072 28148 15041 28149 15075 28149 15042 28149 15076 28150 15071 28150 15074 28150 15077 28151 15075 28151 15041 28151 15073 28152 15071 28152 15076 28152 15077 28153 15074 28153 15075 28153 15076 28154 15074 28154 15077 28154 15079 28155 15076 28155 15077 28155 15040 28156 15077 28156 15041 28156 15080 28157 15077 28157 15040 28157 15078 28158 15073 28158 15076 28158 15080 28159 15079 28159 15077 28159 15078 28160 15076 28160 15079 28160 15081 28161 15080 28161 15040 28161 15078 28162 15079 28162 15080 28162 15081 28163 15040 28163 15039 28163 15082 28164 15080 28164 15081 28164 15082 28165 15078 28165 15080 28165 15083 28166 15039 28166 15038 28166 15083 28167 15081 28167 15039 28167 15083 28168 15082 28168 15081 28168 15084 28169 15078 28169 15082 28169 15085 28170 15082 28170 15083 28170 15086 28171 15082 28171 15085 28171 15037 28172 15083 28172 15038 28172 15085 28173 15083 28173 15037 28173 15084 28174 15082 28174 15086 28174 15087 28175 15037 28175 15036 28175 15087 28176 15085 28176 15037 28176 15088 28177 15085 28177 15087 28177 15088 28178 15086 28178 15085 28178 15089 28179 15084 28179 15086 28179 15089 28180 15086 28180 15088 28180 15035 28181 15087 28181 15036 28181 15090 28182 15088 28182 15087 28182 15089 28183 15088 28183 15090 28183 15090 28184 15087 28184 15035 28184 15091 28185 15089 28185 15090 28185 15034 28186 15090 28186 15035 28186 15091 28187 15090 28187 15034 28187 15092 28188 15089 28188 15091 28188 15093 28189 15034 28189 15033 28189 15093 28190 15091 28190 15034 28190 15094 28191 15091 28191 15093 28191 15094 28192 15092 28192 15091 28192 15095 28193 15033 28193 15032 28193 15095 28194 15093 28194 15033 28194 15095 28195 15094 28195 15093 28195 15031 28196 15095 28196 15032 28196 15096 28197 15095 28197 15031 28197 15097 28198 15095 28198 15096 28198 15097 28199 15094 28199 15095 28199 15092 28200 15094 28200 15097 28200 15096 28201 15031 28201 15030 28201 15098 28202 15096 28202 15030 28202 15099 28203 15092 28203 15097 28203 15098 28204 15097 28204 15096 28204 15100 28205 15097 28205 15098 28205 15098 28206 15030 28206 15029 28206 15099 28207 15097 28207 15100 28207 15101 28208 15098 28208 15029 28208 15101 28209 15100 28209 15098 28209 15028 28210 15101 28210 15029 28210 15102 28211 15100 28211 15101 28211 15102 28212 15101 28212 15028 28212 15103 28213 15100 28213 15102 28213 15099 28214 15100 28214 15103 28214 15104 28215 15102 28215 15028 28215 15104 28216 15028 28216 15027 28216 15105 28217 15104 28217 15027 28217 15106 28218 15099 28218 15103 28218 15105 28219 15102 28219 15104 28219 15103 28220 15102 28220 15105 28220 15105 28221 15027 28221 15026 28221 15107 28222 15103 28222 15105 28222 15025 28223 15105 28223 15026 28223 15106 28224 15103 28224 15107 28224 15108 28225 15105 28225 15025 28225 15109 28226 15105 28226 15108 28226 15109 28227 15107 28227 15105 28227 15110 28228 15107 28228 15109 28228 15110 28229 15106 28229 15107 28229 15024 28230 15108 28230 15025 28230 15111 28231 15108 28231 15024 28231 15111 28232 15109 28232 15108 28232 15112 28233 15109 28233 15111 28233 15112 28234 15110 28234 15109 28234 15111 28235 15024 28235 15023 28235 15113 28236 15110 28236 15112 28236 15114 28237 15111 28237 15023 28237 15114 28238 15112 28238 15111 28238 15113 28239 15112 28239 15114 28239 15114 28240 15023 28240 15022 28240 15116 28241 15110 28241 15113 28241 15115 28242 15113 28242 15114 28242 15021 28243 15114 28243 15022 28243 15115 28244 15114 28244 15021 28244 15116 28245 15113 28245 15115 28245 15117 28246 15021 28246 15020 28246 15117 28247 15115 28247 15021 28247 15118 28248 15020 28248 15019 28248 15118 28249 15117 28249 15020 28249 15119 28250 15117 28250 15118 28250 15119 28251 15115 28251 15117 28251 15119 28252 15116 28252 15115 28252 15018 28253 15118 28253 15019 28253 15121 28254 15116 28254 15119 28254 15120 28255 15118 28255 15018 28255 15120 28256 15119 28256 15118 28256 15121 28257 15119 28257 15120 28257 15122 28258 15018 28258 15017 28258 15122 28259 15120 28259 15018 28259 15123 28260 15120 28260 15122 28260 15123 28261 15121 28261 15120 28261 15016 28262 15122 28262 15017 28262 15124 28263 15122 28263 15016 28263 15124 28264 15123 28264 15122 28264 15125 28265 15123 28265 15124 28265 15125 28266 15121 28266 15123 28266 15015 28267 15124 28267 15016 28267 15126 28268 15124 28268 15015 28268 15126 28269 15125 28269 15124 28269 15127 28270 15121 28270 15125 28270 15014 28271 15126 28271 15015 28271 15128 28272 15125 28272 15126 28272 15128 28273 15126 28273 15014 28273 15129 28274 15014 28274 15013 28274 15127 28275 15125 28275 15128 28275 15129 28276 15128 28276 15014 28276 15130 28277 15128 28277 15129 28277 15012 28278 15129 28278 15013 28278 15131 28279 15129 28279 15012 28279 15130 28280 15127 28280 15128 28280 15130 28281 15129 28281 15131 28281 15132 28282 15131 28282 15012 28282 15133 28283 15130 28283 15131 28283 15134 28284 15130 28284 15133 28284 15011 28285 15131 28285 15132 28285 15134 28286 15127 28286 15130 28286 15133 28287 15131 28287 15011 28287 15135 28288 15011 28288 15010 28288 15135 28289 15133 28289 15011 28289 15137 28290 15127 28290 15134 28290 15136 28291 15133 28291 15135 28291 15136 28292 15134 28292 15133 28292 15135 28293 15010 28293 15009 28293 15137 28294 15134 28294 15136 28294 15008 28295 15135 28295 15009 28295 15138 28296 15137 28296 15136 28296 15139 28297 15135 28297 15008 28297 15139 28298 15136 28298 15135 28298 15138 28299 15136 28299 15139 28299 15140 28300 15139 28300 15008 28300 15141 28301 15138 28301 15139 28301 15142 28302 15140 28302 15007 28302 15142 28303 15139 28303 15140 28303 15141 28304 15139 28304 15142 28304 15143 28305 15141 28305 15142 28305 15144 28306 15142 28306 15007 28306 15144 28307 15007 28307 15006 28307 15143 28308 15138 28308 15141 28308 15143 28309 15142 28309 15144 28309 15147 28310 15138 28310 15143 28310 15145 28311 15143 28311 15144 28311 15146 28312 15144 28312 15006 28312 15145 28313 15144 28313 15146 28313 15147 28314 15143 28314 15145 28314 15148 28315 15145 28315 15146 28315 15147 28316 15145 28316 15148 28316 15148 28317 15146 28317 15005 28317 15004 28318 15148 28318 15005 28318 15149 28319 15148 28319 15004 28319 15147 28320 15148 28320 15149 28320 15150 28321 15149 28321 15004 28321 15151 28322 15149 28322 15150 28322 15152 28323 15149 28323 15151 28323 15152 28324 15147 28324 15149 28324 15150 28325 15004 28325 15003 28325 15153 28326 15150 28326 15003 28326 15151 28327 15150 28327 15153 28327 15153 28328 15003 28328 15002 28328 15154 28329 15152 28329 15151 28329 15154 28330 15151 28330 15153 28330 15155 28331 15153 28331 15002 28331 15155 28332 15154 28332 15153 28332 15155 28333 15002 28333 15001 28333 15156 28334 15152 28334 15154 28334 15053 28335 15154 28335 15155 28335 15156 28336 15154 28336 15053 28336 15053 28337 15155 28337 15001 28337 15156 28338 15053 28338 15054 28338 14808 28339 15062 28339 15068 28339 14806 28340 15062 28340 14808 28340 14810 28341 14808 28341 15068 28341 14804 28342 15058 28342 15062 28342 14804 28343 15062 28343 14806 28343 14810 28344 15068 28344 15073 28344 14803 28345 15058 28345 14804 28345 14812 28346 14810 28346 15073 28346 14812 28347 15073 28347 15078 28347 14803 28348 15156 28348 15058 28348 14814 28349 14812 28349 15078 28349 14803 28350 15152 28350 15156 28350 14814 28351 15078 28351 15084 28351 14841 28352 15152 28352 14803 28352 14814 28353 15084 28353 15089 28353 14839 28354 15147 28354 15152 28354 14839 28355 15152 28355 14841 28355 14816 28356 14814 28356 15089 28356 14816 28357 15089 28357 15092 28357 14818 28358 14816 28358 15092 28358 14836 28359 15147 28359 14839 28359 15138 28360 15147 28360 14836 28360 15138 28361 14836 28361 14834 28361 15099 28362 14818 28362 15092 28362 15137 28363 15138 28363 14834 28363 15099 28364 14820 28364 14818 28364 15127 28365 15137 28365 14834 28365 15127 28366 14834 28366 14832 28366 15099 28367 14823 28367 14820 28367 15106 28368 14823 28368 15099 28368 15106 28369 14824 28369 14823 28369 15110 28370 14824 28370 15106 28370 15127 28371 14832 28371 14830 28371 15121 28372 15127 28372 14830 28372 15116 28373 14824 28373 15110 28373 15116 28374 14826 28374 14824 28374 15121 28375 14830 28375 14828 28375 15116 28376 15121 28376 14828 28376 15116 28377 14828 28377 14826 28377 15159 28378 15158 28378 15157 28378 15160 28379 15161 28379 15159 28379 15162 28380 15159 28380 15157 28380 15160 28381 15159 28381 15162 28381 15162 28382 15157 28382 15164 28382 15165 28383 15161 28383 15160 28383 15163 28384 15161 28384 15165 28384 15165 28385 15160 28385 15162 28385 15167 28386 15162 28386 15164 28386 15167 28387 15164 28387 15166 28387 15167 28388 15165 28388 15162 28388 15168 28389 15167 28389 15166 28389 15169 28390 15165 28390 15167 28390 15163 28391 15165 28391 15169 28391 15172 28392 15163 28392 15169 28392 15170 28393 15167 28393 15168 28393 15170 28394 15169 28394 15167 28394 15170 28395 15168 28395 15171 28395 15172 28396 15169 28396 15170 28396 15172 28397 15170 28397 15173 28397 15174 28398 15170 28398 15171 28398 15173 28399 15170 28399 15174 28399 15176 28400 15173 28400 15174 28400 15176 28401 15172 28401 15173 28401 15177 28402 15174 28402 15175 28402 15176 28403 15174 28403 15177 28403 15177 28404 15175 28404 15178 28404 15179 28405 15172 28405 15176 28405 15183 28406 15172 28406 15179 28406 15181 28407 15176 28407 15177 28407 15180 28408 15177 28408 15178 28408 15181 28409 15179 28409 15176 28409 15182 28410 15177 28410 15180 28410 15181 28411 15177 28411 15182 28411 15183 28412 15179 28412 15181 28412 15184 28413 15182 28413 15180 28413 15186 28414 15181 28414 15182 28414 15186 28415 15183 28415 15181 28415 15185 28416 15182 28416 15184 28416 15186 28417 15182 28417 15185 28417 15185 28418 15184 28418 15187 28418 15189 28419 15185 28419 15187 28419 15188 28420 15183 28420 15186 28420 15189 28421 15186 28421 15185 28421 15188 28422 15186 28422 15189 28422 15190 28423 15189 28423 15187 28423 15191 28424 15189 28424 15190 28424 15192 28425 15183 28425 15188 28425 15193 28426 15189 28426 15191 28426 15191 28427 15190 28427 15194 28427 15193 28428 15188 28428 15189 28428 15192 28429 15188 28429 15193 28429 15195 28430 15191 28430 15194 28430 15192 28431 15193 28431 15196 28431 15193 28432 15191 28432 15195 28432 15197 28433 15193 28433 15195 28433 15196 28434 15193 28434 15197 28434 15199 28435 15196 28435 15197 28435 15198 28436 15197 28436 15195 28436 15199 28437 15197 28437 15198 28437 15200 28438 15192 28438 15196 28438 15200 28439 15196 28439 15199 28439 15200 28440 15199 28440 15202 28440 15202 28441 15198 28441 15201 28441 15202 28442 15199 28442 15198 28442 15204 28443 15201 28443 15203 28443 15205 28444 15200 28444 15202 28444 15204 28445 15202 28445 15201 28445 15205 28446 15202 28446 15204 28446 15206 28447 15204 28447 15203 28447 15207 28448 15204 28448 15206 28448 15207 28449 15205 28449 15204 28449 15209 28450 15206 28450 15208 28450 15212 28451 15205 28451 15207 28451 15209 28452 15207 28452 15206 28452 15210 28453 15207 28453 15209 28453 15211 28454 15209 28454 15208 28454 15212 28455 15207 28455 15210 28455 15210 28456 15209 28456 15211 28456 15214 28457 15211 28457 15213 28457 15215 28458 15210 28458 15211 28458 15215 28459 15211 28459 15214 28459 15215 28460 15212 28460 15210 28460 15214 28461 15213 28461 15216 28461 15218 28462 15212 28462 15215 28462 15217 28463 15215 28463 15214 28463 15218 28464 15215 28464 15217 28464 15217 28465 15214 28465 15216 28465 15220 28466 15218 28466 15217 28466 15219 28467 15217 28467 15216 28467 15221 28468 15217 28468 15219 28468 15220 28469 15217 28469 15221 28469 15221 28470 15219 28470 15222 28470 15223 28471 15221 28471 15222 28471 15224 28472 15218 28472 15220 28472 15225 28473 15220 28473 15221 28473 15225 28474 15224 28474 15220 28474 15226 28475 15221 28475 15223 28475 15225 28476 15221 28476 15226 28476 15226 28477 15223 28477 15227 28477 15229 28478 15225 28478 15226 28478 15228 28479 15226 28479 15227 28479 15229 28480 15224 28480 15225 28480 15230 28481 15226 28481 15228 28481 15230 28482 15229 28482 15226 28482 15231 28483 15230 28483 15228 28483 15232 28484 15231 28484 15228 28484 15233 28485 15230 28485 15231 28485 15233 28486 15229 28486 15230 28486 15236 28487 15229 28487 15233 28487 15234 28488 15231 28488 15232 28488 15235 28489 15231 28489 15234 28489 15235 28490 15233 28490 15231 28490 15235 28491 15234 28491 15237 28491 15238 28492 15233 28492 15235 28492 15239 28493 15233 28493 15238 28493 15238 28494 15235 28494 15237 28494 15236 28495 15233 28495 15239 28495 15238 28496 15237 28496 15240 28496 15241 28497 15236 28497 15239 28497 15242 28498 15238 28498 15240 28498 15239 28499 15238 28499 15242 28499 15242 28500 15240 28500 15243 28500 15244 28501 15239 28501 15242 28501 15241 28502 15239 28502 15244 28502 15244 28503 15242 28503 15243 28503 15244 28504 15243 28504 15245 28504 15247 28505 15244 28505 15246 28505 15247 28506 15241 28506 15244 28506 15246 28507 15244 28507 15245 28507 15248 28508 15246 28508 15245 28508 15250 28509 15246 28509 15248 28509 15249 28510 15246 28510 15250 28510 15249 28511 15247 28511 15246 28511 15251 28512 15249 28512 15250 28512 15252 28513 15249 28513 15251 28513 15253 28514 15251 28514 15250 28514 15254 28515 15247 28515 15249 28515 15255 28516 15251 28516 15253 28516 15254 28517 15249 28517 15252 28517 15252 28518 15251 28518 15255 28518 15260 28519 15247 28519 15254 28519 15256 28520 15255 28520 15253 28520 15255 28521 15254 28521 15252 28521 15258 28522 15254 28522 15255 28522 15259 28523 15256 28523 15257 28523 15259 28524 15255 28524 15256 28524 15258 28525 15255 28525 15259 28525 15260 28526 15254 28526 15258 28526 15261 28527 15259 28527 15257 28527 15262 28528 15259 28528 15261 28528 15258 28529 15259 28529 15262 28529 15263 28530 15258 28530 15262 28530 15263 28531 15260 28531 15258 28531 15264 28532 15262 28532 15261 28532 15264 28533 15263 28533 15262 28533 15265 28534 15264 28534 15261 28534 15266 28535 15260 28535 15263 28535 15266 28536 15263 28536 15264 28536 15267 28537 15264 28537 15265 28537 15266 28538 15264 28538 15267 28538 15267 28539 15265 28539 15268 28539 15269 28540 15266 28540 15267 28540 15270 28541 15267 28541 15268 28541 15269 28542 15267 28542 15270 28542 15271 28543 15270 28543 15268 28543 15272 28544 15266 28544 15269 28544 15273 28545 15270 28545 15271 28545 15269 28546 15270 28546 15273 28546 15274 28547 15273 28547 15271 28547 15277 28548 15269 28548 15273 28548 15276 28549 15269 28549 15277 28549 15275 28550 15273 28550 15274 28550 15276 28551 15272 28551 15269 28551 15277 28552 15273 28552 15275 28552 15278 28553 15272 28553 15276 28553 15279 28554 15277 28554 15275 28554 15280 28555 15276 28555 15277 28555 15280 28556 15278 28556 15276 28556 15281 28557 15277 28557 15279 28557 15280 28558 15277 28558 15281 28558 15282 28559 15281 28559 15279 28559 15284 28560 15280 28560 15281 28560 15278 28561 15280 28561 15284 28561 15284 28562 15281 28562 15282 28562 15285 28563 15282 28563 15283 28563 15285 28564 15284 28564 15282 28564 15286 28565 15278 28565 15284 28565 15288 28566 15284 28566 15285 28566 15288 28567 15286 28567 15284 28567 15287 28568 15285 28568 15283 28568 15288 28569 15285 28569 15287 28569 15289 28570 15288 28570 15287 28570 15290 28571 15288 28571 15289 28571 15291 28572 15288 28572 15290 28572 15291 28573 15286 28573 15288 28573 15290 28574 15289 28574 15292 28574 15293 28575 15291 28575 15290 28575 15295 28576 15292 28576 15294 28576 15295 28577 15290 28577 15292 28577 15293 28578 15290 28578 15295 28578 15297 28579 15293 28579 15295 28579 15296 28580 15295 28580 15294 28580 15297 28581 15295 28581 15296 28581 15299 28582 15296 28582 15298 28582 15299 28583 15297 28583 15296 28583 15300 28584 15293 28584 15297 28584 15301 28585 15297 28585 15299 28585 15302 28586 15299 28586 15298 28586 15300 28587 15297 28587 15301 28587 15301 28588 15299 28588 15302 28588 15303 28589 15302 28589 15298 28589 15305 28590 15300 28590 15301 28590 15305 28591 15301 28591 15302 28591 15304 28592 15302 28592 15303 28592 15307 28593 15302 28593 15304 28593 15306 28594 15300 28594 15305 28594 15305 28595 15302 28595 15307 28595 15306 28596 15305 28596 15308 28596 15308 28597 15305 28597 15307 28597 15307 28598 15304 28598 15309 28598 15313 28599 15306 28599 15308 28599 15310 28600 15307 28600 15309 28600 15311 28601 15307 28601 15310 28601 15312 28602 15306 28602 15313 28602 15311 28603 15308 28603 15307 28603 15313 28604 15308 28604 15311 28604 15314 28605 15311 28605 15310 28605 15315 28606 15311 28606 15314 28606 15315 28607 15313 28607 15311 28607 15161 28608 15313 28608 15315 28608 15159 28609 15314 28609 15158 28609 15159 28610 15315 28610 15314 28610 15312 28611 15313 28611 15161 28611 15315 28612 15159 28612 15161 28612 15312 28613 15161 28613 15163 28613 15317 28614 15158 28614 15314 28614 15317 28615 15316 28615 15158 28615 15318 28616 15314 28616 15310 28616 15318 28617 15317 28617 15314 28617 15319 28618 15310 28618 15309 28618 15319 28619 15318 28619 15310 28619 15319 28620 15309 28620 15304 28620 15320 28621 15319 28621 15304 28621 15320 28622 15304 28622 15303 28622 15321 28623 15320 28623 15303 28623 15321 28624 15303 28624 15298 28624 15322 28625 15321 28625 15298 28625 15322 28626 15298 28626 15296 28626 15323 28627 15322 28627 15296 28627 15323 28628 15296 28628 15294 28628 15324 28629 15323 28629 15294 28629 15324 28630 15294 28630 15292 28630 15325 28631 15324 28631 15292 28631 15325 28632 15292 28632 15289 28632 15326 28633 15289 28633 15287 28633 15326 28634 15325 28634 15289 28634 15327 28635 15287 28635 15283 28635 15327 28636 15326 28636 15287 28636 15328 28637 15283 28637 15282 28637 15328 28638 15327 28638 15283 28638 15329 28639 15328 28639 15282 28639 15329 28640 15282 28640 15279 28640 15330 28641 15329 28641 15279 28641 15330 28642 15279 28642 15275 28642 15331 28643 15330 28643 15275 28643 15331 28644 15275 28644 15274 28644 15332 28645 15331 28645 15274 28645 15332 28646 15274 28646 15271 28646 15333 28647 15332 28647 15271 28647 15333 28648 15271 28648 15268 28648 15334 28649 15333 28649 15268 28649 15334 28650 15268 28650 15265 28650 15335 28651 15334 28651 15265 28651 15336 28652 15265 28652 15261 28652 15336 28653 15335 28653 15265 28653 15337 28654 15336 28654 15261 28654 15337 28655 15261 28655 15257 28655 15338 28656 15337 28656 15257 28656 15338 28657 15257 28657 15256 28657 15339 28658 15338 28658 15256 28658 15339 28659 15256 28659 15253 28659 15340 28660 15339 28660 15253 28660 15340 28661 15253 28661 15250 28661 15341 28662 15340 28662 15250 28662 15341 28663 15250 28663 15248 28663 15342 28664 15341 28664 15248 28664 15342 28665 15248 28665 15245 28665 15343 28666 15342 28666 15245 28666 15343 28667 15245 28667 15243 28667 15344 28668 15343 28668 15243 28668 15344 28669 15243 28669 15240 28669 15345 28670 15344 28670 15240 28670 15346 28671 15345 28671 15240 28671 15346 28672 15240 28672 15237 28672 15346 28673 15237 28673 15234 28673 15347 28674 15346 28674 15234 28674 15347 28675 15234 28675 15232 28675 15348 28676 15347 28676 15232 28676 15349 28677 15348 28677 15232 28677 15349 28678 15232 28678 15228 28678 15349 28679 15228 28679 15227 28679 15350 28680 15349 28680 15227 28680 15351 28681 15350 28681 15227 28681 15351 28682 15227 28682 15223 28682 15352 28683 15351 28683 15223 28683 15352 28684 15223 28684 15222 28684 15353 28685 15352 28685 15222 28685 15353 28686 15222 28686 15219 28686 15354 28687 15219 28687 15216 28687 15354 28688 15353 28688 15219 28688 15355 28689 15216 28689 15213 28689 15355 28690 15354 28690 15216 28690 15356 28691 15355 28691 15213 28691 15356 28692 15213 28692 15211 28692 15357 28693 15356 28693 15211 28693 15357 28694 15211 28694 15208 28694 15358 28695 15357 28695 15208 28695 15358 28696 15208 28696 15206 28696 15358 28697 15206 28697 15203 28697 15359 28698 15358 28698 15203 28698 15360 28699 15359 28699 15203 28699 15360 28700 15203 28700 15201 28700 15360 28701 15201 28701 15198 28701 15361 28702 15360 28702 15198 28702 15361 28703 15198 28703 15195 28703 15362 28704 15361 28704 15195 28704 15362 28705 15195 28705 15194 28705 15363 28706 15362 28706 15194 28706 15363 28707 15194 28707 15190 28707 15364 28708 15363 28708 15190 28708 15365 28709 15190 28709 15187 28709 15365 28710 15364 28710 15190 28710 15366 28711 15187 28711 15184 28711 15366 28712 15365 28712 15187 28712 15366 28713 15184 28713 15180 28713 15367 28714 15366 28714 15180 28714 15368 28715 15180 28715 15178 28715 15368 28716 15367 28716 15180 28716 15369 28717 15178 28717 15175 28717 15369 28718 15368 28718 15178 28718 15369 28719 15175 28719 15174 28719 15370 28720 15369 28720 15174 28720 15370 28721 15174 28721 15171 28721 15371 28722 15370 28722 15171 28722 15371 28723 15171 28723 15168 28723 15372 28724 15371 28724 15168 28724 15372 28725 15168 28725 15166 28725 15373 28726 15166 28726 15164 28726 15373 28727 15372 28727 15166 28727 15373 28728 15164 28728 15157 28728 15316 28729 15373 28729 15157 28729 15316 28730 15157 28730 15158 28730 15374 28731 15316 28731 15317 28731 15375 28732 15474 28732 15374 28732 15375 28733 15473 28733 15474 28733 15375 28734 15374 28734 15317 28734 15376 28735 15473 28735 15375 28735 15318 28736 15375 28736 15317 28736 15377 28737 15375 28737 15318 28737 15376 28738 15375 28738 15377 28738 15379 28739 15376 28739 15377 28739 15378 28740 15318 28740 15319 28740 15378 28741 15377 28741 15318 28741 15379 28742 15377 28742 15378 28742 15380 28743 15319 28743 15320 28743 15380 28744 15378 28744 15319 28744 15380 28745 15379 28745 15378 28745 15381 28746 15376 28746 15379 28746 15382 28747 15376 28747 15381 28747 15381 28748 15379 28748 15380 28748 15383 28749 15320 28749 15321 28749 15383 28750 15380 28750 15320 28750 15381 28751 15380 28751 15383 28751 15322 28752 15383 28752 15321 28752 15384 28753 15381 28753 15383 28753 15382 28754 15381 28754 15384 28754 15385 28755 15383 28755 15322 28755 15384 28756 15383 28756 15385 28756 15386 28757 15384 28757 15385 28757 15323 28758 15385 28758 15322 28758 15386 28759 15382 28759 15384 28759 15387 28760 15382 28760 15386 28760 15386 28761 15385 28761 15323 28761 15388 28762 15323 28762 15324 28762 15388 28763 15386 28763 15323 28763 15389 28764 15387 28764 15386 28764 15389 28765 15386 28765 15388 28765 15390 28766 15324 28766 15325 28766 15390 28767 15388 28767 15324 28767 15391 28768 15387 28768 15389 28768 15392 28769 15388 28769 15390 28769 15392 28770 15389 28770 15388 28770 15393 28771 15390 28771 15325 28771 15393 28772 15325 28772 15326 28772 15392 28773 15390 28773 15393 28773 15391 28774 15389 28774 15392 28774 15327 28775 15393 28775 15326 28775 15394 28776 15393 28776 15327 28776 15394 28777 15392 28777 15393 28777 15394 28778 15391 28778 15392 28778 15396 28779 15391 28779 15394 28779 15397 28780 15327 28780 15328 28780 15395 28781 15391 28781 15396 28781 15397 28782 15394 28782 15327 28782 15396 28783 15394 28783 15397 28783 15398 28784 15397 28784 15328 28784 15398 28785 15328 28785 15329 28785 15399 28786 15398 28786 15329 28786 15399 28787 15397 28787 15398 28787 15399 28788 15396 28788 15397 28788 15330 28789 15399 28789 15329 28789 15401 28790 15396 28790 15399 28790 15400 28791 15396 28791 15401 28791 15401 28792 15399 28792 15330 28792 15400 28793 15395 28793 15396 28793 15401 28794 15330 28794 15331 28794 15402 28795 15400 28795 15401 28795 15402 28796 15401 28796 15331 28796 15403 28797 15400 28797 15402 28797 15402 28798 15331 28798 15332 28798 15404 28799 15402 28799 15332 28799 15403 28800 15402 28800 15404 28800 15404 28801 15332 28801 15333 28801 15405 28802 15404 28802 15333 28802 15406 28803 15400 28803 15403 28803 15403 28804 15404 28804 15405 28804 15406 28805 15403 28805 15405 28805 15407 28806 15333 28806 15334 28806 15407 28807 15405 28807 15333 28807 15408 28808 15405 28808 15407 28808 15408 28809 15406 28809 15405 28809 15335 28810 15407 28810 15334 28810 15409 28811 15407 28811 15335 28811 15409 28812 15408 28812 15407 28812 15409 28813 15335 28813 15336 28813 15410 28814 15406 28814 15408 28814 15410 28815 15408 28815 15409 28815 15411 28816 15336 28816 15337 28816 15411 28817 15409 28817 15336 28817 15412 28818 15406 28818 15410 28818 15413 28819 15409 28819 15411 28819 15413 28820 15410 28820 15409 28820 15411 28821 15337 28821 15338 28821 15412 28822 15410 28822 15413 28822 15414 28823 15338 28823 15339 28823 15414 28824 15411 28824 15338 28824 15415 28825 15412 28825 15413 28825 15416 28826 15411 28826 15414 28826 15416 28827 15413 28827 15411 28827 15415 28828 15413 28828 15416 28828 15340 28829 15414 28829 15339 28829 15341 28830 15414 28830 15340 28830 15417 28831 15414 28831 15341 28831 15417 28832 15416 28832 15414 28832 15417 28833 15415 28833 15416 28833 15418 28834 15412 28834 15415 28834 15418 28835 15415 28835 15417 28835 15419 28836 15417 28836 15341 28836 15419 28837 15418 28837 15417 28837 15342 28838 15419 28838 15341 28838 15420 28839 15342 28839 15343 28839 15420 28840 15419 28840 15342 28840 15421 28841 15419 28841 15420 28841 15344 28842 15420 28842 15343 28842 15421 28843 15418 28843 15419 28843 15344 28844 15421 28844 15420 28844 15422 28845 15421 28845 15344 28845 15422 28846 15344 28846 15345 28846 15423 28847 15418 28847 15421 28847 15424 28848 15345 28848 15346 28848 15423 28849 15421 28849 15422 28849 15424 28850 15422 28850 15345 28850 15425 28851 15422 28851 15424 28851 15423 28852 15422 28852 15425 28852 15347 28853 15424 28853 15346 28853 15427 28854 15424 28854 15347 28854 15426 28855 15423 28855 15425 28855 15427 28856 15425 28856 15424 28856 15428 28857 15425 28857 15427 28857 15348 28858 15427 28858 15347 28858 15426 28859 15425 28859 15428 28859 15428 28860 15427 28860 15348 28860 15429 28861 15348 28861 15349 28861 15430 28862 15426 28862 15428 28862 15429 28863 15428 28863 15348 28863 15430 28864 15428 28864 15429 28864 15431 28865 15429 28865 15349 28865 15431 28866 15349 28866 15350 28866 15431 28867 15430 28867 15429 28867 15433 28868 15350 28868 15351 28868 15432 28869 15430 28869 15431 28869 15433 28870 15431 28870 15350 28870 15432 28871 15431 28871 15433 28871 15352 28872 15433 28872 15351 28872 15434 28873 15433 28873 15352 28873 15436 28874 15430 28874 15432 28874 15434 28875 15432 28875 15433 28875 15435 28876 15352 28876 15353 28876 15435 28877 15434 28877 15352 28877 15436 28878 15434 28878 15435 28878 15436 28879 15432 28879 15434 28879 15354 28880 15435 28880 15353 28880 15437 28881 15435 28881 15354 28881 15437 28882 15436 28882 15435 28882 15438 28883 15436 28883 15437 28883 15355 28884 15437 28884 15354 28884 15439 28885 15437 28885 15355 28885 15439 28886 15438 28886 15437 28886 15356 28887 15439 28887 15355 28887 15441 28888 15439 28888 15440 28888 15441 28889 15438 28889 15439 28889 15442 28890 15439 28890 15356 28890 15440 28891 15439 28891 15442 28891 15442 28892 15356 28892 15357 28892 15443 28893 15438 28893 15441 28893 15358 28894 15442 28894 15357 28894 15443 28895 15441 28895 15440 28895 15444 28896 15442 28896 15358 28896 15444 28897 15440 28897 15442 28897 15445 28898 15440 28898 15444 28898 15443 28899 15440 28899 15445 28899 15359 28900 15444 28900 15358 28900 15445 28901 15444 28901 15359 28901 15360 28902 15445 28902 15359 28902 15446 28903 15443 28903 15445 28903 15447 28904 15445 28904 15360 28904 15447 28905 15446 28905 15445 28905 15447 28906 15360 28906 15361 28906 15448 28907 15447 28907 15361 28907 15449 28908 15443 28908 15446 28908 15450 28909 15447 28909 15448 28909 15362 28910 15448 28910 15361 28910 15450 28911 15446 28911 15447 28911 15451 28912 15448 28912 15362 28912 15449 28913 15446 28913 15450 28913 15451 28914 15450 28914 15448 28914 15363 28915 15451 28915 15362 28915 15453 28916 15450 28916 15451 28916 15449 28917 15450 28917 15453 28917 15453 28918 15363 28918 15452 28918 15453 28919 15451 28919 15363 28919 15452 28920 15363 28920 15364 28920 15449 28921 15453 28921 15454 28921 15454 28922 15453 28922 15452 28922 15365 28923 15452 28923 15364 28923 15455 28924 15452 28924 15365 28924 15456 28925 15449 28925 15454 28925 15455 28926 15454 28926 15452 28926 15457 28927 15455 28927 15365 28927 15457 28928 15365 28928 15366 28928 15458 28929 15454 28929 15455 28929 15458 28930 15455 28930 15457 28930 15458 28931 15456 28931 15454 28931 15367 28932 15457 28932 15366 28932 15459 28933 15457 28933 15367 28933 15460 28934 15457 28934 15459 28934 15460 28935 15458 28935 15457 28935 15461 28936 15367 28936 15368 28936 15461 28937 15459 28937 15367 28937 15462 28938 15456 28938 15458 28938 15461 28939 15460 28939 15459 28939 15462 28940 15458 28940 15460 28940 15462 28941 15460 28941 15461 28941 15369 28942 15461 28942 15368 28942 15463 28943 15461 28943 15369 28943 15462 28944 15461 28944 15463 28944 15464 28945 15463 28945 15369 28945 15465 28946 15462 28946 15463 28946 15464 28947 15369 28947 15370 28947 15465 28948 15463 28948 15464 28948 15466 28949 15465 28949 15464 28949 15371 28950 15464 28950 15370 28950 15467 28951 15464 28951 15371 28951 15466 28952 15464 28952 15467 28952 15468 28953 15465 28953 15466 28953 15468 28954 15462 28954 15465 28954 15469 28955 15467 28955 15371 28955 15469 28956 15466 28956 15467 28956 15470 28957 15466 28957 15469 28957 15469 28958 15371 28958 15372 28958 15468 28959 15466 28959 15470 28959 15470 28960 15469 28960 15372 28960 15471 28961 15468 28961 15470 28961 15472 28962 15372 28962 15373 28962 15472 28963 15470 28963 15372 28963 15472 28964 15471 28964 15470 28964 15473 28965 15468 28965 15471 28965 15474 28966 15471 28966 15472 28966 15374 28967 15373 28967 15316 28967 15374 28968 15472 28968 15373 28968 15473 28969 15471 28969 15474 28969 15474 28970 15472 28970 15374 28970 14796 28971 15436 28971 15438 28971 14798 28972 15436 28972 14796 28972 14798 28973 15430 28973 15436 28973 14794 28974 14796 28974 15438 28974 14799 28975 15430 28975 14798 28975 14794 28976 15438 28976 15443 28976 14801 28977 15430 28977 14799 28977 14792 28978 14794 28978 15443 28978 14801 28979 15426 28979 15430 28979 14759 28980 15423 28980 15426 28980 14759 28981 15426 28981 14801 28981 14792 28982 15443 28982 15449 28982 14790 28983 14792 28983 15449 28983 14762 28984 15423 28984 14759 28984 14762 28985 15418 28985 15423 28985 14788 28986 14790 28986 15449 28986 14788 28987 15449 28987 15456 28987 14764 28988 15418 28988 14762 28988 14764 28989 15412 28989 15418 28989 14786 28990 15456 28990 15462 28990 14786 28991 14788 28991 15456 28991 14766 28992 15412 28992 14764 28992 14784 28993 14786 28993 15462 28993 15406 28994 15412 28994 14766 28994 15406 28995 14766 28995 14768 28995 15462 28996 14783 28996 14784 28996 15468 28997 14783 28997 15462 28997 15400 28998 15406 28998 14768 28998 15473 28999 14783 28999 15468 28999 15473 29000 14781 29000 14783 29000 15400 29001 14768 29001 14771 29001 15395 29002 15400 29002 14771 29002 15473 29003 14779 29003 14781 29003 15376 29004 14779 29004 15473 29004 15395 29005 14771 29005 14773 29005 15391 29006 15395 29006 14773 29006 15382 29007 14779 29007 15376 29007 15382 29008 14777 29008 14779 29008 15387 29009 14777 29009 15382 29009 15387 29010 14775 29010 14777 29010 15387 29011 15391 29011 14773 29011 15387 29012 14773 29012 14775 29012 15476 29013 15545 29013 15475 29013 15477 29014 15476 29014 15475 29014 15477 29015 15475 29015 15478 29015 15479 29016 15477 29016 15478 29016 15479 29017 15478 29017 15480 29017 15481 29018 15479 29018 15480 29018 15482 29019 15481 29019 15480 29019 15483 29020 15482 29020 15480 29020 15483 29021 15480 29021 15484 29021 15485 29022 15483 29022 15484 29022 15486 29023 15485 29023 15484 29023 15487 29024 15486 29024 15484 29024 15487 29025 15484 29025 15488 29025 15489 29026 15487 29026 15488 29026 15490 29027 15489 29027 15488 29027 15490 29028 15488 29028 15491 29028 15492 29029 15490 29029 15491 29029 15493 29030 15492 29030 15491 29030 15494 29031 15493 29031 15491 29031 15494 29032 15491 29032 15495 29032 15496 29033 15494 29033 15495 29033 15497 29034 15496 29034 15495 29034 15498 29035 15497 29035 15495 29035 15498 29036 15495 29036 15499 29036 15500 29037 15498 29037 15499 29037 15501 29038 15500 29038 15499 29038 15501 29039 15499 29039 15502 29039 15503 29040 15501 29040 15502 29040 15504 29041 15503 29041 15502 29041 15504 29042 15502 29042 15505 29042 15506 29043 15504 29043 15505 29043 15507 29044 15505 29044 15508 29044 15507 29045 15506 29045 15505 29045 15509 29046 15507 29046 15508 29046 15510 29047 15509 29047 15508 29047 15511 29048 15508 29048 15512 29048 15511 29049 15510 29049 15508 29049 15513 29050 15511 29050 15512 29050 15514 29051 15513 29051 15512 29051 15515 29052 15514 29052 15512 29052 15515 29053 15512 29053 15516 29053 15517 29054 15515 29054 15516 29054 15517 29055 15516 29055 15518 29055 15519 29056 15517 29056 15518 29056 15520 29057 15519 29057 15518 29057 15520 29058 15518 29058 15521 29058 15522 29059 15520 29059 15521 29059 15523 29060 15522 29060 15521 29060 15523 29061 15521 29061 15524 29061 15525 29062 15523 29062 15524 29062 15526 29063 15525 29063 15524 29063 15526 29064 15524 29064 15527 29064 15528 29065 15526 29065 15527 29065 15529 29066 15527 29066 15530 29066 15529 29067 15528 29067 15527 29067 15531 29068 15529 29068 15530 29068 15532 29069 15531 29069 15530 29069 15533 29070 15530 29070 15534 29070 15533 29071 15532 29071 15530 29071 15535 29072 15533 29072 15534 29072 15535 29073 15534 29073 15536 29073 15537 29074 15535 29074 15536 29074 15538 29075 15537 29075 15536 29075 15539 29076 15538 29076 15536 29076 15539 29077 15536 29077 15540 29077 15792 29078 15539 29078 15540 29078 15541 29079 15792 29079 15540 29079 15542 29080 15541 29080 15540 29080 15542 29081 15540 29081 15543 29081 15544 29082 15542 29082 15543 29082 15545 29083 15544 29083 15543 29083 15545 29084 15543 29084 15475 29084 15546 29085 15547 29085 15548 29085 15549 29086 15546 29086 15548 29086 15549 29087 15548 29087 15705 29087 15549 29088 15705 29088 15702 29088 15550 29089 15702 29089 15699 29089 15550 29090 15549 29090 15702 29090 15550 29091 15699 29091 15551 29091 15552 29092 15551 29092 15694 29092 15552 29093 15550 29093 15551 29093 15552 29094 15694 29094 15553 29094 15554 29095 15552 29095 15553 29095 15554 29096 15553 29096 15555 29096 15556 29097 15555 29097 15557 29097 15556 29098 15554 29098 15555 29098 15556 29099 15557 29099 15558 29099 15556 29100 15558 29100 15559 29100 15560 29101 15556 29101 15559 29101 15560 29102 15559 29102 15561 29102 15562 29103 15560 29103 15561 29103 15562 29104 15561 29104 15563 29104 15562 29105 15563 29105 15564 29105 15565 29106 15562 29106 15564 29106 15565 29107 15564 29107 15566 29107 15567 29108 15565 29108 15566 29108 15567 29109 15566 29109 15568 29109 15567 29110 15568 29110 15569 29110 15570 29111 15567 29111 15569 29111 15570 29112 15569 29112 15571 29112 15570 29113 15571 29113 15572 29113 15570 29114 15572 29114 15573 29114 15574 29115 15573 29115 15575 29115 15574 29116 15570 29116 15573 29116 15574 29117 15575 29117 15576 29117 15577 29118 15574 29118 15576 29118 15577 29119 15576 29119 15655 29119 15577 29120 15655 29120 15578 29120 15579 29121 15577 29121 15578 29121 15579 29122 15578 29122 15580 29122 15579 29123 15580 29123 15581 29123 15582 29124 15579 29124 15581 29124 15582 29125 15581 29125 15648 29125 15582 29126 15648 29126 15583 29126 15584 29127 15583 29127 15585 29127 15584 29128 15582 29128 15583 29128 15584 29129 15585 29129 15586 29129 15584 29130 15586 29130 15639 29130 15587 29131 15639 29131 15588 29131 15587 29132 15584 29132 15639 29132 15587 29133 15588 29133 15589 29133 15587 29134 15589 29134 15590 29134 15591 29135 15587 29135 15590 29135 15591 29136 15590 29136 15592 29136 15593 29137 15592 29137 15594 29137 15593 29138 15591 29138 15592 29138 15593 29139 15594 29139 15595 29139 15596 29140 15593 29140 15595 29140 15596 29141 15595 29141 15597 29141 15596 29142 15597 29142 15623 29142 15598 29143 15596 29143 15623 29143 15598 29144 15623 29144 15599 29144 15600 29145 15599 29145 15601 29145 15600 29146 15598 29146 15599 29146 15600 29147 15601 29147 15616 29147 15602 29148 15616 29148 15603 29148 15602 29149 15600 29149 15616 29149 15604 29150 15603 29150 15605 29150 15604 29151 15602 29151 15603 29151 15604 29152 15605 29152 15606 29152 15604 29153 15606 29153 15547 29153 15546 29154 15604 29154 15547 29154 15607 29155 15547 29155 15606 29155 15608 29156 15709 29156 15607 29156 15608 29157 15607 29157 15606 29157 15609 29158 15709 29158 15608 29158 15605 29159 15608 29159 15606 29159 15610 29160 15609 29160 15608 29160 15612 29161 15608 29161 15605 29161 15611 29162 15609 29162 15610 29162 15610 29163 15608 29163 15612 29163 15612 29164 15605 29164 15603 29164 15613 29165 15612 29165 15603 29165 15614 29166 15611 29166 15610 29166 15613 29167 15610 29167 15612 29167 15615 29168 15610 29168 15613 29168 15616 29169 15613 29169 15603 29169 15614 29170 15610 29170 15615 29170 15615 29171 15613 29171 15616 29171 15617 29172 15616 29172 15601 29172 15617 29173 15615 29173 15616 29173 15618 29174 15614 29174 15615 29174 15618 29175 15615 29175 15617 29175 15619 29176 15617 29176 15601 29176 15618 29177 15617 29177 15619 29177 15599 29178 15619 29178 15601 29178 15620 29179 15619 29179 15599 29179 15622 29180 15614 29180 15618 29180 15620 29181 15618 29181 15619 29181 15621 29182 15618 29182 15620 29182 15622 29183 15618 29183 15621 29183 15623 29184 15620 29184 15599 29184 15621 29185 15620 29185 15623 29185 15624 29186 15621 29186 15623 29186 15625 29187 15621 29187 15624 29187 15624 29188 15623 29188 15597 29188 15626 29189 15621 29189 15625 29189 15626 29190 15622 29190 15621 29190 15627 29191 15624 29191 15597 29191 15627 29192 15625 29192 15624 29192 15595 29193 15627 29193 15597 29193 15628 29194 15627 29194 15595 29194 15628 29195 15625 29195 15627 29195 15628 29196 15626 29196 15625 29196 15629 29197 15595 29197 15594 29197 15629 29198 15628 29198 15595 29198 15630 29199 15626 29199 15628 29199 15631 29200 15628 29200 15629 29200 15630 29201 15628 29201 15631 29201 15632 29202 15631 29202 15629 29202 15632 29203 15594 29203 15592 29203 15630 29204 15631 29204 15632 29204 15632 29205 15629 29205 15594 29205 15633 29206 15632 29206 15592 29206 15634 29207 15632 29207 15633 29207 15634 29208 15630 29208 15632 29208 15635 29209 15630 29209 15634 29209 15633 29210 15592 29210 15590 29210 15636 29211 15633 29211 15590 29211 15636 29212 15634 29212 15633 29212 15636 29213 15590 29213 15589 29213 15637 29214 15634 29214 15636 29214 15637 29215 15635 29215 15634 29215 15638 29216 15636 29216 15589 29216 15638 29217 15637 29217 15636 29217 15639 29218 15589 29218 15588 29218 15639 29219 15638 29219 15589 29219 15640 29220 15637 29220 15638 29220 15641 29221 15638 29221 15639 29221 15642 29222 15637 29222 15640 29222 15641 29223 15639 29223 15586 29223 15640 29224 15638 29224 15641 29224 15643 29225 15640 29225 15641 29225 15644 29226 15641 29226 15586 29226 15642 29227 15640 29227 15643 29227 15644 29228 15643 29228 15641 29228 15644 29229 15586 29229 15585 29229 15645 29230 15642 29230 15643 29230 15645 29231 15643 29231 15644 29231 15583 29232 15644 29232 15585 29232 15646 29233 15642 29233 15645 29233 15647 29234 15644 29234 15583 29234 15647 29235 15645 29235 15644 29235 15651 29236 15642 29236 15646 29236 15648 29237 15647 29237 15583 29237 15646 29238 15645 29238 15647 29238 15649 29239 15648 29239 15581 29239 15649 29240 15647 29240 15648 29240 15650 29241 15647 29241 15649 29241 15650 29242 15646 29242 15647 29242 15649 29243 15581 29243 15580 29243 15651 29244 15646 29244 15650 29244 15652 29245 15650 29245 15649 29245 15653 29246 15649 29246 15580 29246 15652 29247 15651 29247 15650 29247 15653 29248 15652 29248 15649 29248 15578 29249 15653 29249 15580 29249 15654 29250 15651 29250 15652 29250 15655 29251 15653 29251 15578 29251 15656 29252 15653 29252 15655 29252 15656 29253 15652 29253 15653 29253 15657 29254 15655 29254 15576 29254 15658 29255 15652 29255 15656 29255 15658 29256 15654 29256 15652 29256 15657 29257 15656 29257 15655 29257 15659 29258 15656 29258 15657 29258 15658 29259 15656 29259 15659 29259 15660 29260 15657 29260 15576 29260 15660 29261 15659 29261 15657 29261 15575 29262 15660 29262 15576 29262 15661 29263 15654 29263 15658 29263 15662 29264 15659 29264 15660 29264 15663 29265 15575 29265 15573 29265 15661 29266 15659 29266 15662 29266 15663 29267 15660 29267 15575 29267 15661 29268 15658 29268 15659 29268 15662 29269 15660 29269 15663 29269 15572 29270 15663 29270 15573 29270 15664 29271 15662 29271 15663 29271 15664 29272 15663 29272 15572 29272 15664 29273 15572 29273 15571 29273 15665 29274 15662 29274 15664 29274 15665 29275 15661 29275 15662 29275 15666 29276 15661 29276 15665 29276 15667 29277 15664 29277 15571 29277 15667 29278 15665 29278 15664 29278 15569 29279 15667 29279 15571 29279 15666 29280 15665 29280 15668 29280 15669 29281 15665 29281 15667 29281 15668 29282 15665 29282 15669 29282 15568 29283 15667 29283 15569 29283 15669 29284 15667 29284 15568 29284 15670 29285 15669 29285 15568 29285 15671 29286 15668 29286 15669 29286 15672 29287 15669 29287 15670 29287 15671 29288 15666 29288 15668 29288 15566 29289 15670 29289 15568 29289 15673 29290 15670 29290 15566 29290 15672 29291 15671 29291 15669 29291 15672 29292 15670 29292 15673 29292 15674 29293 15666 29293 15671 29293 15675 29294 15672 29294 15673 29294 15674 29295 15672 29295 15675 29295 15674 29296 15671 29296 15672 29296 15675 29297 15673 29297 15566 29297 15675 29298 15566 29298 15564 29298 15676 29299 15674 29299 15675 29299 15677 29300 15564 29300 15563 29300 15677 29301 15675 29301 15564 29301 15678 29302 15674 29302 15676 29302 15676 29303 15675 29303 15677 29303 15678 29304 15676 29304 15677 29304 15677 29305 15563 29305 15561 29305 15680 29306 15674 29306 15678 29306 15679 29307 15677 29307 15561 29307 15681 29308 15677 29308 15679 29308 15681 29309 15678 29309 15677 29309 15680 29310 15678 29310 15681 29310 15559 29311 15679 29311 15561 29311 15682 29312 15679 29312 15559 29312 15682 29313 15681 29313 15679 29313 15683 29314 15680 29314 15681 29314 15684 29315 15682 29315 15559 29315 15683 29316 15681 29316 15682 29316 15558 29317 15684 29317 15559 29317 15685 29318 15683 29318 15682 29318 15685 29319 15682 29319 15684 29319 15686 29320 15684 29320 15558 29320 15685 29321 15684 29321 15686 29321 15687 29322 15683 29322 15685 29322 15686 29323 15558 29323 15557 29323 15687 29324 15685 29324 15686 29324 15688 29325 15557 29325 15555 29325 15688 29326 15686 29326 15557 29326 15689 29327 15686 29327 15688 29327 15689 29328 15687 29328 15686 29328 15692 29329 15687 29329 15689 29329 15690 29330 15688 29330 15555 29330 15690 29331 15689 29331 15688 29331 15691 29332 15687 29332 15692 29332 15692 29333 15689 29333 15690 29333 15553 29334 15690 29334 15555 29334 15693 29335 15690 29335 15553 29335 15693 29336 15692 29336 15690 29336 15693 29337 15553 29337 15694 29337 15691 29338 15692 29338 15693 29338 15696 29339 15693 29339 15694 29339 15695 29340 15691 29340 15693 29340 15695 29341 15693 29341 15696 29341 15696 29342 15694 29342 15551 29342 15697 29343 15691 29343 15695 29343 15698 29344 15695 29344 15696 29344 15698 29345 15697 29345 15695 29345 15698 29346 15696 29346 15551 29346 15698 29347 15551 29347 15699 29347 15701 29348 15698 29348 15699 29348 15700 29349 15697 29349 15698 29349 15700 29350 15698 29350 15701 29350 15702 29351 15701 29351 15699 29351 15703 29352 15700 29352 15701 29352 15704 29353 15701 29353 15702 29353 15703 29354 15697 29354 15700 29354 15704 29355 15703 29355 15701 29355 15705 29356 15704 29356 15702 29356 15706 29357 15697 29357 15703 29357 15706 29358 15703 29358 15704 29358 15707 29359 15705 29359 15548 29359 15707 29360 15704 29360 15705 29360 15708 29361 15704 29361 15707 29361 15708 29362 15706 29362 15704 29362 15547 29363 15707 29363 15548 29363 15607 29364 15707 29364 15547 29364 15706 29365 15708 29365 15709 29365 15607 29366 15708 29366 15707 29366 15709 29367 15708 29367 15607 29367 15609 29368 15706 29368 15709 29368 15706 29369 15609 29369 15611 29369 14787 29370 14785 29370 15622 29370 14785 29371 15614 29371 15622 29371 14787 29372 15622 29372 15626 29372 14782 29373 15614 29373 14785 29373 14789 29374 14787 29374 15626 29374 14782 29375 15611 29375 15614 29375 14789 29376 15626 29376 15630 29376 14791 29377 14789 29377 15630 29377 14780 29378 15611 29378 14782 29378 14791 29379 15630 29379 15635 29379 14780 29380 15706 29380 15611 29380 14778 29381 15706 29381 14780 29381 14793 29382 14791 29382 15635 29382 14793 29383 15635 29383 15637 29383 14795 29384 14793 29384 15637 29384 14776 29385 15697 29385 15706 29385 14776 29386 15706 29386 14778 29386 14795 29387 15637 29387 15642 29387 14797 29388 14795 29388 15642 29388 15691 29389 15697 29389 14776 29389 15691 29390 14776 29390 14774 29390 15651 29391 14797 29391 15642 29391 15691 29392 14774 29392 14772 29392 15651 29393 14800 29393 14797 29393 15687 29394 15691 29394 14772 29394 15683 29395 14772 29395 14770 29395 15683 29396 15687 29396 14772 29396 15654 29397 14800 29397 15651 29397 15654 29398 14760 29398 14800 29398 15683 29399 14770 29399 14769 29399 15661 29400 14761 29400 14760 29400 15661 29401 14760 29401 15654 29401 15680 29402 15683 29402 14769 29402 15680 29403 14769 29403 14767 29403 15666 29404 14761 29404 15661 29404 15666 29405 14763 29405 14761 29405 15674 29406 15680 29406 14767 29406 15674 29407 14767 29407 14765 29407 15674 29408 14763 29408 15666 29408 15674 29409 14765 29409 14763 29409 15476 29410 15710 29410 15545 29410 15712 29411 15710 29411 15476 29411 15711 29412 15710 29412 15712 29412 15477 29413 15712 29413 15476 29413 15714 29414 15712 29414 15477 29414 15711 29415 15712 29415 15714 29415 15479 29416 15714 29416 15477 29416 15715 29417 15711 29417 15714 29417 15715 29418 15713 29418 15711 29418 15715 29419 15714 29419 15479 29419 15716 29420 15715 29420 15479 29420 15717 29421 15713 29421 15715 29421 15481 29422 15716 29422 15479 29422 15717 29423 15715 29423 15716 29423 15720 29424 15713 29424 15717 29424 15482 29425 15716 29425 15481 29425 15718 29426 15716 29426 15482 29426 15718 29427 15717 29427 15716 29427 15720 29428 15717 29428 15718 29428 15718 29429 15482 29429 15719 29429 15483 29430 15719 29430 15482 29430 15720 29431 15718 29431 15719 29431 15485 29432 15719 29432 15483 29432 15721 29433 15719 29433 15485 29433 15721 29434 15720 29434 15719 29434 15722 29435 15720 29435 15721 29435 15723 29436 15485 29436 15486 29436 15723 29437 15721 29437 15485 29437 15724 29438 15720 29438 15722 29438 15722 29439 15721 29439 15723 29439 15723 29440 15486 29440 15487 29440 15725 29441 15722 29441 15723 29441 15725 29442 15723 29442 15487 29442 15726 29443 15722 29443 15725 29443 15726 29444 15724 29444 15722 29444 15489 29445 15725 29445 15487 29445 15728 29446 15725 29446 15489 29446 15728 29447 15726 29447 15725 29447 15727 29448 15724 29448 15726 29448 15729 29449 15489 29449 15490 29449 15729 29450 15728 29450 15489 29450 15727 29451 15726 29451 15728 29451 15730 29452 15729 29452 15490 29452 15731 29453 15729 29453 15730 29453 15731 29454 15728 29454 15729 29454 15731 29455 15727 29455 15728 29455 15492 29456 15730 29456 15490 29456 15732 29457 15730 29457 15492 29457 15732 29458 15731 29458 15730 29458 15727 29459 15731 29459 15734 29459 15733 29460 15732 29460 15492 29460 15733 29461 15492 29461 15493 29461 15734 29462 15731 29462 15732 29462 15734 29463 15732 29463 15733 29463 15494 29464 15733 29464 15493 29464 15735 29465 15734 29465 15733 29465 15736 29466 15727 29466 15734 29466 15735 29467 15733 29467 15494 29467 15736 29468 15734 29468 15735 29468 15737 29469 15494 29469 15496 29469 15737 29470 15735 29470 15494 29470 15497 29471 15737 29471 15496 29471 15736 29472 15735 29472 15737 29472 15738 29473 15737 29473 15497 29473 15739 29474 15737 29474 15738 29474 15738 29475 15497 29475 15498 29475 15739 29476 15736 29476 15737 29476 15500 29477 15738 29477 15498 29477 15740 29478 15738 29478 15500 29478 15741 29479 15736 29479 15739 29479 15740 29480 15739 29480 15738 29480 15740 29481 15500 29481 15501 29481 15742 29482 15740 29482 15501 29482 15741 29483 15739 29483 15740 29483 15503 29484 15742 29484 15501 29484 15743 29485 15740 29485 15742 29485 15743 29486 15741 29486 15740 29486 15744 29487 15742 29487 15503 29487 15744 29488 15743 29488 15742 29488 15745 29489 15741 29489 15743 29489 15746 29490 15503 29490 15504 29490 15746 29491 15744 29491 15503 29491 15747 29492 15744 29492 15746 29492 15747 29493 15743 29493 15744 29493 15745 29494 15743 29494 15747 29494 15506 29495 15746 29495 15504 29495 15748 29496 15746 29496 15506 29496 15749 29497 15746 29497 15748 29497 15749 29498 15747 29498 15746 29498 15749 29499 15745 29499 15747 29499 15507 29500 15748 29500 15506 29500 15745 29501 15749 29501 15750 29501 15750 29502 15749 29502 15748 29502 15752 29503 15745 29503 15750 29503 15509 29504 15748 29504 15507 29504 15751 29505 15748 29505 15509 29505 15751 29506 15750 29506 15748 29506 15753 29507 15509 29507 15510 29507 15753 29508 15751 29508 15509 29508 15754 29509 15751 29509 15753 29509 15754 29510 15750 29510 15751 29510 15752 29511 15750 29511 15754 29511 15511 29512 15753 29512 15510 29512 15754 29513 15753 29513 15511 29513 15755 29514 15754 29514 15511 29514 15755 29515 15511 29515 15513 29515 15756 29516 15752 29516 15754 29516 15756 29517 15754 29517 15755 29517 15758 29518 15513 29518 15514 29518 15758 29519 15755 29519 15513 29519 15757 29520 15756 29520 15755 29520 15757 29521 15755 29521 15758 29521 15759 29522 15757 29522 15758 29522 15760 29523 15757 29523 15759 29523 15760 29524 15756 29524 15757 29524 15515 29525 15758 29525 15514 29525 15759 29526 15758 29526 15515 29526 15761 29527 15759 29527 15515 29527 15762 29528 15759 29528 15761 29528 15763 29529 15756 29529 15760 29529 15761 29530 15515 29530 15517 29530 15762 29531 15760 29531 15759 29531 15763 29532 15760 29532 15762 29532 15765 29533 15762 29533 15761 29533 15764 29534 15762 29534 15765 29534 15765 29535 15761 29535 15517 29535 15764 29536 15763 29536 15762 29536 15519 29537 15765 29537 15517 29537 15766 29538 15764 29538 15765 29538 15766 29539 15765 29539 15519 29539 15767 29540 15766 29540 15519 29540 15767 29541 15519 29541 15520 29541 15768 29542 15764 29542 15766 29542 15768 29543 15763 29543 15764 29543 15769 29544 15767 29544 15520 29544 15770 29545 15763 29545 15768 29545 15768 29546 15766 29546 15767 29546 15768 29547 15767 29547 15769 29547 15522 29548 15769 29548 15520 29548 15771 29549 15769 29549 15522 29549 15771 29550 15768 29550 15769 29550 15771 29551 15522 29551 15523 29551 15772 29552 15768 29552 15771 29552 15773 29553 15771 29553 15523 29553 15772 29554 15770 29554 15768 29554 15525 29555 15773 29555 15523 29555 15773 29556 15772 29556 15771 29556 15774 29557 15773 29557 15525 29557 15772 29558 15773 29558 15774 29558 15774 29559 15525 29559 15526 29559 15775 29560 15770 29560 15772 29560 15775 29561 15772 29561 15776 29561 15776 29562 15772 29562 15774 29562 15776 29563 15774 29563 15777 29563 15777 29564 15526 29564 15528 29564 15777 29565 15774 29565 15526 29565 15778 29566 15777 29566 15528 29566 15779 29567 15776 29567 15777 29567 15775 29568 15776 29568 15779 29568 15779 29569 15777 29569 15778 29569 15778 29570 15528 29570 15529 29570 15781 29571 15775 29571 15779 29571 15780 29572 15779 29572 15778 29572 15531 29573 15778 29573 15529 29573 15780 29574 15778 29574 15531 29574 15782 29575 15531 29575 15532 29575 15781 29576 15779 29576 15780 29576 15782 29577 15780 29577 15531 29577 15783 29578 15780 29578 15782 29578 15781 29579 15780 29579 15783 29579 15533 29580 15782 29580 15532 29580 15784 29581 15781 29581 15783 29581 15783 29582 15782 29582 15533 29582 15787 29583 15781 29583 15784 29583 15785 29584 15533 29584 15535 29584 15785 29585 15783 29585 15533 29585 15786 29586 15783 29586 15785 29586 15786 29587 15784 29587 15783 29587 15537 29588 15785 29588 15535 29588 15787 29589 15784 29589 15786 29589 15786 29590 15785 29590 15537 29590 15788 29591 15786 29591 15537 29591 15789 29592 15786 29592 15788 29592 15789 29593 15787 29593 15786 29593 15790 29594 15537 29594 15538 29594 15790 29595 15788 29595 15537 29595 15789 29596 15788 29596 15790 29596 15539 29597 15790 29597 15538 29597 15791 29598 15790 29598 15539 29598 15793 29599 15787 29599 15789 29599 15791 29600 15789 29600 15790 29600 15791 29601 15539 29601 15792 29601 15793 29602 15789 29602 15791 29602 15794 29603 15791 29603 15792 29603 15793 29604 15791 29604 15794 29604 15541 29605 15794 29605 15792 29605 15795 29606 15794 29606 15541 29606 15795 29607 15793 29607 15794 29607 15795 29608 15541 29608 15542 29608 15798 29609 15795 29609 15542 29609 15797 29610 15793 29610 15795 29610 15796 29611 15793 29611 15797 29611 15798 29612 15797 29612 15795 29612 15544 29613 15798 29613 15542 29613 15799 29614 15797 29614 15798 29614 15799 29615 15798 29615 15544 29615 15800 29616 15797 29616 15799 29616 15801 29617 15797 29617 15800 29617 15801 29618 15796 29618 15797 29618 15802 29619 15799 29619 15544 29619 15800 29620 15799 29620 15802 29620 15802 29621 15544 29621 15545 29621 15710 29622 15802 29622 15545 29622 15802 29623 15710 29623 15711 29623 15800 29624 15802 29624 15711 29624 15800 29625 15711 29625 15713 29625 15801 29626 15800 29626 15713 29626 14817 29627 15763 29627 15770 29627 14815 29628 14817 29628 15770 29628 14819 29629 15763 29629 14817 29629 14815 29630 15770 29630 15775 29630 14821 29631 15763 29631 14819 29631 14813 29632 14815 29632 15775 29632 14821 29633 15756 29633 15763 29633 14822 29634 15756 29634 14821 29634 14813 29635 15775 29635 15781 29635 14822 29636 15752 29636 15756 29636 14811 29637 14813 29637 15781 29637 14825 29638 15752 29638 14822 29638 14811 29639 15781 29639 15787 29639 14809 29640 14811 29640 15787 29640 14827 29641 15752 29641 14825 29641 14827 29642 15745 29642 15752 29642 14807 29643 14809 29643 15787 29643 15741 29644 15745 29644 14827 29644 15793 29645 14807 29645 15787 29645 14829 29646 15741 29646 14827 29646 15793 29647 14805 29647 14807 29647 15796 29648 14805 29648 15793 29648 15741 29649 14829 29649 14831 29649 15736 29650 15741 29650 14831 29650 15736 29651 14831 29651 14833 29651 15801 29652 14805 29652 15796 29652 15801 29653 14802 29653 14805 29653 15713 29654 14802 29654 15801 29654 15713 29655 14842 29655 14802 29655 15727 29656 15736 29656 14833 29656 15727 29657 14833 29657 14835 29657 15720 29658 14842 29658 15713 29658 15720 29659 14840 29659 14842 29659 15727 29660 14835 29660 14837 29660 15724 29661 15727 29661 14837 29661 15720 29662 14838 29662 14840 29662 15724 29663 14838 29663 15720 29663 15724 29664 14837 29664 14838 29664 15805 29665 15803 29665 15804 29665 15805 29666 15804 29666 15806 29666 15807 29667 15805 29667 15806 29667 15808 29668 15807 29668 15806 29668 15808 29669 15806 29669 15809 29669 15810 29670 15808 29670 15809 29670 15811 29671 15810 29671 15809 29671 15811 29672 15809 29672 15812 29672 15813 29673 15811 29673 15812 29673 15814 29674 15813 29674 15812 29674 15814 29675 15812 29675 15815 29675 15816 29676 15814 29676 15815 29676 15817 29677 15816 29677 15815 29677 15817 29678 15815 29678 15818 29678 15819 29679 15817 29679 15818 29679 15820 29680 15819 29680 15818 29680 15821 29681 15820 29681 15818 29681 15822 29682 15818 29682 15823 29682 15822 29683 15821 29683 15818 29683 15824 29684 15822 29684 15823 29684 15825 29685 15823 29685 15826 29685 15825 29686 15824 29686 15823 29686 15827 29687 15825 29687 15826 29687 15828 29688 15827 29688 15826 29688 15828 29689 15826 29689 15829 29689 15830 29690 15828 29690 15829 29690 15831 29691 15830 29691 15829 29691 15831 29692 15829 29692 15832 29692 15833 29693 15831 29693 15832 29693 15834 29694 15833 29694 15832 29694 15835 29695 15832 29695 15836 29695 15835 29696 15834 29696 15832 29696 15837 29697 15835 29697 15836 29697 15837 29698 15836 29698 15838 29698 15839 29699 15837 29699 15838 29699 16106 29700 15839 29700 15838 29700 15840 29701 15838 29701 15841 29701 15840 29702 16106 29702 15838 29702 15842 29703 15840 29703 15841 29703 15842 29704 15841 29704 15843 29704 15844 29705 15842 29705 15843 29705 15845 29706 15844 29706 15843 29706 15845 29707 15843 29707 15846 29707 15847 29708 15845 29708 15846 29708 15848 29709 15847 29709 15846 29709 15848 29710 15846 29710 15849 29710 15850 29711 15848 29711 15849 29711 15851 29712 15850 29712 15849 29712 15852 29713 15851 29713 15849 29713 15852 29714 15849 29714 15853 29714 15854 29715 15852 29715 15853 29715 15855 29716 15854 29716 15853 29716 15855 29717 15853 29717 15856 29717 15857 29718 15855 29718 15856 29718 15858 29719 15856 29719 15859 29719 15858 29720 15857 29720 15856 29720 15860 29721 15858 29721 15859 29721 15861 29722 15860 29722 15859 29722 15861 29723 15859 29723 15862 29723 15863 29724 15861 29724 15862 29724 15864 29725 15863 29725 15862 29725 15864 29726 15862 29726 15865 29726 15866 29727 15864 29727 15865 29727 15867 29728 15866 29728 15865 29728 15868 29729 15867 29729 15865 29729 15869 29730 15865 29730 15870 29730 15869 29731 15868 29731 15865 29731 15871 29732 15869 29732 15870 29732 15872 29733 15870 29733 15873 29733 15872 29734 15871 29734 15870 29734 15874 29735 15872 29735 15873 29735 15875 29736 15873 29736 15876 29736 15875 29737 15874 29737 15873 29737 15877 29738 15875 29738 15876 29738 15877 29739 15876 29739 15878 29739 15879 29740 15877 29740 15878 29740 15880 29741 15879 29741 15878 29741 15880 29742 15878 29742 15881 29742 15882 29743 15880 29743 15881 29743 15883 29744 15882 29744 15881 29744 15803 29745 15883 29745 15881 29745 15803 29746 15881 29746 15804 29746 15884 29747 15885 29747 15886 29747 15884 29748 15886 29748 15887 29748 15884 29749 15887 29749 15888 29749 15889 29750 15884 29750 15888 29750 15889 29751 15888 29751 16052 29751 15889 29752 16052 29752 15890 29752 15891 29753 15889 29753 15890 29753 15891 29754 15890 29754 15892 29754 15891 29755 15892 29755 15893 29755 15891 29756 15893 29756 15894 29756 15895 29757 15891 29757 15894 29757 15895 29758 15894 29758 15896 29758 15895 29759 15896 29759 15897 29759 15898 29760 15897 29760 15899 29760 15898 29761 15895 29761 15897 29761 15898 29762 15899 29762 15900 29762 15898 29763 15900 29763 16038 29763 15901 29764 15898 29764 16038 29764 15901 29765 16038 29765 15902 29765 15901 29766 15902 29766 15903 29766 15901 29767 15903 29767 15904 29767 15905 29768 15901 29768 15904 29768 15905 29769 15904 29769 15906 29769 15905 29770 15906 29770 16030 29770 15905 29771 16030 29771 15907 29771 15908 29772 15905 29772 15907 29772 15908 29773 15907 29773 15909 29773 15908 29774 15909 29774 15910 29774 15911 29775 15908 29775 15910 29775 15911 29776 15910 29776 15912 29776 15911 29777 15912 29777 15913 29777 15911 29778 15913 29778 15914 29778 15915 29779 15911 29779 15914 29779 15915 29780 15914 29780 15916 29780 15915 29781 15916 29781 15917 29781 15915 29782 15917 29782 15918 29782 15919 29783 15915 29783 15918 29783 15919 29784 15918 29784 15920 29784 15919 29785 15920 29785 15921 29785 15919 29786 15921 29786 15922 29786 15923 29787 15919 29787 15922 29787 15923 29788 15922 29788 15924 29788 15925 29789 15923 29789 15924 29789 15925 29790 15924 29790 15926 29790 15925 29791 15926 29791 16003 29791 15925 29792 16003 29792 15927 29792 15928 29793 15925 29793 15927 29793 15928 29794 15927 29794 15929 29794 15930 29795 15929 29795 15931 29795 15930 29796 15928 29796 15929 29796 15930 29797 15931 29797 15932 29797 15930 29798 15932 29798 15933 29798 15934 29799 15930 29799 15933 29799 15934 29800 15933 29800 15935 29800 15934 29801 15935 29801 15990 29801 15934 29802 15990 29802 15936 29802 15937 29803 15934 29803 15936 29803 15937 29804 15936 29804 15938 29804 15939 29805 15937 29805 15938 29805 15939 29806 15938 29806 15940 29806 15939 29807 15940 29807 15941 29807 15942 29808 15941 29808 15980 29808 15942 29809 15939 29809 15941 29809 15942 29810 15980 29810 15943 29810 15942 29811 15943 29811 15944 29811 15945 29812 15942 29812 15944 29812 15945 29813 15944 29813 15946 29813 15945 29814 15946 29814 15947 29814 15945 29815 15947 29815 15948 29815 15949 29816 15945 29816 15948 29816 15949 29817 15948 29817 15950 29817 15949 29818 15950 29818 15952 29818 15951 29819 15949 29819 15952 29819 15951 29820 15952 29820 15953 29820 15954 29821 15951 29821 15953 29821 15954 29822 15953 29822 15955 29822 15954 29823 15955 29823 15956 29823 15957 29824 15954 29824 15956 29824 15957 29825 15956 29825 15958 29825 15957 29826 15958 29826 15885 29826 15884 29827 15957 29827 15885 29827 15959 29828 15885 29828 15958 29828 15961 29829 15958 29829 15956 29829 15961 29830 15959 29830 15958 29830 15962 29831 15959 29831 15961 29831 15960 29832 15959 29832 15962 29832 15963 29833 15961 29833 15956 29833 15964 29834 15960 29834 15962 29834 15964 29835 16058 29835 15960 29835 15963 29836 15962 29836 15961 29836 15955 29837 15963 29837 15956 29837 15965 29838 15962 29838 15963 29838 15965 29839 15964 29839 15962 29839 15953 29840 15963 29840 15955 29840 15966 29841 15963 29841 15953 29841 15966 29842 15965 29842 15963 29842 15952 29843 15966 29843 15953 29843 15967 29844 15965 29844 15966 29844 15967 29845 15964 29845 15965 29845 15968 29846 15964 29846 15967 29846 15969 29847 15966 29847 15952 29847 15967 29848 15966 29848 15969 29848 15969 29849 15952 29849 15950 29849 15970 29850 15969 29850 15950 29850 15971 29851 15969 29851 15970 29851 15971 29852 15967 29852 15969 29852 15971 29853 15968 29853 15967 29853 15970 29854 15950 29854 15948 29854 15972 29855 15971 29855 15970 29855 15973 29856 15971 29856 15972 29856 15947 29857 15970 29857 15948 29857 15973 29858 15968 29858 15971 29858 15972 29859 15970 29859 15947 29859 15974 29860 15973 29860 15972 29860 15972 29861 15947 29861 15946 29861 15975 29862 15972 29862 15946 29862 15974 29863 15972 29863 15975 29863 15944 29864 15975 29864 15946 29864 15976 29865 15973 29865 15974 29865 15977 29866 15974 29866 15975 29866 15976 29867 15974 29867 15977 29867 15977 29868 15975 29868 15944 29868 15977 29869 15944 29869 15943 29869 15979 29870 15973 29870 15976 29870 15978 29871 15976 29871 15977 29871 15979 29872 15976 29872 15978 29872 15978 29873 15977 29873 15943 29873 15980 29874 15978 29874 15943 29874 15981 29875 15978 29875 15980 29875 15979 29876 15978 29876 15981 29876 15982 29877 15980 29877 15941 29877 15982 29878 15981 29878 15980 29878 15983 29879 15982 29879 15941 29879 15985 29880 15979 29880 15981 29880 15984 29881 15982 29881 15983 29881 15984 29882 15981 29882 15982 29882 15940 29883 15983 29883 15941 29883 15985 29884 15981 29884 15984 29884 15986 29885 15984 29885 15983 29885 15938 29886 15983 29886 15940 29886 15987 29887 15985 29887 15984 29887 15986 29888 15983 29888 15938 29888 15988 29889 15984 29889 15986 29889 15988 29890 15987 29890 15984 29890 15989 29891 15986 29891 15938 29891 15988 29892 15986 29892 15989 29892 15936 29893 15989 29893 15938 29893 15990 29894 15989 29894 15936 29894 15988 29895 15989 29895 15990 29895 15991 29896 15987 29896 15988 29896 15991 29897 15985 29897 15987 29897 15992 29898 15988 29898 15990 29898 15993 29899 15988 29899 15992 29899 15935 29900 15992 29900 15990 29900 15993 29901 15991 29901 15988 29901 15994 29902 15992 29902 15935 29902 15993 29903 15992 29903 15994 29903 15994 29904 15935 29904 15933 29904 15995 29905 15991 29905 15993 29905 15995 29906 15993 29906 15994 29906 15996 29907 15994 29907 15933 29907 15996 29908 15995 29908 15994 29908 15996 29909 15933 29909 15932 29909 15997 29910 15996 29910 15932 29910 15998 29911 15991 29911 15995 29911 15999 29912 15996 29912 15997 29912 15999 29913 15995 29913 15996 29913 15931 29914 15997 29914 15932 29914 15998 29915 15995 29915 15999 29915 15929 29916 15997 29916 15931 29916 16000 29917 15997 29917 15929 29917 16000 29918 15999 29918 15997 29918 15998 29919 15999 29919 16000 29919 16001 29920 15998 29920 16000 29920 15927 29921 16000 29921 15929 29921 16001 29922 16000 29922 15927 29922 16002 29923 16001 29923 15927 29923 16002 29924 15927 29924 16003 29924 16004 29925 15998 29925 16001 29925 16005 29926 16001 29926 16002 29926 16006 29927 16003 29927 15926 29927 16005 29928 16004 29928 16001 29928 16006 29929 16002 29929 16003 29929 16006 29930 16005 29930 16002 29930 15924 29931 16006 29931 15926 29931 16009 29932 16004 29932 16005 29932 16007 29933 16006 29933 15924 29933 16008 29934 16009 29934 16005 29934 16007 29935 16005 29935 16006 29935 16008 29936 16005 29936 16007 29936 16007 29937 15924 29937 15922 29937 16010 29938 16008 29938 16007 29938 16009 29939 16008 29939 16010 29939 16011 29940 16007 29940 15922 29940 16010 29941 16007 29941 16011 29941 16011 29942 15922 29942 15921 29942 16013 29943 16011 29943 15921 29943 16012 29944 16009 29944 16010 29944 16014 29945 16011 29945 16013 29945 16014 29946 16010 29946 16011 29946 16013 29947 15921 29947 15920 29947 16012 29948 16010 29948 16014 29948 16015 29949 16014 29949 16013 29949 15918 29950 16013 29950 15920 29950 16015 29951 16013 29951 15918 29951 16012 29952 16014 29952 16015 29952 16016 29953 16015 29953 15918 29953 16017 29954 16012 29954 16015 29954 16016 29955 15918 29955 15917 29955 16017 29956 16015 29956 16016 29956 15916 29957 16016 29957 15917 29957 16018 29958 16016 29958 15916 29958 16021 29959 16012 29959 16017 29959 16019 29960 16017 29960 16016 29960 16019 29961 16016 29961 16018 29961 15914 29962 16018 29962 15916 29962 16020 29963 16018 29963 15914 29963 16021 29964 16017 29964 16019 29964 16020 29965 16019 29965 16018 29965 16022 29966 16019 29966 16020 29966 16021 29967 16019 29967 16022 29967 16022 29968 16020 29968 15914 29968 16023 29969 16021 29969 16022 29969 15913 29970 16022 29970 15914 29970 16024 29971 16023 29971 16022 29971 15912 29972 16022 29972 15913 29972 16024 29973 16022 29973 15912 29973 16025 29974 16024 29974 15912 29974 16025 29975 15912 29975 15910 29975 16026 29976 16023 29976 16024 29976 16026 29977 16024 29977 16025 29977 16025 29978 15910 29978 15909 29978 16029 29979 16023 29979 16026 29979 16027 29980 16025 29980 15909 29980 16028 29981 16025 29981 16027 29981 16026 29982 16025 29982 16028 29982 16027 29983 15909 29983 15907 29983 16029 29984 16026 29984 16028 29984 16030 29985 16027 29985 15907 29985 16031 29986 16027 29986 16030 29986 16031 29987 16028 29987 16027 29987 16029 29988 16028 29988 16031 29988 16032 29989 16030 29989 15906 29989 16033 29990 16029 29990 16031 29990 16032 29991 16031 29991 16030 29991 16032 29992 15906 29992 15904 29992 16034 29993 16031 29993 16032 29993 16034 29994 16033 29994 16031 29994 16035 29995 16032 29995 15904 29995 16035 29996 16034 29996 16032 29996 16035 29997 15904 29997 15903 29997 16037 29998 16034 29998 16035 29998 15902 29999 16035 29999 15903 29999 16037 30000 16033 30000 16034 30000 16036 30001 16035 30001 15902 30001 16037 30002 16035 30002 16036 30002 16039 30003 16033 30003 16037 30003 16038 30004 16036 30004 15902 30004 16040 30005 16036 30005 16038 30005 16040 30006 16037 30006 16036 30006 16039 30007 16037 30007 16040 30007 16040 30008 16038 30008 15900 30008 16041 30009 15900 30009 15899 30009 16041 30010 16040 30010 15900 30010 16042 30011 16040 30011 16041 30011 15897 30012 16041 30012 15899 30012 16042 30013 16039 30013 16040 30013 16043 30014 15897 30014 15896 30014 16043 30015 16041 30015 15897 30015 16044 30016 16039 30016 16042 30016 16042 30017 16041 30017 16043 30017 16045 30018 16042 30018 16043 30018 15894 30019 16043 30019 15896 30019 16044 30020 16042 30020 16045 30020 16046 30021 16043 30021 15894 30021 16045 30022 16043 30022 16046 30022 15893 30023 16046 30023 15894 30023 16047 30024 16045 30024 16046 30024 16047 30025 16046 30025 15893 30025 16048 30026 16044 30026 16045 30026 16047 30027 16048 30027 16045 30027 15892 30028 16047 30028 15893 30028 16049 30029 16047 30029 15892 30029 16050 30030 16047 30030 16049 30030 16050 30031 16048 30031 16047 30031 16049 30032 15892 30032 15890 30032 16051 30033 16049 30033 15890 30033 16053 30034 16048 30034 16050 30034 16050 30035 16049 30035 16051 30035 16051 30036 15890 30036 16052 30036 16054 30037 16052 30037 15888 30037 16053 30038 16050 30038 16051 30038 16051 30039 16052 30039 16054 30039 16055 30040 16051 30040 16054 30040 16055 30041 16053 30041 16051 30041 16056 30042 16054 30042 15888 30042 16055 30043 16054 30043 16056 30043 16056 30044 15888 30044 15887 30044 16057 30045 16056 30045 15887 30045 16058 30046 16053 30046 16055 30046 15886 30047 16057 30047 15887 30047 16059 30048 16056 30048 16057 30048 16059 30049 16055 30049 16056 30049 16057 30050 15886 30050 15885 30050 16059 30051 16058 30051 16055 30051 16057 30052 15885 30052 15959 30052 16059 30053 16057 30053 15959 30053 16059 30054 15959 30054 15960 30054 16058 30055 16059 30055 15960 30055 15600 30056 15973 30056 15598 30056 15600 30057 15968 30057 15973 30057 15596 30058 15598 30058 15973 30058 15602 30059 15968 30059 15600 30059 15602 30060 15964 30060 15968 30060 15596 30061 15973 30061 15979 30061 15593 30062 15596 30062 15979 30062 15604 30063 15964 30063 15602 30063 15604 30064 16058 30064 15964 30064 15593 30065 15979 30065 15985 30065 15591 30066 15593 30066 15985 30066 15546 30067 16058 30067 15604 30067 15549 30068 16053 30068 16058 30068 15549 30069 16058 30069 15546 30069 15587 30070 15591 30070 15985 30070 15991 30071 15587 30071 15985 30071 15550 30072 16053 30072 15549 30072 15550 30073 16048 30073 16053 30073 15584 30074 15587 30074 15991 30074 15998 30075 15584 30075 15991 30075 16048 30076 15550 30076 15552 30076 15998 30077 15582 30077 15584 30077 16044 30078 16048 30078 15552 30078 16039 30079 15552 30079 15554 30079 16039 30080 16044 30080 15552 30080 16004 30081 15582 30081 15998 30081 16004 30082 15579 30082 15582 30082 16009 30083 15579 30083 16004 30083 16039 30084 15554 30084 15556 30084 16009 30085 15577 30085 15579 30085 16039 30086 15556 30086 15560 30086 16012 30087 15577 30087 16009 30087 16033 30088 16039 30088 15560 30088 16012 30089 15574 30089 15577 30089 16033 30090 15560 30090 15562 30090 16012 30091 15570 30091 15574 30091 16021 30092 15570 30092 16012 30092 16029 30093 16033 30093 15562 30093 16029 30094 15562 30094 15565 30094 16023 30095 16029 30095 15565 30095 16021 30096 15567 30096 15570 30096 16023 30097 15565 30097 15567 30097 16023 30098 15567 30098 16021 30098 16061 30099 16160 30099 16060 30099 16061 30100 16062 30100 16160 30100 15805 30101 16060 30101 15803 30101 16063 30102 16060 30102 15805 30102 16063 30103 16061 30103 16060 30103 16061 30104 16064 30104 16062 30104 16065 30105 15805 30105 15807 30105 16065 30106 16063 30106 15805 30106 16066 30107 16063 30107 16065 30107 16066 30108 16061 30108 16063 30108 16064 30109 16061 30109 16066 30109 16067 30110 16066 30110 16065 30110 15808 30111 16065 30111 15807 30111 16067 30112 16065 30112 15808 30112 16070 30113 16064 30113 16066 30113 16069 30114 15808 30114 15810 30114 16068 30115 16066 30115 16067 30115 16069 30116 16067 30116 15808 30116 16070 30117 16066 30117 16068 30117 16069 30118 16068 30118 16067 30118 16071 30119 15810 30119 15811 30119 16071 30120 16069 30120 15810 30120 16071 30121 16068 30121 16069 30121 16072 30122 16070 30122 16068 30122 16072 30123 16068 30123 16071 30123 16073 30124 16071 30124 15811 30124 16073 30125 15811 30125 15813 30125 16074 30126 16070 30126 16072 30126 16075 30127 16071 30127 16073 30127 16075 30128 16072 30128 16071 30128 16075 30129 16073 30129 15813 30129 16076 30130 16072 30130 16075 30130 15814 30131 16075 30131 15813 30131 16077 30132 16075 30132 15814 30132 16077 30133 16076 30133 16075 30133 16078 30134 16072 30134 16076 30134 16078 30135 16074 30135 16072 30135 16078 30136 16076 30136 16077 30136 16077 30137 15814 30137 15816 30137 16079 30138 16077 30138 15816 30138 16079 30139 16078 30139 16077 30139 16079 30140 15816 30140 15817 30140 16080 30141 16078 30141 16079 30141 16081 30142 16079 30142 15817 30142 16082 30143 16074 30143 16078 30143 16080 30144 16079 30144 16081 30144 15819 30145 16081 30145 15817 30145 16082 30146 16078 30146 16080 30146 15820 30147 16081 30147 15819 30147 16084 30148 16081 30148 15820 30148 16083 30149 16082 30149 16080 30149 16084 30150 16080 30150 16081 30150 16083 30151 16080 30151 16084 30151 15821 30152 16084 30152 15820 30152 16085 30153 16084 30153 15821 30153 16083 30154 16084 30154 16085 30154 16086 30155 16082 30155 16083 30155 16085 30156 15821 30156 15822 30156 16086 30157 16083 30157 16085 30157 16087 30158 16085 30158 15822 30158 16087 30159 15822 30159 15824 30159 16087 30160 16086 30160 16085 30160 16088 30161 16086 30161 16087 30161 16089 30162 16087 30162 15824 30162 16088 30163 16087 30163 16089 30163 16089 30164 15824 30164 15825 30164 16091 30165 15825 30165 15827 30165 16088 30166 16089 30166 16090 30166 16091 30167 16089 30167 15825 30167 16092 30168 16086 30168 16088 30168 16090 30169 16089 30169 16091 30169 16092 30170 16088 30170 16090 30170 16091 30171 15827 30171 15828 30171 16093 30172 16090 30172 16091 30172 16092 30173 16090 30173 16093 30173 16094 30174 16091 30174 15828 30174 16093 30175 16091 30175 16094 30175 15830 30176 16094 30176 15828 30176 16095 30177 16092 30177 16093 30177 16096 30178 16093 30178 16094 30178 16095 30179 16093 30179 16096 30179 16096 30180 16094 30180 15830 30180 15831 30181 16096 30181 15830 30181 16097 30182 16096 30182 15831 30182 16097 30183 16095 30183 16096 30183 16099 30184 16095 30184 16097 30184 15833 30185 16097 30185 15831 30185 16098 30186 16095 30186 16099 30186 16100 30187 16097 30187 15833 30187 16099 30188 16097 30188 16100 30188 16100 30189 15833 30189 15834 30189 16102 30190 16099 30190 16100 30190 16101 30191 15834 30191 15835 30191 16102 30192 16098 30192 16099 30192 16101 30193 16100 30193 15834 30193 16102 30194 16100 30194 16101 30194 16101 30195 15835 30195 15837 30195 16103 30196 16098 30196 16102 30196 15839 30197 16101 30197 15837 30197 16104 30198 16101 30198 15839 30198 16104 30199 16102 30199 16101 30199 16105 30200 16098 30200 16103 30200 16103 30201 16102 30201 16104 30201 16106 30202 16104 30202 15839 30202 16107 30203 16104 30203 16106 30203 16107 30204 16103 30204 16104 30204 16105 30205 16103 30205 16107 30205 16108 30206 16107 30206 16106 30206 16108 30207 16106 30207 15840 30207 16109 30208 16107 30208 16108 30208 16105 30209 16107 30209 16109 30209 16110 30210 16108 30210 15840 30210 16109 30211 16108 30211 16110 30211 15842 30212 16110 30212 15840 30212 16111 30213 16110 30213 15842 30213 16112 30214 16105 30214 16109 30214 16111 30215 16109 30215 16110 30215 16113 30216 16109 30216 16111 30216 16113 30217 16112 30217 16109 30217 15844 30218 16111 30218 15842 30218 16114 30219 16111 30219 15844 30219 16113 30220 16111 30220 16114 30220 15845 30221 16114 30221 15844 30221 16115 30222 16114 30222 15845 30222 16115 30223 16113 30223 16114 30223 16116 30224 16113 30224 16115 30224 16117 30225 16112 30225 16113 30225 15847 30226 16115 30226 15845 30226 16117 30227 16113 30227 16116 30227 16118 30228 16116 30228 16115 30228 16119 30229 16115 30229 15847 30229 16118 30230 16117 30230 16116 30230 16119 30231 16118 30231 16115 30231 15848 30232 16119 30232 15847 30232 15850 30233 16119 30233 15848 30233 16120 30234 16117 30234 16118 30234 16121 30235 16119 30235 15850 30235 16121 30236 16118 30236 16119 30236 16124 30237 16117 30237 16120 30237 16120 30238 16118 30238 16121 30238 16122 30239 15850 30239 15851 30239 16121 30240 15850 30240 16122 30240 16125 30241 16120 30241 16121 30241 16123 30242 15851 30242 15852 30242 16123 30243 16122 30243 15851 30243 16124 30244 16120 30244 16125 30244 16125 30245 16121 30245 16122 30245 16123 30246 16125 30246 16122 30246 16126 30247 16124 30247 16125 30247 15854 30248 16123 30248 15852 30248 16127 30249 16123 30249 15854 30249 16127 30250 16125 30250 16123 30250 16126 30251 16125 30251 16127 30251 16127 30252 15854 30252 15855 30252 16128 30253 16126 30253 16127 30253 16129 30254 16127 30254 15855 30254 16128 30255 16127 30255 16129 30255 16129 30256 15855 30256 15857 30256 16130 30257 16128 30257 16129 30257 16129 30258 15857 30258 15858 30258 16132 30259 16126 30259 16128 30259 16131 30260 16129 30260 15858 30260 16131 30261 16130 30261 16129 30261 16131 30262 15858 30262 15860 30262 16133 30263 16128 30263 16130 30263 16133 30264 16130 30264 16131 30264 16132 30265 16128 30265 16133 30265 16134 30266 16133 30266 16131 30266 15861 30267 16131 30267 15860 30267 16135 30268 16131 30268 15861 30268 16134 30269 16131 30269 16135 30269 16135 30270 15861 30270 15863 30270 16136 30271 16133 30271 16134 30271 16136 30272 16132 30272 16133 30272 16136 30273 16134 30273 16135 30273 15864 30274 16135 30274 15863 30274 16137 30275 16136 30275 16135 30275 16138 30276 16132 30276 16136 30276 16137 30277 16135 30277 15864 30277 16138 30278 16136 30278 16137 30278 16139 30279 16137 30279 15864 30279 16139 30280 15864 30280 15866 30280 16138 30281 16137 30281 16139 30281 15867 30282 16139 30282 15866 30282 16140 30283 16138 30283 16139 30283 16140 30284 16139 30284 15867 30284 15868 30285 16140 30285 15867 30285 16142 30286 16138 30286 16140 30286 16141 30287 16138 30287 16142 30287 16143 30288 16140 30288 15868 30288 16142 30289 16140 30289 16143 30289 16143 30290 15868 30290 15869 30290 16141 30291 16142 30291 16143 30291 16144 30292 16141 30292 16143 30292 16145 30293 15869 30293 15871 30293 16145 30294 16143 30294 15869 30294 16144 30295 16143 30295 16145 30295 16146 30296 16141 30296 16144 30296 15872 30297 16145 30297 15871 30297 16147 30298 16144 30298 16145 30298 16147 30299 16146 30299 16144 30299 16147 30300 16145 30300 15872 30300 16148 30301 15872 30301 15874 30301 16148 30302 16147 30302 15872 30302 16149 30303 15874 30303 15875 30303 16149 30304 16148 30304 15874 30304 16150 30305 16146 30305 16147 30305 16151 30306 16148 30306 16149 30306 16151 30307 16147 30307 16148 30307 16150 30308 16147 30308 16151 30308 16151 30309 16149 30309 15875 30309 16152 30310 16151 30310 15875 30310 16150 30311 16151 30311 16152 30311 15877 30312 16152 30312 15875 30312 16153 30313 16150 30313 16152 30313 16154 30314 16152 30314 15877 30314 16155 30315 16150 30315 16153 30315 16153 30316 16152 30316 16154 30316 16154 30317 15877 30317 15879 30317 15880 30318 16154 30318 15879 30318 16157 30319 16153 30319 16154 30319 16156 30320 16154 30320 15880 30320 16157 30321 16155 30321 16153 30321 16157 30322 16154 30322 16156 30322 15882 30323 16156 30323 15880 30323 16158 30324 16156 30324 15882 30324 16158 30325 16157 30325 16156 30325 16159 30326 16155 30326 16157 30326 16159 30327 16157 30327 16158 30327 16160 30328 16158 30328 15882 30328 16159 30329 16158 30329 16160 30329 16160 30330 15882 30330 15883 30330 15883 30331 15803 30331 16060 30331 16062 30332 16159 30332 16160 30332 16160 30333 15883 30333 16060 30333 16064 30334 16155 30334 16159 30334 16064 30335 16159 30335 16062 30335 15521 30336 16124 30336 16126 30336 15521 30337 15518 30337 16124 30337 15521 30338 16126 30338 16132 30338 15524 30339 15521 30339 16132 30339 15516 30340 16124 30340 15518 30340 15516 30341 16117 30341 16124 30341 15527 30342 15524 30342 16132 30342 15512 30343 16117 30343 15516 30343 15512 30344 16112 30344 16117 30344 15530 30345 16132 30345 16138 30345 15530 30346 15527 30346 16132 30346 15512 30347 16105 30347 16112 30347 15508 30348 16105 30348 15512 30348 15530 30349 16138 30349 16141 30349 15534 30350 15530 30350 16141 30350 15534 30351 16141 30351 16146 30351 15505 30352 16105 30352 15508 30352 15536 30353 15534 30353 16146 30353 15505 30354 16098 30354 16105 30354 15502 30355 16098 30355 15505 30355 15536 30356 16146 30356 16150 30356 16155 30357 15536 30357 16150 30357 15540 30358 15536 30358 16155 30358 15499 30359 16098 30359 15502 30359 16095 30360 16098 30360 15499 30360 15495 30361 16095 30361 15499 30361 16155 30362 15543 30362 15540 30362 16092 30363 16095 30363 15495 30363 16086 30364 16092 30364 15495 30364 16064 30365 15543 30365 16155 30365 16086 30366 15495 30366 15491 30366 16064 30367 15475 30367 15543 30367 16082 30368 16086 30368 15491 30368 16082 30369 15491 30369 15488 30369 16064 30370 15478 30370 15475 30370 16070 30371 15478 30371 16064 30371 16070 30372 15480 30372 15478 30372 16074 30373 16082 30373 15488 30373 16074 30374 15488 30374 15484 30374 16070 30375 15484 30375 15480 30375 16074 30376 15484 30376 16070 30376 16162 30377 16161 30377 16246 30377 16162 30378 16246 30378 16163 30378 16164 30379 16162 30379 16163 30379 16164 30380 16163 30380 16165 30380 16166 30381 16164 30381 16165 30381 16167 30382 16166 30382 16165 30382 16168 30383 16165 30383 16169 30383 16168 30384 16167 30384 16165 30384 16170 30385 16168 30385 16169 30385 16171 30386 16170 30386 16169 30386 16171 30387 16169 30387 16172 30387 16173 30388 16171 30388 16172 30388 16174 30389 16173 30389 16172 30389 16174 30390 16172 30390 16175 30390 16176 30391 16174 30391 16175 30391 16176 30392 16175 30392 16177 30392 16178 30393 16176 30393 16177 30393 16179 30394 16178 30394 16177 30394 16179 30395 16177 30395 16180 30395 16181 30396 16179 30396 16180 30396 16182 30397 16181 30397 16180 30397 16182 30398 16180 30398 16183 30398 16184 30399 16182 30399 16183 30399 16185 30400 16183 30400 16186 30400 16185 30401 16184 30401 16183 30401 16187 30402 16185 30402 16186 30402 16187 30403 16186 30403 16188 30403 16189 30404 16187 30404 16188 30404 16190 30405 16189 30405 16188 30405 16190 30406 16188 30406 16191 30406 16192 30407 16190 30407 16191 30407 16192 30408 16191 30408 16193 30408 16194 30409 16192 30409 16193 30409 16195 30410 16194 30410 16193 30410 16196 30411 16193 30411 16197 30411 16196 30412 16195 30412 16193 30412 16198 30413 16196 30413 16197 30413 16199 30414 16198 30414 16197 30414 16199 30415 16197 30415 16200 30415 16201 30416 16199 30416 16200 30416 16202 30417 16201 30417 16200 30417 16202 30418 16200 30418 16203 30418 16204 30419 16202 30419 16203 30419 16205 30420 16204 30420 16203 30420 16205 30421 16203 30421 16206 30421 16207 30422 16205 30422 16206 30422 16208 30423 16207 30423 16206 30423 16208 30424 16206 30424 16209 30424 16210 30425 16208 30425 16209 30425 16211 30426 16210 30426 16209 30426 16211 30427 16209 30427 16212 30427 16213 30428 16211 30428 16212 30428 16214 30429 16213 30429 16212 30429 16215 30430 16212 30430 16216 30430 16215 30431 16214 30431 16212 30431 16217 30432 16215 30432 16216 30432 16218 30433 16217 30433 16216 30433 16219 30434 16216 30434 16220 30434 16219 30435 16218 30435 16216 30435 16221 30436 16219 30436 16220 30436 16222 30437 16221 30437 16220 30437 16223 30438 16222 30438 16220 30438 16223 30439 16220 30439 16224 30439 16225 30440 16223 30440 16224 30440 16225 30441 16224 30441 16226 30441 16227 30442 16225 30442 16226 30442 16228 30443 16227 30443 16226 30443 16228 30444 16226 30444 16229 30444 16230 30445 16228 30445 16229 30445 16231 30446 16230 30446 16229 30446 16231 30447 16229 30447 16232 30447 16233 30448 16231 30448 16232 30448 16234 30449 16233 30449 16232 30449 16235 30450 16232 30450 16236 30450 16235 30451 16234 30451 16232 30451 16237 30452 16236 30452 16238 30452 16237 30453 16235 30453 16236 30453 16239 30454 16237 30454 16238 30454 16240 30455 16239 30455 16238 30455 16241 30456 16240 30456 16238 30456 16241 30457 16238 30457 16242 30457 16243 30458 16241 30458 16242 30458 16244 30459 16243 30459 16242 30459 16245 30460 16244 30460 16242 30460 16245 30461 16242 30461 16246 30461 16161 30462 16245 30462 16246 30462 16247 30463 16248 30463 16434 30463 16247 30464 16434 30464 16249 30464 16247 30465 16249 30465 16250 30465 16251 30466 16247 30466 16250 30466 16251 30467 16250 30467 16252 30467 16251 30468 16252 30468 16253 30468 16254 30469 16251 30469 16253 30469 16254 30470 16253 30470 16255 30470 16254 30471 16255 30471 16256 30471 16257 30472 16256 30472 16258 30472 16257 30473 16254 30473 16256 30473 16257 30474 16258 30474 16259 30474 16260 30475 16257 30475 16259 30475 16260 30476 16259 30476 16261 30476 16262 30477 16261 30477 16263 30477 16262 30478 16260 30478 16261 30478 16262 30479 16263 30479 16413 30479 16264 30480 16262 30480 16413 30480 16264 30481 16413 30481 16265 30481 16264 30482 16265 30482 16266 30482 16267 30483 16264 30483 16266 30483 16267 30484 16266 30484 16268 30484 16267 30485 16268 30485 16406 30485 16269 30486 16267 30486 16406 30486 16269 30487 16406 30487 16270 30487 16269 30488 16270 30488 16271 30488 16272 30489 16269 30489 16271 30489 16272 30490 16271 30490 16273 30490 16274 30491 16272 30491 16273 30491 16274 30492 16273 30492 16275 30492 16274 30493 16275 30493 16276 30493 16274 30494 16276 30494 16277 30494 16278 30495 16274 30495 16277 30495 16278 30496 16277 30496 16279 30496 16280 30497 16278 30497 16279 30497 16280 30498 16279 30498 16281 30498 16280 30499 16281 30499 16282 30499 16283 30500 16282 30500 16386 30500 16283 30501 16280 30501 16282 30501 16283 30502 16386 30502 16284 30502 16285 30503 16283 30503 16284 30503 16285 30504 16284 30504 16286 30504 16285 30505 16286 30505 16287 30505 16288 30506 16285 30506 16287 30506 16288 30507 16287 30507 16289 30507 16288 30508 16289 30508 16290 30508 16288 30509 16290 30509 16291 30509 16292 30510 16288 30510 16291 30510 16292 30511 16291 30511 16293 30511 16292 30512 16293 30512 16294 30512 16295 30513 16292 30513 16294 30513 16295 30514 16294 30514 16296 30514 16295 30515 16296 30515 16297 30515 16295 30516 16297 30516 16298 30516 16299 30517 16295 30517 16298 30517 16299 30518 16298 30518 16300 30518 16301 30519 16299 30519 16300 30519 16301 30520 16300 30520 16302 30520 16301 30521 16302 30521 16303 30521 16304 30522 16301 30522 16303 30522 16304 30523 16303 30523 16305 30523 16304 30524 16305 30524 16306 30524 16307 30525 16304 30525 16306 30525 16307 30526 16306 30526 16308 30526 16307 30527 16308 30527 16309 30527 16310 30528 16307 30528 16309 30528 16310 30529 16309 30529 16352 30529 16310 30530 16352 30530 16311 30530 16312 30531 16310 30531 16311 30531 16312 30532 16311 30532 16313 30532 16314 30533 16313 30533 16344 30533 16314 30534 16312 30534 16313 30534 16314 30535 16344 30535 16315 30535 16316 30536 16314 30536 16315 30536 16316 30537 16315 30537 16317 30537 16316 30538 16317 30538 16318 30538 16319 30539 16316 30539 16318 30539 16319 30540 16318 30540 16320 30540 16319 30541 16320 30541 16321 30541 16319 30542 16321 30542 16322 30542 16323 30543 16319 30543 16322 30543 16323 30544 16324 30544 16325 30544 16323 30545 16322 30545 16324 30545 16326 30546 16325 30546 16327 30546 16326 30547 16323 30547 16325 30547 16326 30548 16327 30548 16248 30548 16247 30549 16326 30549 16248 30549 16330 30550 16248 30550 16327 30550 16330 30551 16328 30551 16248 30551 16331 30552 16430 30552 16329 30552 16332 30553 16328 30553 16330 30553 16332 30554 16329 30554 16328 30554 16325 30555 16330 30555 16327 30555 16331 30556 16329 30556 16332 30556 16332 30557 16330 30557 16325 30557 16333 30558 16331 30558 16332 30558 16334 30559 16325 30559 16324 30559 16334 30560 16332 30560 16325 30560 16333 30561 16332 30561 16334 30561 16322 30562 16334 30562 16324 30562 16335 30563 16334 30563 16322 30563 16337 30564 16334 30564 16335 30564 16337 30565 16333 30565 16334 30565 16335 30566 16322 30566 16321 30566 16336 30567 16335 30567 16321 30567 16337 30568 16335 30568 16336 30568 16336 30569 16321 30569 16320 30569 16338 30570 16333 30570 16337 30570 16318 30571 16336 30571 16320 30571 16339 30572 16337 30572 16336 30572 16339 30573 16338 30573 16337 30573 16340 30574 16336 30574 16318 30574 16339 30575 16336 30575 16340 30575 16317 30576 16340 30576 16318 30576 16341 30577 16340 30577 16317 30577 16341 30578 16339 30578 16340 30578 16342 30579 16339 30579 16341 30579 16341 30580 16317 30580 16315 30580 16342 30581 16338 30581 16339 30581 16343 30582 16342 30582 16341 30582 16344 30583 16341 30583 16315 30583 16343 30584 16341 30584 16344 30584 16345 30585 16343 30585 16344 30585 16346 30586 16343 30586 16345 30586 16346 30587 16342 30587 16343 30587 16345 30588 16344 30588 16313 30588 16347 30589 16342 30589 16346 30589 16348 30590 16342 30590 16347 30590 16349 30591 16346 30591 16345 30591 16347 30592 16346 30592 16349 30592 16350 30593 16345 30593 16313 30593 16350 30594 16349 30594 16345 30594 16311 30595 16350 30595 16313 30595 16351 30596 16349 30596 16350 30596 16351 30597 16347 30597 16349 30597 16352 30598 16350 30598 16311 30598 16351 30599 16348 30599 16347 30599 16351 30600 16350 30600 16352 30600 16353 30601 16351 30601 16352 30601 16353 30602 16352 30602 16309 30602 16354 30603 16348 30603 16351 30603 16355 30604 16351 30604 16353 30604 16354 30605 16351 30605 16355 30605 16355 30606 16353 30606 16309 30606 16356 30607 16309 30607 16308 30607 16356 30608 16355 30608 16309 30608 16357 30609 16355 30609 16356 30609 16354 30610 16355 30610 16357 30610 16356 30611 16308 30611 16306 30611 16358 30612 16354 30612 16357 30612 16359 30613 16356 30613 16306 30613 16359 30614 16357 30614 16356 30614 16360 30615 16357 30615 16359 30615 16358 30616 16357 30616 16360 30616 16359 30617 16306 30617 16305 30617 16360 30618 16359 30618 16305 30618 16361 30619 16358 30619 16360 30619 16362 30620 16305 30620 16303 30620 16362 30621 16360 30621 16305 30621 16363 30622 16360 30622 16362 30622 16363 30623 16361 30623 16360 30623 16302 30624 16362 30624 16303 30624 16364 30625 16362 30625 16302 30625 16364 30626 16363 30626 16362 30626 16365 30627 16358 30627 16361 30627 16365 30628 16361 30628 16363 30628 16365 30629 16363 30629 16364 30629 16300 30630 16364 30630 16302 30630 16366 30631 16364 30631 16300 30631 16367 30632 16364 30632 16366 30632 16367 30633 16365 30633 16364 30633 16298 30634 16366 30634 16300 30634 16368 30635 16366 30635 16298 30635 16369 30636 16365 30636 16367 30636 16367 30637 16366 30637 16368 30637 16368 30638 16298 30638 16297 30638 16369 30639 16367 30639 16368 30639 16370 30640 16369 30640 16368 30640 16371 30641 16297 30641 16296 30641 16371 30642 16368 30642 16297 30642 16370 30643 16368 30643 16371 30643 16372 30644 16370 30644 16371 30644 16372 30645 16371 30645 16296 30645 16373 30646 16370 30646 16372 30646 16373 30647 16369 30647 16370 30647 16372 30648 16296 30648 16294 30648 16374 30649 16369 30649 16373 30649 16375 30650 16372 30650 16294 30650 16373 30651 16372 30651 16375 30651 16293 30652 16375 30652 16294 30652 16376 30653 16373 30653 16375 30653 16377 30654 16293 30654 16291 30654 16374 30655 16373 30655 16376 30655 16377 30656 16375 30656 16293 30656 16377 30657 16376 30657 16375 30657 16290 30658 16377 30658 16291 30658 16378 30659 16374 30659 16376 30659 16379 30660 16377 30660 16290 30660 16379 30661 16376 30661 16377 30661 16378 30662 16376 30662 16379 30662 16380 30663 16379 30663 16290 30663 16378 30664 16379 30664 16380 30664 16380 30665 16290 30665 16289 30665 16287 30666 16380 30666 16289 30666 16382 30667 16378 30667 16380 30667 16381 30668 16380 30668 16287 30668 16382 30669 16380 30669 16381 30669 16381 30670 16287 30670 16286 30670 16383 30671 16378 30671 16382 30671 16284 30672 16381 30672 16286 30672 16384 30673 16381 30673 16284 30673 16384 30674 16382 30674 16381 30674 16385 30675 16382 30675 16384 30675 16383 30676 16382 30676 16385 30676 16386 30677 16384 30677 16284 30677 16387 30678 16384 30678 16386 30678 16385 30679 16384 30679 16387 30679 16388 30680 16386 30680 16282 30680 16388 30681 16387 30681 16386 30681 16388 30682 16385 30682 16387 30682 16389 30683 16385 30683 16388 30683 16389 30684 16383 30684 16385 30684 16390 30685 16388 30685 16282 30685 16390 30686 16389 30686 16388 30686 16281 30687 16390 30687 16282 30687 16391 30688 16383 30688 16389 30688 16393 30689 16389 30689 16390 30689 16391 30690 16389 30690 16393 30690 16392 30691 16390 30691 16281 30691 16393 30692 16390 30692 16392 30692 16279 30693 16392 30693 16281 30693 16394 30694 16392 30694 16279 30694 16396 30695 16391 30695 16393 30695 16394 30696 16393 30696 16392 30696 16277 30697 16394 30697 16279 30697 16395 30698 16394 30698 16277 30698 16395 30699 16393 30699 16394 30699 16396 30700 16393 30700 16395 30700 16395 30701 16277 30701 16276 30701 16275 30702 16395 30702 16276 30702 16397 30703 16395 30703 16275 30703 16398 30704 16395 30704 16397 30704 16398 30705 16396 30705 16395 30705 16399 30706 16396 30706 16398 30706 16273 30707 16397 30707 16275 30707 16400 30708 16397 30708 16273 30708 16401 30709 16396 30709 16399 30709 16398 30710 16397 30710 16400 30710 16400 30711 16273 30711 16271 30711 16402 30712 16398 30712 16400 30712 16402 30713 16399 30713 16398 30713 16402 30714 16401 30714 16399 30714 16403 30715 16400 30715 16271 30715 16402 30716 16400 30716 16403 30716 16403 30717 16271 30717 16270 30717 16405 30718 16401 30718 16402 30718 16404 30719 16403 30719 16270 30719 16404 30720 16402 30720 16403 30720 16405 30721 16402 30721 16404 30721 16406 30722 16404 30722 16270 30722 16407 30723 16401 30723 16405 30723 16408 30724 16404 30724 16406 30724 16408 30725 16405 30725 16404 30725 16407 30726 16405 30726 16408 30726 16409 30727 16406 30727 16268 30727 16409 30728 16408 30728 16406 30728 16407 30729 16408 30729 16409 30729 16410 30730 16409 30730 16268 30730 16411 30731 16407 30731 16409 30731 16410 30732 16268 30732 16266 30732 16411 30733 16409 30733 16410 30733 16412 30734 16266 30734 16265 30734 16412 30735 16410 30735 16266 30735 16412 30736 16411 30736 16410 30736 16414 30737 16407 30737 16411 30737 16414 30738 16411 30738 16412 30738 16413 30739 16412 30739 16265 30739 16415 30740 16412 30740 16413 30740 16415 30741 16414 30741 16412 30741 16416 30742 16413 30742 16263 30742 16416 30743 16415 30743 16413 30743 16417 30744 16415 30744 16416 30744 16416 30745 16263 30745 16261 30745 16418 30746 16414 30746 16415 30746 16418 30747 16415 30747 16417 30747 16417 30748 16416 30748 16261 30748 16419 30749 16261 30749 16259 30749 16419 30750 16417 30750 16261 30750 16420 30751 16417 30751 16419 30751 16420 30752 16418 30752 16417 30752 16419 30753 16259 30753 16258 30753 16421 30754 16420 30754 16419 30754 16421 30755 16419 30755 16258 30755 16423 30756 16418 30756 16420 30756 16422 30757 16421 30757 16258 30757 16424 30758 16421 30758 16422 30758 16424 30759 16420 30759 16421 30759 16256 30760 16422 30760 16258 30760 16423 30761 16420 30761 16424 30761 16425 30762 16422 30762 16256 30762 16425 30763 16424 30763 16422 30763 16425 30764 16256 30764 16255 30764 16426 30765 16424 30765 16425 30765 16426 30766 16423 30766 16424 30766 16427 30767 16425 30767 16255 30767 16253 30768 16427 30768 16255 30768 16428 30769 16425 30769 16427 30769 16426 30770 16425 30770 16428 30770 16428 30771 16427 30771 16253 30771 16431 30772 16426 30772 16428 30772 16252 30773 16428 30773 16253 30773 16429 30774 16428 30774 16252 30774 16430 30775 16426 30775 16431 30775 16431 30776 16428 30776 16429 30776 16429 30777 16252 30777 16250 30777 16432 30778 16431 30778 16429 30778 16433 30779 16429 30779 16250 30779 16433 30780 16432 30780 16429 30780 16433 30781 16250 30781 16249 30781 16430 30782 16431 30782 16432 30782 16434 30783 16433 30783 16249 30783 16432 30784 16433 30784 16434 30784 16329 30785 16430 30785 16432 30785 16434 30786 16248 30786 16328 30786 16328 30787 16432 30787 16434 30787 16329 30788 16432 30788 16328 30788 15949 30789 16338 30789 16342 30789 15945 30790 15949 30790 16342 30790 15951 30791 16338 30791 15949 30791 15945 30792 16342 30792 16348 30792 15951 30793 16333 30793 16338 30793 15954 30794 16333 30794 15951 30794 15942 30795 15945 30795 16348 30795 15957 30796 16331 30796 16333 30796 15957 30797 16333 30797 15954 30797 15942 30798 16348 30798 16354 30798 15939 30799 15942 30799 16354 30799 15884 30800 16430 30800 16331 30800 15884 30801 16331 30801 15957 30801 15939 30802 16354 30802 16358 30802 15937 30803 15939 30803 16358 30803 15889 30804 16430 30804 15884 30804 16365 30805 15937 30805 16358 30805 15934 30806 15937 30806 16365 30806 15889 30807 16426 30807 16430 30807 15891 30808 16426 30808 15889 30808 15891 30809 16423 30809 16426 30809 15930 30810 15934 30810 16365 30810 16369 30811 15930 30811 16365 30811 15895 30812 16423 30812 15891 30812 16418 30813 16423 30813 15895 30813 16369 30814 15928 30814 15930 30814 16374 30815 15928 30815 16369 30815 16418 30816 15895 30816 15898 30816 16374 30817 15925 30817 15928 30817 16414 30818 16418 30818 15898 30818 16378 30819 15925 30819 16374 30819 16414 30820 15898 30820 15901 30820 16378 30821 15923 30821 15925 30821 16407 30822 16414 30822 15901 30822 16378 30823 15919 30823 15923 30823 16407 30824 15901 30824 15905 30824 16383 30825 15919 30825 16378 30825 16401 30826 16407 30826 15905 30826 16383 30827 15915 30827 15919 30827 16401 30828 15905 30828 15908 30828 16391 30829 15915 30829 16383 30829 16396 30830 16401 30830 15908 30830 16396 30831 15908 30831 15911 30831 16391 30832 15911 30832 15915 30832 16396 30833 15911 30833 16391 30833 16437 30834 16161 30834 16162 30834 16438 30835 16544 30835 16436 30835 16437 30836 16435 30836 16161 30836 16438 30837 16435 30837 16437 30837 16438 30838 16436 30838 16435 30838 16439 30839 16544 30839 16438 30839 16440 30840 16162 30840 16164 30840 16440 30841 16437 30841 16162 30841 16441 30842 16437 30842 16440 30842 16441 30843 16438 30843 16437 30843 16439 30844 16438 30844 16441 30844 16166 30845 16440 30845 16164 30845 16442 30846 16440 30846 16166 30846 16442 30847 16441 30847 16440 30847 16439 30848 16441 30848 16442 30848 16443 30849 16166 30849 16167 30849 16443 30850 16442 30850 16166 30850 16444 30851 16442 30851 16443 30851 16444 30852 16439 30852 16442 30852 16445 30853 16439 30853 16444 30853 16443 30854 16167 30854 16168 30854 16446 30855 16443 30855 16168 30855 16446 30856 16444 30856 16443 30856 16447 30857 16444 30857 16446 30857 16447 30858 16445 30858 16444 30858 16446 30859 16168 30859 16170 30859 16448 30860 16446 30860 16170 30860 16448 30861 16447 30861 16446 30861 16171 30862 16448 30862 16170 30862 16449 30863 16445 30863 16447 30863 16450 30864 16447 30864 16448 30864 16173 30865 16448 30865 16171 30865 16449 30866 16447 30866 16450 30866 16450 30867 16448 30867 16173 30867 16451 30868 16450 30868 16173 30868 16174 30869 16451 30869 16173 30869 16452 30870 16450 30870 16451 30870 16453 30871 16450 30871 16452 30871 16453 30872 16449 30872 16450 30872 16174 30873 16452 30873 16451 30873 16454 30874 16449 30874 16453 30874 16176 30875 16452 30875 16174 30875 16455 30876 16452 30876 16176 30876 16456 30877 16452 30877 16455 30877 16456 30878 16453 30878 16452 30878 16456 30879 16454 30879 16453 30879 16457 30880 16456 30880 16455 30880 16178 30881 16455 30881 16176 30881 16454 30882 16456 30882 16457 30882 16457 30883 16455 30883 16178 30883 16458 30884 16178 30884 16179 30884 16458 30885 16457 30885 16178 30885 16459 30886 16454 30886 16457 30886 16459 30887 16457 30887 16458 30887 16181 30888 16458 30888 16179 30888 16460 30889 16458 30889 16181 30889 16460 30890 16459 30890 16458 30890 16461 30891 16454 30891 16459 30891 16182 30892 16460 30892 16181 30892 16462 30893 16460 30893 16182 30893 16462 30894 16459 30894 16460 30894 16461 30895 16459 30895 16462 30895 16463 30896 16182 30896 16184 30896 16463 30897 16462 30897 16182 30897 16461 30898 16462 30898 16463 30898 16464 30899 16461 30899 16463 30899 16465 30900 16184 30900 16185 30900 16465 30901 16463 30901 16184 30901 16466 30902 16463 30902 16465 30902 16466 30903 16464 30903 16463 30903 16467 30904 16465 30904 16185 30904 16466 30905 16465 30905 16467 30905 16467 30906 16185 30906 16187 30906 16468 30907 16466 30907 16467 30907 16468 30908 16467 30908 16187 30908 16469 30909 16464 30909 16466 30909 16469 30910 16466 30910 16468 30910 16468 30911 16187 30911 16189 30911 16470 30912 16468 30912 16189 30912 16471 30913 16468 30913 16470 30913 16471 30914 16469 30914 16468 30914 16190 30915 16470 30915 16189 30915 16472 30916 16469 30916 16471 30916 16473 30917 16470 30917 16190 30917 16473 30918 16471 30918 16470 30918 16474 30919 16471 30919 16473 30919 16472 30920 16471 30920 16474 30920 16475 30921 16473 30921 16190 30921 16474 30922 16473 30922 16475 30922 16475 30923 16190 30923 16192 30923 16476 30924 16472 30924 16474 30924 16477 30925 16475 30925 16192 30925 16477 30926 16474 30926 16475 30926 16476 30927 16474 30927 16477 30927 16478 30928 16472 30928 16476 30928 16479 30929 16476 30929 16477 30929 16479 30930 16478 30930 16476 30930 16477 30931 16192 30931 16194 30931 16480 30932 16477 30932 16194 30932 16479 30933 16477 30933 16480 30933 16195 30934 16480 30934 16194 30934 16481 30935 16478 30935 16479 30935 16196 30936 16480 30936 16195 30936 16482 30937 16480 30937 16196 30937 16482 30938 16479 30938 16480 30938 16481 30939 16479 30939 16482 30939 16198 30940 16482 30940 16196 30940 16483 30941 16481 30941 16482 30941 16484 30942 16198 30942 16199 30942 16484 30943 16482 30943 16198 30943 16483 30944 16482 30944 16484 30944 16485 30945 16199 30945 16201 30945 16485 30946 16484 30946 16199 30946 16485 30947 16483 30947 16484 30947 16486 30948 16481 30948 16483 30948 16487 30949 16485 30949 16201 30949 16488 30950 16483 30950 16485 30950 16202 30951 16487 30951 16201 30951 16486 30952 16483 30952 16488 30952 16488 30953 16485 30953 16487 30953 16204 30954 16487 30954 16202 30954 16489 30955 16487 30955 16204 30955 16489 30956 16488 30956 16487 30956 16490 30957 16488 30957 16489 30957 16489 30958 16204 30958 16205 30958 16491 30959 16486 30959 16488 30959 16491 30960 16488 30960 16490 30960 16492 30961 16489 30961 16205 30961 16492 30962 16490 30962 16489 30962 16492 30963 16205 30963 16207 30963 16493 30964 16491 30964 16490 30964 16493 30965 16490 30965 16492 30965 16494 30966 16491 30966 16493 30966 16208 30967 16492 30967 16207 30967 16494 30968 16493 30968 16492 30968 16495 30969 16492 30969 16208 30969 16495 30970 16494 30970 16492 30970 16495 30971 16208 30971 16210 30971 16496 30972 16491 30972 16494 30972 16496 30973 16494 30973 16495 30973 16497 30974 16495 30974 16210 30974 16498 30975 16495 30975 16497 30975 16498 30976 16496 30976 16495 30976 16211 30977 16497 30977 16210 30977 16499 30978 16496 30978 16498 30978 16500 30979 16497 30979 16211 30979 16500 30980 16498 30980 16497 30980 16499 30981 16498 30981 16500 30981 16213 30982 16500 30982 16211 30982 16501 30983 16500 30983 16213 30983 16499 30984 16500 30984 16501 30984 16501 30985 16213 30985 16214 30985 16215 30986 16501 30986 16214 30986 16502 30987 16501 30987 16215 30987 16503 30988 16501 30988 16502 30988 16503 30989 16499 30989 16501 30989 16504 30990 16499 30990 16503 30990 16217 30991 16502 30991 16215 30991 16505 30992 16502 30992 16217 30992 16503 30993 16502 30993 16505 30993 16218 30994 16505 30994 16217 30994 16506 30995 16503 30995 16505 30995 16507 30996 16503 30996 16506 30996 16507 30997 16504 30997 16503 30997 16508 30998 16505 30998 16218 30998 16508 30999 16506 30999 16505 30999 16508 31000 16218 31000 16219 31000 16509 31001 16508 31001 16219 31001 16509 31002 16506 31002 16508 31002 16510 31003 16506 31003 16509 31003 16510 31004 16507 31004 16506 31004 16509 31005 16219 31005 16221 31005 16511 31006 16509 31006 16221 31006 16512 31007 16509 31007 16511 31007 16512 31008 16510 31008 16509 31008 16511 31009 16221 31009 16222 31009 16513 31010 16507 31010 16510 31010 16513 31011 16510 31011 16512 31011 16514 31012 16511 31012 16222 31012 16512 31013 16511 31013 16514 31013 16514 31014 16222 31014 16223 31014 16515 31015 16512 31015 16514 31015 16513 31016 16512 31016 16515 31016 16516 31017 16514 31017 16223 31017 16516 31018 16515 31018 16514 31018 16225 31019 16516 31019 16223 31019 16518 31020 16516 31020 16225 31020 16517 31021 16513 31021 16515 31021 16519 31022 16516 31022 16518 31022 16519 31023 16515 31023 16516 31023 16519 31024 16517 31024 16515 31024 16227 31025 16518 31025 16225 31025 16520 31026 16518 31026 16227 31026 16519 31027 16518 31027 16520 31027 16228 31028 16520 31028 16227 31028 16521 31029 16517 31029 16519 31029 16522 31030 16519 31030 16520 31030 16521 31031 16519 31031 16522 31031 16230 31032 16520 31032 16228 31032 16522 31033 16520 31033 16230 31033 16523 31034 16522 31034 16230 31034 16523 31035 16230 31035 16231 31035 16524 31036 16521 31036 16522 31036 16525 31037 16522 31037 16523 31037 16524 31038 16522 31038 16525 31038 16525 31039 16523 31039 16231 31039 16526 31040 16525 31040 16231 31040 16526 31041 16231 31041 16233 31041 16527 31042 16525 31042 16526 31042 16528 31043 16233 31043 16234 31043 16524 31044 16525 31044 16527 31044 16528 31045 16526 31045 16233 31045 16527 31046 16526 31046 16528 31046 16529 31047 16524 31047 16527 31047 16530 31048 16527 31048 16528 31048 16531 31049 16234 31049 16235 31049 16529 31050 16527 31050 16530 31050 16531 31051 16528 31051 16234 31051 16530 31052 16528 31052 16531 31052 16532 31053 16531 31053 16235 31053 16530 31054 16531 31054 16532 31054 16532 31055 16235 31055 16237 31055 16534 31056 16529 31056 16530 31056 16533 31057 16530 31057 16532 31057 16534 31058 16530 31058 16533 31058 16239 31059 16532 31059 16237 31059 16533 31060 16532 31060 16239 31060 16535 31061 16533 31061 16239 31061 16536 31062 16533 31062 16535 31062 16535 31063 16239 31063 16240 31063 16536 31064 16534 31064 16533 31064 16535 31065 16240 31065 16241 31065 16539 31066 16534 31066 16536 31066 16537 31067 16536 31067 16535 31067 16538 31068 16535 31068 16241 31068 16537 31069 16535 31069 16538 31069 16243 31070 16538 31070 16241 31070 16539 31071 16536 31071 16537 31071 16540 31072 16538 31072 16243 31072 16540 31073 16537 31073 16538 31073 16539 31074 16537 31074 16540 31074 16541 31075 16539 31075 16540 31075 16542 31076 16243 31076 16244 31076 16542 31077 16540 31077 16243 31077 16541 31078 16540 31078 16542 31078 16245 31079 16542 31079 16244 31079 16543 31080 16542 31080 16245 31080 16544 31081 16539 31081 16541 31081 16543 31082 16541 31082 16542 31082 16544 31083 16541 31083 16543 31083 16435 31084 16245 31084 16161 31084 16435 31085 16543 31085 16245 31085 16436 31086 16543 31086 16435 31086 16436 31087 16544 31087 16543 31087 15849 31088 16504 31088 15853 31088 15853 31089 16504 31089 16507 31089 15849 31090 16499 31090 16504 31090 15856 31091 15853 31091 16507 31091 15849 31092 16496 31092 16499 31092 15846 31093 16496 31093 15849 31093 15859 31094 15856 31094 16507 31094 15859 31095 16507 31095 16513 31095 15846 31096 16491 31096 16496 31096 15859 31097 16513 31097 16517 31097 15843 31098 16491 31098 15846 31098 15862 31099 15859 31099 16517 31099 15841 31100 16491 31100 15843 31100 15865 31101 16517 31101 16521 31101 15865 31102 15862 31102 16517 31102 15841 31103 16486 31103 16491 31103 15838 31104 16481 31104 16486 31104 15838 31105 16486 31105 15841 31105 16524 31106 15865 31106 16521 31106 15870 31107 15865 31107 16524 31107 15870 31108 16524 31108 16529 31108 15836 31109 16481 31109 15838 31109 15873 31110 15870 31110 16529 31110 15836 31111 16478 31111 16481 31111 15832 31112 16478 31112 15836 31112 15873 31113 16529 31113 16534 31113 16534 31114 15876 31114 15873 31114 16472 31115 16478 31115 15832 31115 15829 31116 16472 31116 15832 31116 16534 31117 15878 31117 15876 31117 16539 31118 15878 31118 16534 31118 15826 31119 16472 31119 15829 31119 16469 31120 16472 31120 15826 31120 15881 31121 15878 31121 16539 31121 16464 31122 16469 31122 15826 31122 15823 31123 16464 31123 15826 31123 16544 31124 15881 31124 16539 31124 16544 31125 15804 31125 15881 31125 16464 31126 15823 31126 15818 31126 16461 31127 16464 31127 15818 31127 16439 31128 15804 31128 16544 31128 16439 31129 15806 31129 15804 31129 16454 31130 16461 31130 15818 31130 16454 31131 15818 31131 15815 31131 16445 31132 15806 31132 16439 31132 16445 31133 15809 31133 15806 31133 16449 31134 15809 31134 16445 31134 16454 31135 15815 31135 15812 31135 16449 31136 15812 31136 15809 31136 16449 31137 16454 31137 15812 31137 16547 31138 16546 31138 16545 31138 16548 31139 16710 31139 16547 31139 16549 31140 16547 31140 16545 31140 16548 31141 16704 31141 16710 31141 16550 31142 16547 31142 16549 31142 16548 31143 16547 31143 16550 31143 16552 31144 16550 31144 16549 31144 16551 31145 16549 31145 16545 31145 16553 31146 16548 31146 16550 31146 16552 31147 16549 31147 16551 31147 16553 31148 16550 31148 16552 31148 16554 31149 16553 31149 16552 31149 16555 31150 16552 31150 16551 31150 16555 31151 16554 31151 16552 31151 16556 31152 16555 31152 16551 31152 16557 31153 16555 31153 16556 31153 16557 31154 16554 31154 16555 31154 16559 31155 16553 31155 16554 31155 16558 31156 16553 31156 16559 31156 16559 31157 16554 31157 16557 31157 16560 31158 16557 31158 16556 31158 16561 31159 16557 31159 16560 31159 16559 31160 16557 31160 16561 31160 16562 31161 16561 31161 16560 31161 16563 31162 16561 31162 16562 31162 16563 31163 16559 31163 16561 31163 16564 31164 16559 31164 16563 31164 16564 31165 16558 31165 16559 31165 16566 31166 16562 31166 16565 31166 16566 31167 16563 31167 16562 31167 16567 31168 16563 31168 16566 31168 16564 31169 16563 31169 16567 31169 16569 31170 16564 31170 16567 31170 16568 31171 16566 31171 16565 31171 16570 31172 16567 31172 16566 31172 16569 31173 16567 31173 16570 31173 16570 31174 16566 31174 16568 31174 16572 31175 16564 31175 16569 31175 16573 31176 16569 31176 16570 31176 16572 31177 16569 31177 16573 31177 16571 31178 16570 31178 16568 31178 16573 31179 16570 31179 16571 31179 16575 31180 16572 31180 16573 31180 16575 31181 16571 31181 16574 31181 16575 31182 16573 31182 16571 31182 16576 31183 16575 31183 16574 31183 16576 31184 16574 31184 16577 31184 16580 31185 16575 31185 16576 31185 16580 31186 16572 31186 16575 31186 16579 31187 16577 31187 16578 31187 16579 31188 16576 31188 16577 31188 16580 31189 16576 31189 16579 31189 16582 31190 16579 31190 16578 31190 16582 31191 16578 31191 16581 31191 16583 31192 16579 31192 16582 31192 16583 31193 16580 31193 16579 31193 16584 31194 16580 31194 16583 31194 16586 31195 16581 31195 16585 31195 16586 31196 16582 31196 16581 31196 16586 31197 16583 31197 16582 31197 16584 31198 16583 31198 16586 31198 16588 31199 16585 31199 16587 31199 16588 31200 16586 31200 16585 31200 16588 31201 16584 31201 16586 31201 16589 31202 16584 31202 16588 31202 16590 31203 16588 31203 16587 31203 16591 31204 16588 31204 16590 31204 16589 31205 16588 31205 16591 31205 16592 31206 16584 31206 16589 31206 16594 31207 16590 31207 16593 31207 16594 31208 16591 31208 16590 31208 16595 31209 16591 31209 16594 31209 16595 31210 16589 31210 16591 31210 16595 31211 16592 31211 16589 31211 16596 31212 16594 31212 16593 31212 16595 31213 16594 31213 16596 31213 16596 31214 16593 31214 16597 31214 16598 31215 16595 31215 16596 31215 16600 31216 16595 31216 16598 31216 16599 31217 16596 31217 16597 31217 16600 31218 16592 31218 16595 31218 16601 31219 16596 31219 16599 31219 16601 31220 16598 31220 16596 31220 16600 31221 16598 31221 16601 31221 16600 31222 16601 31222 16603 31222 16604 31223 16599 31223 16602 31223 16604 31224 16601 31224 16599 31224 16603 31225 16601 31225 16604 31225 16605 31226 16592 31226 16600 31226 16605 31227 16600 31227 16603 31227 16606 31228 16604 31228 16602 31228 16606 31229 16603 31229 16604 31229 16605 31230 16603 31230 16606 31230 16606 31231 16602 31231 16607 31231 16608 31232 16605 31232 16606 31232 16610 31233 16607 31233 16609 31233 16610 31234 16606 31234 16607 31234 16610 31235 16608 31235 16606 31235 16613 31236 16605 31236 16608 31236 16612 31237 16608 31237 16610 31237 16613 31238 16608 31238 16612 31238 16611 31239 16610 31239 16609 31239 16612 31240 16610 31240 16611 31240 16614 31241 16612 31241 16611 31241 16616 31242 16612 31242 16614 31242 16616 31243 16613 31243 16612 31243 16615 31244 16614 31244 16611 31244 16617 31245 16613 31245 16616 31245 16618 31246 16614 31246 16615 31246 16616 31247 16614 31247 16618 31247 16618 31248 16615 31248 16619 31248 16620 31249 16616 31249 16618 31249 16620 31250 16618 31250 16619 31250 16621 31251 16616 31251 16620 31251 16621 31252 16617 31252 16616 31252 16622 31253 16620 31253 16619 31253 16623 31254 16620 31254 16622 31254 16624 31255 16620 31255 16623 31255 16624 31256 16621 31256 16620 31256 16625 31257 16623 31257 16622 31257 16625 31258 16624 31258 16623 31258 16627 31259 16624 31259 16625 31259 16627 31260 16621 31260 16624 31260 16628 31261 16622 31261 16626 31261 16628 31262 16625 31262 16622 31262 16632 31263 16621 31263 16627 31263 16628 31264 16627 31264 16625 31264 16629 31265 16628 31265 16626 31265 16630 31266 16627 31266 16628 31266 16630 31267 16628 31267 16629 31267 16632 31268 16627 31268 16630 31268 16633 31269 16629 31269 16631 31269 16633 31270 16630 31270 16629 31270 16634 31271 16632 31271 16630 31271 16634 31272 16630 31272 16633 31272 16633 31273 16631 31273 16635 31273 16636 31274 16634 31274 16633 31274 16636 31275 16633 31275 16635 31275 16638 31276 16634 31276 16636 31276 16632 31277 16634 31277 16638 31277 16637 31278 16636 31278 16635 31278 16639 31279 16636 31279 16637 31279 16639 31280 16638 31280 16636 31280 16639 31281 16637 31281 16640 31281 16643 31282 16632 31282 16638 31282 16641 31283 16638 31283 16639 31283 16643 31284 16638 31284 16641 31284 16642 31285 16639 31285 16640 31285 16641 31286 16639 31286 16642 31286 16644 31287 16641 31287 16642 31287 16645 31288 16641 31288 16644 31288 16645 31289 16643 31289 16641 31289 16648 31290 16643 31290 16645 31290 16646 31291 16645 31291 16644 31291 16647 31292 16643 31292 16648 31292 16649 31293 16645 31293 16646 31293 16648 31294 16645 31294 16649 31294 16649 31295 16646 31295 16650 31295 16651 31296 16649 31296 16650 31296 16647 31297 16648 31297 16649 31297 16651 31298 16650 31298 16652 31298 16647 31299 16649 31299 16651 31299 16653 31300 16651 31300 16652 31300 16654 31301 16651 31301 16653 31301 16654 31302 16647 31302 16651 31302 16655 31303 16653 31303 16652 31303 16657 31304 16647 31304 16654 31304 16654 31305 16653 31305 16655 31305 16659 31306 16655 31306 16656 31306 16659 31307 16654 31307 16655 31307 16659 31308 16656 31308 16658 31308 16660 31309 16654 31309 16659 31309 16657 31310 16654 31310 16660 31310 16661 31311 16659 31311 16658 31311 16660 31312 16659 31312 16661 31312 16663 31313 16661 31313 16658 31313 16662 31314 16657 31314 16660 31314 16664 31315 16660 31315 16661 31315 16662 31316 16660 31316 16664 31316 16665 31317 16661 31317 16663 31317 16665 31318 16664 31318 16661 31318 16666 31319 16664 31319 16665 31319 16666 31320 16665 31320 16667 31320 16668 31321 16662 31321 16664 31321 16668 31322 16664 31322 16666 31322 16671 31323 16662 31323 16668 31323 16669 31324 16666 31324 16667 31324 16669 31325 16668 31325 16666 31325 16671 31326 16668 31326 16669 31326 16669 31327 16667 31327 16670 31327 16672 31328 16669 31328 16670 31328 16672 31329 16670 31329 16673 31329 16674 31330 16669 31330 16672 31330 16675 31331 16669 31331 16674 31331 16675 31332 16671 31332 16669 31332 16674 31333 16672 31333 16673 31333 16676 31334 16671 31334 16675 31334 16677 31335 16675 31335 16674 31335 16678 31336 16674 31336 16673 31336 16677 31337 16674 31337 16678 31337 16676 31338 16675 31338 16677 31338 16679 31339 16677 31339 16678 31339 16681 31340 16677 31340 16679 31340 16681 31341 16676 31341 16677 31341 16681 31342 16679 31342 16680 31342 16682 31343 16681 31343 16680 31343 16683 31344 16681 31344 16682 31344 16683 31345 16676 31345 16681 31345 16685 31346 16676 31346 16683 31346 16682 31347 16680 31347 16684 31347 16686 31348 16682 31348 16684 31348 16683 31349 16682 31349 16686 31349 16686 31350 16684 31350 16687 31350 16688 31351 16683 31351 16686 31351 16689 31352 16683 31352 16688 31352 16685 31353 16683 31353 16689 31353 16688 31354 16686 31354 16687 31354 16691 31355 16687 31355 16690 31355 16691 31356 16688 31356 16687 31356 16691 31357 16689 31357 16688 31357 16694 31358 16689 31358 16691 31358 16693 31359 16689 31359 16694 31359 16692 31360 16691 31360 16690 31360 16693 31361 16685 31361 16689 31361 16694 31362 16691 31362 16692 31362 16695 31363 16694 31363 16692 31363 16695 31364 16692 31364 16696 31364 16695 31365 16693 31365 16694 31365 16697 31366 16695 31366 16696 31366 16699 31367 16695 31367 16697 31367 16698 31368 16697 31368 16696 31368 16699 31369 16693 31369 16695 31369 16700 31370 16693 31370 16699 31370 16701 31371 16697 31371 16698 31371 16699 31372 16697 31372 16701 31372 16701 31373 16698 31373 16702 31373 16703 31374 16701 31374 16702 31374 16703 31375 16699 31375 16701 31375 16706 31376 16699 31376 16703 31376 16706 31377 16700 31377 16699 31377 16703 31378 16702 31378 16705 31378 16704 31379 16700 31379 16706 31379 16707 31380 16703 31380 16705 31380 16706 31381 16703 31381 16707 31381 16708 31382 16707 31382 16705 31382 16709 31383 16707 31383 16708 31383 16710 31384 16707 31384 16709 31384 16710 31385 16706 31385 16707 31385 16710 31386 16704 31386 16706 31386 16709 31387 16708 31387 16546 31387 16709 31388 16546 31388 16547 31388 16710 31389 16709 31389 16547 31389 16711 31390 16546 31390 16708 31390 16712 31391 16711 31391 16708 31391 16712 31392 16708 31392 16705 31392 16713 31393 16712 31393 16705 31393 16713 31394 16705 31394 16702 31394 16714 31395 16702 31395 16698 31395 16714 31396 16713 31396 16702 31396 16715 31397 16698 31397 16696 31397 16715 31398 16714 31398 16698 31398 16716 31399 16715 31399 16696 31399 16716 31400 16696 31400 16692 31400 16717 31401 16716 31401 16692 31401 16717 31402 16692 31402 16690 31402 16783 31403 16717 31403 16690 31403 16783 31404 16690 31404 16687 31404 16718 31405 16783 31405 16687 31405 16719 31406 16687 31406 16684 31406 16719 31407 16718 31407 16687 31407 16720 31408 16684 31408 16680 31408 16720 31409 16719 31409 16684 31409 16721 31410 16680 31410 16679 31410 16721 31411 16720 31411 16680 31411 16721 31412 16679 31412 16678 31412 16722 31413 16721 31413 16678 31413 16722 31414 16678 31414 16673 31414 16723 31415 16722 31415 16673 31415 16724 31416 16673 31416 16670 31416 16724 31417 16723 31417 16673 31417 16725 31418 16670 31418 16667 31418 16725 31419 16724 31419 16670 31419 16726 31420 16667 31420 16665 31420 16726 31421 16725 31421 16667 31421 16726 31422 16665 31422 16663 31422 16727 31423 16726 31423 16663 31423 16727 31424 16663 31424 16658 31424 16728 31425 16727 31425 16658 31425 16728 31426 16658 31426 16656 31426 16729 31427 16728 31427 16656 31427 16730 31428 16656 31428 16655 31428 16730 31429 16729 31429 16656 31429 16730 31430 16655 31430 16652 31430 16731 31431 16652 31431 16650 31431 16731 31432 16730 31432 16652 31432 16732 31433 16650 31433 16646 31433 16732 31434 16731 31434 16650 31434 16733 31435 16646 31435 16644 31435 16733 31436 16732 31436 16646 31436 16734 31437 16644 31437 16642 31437 16734 31438 16733 31438 16644 31438 16735 31439 16734 31439 16642 31439 16735 31440 16642 31440 16640 31440 16735 31441 16640 31441 16637 31441 16736 31442 16735 31442 16637 31442 16736 31443 16637 31443 16635 31443 16737 31444 16635 31444 16631 31444 16737 31445 16736 31445 16635 31445 16738 31446 16631 31446 16629 31446 16738 31447 16737 31447 16631 31447 16739 31448 16738 31448 16629 31448 16739 31449 16629 31449 16626 31449 16740 31450 16739 31450 16626 31450 16740 31451 16626 31451 16622 31451 16741 31452 16740 31452 16622 31452 16741 31453 16622 31453 16619 31453 16742 31454 16741 31454 16619 31454 16742 31455 16619 31455 16615 31455 16743 31456 16742 31456 16615 31456 16743 31457 16615 31457 16611 31457 16744 31458 16743 31458 16611 31458 16745 31459 16744 31459 16611 31459 16745 31460 16611 31460 16609 31460 16746 31461 16745 31461 16609 31461 16746 31462 16609 31462 16607 31462 16746 31463 16607 31463 16602 31463 16747 31464 16746 31464 16602 31464 16747 31465 16602 31465 16599 31465 16748 31466 16747 31466 16599 31466 16748 31467 16599 31467 16597 31467 16749 31468 16748 31468 16597 31468 16749 31469 16597 31469 16593 31469 16750 31470 16749 31470 16593 31470 16750 31471 16593 31471 16590 31471 16751 31472 16750 31472 16590 31472 16751 31473 16590 31473 16587 31473 16752 31474 16751 31474 16587 31474 16752 31475 16587 31475 16585 31475 16753 31476 16752 31476 16585 31476 16753 31477 16585 31477 16581 31477 16754 31478 16753 31478 16581 31478 16754 31479 16581 31479 16578 31479 16755 31480 16754 31480 16578 31480 16755 31481 16578 31481 16577 31481 16756 31482 16755 31482 16577 31482 16756 31483 16577 31483 16574 31483 16757 31484 16756 31484 16574 31484 16757 31485 16574 31485 16571 31485 16758 31486 16757 31486 16571 31486 16759 31487 16571 31487 16568 31487 16759 31488 16758 31488 16571 31488 16760 31489 16759 31489 16568 31489 16760 31490 16568 31490 16565 31490 16761 31491 16760 31491 16565 31491 16761 31492 16565 31492 16562 31492 16762 31493 16761 31493 16562 31493 16762 31494 16562 31494 16560 31494 16763 31495 16762 31495 16560 31495 16763 31496 16560 31496 16556 31496 16764 31497 16763 31497 16556 31497 16764 31498 16556 31498 16551 31498 16765 31499 16764 31499 16551 31499 16765 31500 16551 31500 16545 31500 16766 31501 16765 31501 16545 31501 16711 31502 16545 31502 16546 31502 16711 31503 16766 31503 16545 31503 16316 31504 16564 31504 16572 31504 16319 31505 16564 31505 16316 31505 16314 31506 16316 31506 16572 31506 16319 31507 16558 31507 16564 31507 16312 31508 16314 31508 16572 31508 16323 31509 16558 31509 16319 31509 16312 31510 16572 31510 16580 31510 16323 31511 16553 31511 16558 31511 16310 31512 16312 31512 16580 31512 16326 31513 16548 31513 16553 31513 16326 31514 16553 31514 16323 31514 16310 31515 16580 31515 16584 31515 16307 31516 16310 31516 16584 31516 16326 31517 16704 31517 16548 31517 16247 31518 16704 31518 16326 31518 16307 31519 16584 31519 16592 31519 16251 31520 16704 31520 16247 31520 16304 31521 16307 31521 16592 31521 16301 31522 16304 31522 16592 31522 16254 31523 16700 31523 16704 31523 16254 31524 16704 31524 16251 31524 16254 31525 16693 31525 16700 31525 16605 31526 16301 31526 16592 31526 16299 31527 16301 31527 16605 31527 16257 31528 16693 31528 16254 31528 16613 31529 16299 31529 16605 31529 16685 31530 16693 31530 16257 31530 16613 31531 16295 31531 16299 31531 16260 31532 16685 31532 16257 31532 16617 31533 16295 31533 16613 31533 16262 31534 16685 31534 16260 31534 16676 31535 16685 31535 16262 31535 16617 31536 16292 31536 16295 31536 16621 31537 16292 31537 16617 31537 16264 31538 16676 31538 16262 31538 16621 31539 16288 31539 16292 31539 16671 31540 16676 31540 16264 31540 16267 31541 16671 31541 16264 31541 16632 31542 16288 31542 16621 31542 16632 31543 16285 31543 16288 31543 16662 31544 16267 31544 16269 31544 16662 31545 16671 31545 16267 31545 16632 31546 16283 31546 16285 31546 16662 31547 16269 31547 16272 31547 16643 31548 16283 31548 16632 31548 16657 31549 16662 31549 16272 31549 16643 31550 16280 31550 16283 31550 16657 31551 16272 31551 16274 31551 16643 31552 16278 31552 16280 31552 16647 31553 16278 31553 16643 31553 16647 31554 16274 31554 16278 31554 16647 31555 16657 31555 16274 31555 16767 31556 16768 31556 16711 31556 16770 31557 16878 31557 16767 31557 16769 31558 16711 31558 16712 31558 16769 31559 16767 31559 16711 31559 16770 31560 16767 31560 16769 31560 16773 31561 16878 31561 16770 31561 16771 31562 16712 31562 16713 31562 16771 31563 16769 31563 16712 31563 16772 31564 16769 31564 16771 31564 16772 31565 16770 31565 16769 31565 16773 31566 16770 31566 16772 31566 16774 31567 16771 31567 16713 31567 16774 31568 16772 31568 16771 31568 16775 31569 16772 31569 16774 31569 16773 31570 16772 31570 16775 31570 16714 31571 16774 31571 16713 31571 16776 31572 16773 31572 16775 31572 16777 31573 16714 31573 16715 31573 16777 31574 16774 31574 16714 31574 16778 31575 16774 31575 16777 31575 16778 31576 16775 31576 16774 31576 16778 31577 16776 31577 16775 31577 16716 31578 16777 31578 16715 31578 16779 31579 16777 31579 16716 31579 16779 31580 16778 31580 16777 31580 16780 31581 16778 31581 16779 31581 16776 31582 16778 31582 16780 31582 16781 31583 16779 31583 16716 31583 16781 31584 16716 31584 16717 31584 16780 31585 16779 31585 16781 31585 16782 31586 16780 31586 16781 31586 16783 31587 16781 31587 16717 31587 16782 31588 16781 31588 16783 31588 16784 31589 16776 31589 16780 31589 16784 31590 16780 31590 16782 31590 16785 31591 16782 31591 16783 31591 16786 31592 16782 31592 16785 31592 16786 31593 16784 31593 16782 31593 16785 31594 16783 31594 16718 31594 16787 31595 16785 31595 16718 31595 16786 31596 16785 31596 16787 31596 16787 31597 16718 31597 16719 31597 16788 31598 16786 31598 16787 31598 16788 31599 16784 31599 16786 31599 16788 31600 16787 31600 16719 31600 16789 31601 16719 31601 16720 31601 16790 31602 16784 31602 16788 31602 16789 31603 16788 31603 16719 31603 16721 31604 16789 31604 16720 31604 16791 31605 16788 31605 16789 31605 16791 31606 16790 31606 16788 31606 16722 31607 16789 31607 16721 31607 16791 31608 16789 31608 16722 31608 16790 31609 16791 31609 16792 31609 16793 31610 16722 31610 16723 31610 16793 31611 16791 31611 16722 31611 16792 31612 16791 31612 16793 31612 16794 31613 16793 31613 16723 31613 16795 31614 16792 31614 16793 31614 16724 31615 16794 31615 16723 31615 16795 31616 16793 31616 16794 31616 16796 31617 16795 31617 16794 31617 16725 31618 16794 31618 16724 31618 16797 31619 16792 31619 16795 31619 16796 31620 16794 31620 16725 31620 16797 31621 16795 31621 16796 31621 16798 31622 16796 31622 16725 31622 16799 31623 16796 31623 16798 31623 16726 31624 16798 31624 16725 31624 16797 31625 16796 31625 16799 31625 16800 31626 16798 31626 16726 31626 16799 31627 16798 31627 16800 31627 16800 31628 16726 31628 16727 31628 16801 31629 16799 31629 16800 31629 16801 31630 16797 31630 16799 31630 16802 31631 16800 31631 16727 31631 16801 31632 16800 31632 16802 31632 16803 31633 16801 31633 16802 31633 16804 31634 16801 31634 16803 31634 16805 31635 16727 31635 16728 31635 16805 31636 16802 31636 16727 31636 16804 31637 16797 31637 16801 31637 16803 31638 16802 31638 16805 31638 16729 31639 16805 31639 16728 31639 16806 31640 16803 31640 16805 31640 16806 31641 16804 31641 16803 31641 16806 31642 16805 31642 16729 31642 16807 31643 16729 31643 16730 31643 16807 31644 16806 31644 16729 31644 16808 31645 16804 31645 16806 31645 16808 31646 16806 31646 16807 31646 16809 31647 16730 31647 16731 31647 16809 31648 16807 31648 16730 31648 16809 31649 16808 31649 16807 31649 16812 31650 16809 31650 16811 31650 16812 31651 16808 31651 16809 31651 16732 31652 16809 31652 16731 31652 16811 31653 16809 31653 16732 31653 16810 31654 16808 31654 16812 31654 16813 31655 16732 31655 16733 31655 16813 31656 16811 31656 16732 31656 16814 31657 16811 31657 16813 31657 16814 31658 16812 31658 16811 31658 16814 31659 16810 31659 16812 31659 16734 31660 16813 31660 16733 31660 16815 31661 16813 31661 16734 31661 16814 31662 16813 31662 16815 31662 16816 31663 16810 31663 16814 31663 16817 31664 16814 31664 16815 31664 16816 31665 16814 31665 16817 31665 16818 31666 16734 31666 16735 31666 16818 31667 16815 31667 16734 31667 16817 31668 16815 31668 16818 31668 16819 31669 16818 31669 16735 31669 16820 31670 16818 31670 16819 31670 16820 31671 16817 31671 16818 31671 16816 31672 16817 31672 16820 31672 16736 31673 16819 31673 16735 31673 16821 31674 16816 31674 16820 31674 16822 31675 16816 31675 16821 31675 16823 31676 16819 31676 16736 31676 16823 31677 16820 31677 16819 31677 16821 31678 16820 31678 16823 31678 16737 31679 16823 31679 16736 31679 16824 31680 16823 31680 16737 31680 16824 31681 16821 31681 16823 31681 16822 31682 16821 31682 16824 31682 16825 31683 16737 31683 16738 31683 16825 31684 16824 31684 16737 31684 16826 31685 16822 31685 16824 31685 16827 31686 16824 31686 16825 31686 16826 31687 16824 31687 16827 31687 16739 31688 16825 31688 16738 31688 16828 31689 16825 31689 16739 31689 16828 31690 16827 31690 16825 31690 16740 31691 16828 31691 16739 31691 16831 31692 16827 31692 16829 31692 16831 31693 16826 31693 16827 31693 16829 31694 16828 31694 16740 31694 16829 31695 16827 31695 16828 31695 16830 31696 16829 31696 16740 31696 16830 31697 16740 31697 16741 31697 16831 31698 16829 31698 16830 31698 16832 31699 16830 31699 16741 31699 16832 31700 16831 31700 16830 31700 16832 31701 16741 31701 16742 31701 16833 31702 16831 31702 16832 31702 16834 31703 16832 31703 16742 31703 16835 31704 16832 31704 16834 31704 16833 31705 16832 31705 16835 31705 16743 31706 16834 31706 16742 31706 16836 31707 16834 31707 16743 31707 16836 31708 16835 31708 16834 31708 16836 31709 16743 31709 16744 31709 16837 31710 16835 31710 16836 31710 16837 31711 16833 31711 16835 31711 16838 31712 16836 31712 16744 31712 16838 31713 16837 31713 16836 31713 16838 31714 16744 31714 16745 31714 16746 31715 16838 31715 16745 31715 16840 31716 16837 31716 16838 31716 16839 31717 16838 31717 16746 31717 16840 31718 16838 31718 16839 31718 16841 31719 16746 31719 16747 31719 16841 31720 16839 31720 16746 31720 16842 31721 16839 31721 16841 31721 16842 31722 16840 31722 16839 31722 16844 31723 16841 31723 16747 31723 16843 31724 16840 31724 16842 31724 16844 31725 16842 31725 16841 31725 16845 31726 16842 31726 16844 31726 16843 31727 16842 31727 16845 31727 16748 31728 16844 31728 16747 31728 16846 31729 16748 31729 16749 31729 16846 31730 16844 31730 16748 31730 16845 31731 16844 31731 16846 31731 16847 31732 16843 31732 16845 31732 16848 31733 16846 31733 16749 31733 16849 31734 16846 31734 16848 31734 16849 31735 16845 31735 16846 31735 16847 31736 16845 31736 16849 31736 16848 31737 16749 31737 16750 31737 16851 31738 16848 31738 16750 31738 16851 31739 16849 31739 16848 31739 16852 31740 16849 31740 16851 31740 16852 31741 16847 31741 16849 31741 16851 31742 16750 31742 16751 31742 16850 31743 16847 31743 16852 31743 16853 31744 16852 31744 16851 31744 16853 31745 16850 31745 16852 31745 16752 31746 16851 31746 16751 31746 16853 31747 16851 31747 16752 31747 16854 31748 16850 31748 16853 31748 16855 31749 16850 31749 16854 31749 16753 31750 16853 31750 16752 31750 16856 31751 16853 31751 16753 31751 16856 31752 16854 31752 16853 31752 16855 31753 16854 31753 16856 31753 16857 31754 16753 31754 16754 31754 16857 31755 16856 31755 16753 31755 16858 31756 16856 31756 16857 31756 16855 31757 16856 31757 16858 31757 16857 31758 16754 31758 16755 31758 16859 31759 16855 31759 16858 31759 16858 31760 16857 31760 16755 31760 16860 31761 16755 31761 16756 31761 16860 31762 16858 31762 16755 31762 16861 31763 16858 31763 16860 31763 16861 31764 16859 31764 16858 31764 16757 31765 16860 31765 16756 31765 16862 31766 16860 31766 16757 31766 16862 31767 16861 31767 16860 31767 16863 31768 16859 31768 16861 31768 16864 31769 16861 31769 16862 31769 16863 31770 16861 31770 16864 31770 16758 31771 16862 31771 16757 31771 16864 31772 16862 31772 16758 31772 16864 31773 16758 31773 16759 31773 16865 31774 16864 31774 16759 31774 16866 31775 16864 31775 16865 31775 16866 31776 16863 31776 16864 31776 16865 31777 16759 31777 16760 31777 16867 31778 16760 31778 16761 31778 16867 31779 16865 31779 16760 31779 16868 31780 16863 31780 16866 31780 16867 31781 16866 31781 16865 31781 16869 31782 16866 31782 16867 31782 16762 31783 16867 31783 16761 31783 16868 31784 16866 31784 16869 31784 16870 31785 16867 31785 16762 31785 16869 31786 16867 31786 16870 31786 16871 31787 16869 31787 16870 31787 16868 31788 16869 31788 16871 31788 16763 31789 16870 31789 16762 31789 16872 31790 16870 31790 16763 31790 16872 31791 16871 31791 16870 31791 16873 31792 16868 31792 16871 31792 16874 31793 16871 31793 16872 31793 16873 31794 16871 31794 16874 31794 16872 31795 16763 31795 16764 31795 16875 31796 16872 31796 16764 31796 16875 31797 16874 31797 16872 31797 16875 31798 16764 31798 16765 31798 16876 31799 16874 31799 16875 31799 16876 31800 16873 31800 16874 31800 16877 31801 16875 31801 16765 31801 16876 31802 16875 31802 16877 31802 16879 31803 16873 31803 16876 31803 16879 31804 16876 31804 16877 31804 16766 31805 16877 31805 16765 31805 16878 31806 16873 31806 16879 31806 16768 31807 16766 31807 16711 31807 16768 31808 16877 31808 16766 31808 16768 31809 16879 31809 16877 31809 16879 31810 16768 31810 16767 31810 16879 31811 16767 31811 16878 31811 16212 31812 16837 31812 16216 31812 16216 31813 16837 31813 16840 31813 16216 31814 16840 31814 16843 31814 16209 31815 16837 31815 16212 31815 16220 31816 16216 31816 16843 31816 16209 31817 16833 31817 16837 31817 16220 31818 16843 31818 16847 31818 16206 31819 16833 31819 16209 31819 16224 31820 16847 31820 16850 31820 16224 31821 16220 31821 16847 31821 16206 31822 16831 31822 16833 31822 16203 31823 16831 31823 16206 31823 16226 31824 16224 31824 16850 31824 16226 31825 16850 31825 16855 31825 16203 31826 16826 31826 16831 31826 16200 31827 16826 31827 16203 31827 16229 31828 16226 31828 16855 31828 16200 31829 16822 31829 16826 31829 16229 31830 16855 31830 16859 31830 16197 31831 16822 31831 16200 31831 16197 31832 16816 31832 16822 31832 16232 31833 16859 31833 16863 31833 16232 31834 16229 31834 16859 31834 16193 31835 16816 31835 16197 31835 16193 31836 16810 31836 16816 31836 16236 31837 16232 31837 16863 31837 16191 31838 16810 31838 16193 31838 16868 31839 16238 31839 16236 31839 16868 31840 16236 31840 16863 31840 16808 31841 16810 31841 16191 31841 16188 31842 16808 31842 16191 31842 16804 31843 16808 31843 16188 31843 16873 31844 16238 31844 16868 31844 16873 31845 16242 31845 16238 31845 16186 31846 16804 31846 16188 31846 16797 31847 16804 31847 16186 31847 16878 31848 16242 31848 16873 31848 16183 31849 16797 31849 16186 31849 16878 31850 16246 31850 16242 31850 16797 31851 16183 31851 16180 31851 16773 31852 16246 31852 16878 31852 16792 31853 16797 31853 16180 31853 16773 31854 16163 31854 16246 31854 16792 31855 16180 31855 16177 31855 16773 31856 16165 31856 16163 31856 16790 31857 16792 31857 16177 31857 16776 31858 16165 31858 16773 31858 16790 31859 16177 31859 16175 31859 16776 31860 16169 31860 16165 31860 16784 31861 16790 31861 16175 31861 16784 31862 16175 31862 16172 31862 16784 31863 16169 31863 16776 31863 16784 31864 16172 31864 16169 31864

+
+ + + +

16881 31865 16880 31865 16882 31865 16885 31866 16881 31866 16882 31866 16885 31867 16883 31867 16881 31867 16884 31868 16883 31868 16885 31868 16885 31869 16882 31869 16886 31869 16888 31870 16886 31870 16887 31870 16888 31871 16885 31871 16886 31871 16884 31872 16885 31872 16888 31872 16889 31873 16888 31873 16887 31873 16891 31874 16884 31874 16888 31874 16890 31875 16889 31875 16887 31875 16889 31876 16891 31876 16888 31876 16892 31877 16889 31877 16890 31877 16894 31878 16889 31878 16892 31878 16893 31879 16889 31879 16894 31879 16895 31880 16891 31880 16889 31880 16895 31881 16889 31881 16893 31881 16895 31882 16893 31882 16894 31882 16897 31883 16894 31883 16896 31883 16897 31884 16895 31884 16894 31884 16897 31885 16896 31885 16898 31885 16899 31886 16895 31886 16897 31886 16900 31887 16897 31887 16898 31887 16899 31888 16897 31888 16900 31888 16903 31889 16895 31889 16899 31889 16901 31890 16899 31890 16900 31890 16903 31891 16899 31891 16901 31891 16901 31892 16900 31892 16902 31892 16904 31893 16901 31893 16902 31893 16905 31894 16901 31894 16904 31894 16903 31895 16901 31895 16905 31895 16907 31896 16904 31896 16906 31896 16907 31897 16905 31897 16904 31897 16908 31898 16907 31898 16906 31898 16909 31899 16907 31899 16908 31899 16910 31900 16907 31900 16909 31900 16910 31901 16905 31901 16907 31901 16911 31902 16909 31902 16908 31902 16910 31903 16909 31903 16911 31903 16912 31904 16905 31904 16910 31904 16912 31905 16910 31905 16911 31905 16914 31906 16911 31906 16913 31906 16912 31907 16911 31907 16914 31907 16915 31908 16912 31908 16914 31908 16917 31909 16912 31909 16915 31909 16915 31910 16914 31910 16916 31910 16918 31911 16915 31911 16916 31911 16917 31912 16915 31912 16918 31912 16920 31913 16917 31913 16918 31913 16919 31914 16918 31914 16916 31914 16921 31915 16918 31915 16919 31915 16920 31916 16918 31916 16921 31916 16921 31917 16919 31917 16922 31917 16923 31918 16921 31918 16922 31918 16924 31919 16920 31919 16921 31919 16925 31920 16921 31920 16923 31920 16925 31921 16924 31921 16921 31921 16926 31922 16925 31922 16923 31922 16928 31923 16926 31923 16927 31923 16928 31924 16925 31924 16926 31924 16929 31925 16925 31925 16928 31925 16929 31926 16924 31926 16925 31926 16930 31927 16928 31927 16927 31927 16931 31928 16924 31928 16929 31928 16932 31929 16928 31929 16930 31929 16929 31930 16928 31930 16932 31930 16931 31931 16929 31931 16932 31931 16932 31932 16930 31932 16933 31932 16934 31933 16932 31933 16933 31933 16931 31934 16932 31934 16934 31934 16935 31935 16934 31935 16933 31935 16931 31936 16934 31936 16936 31936 16938 31937 16935 31937 16937 31937 16938 31938 16934 31938 16935 31938 16936 31939 16934 31939 16938 31939 16939 31940 16938 31940 16937 31940 16940 31941 16939 31941 16937 31941 16942 31942 16936 31942 16938 31942 16939 31943 16940 31943 16941 31943 16942 31944 16938 31944 16939 31944 16943 31945 16939 31945 16941 31945 16942 31946 16939 31946 16943 31946 16943 31947 16941 31947 16944 31947 16945 31948 16943 31948 16944 31948 16946 31949 16943 31949 16945 31949 16946 31950 16942 31950 16943 31950 16945 31951 16944 31951 16947 31951 16948 31952 16945 31952 16947 31952 16942 31953 16946 31953 16951 31953 16948 31954 16946 31954 16945 31954 16951 31955 16946 31955 16948 31955 16948 31956 16947 31956 16949 31956 16950 31957 16948 31957 16949 31957 16952 31958 16948 31958 16950 31958 16951 31959 16948 31959 16952 31959 16952 31960 16950 31960 16953 31960 16954 31961 16951 31961 16952 31961 16955 31962 16952 31962 16953 31962 16956 31963 16952 31963 16955 31963 16954 31964 16952 31964 16956 31964 16957 31965 16956 31965 16955 31965 16954 31966 16956 31966 16957 31966 16958 31967 16957 31967 16955 31967 16959 31968 16957 31968 16958 31968 16959 31969 16954 31969 16957 31969 16960 31970 16954 31970 16959 31970 16959 31971 16958 31971 16961 31971 16963 31972 16961 31972 16962 31972 16963 31973 16959 31973 16961 31973 16960 31974 16959 31974 16963 31974 16965 31975 16960 31975 16963 31975 16964 31976 16963 31976 16962 31976 16965 31977 16963 31977 16964 31977 16965 31978 16964 31978 16966 31978 16968 31979 16965 31979 16966 31979 16968 31980 16966 31980 16967 31980 16969 31981 16968 31981 16967 31981 16970 31982 16965 31982 16968 31982 16970 31983 16968 31983 16971 31983 16971 31984 16968 31984 16969 31984 16971 31985 16969 31985 16972 31985 16970 31986 16971 31986 16973 31986 16973 31987 16971 31987 16972 31987 16883 31988 16970 31988 16973 31988 16973 31989 16972 31989 16974 31989 16974 31990 16880 31990 16881 31990 16973 31991 16974 31991 16881 31991 16973 31992 16881 31992 16883 31992 16930 31993 16927 31993 16975 31993 16975 31994 16927 31994 16976 31994 16976 31995 16926 31995 16977 31995 16927 31996 16926 31996 16976 31996 16977 31997 16923 31997 16978 31997 16926 31998 16923 31998 16977 31998 16923 31999 16922 31999 16978 31999 16978 32000 16922 32000 16979 32000 16922 32001 16919 32001 16979 32001 16979 32002 16919 32002 16980 32002 16919 32003 16916 32003 16980 32003 16980 32004 16916 32004 16981 32004 16916 32005 16914 32005 16981 32005 16981 32006 16913 32006 16982 32006 16914 32007 16913 32007 16981 32007 16982 32008 16913 32008 16983 32008 16913 32009 16911 32009 16983 32009 16911 32010 16908 32010 16983 32010 16983 32011 16908 32011 17026 32011 17026 32012 16908 32012 16984 32012 16908 32013 16906 32013 16984 32013 16984 32014 16904 32014 16985 32014 16906 32015 16904 32015 16984 32015 16904 32016 16902 32016 16985 32016 16985 32017 16902 32017 16986 32017 16902 32018 16900 32018 16986 32018 16986 32019 16900 32019 16987 32019 16900 32020 16898 32020 16987 32020 16987 32021 16898 32021 16988 32021 16898 32022 16896 32022 16988 32022 16896 32023 16894 32023 16988 32023 16988 32024 16894 32024 16989 32024 16894 32025 16892 32025 16989 32025 16989 32026 16892 32026 16990 32026 16892 32027 16890 32027 16990 32027 16990 32028 16890 32028 16991 32028 16890 32029 16887 32029 16991 32029 16991 32030 16887 32030 16992 32030 16887 32031 16886 32031 16992 32031 16992 32032 16886 32032 16993 32032 16886 32033 16882 32033 16993 32033 16993 32034 16880 32034 16994 32034 16882 32035 16880 32035 16993 32035 16880 32036 16974 32036 16994 32036 16994 32037 16974 32037 16995 32037 16974 32038 16972 32038 16995 32038 16995 32039 16972 32039 16996 32039 16996 32040 16972 32040 16997 32040 16972 32041 16969 32041 16997 32041 16969 32042 16967 32042 16997 32042 16997 32043 16967 32043 16998 32043 16967 32044 16966 32044 16998 32044 16966 32045 16964 32045 16998 32045 16998 32046 16964 32046 16999 32046 16964 32047 16962 32047 16999 32047 16999 32048 16962 32048 17000 32048 17000 32049 16961 32049 17001 32049 16962 32050 16961 32050 17000 32050 17001 32051 16958 32051 17002 32051 16961 32052 16958 32052 17001 32052 17002 32053 16958 32053 17003 32053 16958 32054 16955 32054 17003 32054 17003 32055 16955 32055 17004 32055 16955 32056 16953 32056 17004 32056 17004 32057 16953 32057 17005 32057 16953 32058 16950 32058 17005 32058 17005 32059 16950 32059 17006 32059 16950 32060 16949 32060 17006 32060 17006 32061 16947 32061 17007 32061 16949 32062 16947 32062 17006 32062 17007 32063 16944 32063 17008 32063 16947 32064 16944 32064 17007 32064 17008 32065 16944 32065 17009 32065 16944 32066 16941 32066 17009 32066 17009 32067 16941 32067 17010 32067 17010 32068 16940 32068 17011 32068 16941 32069 16940 32069 17010 32069 16940 32070 16937 32070 17011 32070 17011 32071 16937 32071 17012 32071 17012 32072 16937 32072 17013 32072 16937 32073 16935 32073 17013 32073 16935 32074 16933 32074 17013 32074 17013 32075 16933 32075 17014 32075 16933 32076 16930 32076 17014 32076 17014 32077 16930 32077 16975 32077 16891 32078 16895 32078 17504 32078 16895 32079 17500 32079 17504 32079 16903 32080 17500 32080 16895 32080 16903 32081 17490 32081 17500 32081 16884 32082 17504 32082 17511 32082 16884 32083 16891 32083 17504 32083 16884 32084 17511 32084 17516 32084 16884 32085 17516 32085 17526 32085 16903 32086 17640 32086 17490 32086 16883 32087 16884 32087 17526 32087 16905 32088 17640 32088 16903 32088 16970 32089 16883 32089 17526 32089 16912 32090 17640 32090 16905 32090 16912 32091 17629 32091 17640 32091 16970 32092 17526 32092 17534 32092 16965 32093 16970 32093 17534 32093 16912 32094 17619 32094 17629 32094 16965 32095 17534 32095 17539 32095 16917 32096 17619 32096 16912 32096 17619 32097 16917 32097 16920 32097 17547 32098 16965 32098 17539 32098 17547 32099 16960 32099 16965 32099 17619 32100 16920 32100 16924 32100 17552 32101 16960 32101 17547 32101 17614 32102 17619 32102 16924 32102 17552 32103 16954 32103 16960 32103 17605 32104 17614 32104 16924 32104 17559 32105 16954 32105 17552 32105 17605 32106 16924 32106 16931 32106 17559 32107 16951 32107 16954 32107 17597 32108 17605 32108 16931 32108 17568 32109 16951 32109 17559 32109 17589 32110 17597 32110 16931 32110 17568 32111 16942 32111 16951 32111 17589 32112 16931 32112 16936 32112 17574 32113 16942 32113 17568 32113 17578 32114 17589 32114 16936 32114 17578 32115 16936 32115 16942 32115 17578 32116 16942 32116 17574 32116 17015 32117 17072 32117 16975 32117 17016 32118 17072 32118 17015 32118 17015 32119 16975 32119 16976 32119 17017 32120 17016 32120 17015 32120 16977 32121 17015 32121 16976 32121 17018 32122 17016 32122 17017 32122 17017 32123 17015 32123 16977 32123 17019 32124 17017 32124 16977 32124 17018 32125 17017 32125 17019 32125 17019 32126 16977 32126 16978 32126 17018 32127 17019 32127 17020 32127 16979 32128 17019 32128 16978 32128 16979 32129 17020 32129 17019 32129 17022 32130 17018 32130 17020 32130 17021 32131 16979 32131 16980 32131 17022 32132 17020 32132 16979 32132 17022 32133 16979 32133 17021 32133 17021 32134 16980 32134 16981 32134 17023 32135 17018 32135 17022 32135 17023 32136 17022 32136 17021 32136 17024 32137 17021 32137 16981 32137 17023 32138 17021 32138 17024 32138 16982 32139 17024 32139 16981 32139 16983 32140 17024 32140 16982 32140 17025 32141 17024 32141 16983 32141 17025 32142 17023 32142 17024 32142 17027 32143 16983 32143 17026 32143 17027 32144 17025 32144 16983 32144 17028 32145 17027 32145 17026 32145 17028 32146 17026 32146 16984 32146 17029 32147 17028 32147 16984 32147 17029 32148 17027 32148 17028 32148 16985 32149 17029 32149 16984 32149 17030 32150 17029 32150 16985 32150 17030 32151 16985 32151 16986 32151 17031 32152 17030 32152 16986 32152 17032 32153 17030 32153 17031 32153 17032 32154 17029 32154 17030 32154 16987 32155 17031 32155 16986 32155 17033 32156 17031 32156 16987 32156 17033 32157 17032 32157 17031 32157 17034 32158 16987 32158 16988 32158 17033 32159 16987 32159 17034 32159 17035 32160 17032 32160 17033 32160 17036 32161 17033 32161 17034 32161 17034 32162 16988 32162 16989 32162 17035 32163 17033 32163 17036 32163 17036 32164 17034 32164 16989 32164 17037 32165 17035 32165 17036 32165 17038 32166 16989 32166 16990 32166 17038 32167 17036 32167 16989 32167 17038 32168 17037 32168 17036 32168 16991 32169 17038 32169 16990 32169 17039 32170 17038 32170 16991 32170 17037 32171 17038 32171 17039 32171 16992 32172 17039 32172 16991 32172 17040 32173 17037 32173 17039 32173 17041 32174 17039 32174 16992 32174 17041 32175 16992 32175 16993 32175 17040 32176 17039 32176 17041 32176 17042 32177 17041 32177 16993 32177 17042 32178 17040 32178 17041 32178 16994 32179 17042 32179 16993 32179 17043 32180 17040 32180 17042 32180 17043 32181 17042 32181 17044 32181 17044 32182 17042 32182 16994 32182 17044 32183 16994 32183 16995 32183 17045 32184 17044 32184 16995 32184 17043 32185 17044 32185 17045 32185 17045 32186 16995 32186 16996 32186 17046 32187 16996 32187 16997 32187 17047 32188 17043 32188 17045 32188 17046 32189 17045 32189 16996 32189 17047 32190 17045 32190 17046 32190 17046 32191 16997 32191 16998 32191 17047 32192 17046 32192 17049 32192 17049 32193 17046 32193 16998 32193 17048 32194 17047 32194 17049 32194 17050 32195 17049 32195 16998 32195 17048 32196 17049 32196 17050 32196 17050 32197 16998 32197 16999 32197 17051 32198 17048 32198 17050 32198 17000 32199 17050 32199 16999 32199 17051 32200 17050 32200 17000 32200 17052 32201 17000 32201 17001 32201 17052 32202 17051 32202 17000 32202 17053 32203 17052 32203 17001 32203 17054 32204 17051 32204 17052 32204 17054 32205 17052 32205 17053 32205 17002 32206 17053 32206 17001 32206 17003 32207 17053 32207 17002 32207 17055 32208 17053 32208 17003 32208 17055 32209 17054 32209 17053 32209 17056 32210 17003 32210 17004 32210 17056 32211 17055 32211 17003 32211 17058 32212 17004 32212 17005 32212 17058 32213 17056 32213 17004 32213 17057 32214 17054 32214 17055 32214 17058 32215 17055 32215 17056 32215 17058 32216 17057 32216 17055 32216 17059 32217 17057 32217 17058 32217 17006 32218 17058 32218 17005 32218 17059 32219 17058 32219 17006 32219 17059 32220 17006 32220 17060 32220 17061 32221 17057 32221 17059 32221 17061 32222 17059 32222 17060 32222 17007 32223 17060 32223 17006 32223 17062 32224 17060 32224 17007 32224 17062 32225 17061 32225 17060 32225 17062 32226 17007 32226 17008 32226 17064 32227 17061 32227 17062 32227 17063 32228 17008 32228 17009 32228 17063 32229 17062 32229 17008 32229 17064 32230 17062 32230 17063 32230 17010 32231 17063 32231 17009 32231 17065 32232 17063 32232 17010 32232 17064 32233 17063 32233 17065 32233 17066 32234 17010 32234 17011 32234 17067 32235 17064 32235 17065 32235 17065 32236 17010 32236 17066 32236 17012 32237 17066 32237 17011 32237 17067 32238 17065 32238 17066 32238 17068 32239 17012 32239 17013 32239 17068 32240 17066 32240 17012 32240 17067 32241 17066 32241 17068 32241 17070 32242 17067 32242 17068 32242 17069 32243 17068 32243 17013 32243 17070 32244 17068 32244 17069 32244 17069 32245 17013 32245 17014 32245 17071 32246 17069 32246 17014 32246 17071 32247 17070 32247 17069 32247 17016 32248 17070 32248 17071 32248 17072 32249 17071 32249 17014 32249 17072 32250 17014 32250 16975 32250 17071 32251 17072 32251 17016 32251 17048 32252 17256 32252 17262 32252 17051 32253 17256 32253 17048 32253 17048 32254 17262 32254 17073 32254 17054 32255 17256 32255 17051 32255 17054 32256 17249 32256 17256 32256 17047 32257 17048 32257 17073 32257 17054 32258 17242 32258 17249 32258 17047 32259 17073 32259 17275 32259 17043 32260 17047 32260 17275 32260 17054 32261 17237 32261 17242 32261 17057 32262 17237 32262 17054 32262 17061 32263 17237 32263 17057 32263 17040 32264 17043 32264 17275 32264 17040 32265 17275 32265 17285 32265 17061 32266 17230 32266 17237 32266 17037 32267 17040 32267 17285 32267 17061 32268 17223 32268 17230 32268 17037 32269 17285 32269 17290 32269 17064 32270 17223 32270 17061 32270 17037 32271 17290 32271 17295 32271 17035 32272 17037 32272 17295 32272 17216 32273 17223 32273 17064 32273 17067 32274 17216 32274 17064 32274 17304 32275 17035 32275 17295 32275 17304 32276 17032 32276 17035 32276 17216 32277 17067 32277 17070 32277 17312 32278 17032 32278 17304 32278 17209 32279 17216 32279 17070 32279 17209 32280 17070 32280 17016 32280 17312 32281 17029 32281 17032 32281 17200 32282 17209 32282 17016 32282 17165 32283 17029 32283 17312 32283 17165 32284 17027 32284 17029 32284 17169 32285 17027 32285 17165 32285 17195 32286 17200 32286 17016 32286 17169 32287 17025 32287 17027 32287 17191 32288 17195 32288 17016 32288 17191 32289 17016 32289 17018 32289 17169 32290 17023 32290 17025 32290 17178 32291 17023 32291 17169 32291 17185 32292 17191 32292 17018 32292 17178 32293 17018 32293 17023 32293 17178 32294 17185 32294 17018 32294 17074 32295 17075 32295 17076 32295 17077 32296 17074 32296 17076 32296 17077 32297 17076 32297 17078 32297 17077 32298 17078 32298 17079 32298 17080 32299 17077 32299 17079 32299 17080 32300 17079 32300 17081 32300 17082 32301 17080 32301 17081 32301 17083 32302 17081 32302 17084 32302 17083 32303 17082 32303 17081 32303 17085 32304 17083 32304 17084 32304 17085 32305 17084 32305 17086 32305 17085 32306 17086 32306 17087 32306 17088 32307 17085 32307 17087 32307 17088 32308 17087 32308 17089 32308 17090 32309 17088 32309 17089 32309 17090 32310 17089 32310 17091 32310 17092 32311 17090 32311 17091 32311 17092 32312 17091 32312 17093 32312 17094 32313 17092 32313 17093 32313 17094 32314 17093 32314 17095 32314 17096 32315 17094 32315 17095 32315 17096 32316 17095 32316 17097 32316 17098 32317 17096 32317 17097 32317 17098 32318 17097 32318 17099 32318 17100 32319 17098 32319 17099 32319 17100 32320 17099 32320 17101 32320 17102 32321 17100 32321 17101 32321 17103 32322 17102 32322 17101 32322 17103 32323 17101 32323 17104 32323 17103 32324 17104 32324 17105 32324 17106 32325 17103 32325 17105 32325 17106 32326 17105 32326 17107 32326 17108 32327 17106 32327 17107 32327 17108 32328 17107 32328 17109 32328 17110 32329 17108 32329 17109 32329 17110 32330 17109 32330 17111 32330 17112 32331 17110 32331 17111 32331 17112 32332 17111 32332 17113 32332 17114 32333 17112 32333 17113 32333 17114 32334 17113 32334 17115 32334 17116 32335 17114 32335 17115 32335 17116 32336 17115 32336 17075 32336 17074 32337 17116 32337 17075 32337 17117 32338 17118 32338 17119 32338 17120 32339 17117 32339 17119 32339 17120 32340 17119 32340 17121 32340 17122 32341 17120 32341 17121 32341 17122 32342 17121 32342 17123 32342 17124 32343 17122 32343 17123 32343 17124 32344 17123 32344 17125 32344 17126 32345 17124 32345 17125 32345 17126 32346 17125 32346 17127 32346 17126 32347 17127 32347 17128 32347 17129 32348 17126 32348 17128 32348 17130 32349 17129 32349 17128 32349 17130 32350 17128 32350 17131 32350 17132 32351 17130 32351 17131 32351 17132 32352 17131 32352 17133 32352 17134 32353 17132 32353 17133 32353 17134 32354 17133 32354 17135 32354 17136 32355 17134 32355 17135 32355 17136 32356 17135 32356 17137 32356 17138 32357 17137 32357 17139 32357 17138 32358 17136 32358 17137 32358 17140 32359 17138 32359 17139 32359 17140 32360 17139 32360 17141 32360 17140 32361 17141 32361 17142 32361 17143 32362 17140 32362 17142 32362 17144 32363 17142 32363 17145 32363 17144 32364 17143 32364 17142 32364 17144 32365 17145 32365 17146 32365 17147 32366 17144 32366 17146 32366 17147 32367 17146 32367 17148 32367 17149 32368 17147 32368 17148 32368 17150 32369 17148 32369 17151 32369 17150 32370 17149 32370 17148 32370 17150 32371 17151 32371 17152 32371 17153 32372 17150 32372 17152 32372 17153 32373 17152 32373 17154 32373 17155 32374 17153 32374 17154 32374 17155 32375 17154 32375 17156 32375 17157 32376 17155 32376 17156 32376 17157 32377 17156 32377 17158 32377 17159 32378 17157 32378 17158 32378 17159 32379 17158 32379 17118 32379 17117 32380 17159 32380 17118 32380 17160 32381 17162 32381 17161 32381 17163 32382 17162 32382 17160 32382 17164 32383 17165 32383 17162 32383 17164 32384 17162 32384 17163 32384 17167 32385 17160 32385 17166 32385 17167 32386 17163 32386 17160 32386 17164 32387 17163 32387 17167 32387 17168 32388 17167 32388 17166 32388 17169 32389 17165 32389 17164 32389 17168 32390 17164 32390 17167 32390 17171 32391 17164 32391 17168 32391 17168 32392 17166 32392 17170 32392 17171 32393 17169 32393 17164 32393 17172 32394 17171 32394 17168 32394 17172 32395 17168 32395 17170 32395 17173 32396 17172 32396 17170 32396 17175 32397 17171 32397 17172 32397 17174 32398 17172 32398 17173 32398 17175 32399 17169 32399 17171 32399 17174 32400 17173 32400 17176 32400 17175 32401 17172 32401 17174 32401 17177 32402 17174 32402 17176 32402 17178 32403 17169 32403 17175 32403 17175 32404 17174 32404 17177 32404 17180 32405 17175 32405 17177 32405 17179 32406 17177 32406 17176 32406 17180 32407 17177 32407 17179 32407 17178 32408 17175 32408 17180 32408 17181 32409 17180 32409 17179 32409 17182 32410 17178 32410 17180 32410 17182 32411 17180 32411 17181 32411 17184 32412 17181 32412 17183 32412 17184 32413 17182 32413 17181 32413 17185 32414 17178 32414 17182 32414 17186 32415 17184 32415 17183 32415 17188 32416 17184 32416 17186 32416 17188 32417 17182 32417 17184 32417 17186 32418 17183 32418 17187 32418 17185 32419 17182 32419 17188 32419 17189 32420 17186 32420 17187 32420 17189 32421 17188 32421 17186 32421 17190 32422 17189 32422 17187 32422 17191 32423 17188 32423 17189 32423 17191 32424 17185 32424 17188 32424 17193 32425 17190 32425 17192 32425 17193 32426 17189 32426 17190 32426 17191 32427 17189 32427 17193 32427 17195 32428 17191 32428 17193 32428 17194 32429 17193 32429 17192 32429 17197 32430 17195 32430 17193 32430 17197 32431 17193 32431 17194 32431 17197 32432 17194 32432 17196 32432 17198 32433 17197 32433 17196 32433 17198 32434 17195 32434 17197 32434 17200 32435 17195 32435 17198 32435 17198 32436 17196 32436 17199 32436 17201 32437 17198 32437 17199 32437 17201 32438 17199 32438 17202 32438 17204 32439 17198 32439 17201 32439 17205 32440 17198 32440 17204 32440 17205 32441 17200 32441 17198 32441 17201 32442 17202 32442 17203 32442 17206 32443 17201 32443 17203 32443 17206 32444 17204 32444 17201 32444 17207 32445 17206 32445 17203 32445 17209 32446 17200 32446 17205 32446 17208 32447 17206 32447 17207 32447 17209 32448 17204 32448 17206 32448 17209 32449 17205 32449 17204 32449 17208 32450 17207 32450 17210 32450 17211 32451 17206 32451 17208 32451 17211 32452 17209 32452 17206 32452 17212 32453 17208 32453 17210 32453 17211 32454 17208 32454 17212 32454 17212 32455 17210 32455 17213 32455 17214 32456 17209 32456 17211 32456 17215 32457 17212 32457 17213 32457 17216 32458 17209 32458 17214 32458 17215 32459 17211 32459 17212 32459 17214 32460 17211 32460 17215 32460 17215 32461 17213 32461 17217 32461 17219 32462 17214 32462 17215 32462 17218 32463 17215 32463 17217 32463 17216 32464 17214 32464 17219 32464 17219 32465 17215 32465 17218 32465 17220 32466 17219 32466 17218 32466 17221 32467 17219 32467 17220 32467 17221 32468 17216 32468 17219 32468 17222 32469 17221 32469 17220 32469 17223 32470 17216 32470 17221 32470 17225 32471 17221 32471 17222 32471 17226 32472 17221 32472 17225 32472 17225 32473 17222 32473 17224 32473 17226 32474 17223 32474 17221 32474 17227 32475 17225 32475 17224 32475 17228 32476 17225 32476 17227 32476 17226 32477 17225 32477 17228 32477 17228 32478 17227 32478 17229 32478 17230 32479 17223 32479 17226 32479 17231 32480 17226 32480 17228 32480 17231 32481 17228 32481 17229 32481 17230 32482 17226 32482 17231 32482 17231 32483 17229 32483 17232 32483 17233 32484 17231 32484 17232 32484 17234 32485 17231 32485 17233 32485 17233 32486 17232 32486 17235 32486 17234 32487 17230 32487 17231 32487 17237 32488 17230 32488 17234 32488 17233 32489 17235 32489 17236 32489 17238 32490 17234 32490 17233 32490 17238 32491 17237 32491 17234 32491 17239 32492 17233 32492 17236 32492 17239 32493 17238 32493 17233 32493 17239 32494 17236 32494 17240 32494 17241 32495 17239 32495 17240 32495 17242 32496 17237 32496 17238 32496 17243 32497 17241 32497 17240 32497 17244 32498 17239 32498 17241 32498 17244 32499 17238 32499 17239 32499 17242 32500 17238 32500 17244 32500 17245 32501 17241 32501 17243 32501 17246 32502 17241 32502 17245 32502 17246 32503 17244 32503 17241 32503 17242 32504 17244 32504 17246 32504 17248 32505 17245 32505 17247 32505 17249 32506 17242 32506 17246 32506 17248 32507 17246 32507 17245 32507 17251 32508 17246 32508 17248 32508 17252 32509 17247 32509 17250 32509 17252 32510 17248 32510 17247 32510 17249 32511 17246 32511 17251 32511 17251 32512 17248 32512 17252 32512 17253 32513 17251 32513 17252 32513 17255 32514 17251 32514 17253 32514 17254 32515 17252 32515 17250 32515 17249 32516 17251 32516 17255 32516 17253 32517 17252 32517 17254 32517 17256 32518 17249 32518 17255 32518 17257 32519 17253 32519 17254 32519 17257 32520 17255 32520 17253 32520 17257 32521 17254 32521 17258 32521 17259 32522 17257 32522 17258 32522 17261 32523 17257 32523 17259 32523 17261 32524 17255 32524 17257 32524 17259 32525 17258 32525 17260 32525 17262 32526 17255 32526 17261 32526 17262 32527 17256 32527 17255 32527 17263 32528 17259 32528 17260 32528 17263 32529 17261 32529 17259 32529 17262 32530 17261 32530 17263 32530 17264 32531 17263 32531 17260 32531 17073 32532 17262 32532 17263 32532 17265 32533 17263 32533 17264 32533 17073 32534 17263 32534 17265 32534 17265 32535 17264 32535 17266 32535 17267 32536 17265 32536 17266 32536 17269 32537 17265 32537 17267 32537 17268 32538 17267 32538 17266 32538 17269 32539 17073 32539 17265 32539 17270 32540 17267 32540 17268 32540 17270 32541 17269 32541 17267 32541 17271 32542 17270 32542 17268 32542 17272 32543 17270 32543 17271 32543 17274 32544 17270 32544 17272 32544 17274 32545 17269 32545 17270 32545 17272 32546 17271 32546 17273 32546 17274 32547 17073 32547 17269 32547 17275 32548 17073 32548 17274 32548 17277 32549 17274 32549 17272 32549 17276 32550 17272 32550 17273 32550 17275 32551 17274 32551 17277 32551 17278 32552 17272 32552 17276 32552 17277 32553 17272 32553 17278 32553 17279 32554 17278 32554 17276 32554 17280 32555 17277 32555 17278 32555 17280 32556 17275 32556 17277 32556 17281 32557 17278 32557 17279 32557 17281 32558 17279 32558 17282 32558 17280 32559 17278 32559 17281 32559 17284 32560 17282 32560 17283 32560 17284 32561 17281 32561 17282 32561 17285 32562 17275 32562 17280 32562 17284 32563 17280 32563 17281 32563 17285 32564 17280 32564 17284 32564 17286 32565 17284 32565 17283 32565 17287 32566 17284 32566 17286 32566 17287 32567 17285 32567 17284 32567 17289 32568 17285 32568 17287 32568 17290 32569 17285 32569 17289 32569 17289 32570 17286 32570 17288 32570 17289 32571 17287 32571 17286 32571 17291 32572 17289 32572 17288 32572 17291 32573 17288 32573 17292 32573 17293 32574 17289 32574 17291 32574 17293 32575 17290 32575 17289 32575 17294 32576 17291 32576 17292 32576 17295 32577 17290 32577 17293 32577 17296 32578 17291 32578 17294 32578 17296 32579 17293 32579 17291 32579 17295 32580 17293 32580 17296 32580 17298 32581 17294 32581 17297 32581 17298 32582 17296 32582 17294 32582 17295 32583 17296 32583 17298 32583 17299 32584 17298 32584 17297 32584 17300 32585 17298 32585 17299 32585 17301 32586 17298 32586 17300 32586 17301 32587 17295 32587 17298 32587 17303 32588 17299 32588 17302 32588 17304 32589 17295 32589 17301 32589 17303 32590 17300 32590 17299 32590 17301 32591 17300 32591 17303 32591 17303 32592 17302 32592 17305 32592 17306 32593 17301 32593 17303 32593 17308 32594 17305 32594 17307 32594 17308 32595 17303 32595 17305 32595 17304 32596 17301 32596 17306 32596 17308 32597 17306 32597 17303 32597 17309 32598 17304 32598 17306 32598 17309 32599 17306 32599 17308 32599 17311 32600 17308 32600 17307 32600 17312 32601 17304 32601 17309 32601 17311 32602 17309 32602 17308 32602 17310 32603 17311 32603 17307 32603 17313 32604 17309 32604 17311 32604 17313 32605 17312 32605 17309 32605 17313 32606 17311 32606 17314 32606 17315 32607 17311 32607 17310 32607 17315 32608 17314 32608 17311 32608 17162 32609 17315 32609 17161 32609 17162 32610 17314 32610 17315 32610 17162 32611 17313 32611 17314 32611 17165 32612 17313 32612 17162 32612 17165 32613 17312 32613 17313 32613 17160 32614 17316 32614 17317 32614 17160 32615 17161 32615 17316 32615 17166 32616 17317 32616 17318 32616 17166 32617 17160 32617 17317 32617 17166 32618 17318 32618 17319 32618 17170 32619 17166 32619 17319 32619 17170 32620 17319 32620 17320 32620 17173 32621 17320 32621 17321 32621 17173 32622 17170 32622 17320 32622 17176 32623 17173 32623 17321 32623 17176 32624 17321 32624 17322 32624 17176 32625 17322 32625 17323 32625 17179 32626 17176 32626 17323 32626 17179 32627 17323 32627 17324 32627 17181 32628 17179 32628 17324 32628 17181 32629 17324 32629 17325 32629 17183 32630 17181 32630 17325 32630 17183 32631 17325 32631 17461 32631 17187 32632 17461 32632 17326 32632 17187 32633 17183 32633 17461 32633 17190 32634 17187 32634 17326 32634 17190 32635 17326 32635 17327 32635 17192 32636 17190 32636 17327 32636 17192 32637 17327 32637 17328 32637 17194 32638 17192 32638 17328 32638 17196 32639 17194 32639 17328 32639 17196 32640 17328 32640 17452 32640 17199 32641 17196 32641 17452 32641 17199 32642 17452 32642 17329 32642 17202 32643 17199 32643 17329 32643 17202 32644 17329 32644 17330 32644 17203 32645 17202 32645 17330 32645 17203 32646 17330 32646 17331 32646 17207 32647 17203 32647 17331 32647 17207 32648 17331 32648 17332 32648 17210 32649 17207 32649 17332 32649 17210 32650 17332 32650 17333 32650 17213 32651 17210 32651 17333 32651 17213 32652 17333 32652 17334 32652 17217 32653 17213 32653 17334 32653 17218 32654 17217 32654 17334 32654 17218 32655 17334 32655 17335 32655 17220 32656 17218 32656 17335 32656 17220 32657 17335 32657 17336 32657 17222 32658 17220 32658 17336 32658 17222 32659 17336 32659 17337 32659 17224 32660 17222 32660 17337 32660 17224 32661 17337 32661 17338 32661 17227 32662 17224 32662 17338 32662 17227 32663 17338 32663 17339 32663 17229 32664 17227 32664 17339 32664 17229 32665 17339 32665 17340 32665 17232 32666 17229 32666 17340 32666 17232 32667 17340 32667 17341 32667 17235 32668 17232 32668 17341 32668 17236 32669 17235 32669 17341 32669 17236 32670 17341 32670 17342 32670 17240 32671 17236 32671 17342 32671 17240 32672 17342 32672 17343 32672 17243 32673 17240 32673 17343 32673 17243 32674 17343 32674 17344 32674 17245 32675 17243 32675 17344 32675 17247 32676 17245 32676 17344 32676 17247 32677 17344 32677 17345 32677 17247 32678 17345 32678 17414 32678 17250 32679 17247 32679 17414 32679 17250 32680 17414 32680 17412 32680 17254 32681 17412 32681 17346 32681 17254 32682 17250 32682 17412 32682 17258 32683 17346 32683 17347 32683 17258 32684 17254 32684 17346 32684 17260 32685 17258 32685 17347 32685 17260 32686 17347 32686 17348 32686 17264 32687 17348 32687 17349 32687 17264 32688 17260 32688 17348 32688 17266 32689 17264 32689 17349 32689 17266 32690 17349 32690 17350 32690 17268 32691 17266 32691 17350 32691 17268 32692 17350 32692 17351 32692 17271 32693 17268 32693 17351 32693 17271 32694 17351 32694 17352 32694 17273 32695 17271 32695 17352 32695 17273 32696 17352 32696 17353 32696 17273 32697 17353 32697 17354 32697 17276 32698 17273 32698 17354 32698 17279 32699 17354 32699 17355 32699 17279 32700 17276 32700 17354 32700 17282 32701 17279 32701 17355 32701 17283 32702 17355 32702 17356 32702 17283 32703 17282 32703 17355 32703 17283 32704 17356 32704 17357 32704 17286 32705 17357 32705 17358 32705 17286 32706 17283 32706 17357 32706 17288 32707 17286 32707 17358 32707 17292 32708 17358 32708 17359 32708 17292 32709 17288 32709 17358 32709 17292 32710 17359 32710 17360 32710 17294 32711 17292 32711 17360 32711 17297 32712 17360 32712 17361 32712 17297 32713 17294 32713 17360 32713 17299 32714 17361 32714 17362 32714 17299 32715 17297 32715 17361 32715 17299 32716 17362 32716 17377 32716 17302 32717 17299 32717 17377 32717 17302 32718 17377 32718 17375 32718 17305 32719 17375 32719 17363 32719 17305 32720 17302 32720 17375 32720 17307 32721 17305 32721 17363 32721 17307 32722 17363 32722 17364 32722 17310 32723 17307 32723 17364 32723 17310 32724 17364 32724 17365 32724 17315 32725 17365 32725 17366 32725 17315 32726 17310 32726 17365 32726 17161 32727 17315 32727 17366 32727 17161 32728 17366 32728 17316 32728 17367 32729 17316 32729 17366 32729 17370 32730 17478 32730 17368 32730 17369 32731 17368 32731 17367 32731 17365 32732 17367 32732 17366 32732 17369 32733 17367 32733 17365 32733 17370 32734 17368 32734 17369 32734 17371 32735 17365 32735 17364 32735 17371 32736 17369 32736 17365 32736 17372 32737 17370 32737 17369 32737 17373 32738 17369 32738 17371 32738 17363 32739 17371 32739 17364 32739 17372 32740 17369 32740 17373 32740 17374 32741 17371 32741 17363 32741 17373 32742 17371 32742 17374 32742 17375 32743 17374 32743 17363 32743 17376 32744 17374 32744 17375 32744 17376 32745 17373 32745 17374 32745 17376 32746 17372 32746 17373 32746 17378 32747 17376 32747 17375 32747 17378 32748 17375 32748 17377 32748 17379 32749 17372 32749 17376 32749 17379 32750 17376 32750 17378 32750 17378 32751 17377 32751 17362 32751 17381 32752 17372 32752 17379 32752 17380 32753 17378 32753 17362 32753 17382 32754 17378 32754 17380 32754 17382 32755 17379 32755 17378 32755 17380 32756 17362 32756 17361 32756 17382 32757 17381 32757 17379 32757 17383 32758 17382 32758 17380 32758 17360 32759 17380 32759 17361 32759 17383 32760 17380 32760 17360 32760 17384 32761 17383 32761 17360 32761 17385 32762 17383 32762 17384 32762 17385 32763 17382 32763 17383 32763 17384 32764 17360 32764 17359 32764 17386 32765 17382 32765 17385 32765 17386 32766 17381 32766 17382 32766 17387 32767 17384 32767 17359 32767 17387 32768 17359 32768 17358 32768 17388 32769 17386 32769 17385 32769 17388 32770 17384 32770 17387 32770 17388 32771 17385 32771 17384 32771 17389 32772 17388 32772 17387 32772 17357 32773 17387 32773 17358 32773 17390 32774 17388 32774 17389 32774 17390 32775 17386 32775 17388 32775 17357 32776 17389 32776 17387 32776 17390 32777 17389 32777 17391 32777 17356 32778 17389 32778 17357 32778 17391 32779 17389 32779 17356 32779 17392 32780 17390 32780 17391 32780 17355 32781 17391 32781 17356 32781 17393 32782 17391 32782 17355 32782 17393 32783 17392 32783 17391 32783 17393 32784 17355 32784 17354 32784 17394 32785 17393 32785 17354 32785 17395 32786 17393 32786 17394 32786 17395 32787 17392 32787 17393 32787 17353 32788 17394 32788 17354 32788 17396 32789 17395 32789 17394 32789 17396 32790 17394 32790 17353 32790 17400 32791 17392 32791 17395 32791 17397 32792 17353 32792 17352 32792 17397 32793 17396 32793 17353 32793 17398 32794 17397 32794 17352 32794 17400 32795 17395 32795 17396 32795 17398 32796 17352 32796 17351 32796 17399 32797 17396 32797 17397 32797 17399 32798 17397 32798 17398 32798 17400 32799 17396 32799 17399 32799 17350 32800 17398 32800 17351 32800 17401 32801 17398 32801 17350 32801 17401 32802 17399 32802 17398 32802 17402 32803 17400 32803 17399 32803 17399 32804 17401 32804 17403 32804 17349 32805 17401 32805 17350 32805 17403 32806 17401 32806 17349 32806 17402 32807 17399 32807 17403 32807 17404 32808 17403 32808 17349 32808 17407 32809 17400 32809 17402 32809 17348 32810 17404 32810 17349 32810 17405 32811 17402 32811 17403 32811 17406 32812 17404 32812 17348 32812 17406 32813 17403 32813 17404 32813 17407 32814 17402 32814 17405 32814 17405 32815 17403 32815 17406 32815 17409 32816 17348 32816 17347 32816 17409 32817 17406 32817 17348 32817 17409 32818 17405 32818 17406 32818 17410 32819 17405 32819 17409 32819 17410 32820 17407 32820 17405 32820 17346 32821 17409 32821 17347 32821 17411 32822 17409 32822 17346 32822 17408 32823 17407 32823 17410 32823 17410 32824 17409 32824 17411 32824 17412 32825 17411 32825 17346 32825 17413 32826 17410 32826 17411 32826 17413 32827 17408 32827 17410 32827 17413 32828 17411 32828 17412 32828 17413 32829 17412 32829 17414 32829 17415 32830 17408 32830 17413 32830 17416 32831 17414 32831 17345 32831 17416 32832 17413 32832 17414 32832 17415 32833 17413 32833 17416 32833 17417 32834 17408 32834 17415 32834 17418 32835 17415 32835 17416 32835 17419 32836 17345 32836 17344 32836 17419 32837 17416 32837 17345 32837 17418 32838 17416 32838 17419 32838 17417 32839 17415 32839 17418 32839 17420 32840 17419 32840 17344 32840 17421 32841 17419 32841 17420 32841 17421 32842 17418 32842 17419 32842 17420 32843 17344 32843 17343 32843 17422 32844 17420 32844 17343 32844 17422 32845 17421 32845 17420 32845 17342 32846 17422 32846 17343 32846 17423 32847 17418 32847 17421 32847 17423 32848 17417 32848 17418 32848 17424 32849 17421 32849 17422 32849 17341 32850 17422 32850 17342 32850 17424 32851 17423 32851 17421 32851 17425 32852 17422 32852 17341 32852 17425 32853 17424 32853 17422 32853 17426 32854 17424 32854 17425 32854 17427 32855 17424 32855 17426 32855 17428 32856 17425 32856 17341 32856 17427 32857 17423 32857 17424 32857 17428 32858 17426 32858 17425 32858 17428 32859 17341 32859 17340 32859 17429 32860 17427 32860 17426 32860 17429 32861 17426 32861 17428 32861 17428 32862 17340 32862 17339 32862 17431 32863 17423 32863 17427 32863 17430 32864 17429 32864 17428 32864 17339 32865 17430 32865 17428 32865 17431 32866 17427 32866 17429 32866 17433 32867 17339 32867 17338 32867 17433 32868 17430 32868 17339 32868 17432 32869 17430 32869 17433 32869 17433 32870 17338 32870 17337 32870 17431 32871 17430 32871 17432 32871 17431 32872 17429 32872 17430 32872 17434 32873 17433 32873 17337 32873 17434 32874 17432 32874 17433 32874 17435 32875 17431 32875 17432 32875 17435 32876 17432 32876 17434 32876 17434 32877 17337 32877 17336 32877 17436 32878 17431 32878 17435 32878 17437 32879 17435 32879 17434 32879 17437 32880 17434 32880 17336 32880 17438 32881 17336 32881 17335 32881 17438 32882 17437 32882 17336 32882 17439 32883 17437 32883 17438 32883 17439 32884 17435 32884 17437 32884 17436 32885 17435 32885 17439 32885 17440 32886 17335 32886 17334 32886 17440 32887 17438 32887 17335 32887 17440 32888 17439 32888 17438 32888 17441 32889 17439 32889 17440 32889 17441 32890 17436 32890 17439 32890 17442 32891 17440 32891 17334 32891 17442 32892 17441 32892 17440 32892 17333 32893 17442 32893 17334 32893 17443 32894 17436 32894 17441 32894 17444 32895 17441 32895 17442 32895 17444 32896 17443 32896 17441 32896 17332 32897 17442 32897 17333 32897 17445 32898 17442 32898 17332 32898 17445 32899 17444 32899 17442 32899 17446 32900 17332 32900 17331 32900 17446 32901 17445 32901 17332 32901 17447 32902 17445 32902 17446 32902 17447 32903 17444 32903 17445 32903 17447 32904 17443 32904 17444 32904 17449 32905 17443 32905 17447 32905 17448 32906 17446 32906 17331 32906 17447 32907 17446 32907 17448 32907 17448 32908 17331 32908 17330 32908 17449 32909 17447 32909 17448 32909 17329 32910 17448 32910 17330 32910 17450 32911 17448 32911 17329 32911 17451 32912 17448 32912 17450 32912 17451 32913 17449 32913 17448 32913 17452 32914 17450 32914 17329 32914 17454 32915 17450 32915 17452 32915 17454 32916 17451 32916 17450 32916 17453 32917 17451 32917 17454 32917 17455 32918 17452 32918 17328 32918 17453 32919 17449 32919 17451 32919 17455 32920 17454 32920 17452 32920 17327 32921 17455 32921 17328 32921 17456 32922 17453 32922 17454 32922 17457 32923 17455 32923 17327 32923 17458 32924 17453 32924 17456 32924 17457 32925 17454 32925 17455 32925 17456 32926 17454 32926 17457 32926 17457 32927 17327 32927 17326 32927 17459 32928 17456 32928 17457 32928 17460 32929 17457 32929 17326 32929 17459 32930 17457 32930 17460 32930 17461 32931 17460 32931 17326 32931 17462 32932 17456 32932 17459 32932 17462 32933 17458 32933 17456 32933 17463 32934 17460 32934 17461 32934 17463 32935 17459 32935 17460 32935 17463 32936 17462 32936 17459 32936 17464 32937 17462 32937 17463 32937 17465 32938 17461 32938 17325 32938 17465 32939 17463 32939 17461 32939 17464 32940 17463 32940 17465 32940 17324 32941 17465 32941 17325 32941 17466 32942 17465 32942 17324 32942 17466 32943 17464 32943 17465 32943 17467 32944 17462 32944 17464 32944 17468 32945 17324 32945 17323 32945 17467 32946 17464 32946 17466 32946 17468 32947 17466 32947 17324 32947 17469 32948 17466 32948 17468 32948 17322 32949 17468 32949 17323 32949 17469 32950 17467 32950 17466 32950 17470 32951 17468 32951 17322 32951 17470 32952 17469 32952 17468 32952 17321 32953 17470 32953 17322 32953 17471 32954 17467 32954 17469 32954 17472 32955 17470 32955 17321 32955 17472 32956 17469 32956 17470 32956 17471 32957 17469 32957 17472 32957 17473 32958 17321 32958 17320 32958 17473 32959 17472 32959 17321 32959 17476 32960 17467 32960 17471 32960 17319 32961 17473 32961 17320 32961 17474 32962 17473 32962 17319 32962 17474 32963 17472 32963 17473 32963 17475 32964 17472 32964 17474 32964 17475 32965 17471 32965 17472 32965 17476 32966 17471 32966 17475 32966 17474 32967 17319 32967 17318 32967 17477 32968 17474 32968 17318 32968 17477 32969 17475 32969 17474 32969 17477 32970 17318 32970 17317 32970 17478 32971 17476 32971 17475 32971 17479 32972 17475 32972 17477 32972 17478 32973 17475 32973 17479 32973 17479 32974 17477 32974 17317 32974 17368 32975 17478 32975 17479 32975 17479 32976 17316 32976 17367 32976 17479 32977 17317 32977 17316 32977 17479 32978 17367 32978 17368 32978 17123 32979 17381 32979 17386 32979 17125 32980 17123 32980 17386 32980 17121 32981 17372 32981 17381 32981 17121 32982 17381 32982 17123 32982 17125 32983 17386 32983 17390 32983 17119 32984 17372 32984 17121 32984 17127 32985 17125 32985 17390 32985 17119 32986 17370 32986 17372 32986 17127 32987 17390 32987 17392 32987 17118 32988 17478 32988 17370 32988 17118 32989 17370 32989 17119 32989 17128 32990 17127 32990 17392 32990 17128 32991 17392 32991 17400 32991 17158 32992 17478 32992 17118 32992 17158 32993 17476 32993 17478 32993 17131 32994 17128 32994 17400 32994 17156 32995 17476 32995 17158 32995 17156 32996 17467 32996 17476 32996 17131 32997 17400 32997 17407 32997 17133 32998 17407 32998 17408 32998 17133 32999 17131 32999 17407 32999 17467 33000 17156 33000 17154 33000 17462 33001 17467 33001 17154 33001 17458 33002 17462 33002 17154 33002 17458 33003 17154 33003 17152 33003 17408 33004 17135 33004 17133 33004 17417 33005 17135 33005 17408 33005 17458 33006 17152 33006 17151 33006 17417 33007 17137 33007 17135 33007 17453 33008 17458 33008 17151 33008 17417 33009 17139 33009 17137 33009 17453 33010 17151 33010 17148 33010 17423 33011 17139 33011 17417 33011 17449 33012 17453 33012 17148 33012 17423 33013 17141 33013 17139 33013 17431 33014 17141 33014 17423 33014 17449 33015 17148 33015 17146 33015 17443 33016 17449 33016 17146 33016 17431 33017 17142 33017 17141 33017 17436 33018 17443 33018 17146 33018 17436 33019 17142 33019 17431 33019 17436 33020 17146 33020 17145 33020 17436 33021 17145 33021 17142 33021 17482 33022 17481 33022 17480 33022 17484 33023 17482 33023 17480 33023 17486 33024 17482 33024 17484 33024 17486 33025 17483 33025 17482 33025 17485 33026 17484 33026 17480 33026 17490 33027 17640 33027 17483 33027 17487 33028 17484 33028 17485 33028 17486 33029 17484 33029 17487 33029 17488 33030 17487 33030 17485 33030 17489 33031 17486 33031 17487 33031 17489 33032 17483 33032 17486 33032 17490 33033 17483 33033 17489 33033 17492 33034 17488 33034 17491 33034 17492 33035 17487 33035 17488 33035 17492 33036 17489 33036 17487 33036 17493 33037 17492 33037 17491 33037 17495 33038 17492 33038 17493 33038 17494 33039 17493 33039 17491 33039 17495 33040 17489 33040 17492 33040 17495 33041 17490 33041 17489 33041 17496 33042 17493 33042 17494 33042 17496 33043 17495 33043 17493 33043 17496 33044 17494 33044 17497 33044 17500 33045 17490 33045 17495 33045 17498 33046 17496 33046 17497 33046 17500 33047 17495 33047 17496 33047 17499 33048 17498 33048 17497 33048 17498 33049 17500 33049 17496 33049 17502 33050 17500 33050 17498 33050 17503 33051 17499 33051 17501 33051 17503 33052 17498 33052 17499 33052 17502 33053 17498 33053 17503 33053 17504 33054 17500 33054 17502 33054 17505 33055 17503 33055 17501 33055 17505 33056 17502 33056 17503 33056 17505 33057 17501 33057 17506 33057 17504 33058 17502 33058 17505 33058 17509 33059 17506 33059 17508 33059 17507 33060 17504 33060 17505 33060 17509 33061 17505 33061 17506 33061 17509 33062 17507 33062 17505 33062 17510 33063 17509 33063 17508 33063 17511 33064 17504 33064 17507 33064 17507 33065 17509 33065 17510 33065 17510 33066 17508 33066 17512 33066 17513 33067 17511 33067 17507 33067 17513 33068 17507 33068 17510 33068 17515 33069 17510 33069 17512 33069 17515 33070 17513 33070 17510 33070 17515 33071 17512 33071 17514 33071 17516 33072 17511 33072 17513 33072 17518 33073 17514 33073 17517 33073 17518 33074 17515 33074 17514 33074 17516 33075 17513 33075 17515 33075 17519 33076 17518 33076 17517 33076 17520 33077 17515 33077 17518 33077 17516 33078 17515 33078 17520 33078 17521 33079 17518 33079 17519 33079 17521 33080 17520 33080 17518 33080 17522 33081 17521 33081 17519 33081 17523 33082 17521 33082 17522 33082 17523 33083 17520 33083 17521 33083 17523 33084 17522 33084 17524 33084 17525 33085 17520 33085 17523 33085 17526 33086 17520 33086 17525 33086 17526 33087 17516 33087 17520 33087 17527 33088 17523 33088 17524 33088 17525 33089 17523 33089 17527 33089 17528 33090 17527 33090 17524 33090 17530 33091 17528 33091 17529 33091 17530 33092 17527 33092 17528 33092 17525 33093 17527 33093 17530 33093 17531 33094 17530 33094 17529 33094 17532 33095 17525 33095 17530 33095 17532 33096 17526 33096 17525 33096 17533 33097 17530 33097 17531 33097 17534 33098 17526 33098 17532 33098 17535 33099 17530 33099 17533 33099 17535 33100 17532 33100 17530 33100 17536 33101 17533 33101 17531 33101 17534 33102 17532 33102 17535 33102 17537 33103 17535 33103 17533 33103 17538 33104 17533 33104 17536 33104 17537 33105 17533 33105 17538 33105 17537 33106 17534 33106 17535 33106 17539 33107 17534 33107 17537 33107 17537 33108 17538 33108 17540 33108 17540 33109 17538 33109 17541 33109 17543 33110 17537 33110 17540 33110 17542 33111 17537 33111 17543 33111 17542 33112 17539 33112 17537 33112 17543 33113 17540 33113 17541 33113 17544 33114 17543 33114 17541 33114 17545 33115 17543 33115 17544 33115 17546 33116 17543 33116 17545 33116 17547 33117 17543 33117 17546 33117 17547 33118 17542 33118 17543 33118 17547 33119 17539 33119 17542 33119 17548 33120 17545 33120 17544 33120 17548 33121 17546 33121 17545 33121 17549 33122 17547 33122 17546 33122 17551 33123 17548 33123 17550 33123 17551 33124 17546 33124 17548 33124 17551 33125 17549 33125 17546 33125 17552 33126 17547 33126 17549 33126 17554 33127 17550 33127 17553 33127 17554 33128 17551 33128 17550 33128 17554 33129 17549 33129 17551 33129 17552 33130 17549 33130 17554 33130 17555 33131 17554 33131 17553 33131 17557 33132 17554 33132 17555 33132 17556 33133 17555 33133 17553 33133 17557 33134 17552 33134 17554 33134 17559 33135 17552 33135 17557 33135 17558 33136 17555 33136 17556 33136 17558 33137 17557 33137 17555 33137 17561 33138 17559 33138 17557 33138 17561 33139 17557 33139 17558 33139 17558 33140 17556 33140 17560 33140 17558 33141 17560 33141 17562 33141 17563 33142 17558 33142 17562 33142 17564 33143 17558 33143 17563 33143 17564 33144 17561 33144 17558 33144 17564 33145 17559 33145 17561 33145 17565 33146 17563 33146 17562 33146 17566 33147 17563 33147 17565 33147 17566 33148 17564 33148 17563 33148 17567 33149 17564 33149 17566 33149 17568 33150 17559 33150 17564 33150 17569 33151 17564 33151 17567 33151 17568 33152 17564 33152 17569 33152 17566 33153 17565 33153 17570 33153 17571 33154 17567 33154 17566 33154 17569 33155 17567 33155 17571 33155 17571 33156 17566 33156 17570 33156 17571 33157 17570 33157 17572 33157 17574 33158 17568 33158 17569 33158 17574 33159 17569 33159 17571 33159 17575 33160 17571 33160 17572 33160 17575 33161 17572 33161 17573 33161 17574 33162 17571 33162 17575 33162 17576 33163 17575 33163 17573 33163 17577 33164 17575 33164 17576 33164 17577 33165 17574 33165 17575 33165 17578 33166 17574 33166 17577 33166 17579 33167 17577 33167 17576 33167 17580 33168 17577 33168 17579 33168 17581 33169 17577 33169 17580 33169 17581 33170 17578 33170 17577 33170 17582 33171 17580 33171 17579 33171 17583 33172 17580 33172 17582 33172 17581 33173 17580 33173 17583 33173 17584 33174 17583 33174 17582 33174 17585 33175 17578 33175 17581 33175 17585 33176 17581 33176 17583 33176 17586 33177 17583 33177 17584 33177 17585 33178 17583 33178 17586 33178 17586 33179 17584 33179 17587 33179 17589 33180 17578 33180 17585 33180 17588 33181 17585 33181 17586 33181 17589 33182 17585 33182 17588 33182 17590 33183 17586 33183 17587 33183 17590 33184 17588 33184 17586 33184 17591 33185 17590 33185 17587 33185 17593 33186 17591 33186 17592 33186 17594 33187 17589 33187 17588 33187 17593 33188 17590 33188 17591 33188 17594 33189 17588 33189 17590 33189 17594 33190 17590 33190 17593 33190 17595 33191 17593 33191 17592 33191 17596 33192 17593 33192 17595 33192 17597 33193 17589 33193 17594 33193 17596 33194 17594 33194 17593 33194 17598 33195 17596 33195 17595 33195 17598 33196 17595 33196 17599 33196 17596 33197 17597 33197 17594 33197 17600 33198 17596 33198 17598 33198 17601 33199 17598 33199 17599 33199 17597 33200 17596 33200 17600 33200 17601 33201 17600 33201 17598 33201 17604 33202 17597 33202 17600 33202 17602 33203 17600 33203 17601 33203 17604 33204 17600 33204 17602 33204 17602 33205 17601 33205 17603 33205 17605 33206 17597 33206 17604 33206 17606 33207 17602 33207 17603 33207 17607 33208 17602 33208 17606 33208 17607 33209 17604 33209 17602 33209 17609 33210 17604 33210 17607 33210 17609 33211 17605 33211 17604 33211 17610 33212 17607 33212 17606 33212 17609 33213 17607 33213 17610 33213 17610 33214 17606 33214 17608 33214 17614 33215 17605 33215 17609 33215 17612 33216 17608 33216 17611 33216 17612 33217 17610 33217 17608 33217 17613 33218 17610 33218 17612 33218 17613 33219 17609 33219 17610 33219 17614 33220 17609 33220 17613 33220 17615 33221 17612 33221 17611 33221 17615 33222 17613 33222 17612 33222 17615 33223 17611 33223 17616 33223 17618 33224 17615 33224 17616 33224 17620 33225 17613 33225 17615 33225 17620 33226 17615 33226 17618 33226 17617 33227 17618 33227 17616 33227 17620 33228 17614 33228 17613 33228 17619 33229 17614 33229 17620 33229 17622 33230 17617 33230 17621 33230 17622 33231 17618 33231 17617 33231 17623 33232 17618 33232 17622 33232 17623 33233 17620 33233 17618 33233 17622 33234 17621 33234 17624 33234 17619 33235 17620 33235 17623 33235 17625 33236 17622 33236 17624 33236 17625 33237 17623 33237 17622 33237 17626 33238 17619 33238 17623 33238 17628 33239 17623 33239 17625 33239 17628 33240 17626 33240 17623 33240 17627 33241 17625 33241 17624 33241 17628 33242 17625 33242 17627 33242 17629 33243 17619 33243 17626 33243 17631 33244 17627 33244 17630 33244 17629 33245 17626 33245 17628 33245 17628 33246 17627 33246 17631 33246 17632 33247 17628 33247 17631 33247 17629 33248 17628 33248 17632 33248 17632 33249 17631 33249 17633 33249 17634 33250 17631 33250 17630 33250 17633 33251 17631 33251 17634 33251 17635 33252 17633 33252 17634 33252 17640 33253 17629 33253 17632 33253 17637 33254 17632 33254 17633 33254 17635 33255 17634 33255 17636 33255 17637 33256 17633 33256 17635 33256 17640 33257 17632 33257 17637 33257 17639 33258 17637 33258 17635 33258 17638 33259 17635 33259 17636 33259 17639 33260 17635 33260 17638 33260 17641 33261 17637 33261 17639 33261 17640 33262 17637 33262 17641 33262 17481 33263 17639 33263 17638 33263 17641 33264 17639 33264 17481 33264 17641 33265 17481 33265 17482 33265 17641 33266 17482 33266 17483 33266 17640 33267 17641 33267 17483 33267 17642 33268 17481 33268 17638 33268 17643 33269 17638 33269 17636 33269 17643 33270 17642 33270 17638 33270 17644 33271 17636 33271 17634 33271 17644 33272 17643 33272 17636 33272 17645 33273 17634 33273 17630 33273 17645 33274 17644 33274 17634 33274 17646 33275 17630 33275 17627 33275 17646 33276 17645 33276 17630 33276 17646 33277 17627 33277 17624 33277 17647 33278 17646 33278 17624 33278 17648 33279 17647 33279 17624 33279 17648 33280 17624 33280 17621 33280 17649 33281 17648 33281 17621 33281 17649 33282 17621 33282 17617 33282 17650 33283 17617 33283 17616 33283 17650 33284 17649 33284 17617 33284 17651 33285 17616 33285 17611 33285 17651 33286 17650 33286 17616 33286 17652 33287 17611 33287 17608 33287 17652 33288 17651 33288 17611 33288 17653 33289 17608 33289 17606 33289 17653 33290 17652 33290 17608 33290 17654 33291 17653 33291 17606 33291 17654 33292 17606 33292 17603 33292 17655 33293 17603 33293 17601 33293 17655 33294 17654 33294 17603 33294 17656 33295 17601 33295 17599 33295 17656 33296 17655 33296 17601 33296 17656 33297 17599 33297 17595 33297 17657 33298 17656 33298 17595 33298 17657 33299 17595 33299 17592 33299 17658 33300 17592 33300 17591 33300 17658 33301 17657 33301 17592 33301 17658 33302 17591 33302 17587 33302 17659 33303 17658 33303 17587 33303 17659 33304 17587 33304 17584 33304 17660 33305 17659 33305 17584 33305 17660 33306 17584 33306 17582 33306 17661 33307 17660 33307 17582 33307 17661 33308 17582 33308 17579 33308 17662 33309 17579 33309 17576 33309 17662 33310 17661 33310 17579 33310 17663 33311 17662 33311 17576 33311 17663 33312 17576 33312 17573 33312 17664 33313 17663 33313 17573 33313 17664 33314 17573 33314 17572 33314 17665 33315 17664 33315 17572 33315 17665 33316 17572 33316 17570 33316 17666 33317 17665 33317 17570 33317 17666 33318 17570 33318 17565 33318 17667 33319 17666 33319 17565 33319 17667 33320 17565 33320 17562 33320 17668 33321 17667 33321 17562 33321 17669 33322 17668 33322 17562 33322 17669 33323 17562 33323 17560 33323 17670 33324 17669 33324 17560 33324 17670 33325 17560 33325 17556 33325 17671 33326 17670 33326 17556 33326 17671 33327 17556 33327 17553 33327 17672 33328 17671 33328 17553 33328 17672 33329 17553 33329 17550 33329 17673 33330 17672 33330 17550 33330 17674 33331 17673 33331 17550 33331 17674 33332 17550 33332 17548 33332 17674 33333 17548 33333 17544 33333 17675 33334 17674 33334 17544 33334 17676 33335 17675 33335 17544 33335 17676 33336 17544 33336 17541 33336 17676 33337 17541 33337 17538 33337 17677 33338 17676 33338 17538 33338 17678 33339 17538 33339 17536 33339 17678 33340 17677 33340 17538 33340 17679 33341 17536 33341 17531 33341 17679 33342 17678 33342 17536 33342 17680 33343 17679 33343 17531 33343 17680 33344 17531 33344 17529 33344 17681 33345 17680 33345 17529 33345 17681 33346 17529 33346 17528 33346 17682 33347 17681 33347 17528 33347 17682 33348 17528 33348 17524 33348 17775 33349 17682 33349 17524 33349 17775 33350 17522 33350 17519 33350 17775 33351 17524 33351 17522 33351 17683 33352 17775 33352 17519 33352 17684 33353 17683 33353 17519 33353 17684 33354 17519 33354 17517 33354 17685 33355 17684 33355 17517 33355 17685 33356 17517 33356 17514 33356 17686 33357 17685 33357 17514 33357 17686 33358 17514 33358 17512 33358 17687 33359 17512 33359 17508 33359 17687 33360 17686 33360 17512 33360 17688 33361 17687 33361 17508 33361 17689 33362 17508 33362 17506 33362 17689 33363 17688 33363 17508 33363 17689 33364 17506 33364 17501 33364 17690 33365 17689 33365 17501 33365 17691 33366 17690 33366 17501 33366 17691 33367 17501 33367 17499 33367 17691 33368 17499 33368 17497 33368 17692 33369 17691 33369 17497 33369 17692 33370 17497 33370 17494 33370 17693 33371 17692 33371 17494 33371 17693 33372 17494 33372 17491 33372 17694 33373 17693 33373 17491 33373 17695 33374 17694 33374 17491 33374 17695 33375 17491 33375 17488 33375 17696 33376 17695 33376 17488 33376 17696 33377 17488 33377 17485 33377 17697 33378 17485 33378 17480 33378 17697 33379 17696 33379 17485 33379 17642 33380 17480 33380 17481 33380 17642 33381 17697 33381 17480 33381 17701 33382 17699 33382 17698 33382 17701 33383 17642 33383 17643 33383 17701 33384 17698 33384 17642 33384 17702 33385 17699 33385 17701 33385 17703 33386 17699 33386 17702 33386 17703 33387 17700 33387 17699 33387 17644 33388 17701 33388 17643 33388 17704 33389 17701 33389 17644 33389 17702 33390 17701 33390 17704 33390 17705 33391 17644 33391 17645 33391 17705 33392 17704 33392 17644 33392 17706 33393 17704 33393 17705 33393 17706 33394 17702 33394 17704 33394 17703 33395 17702 33395 17706 33395 17707 33396 17705 33396 17645 33396 17708 33397 17705 33397 17707 33397 17708 33398 17706 33398 17705 33398 17707 33399 17645 33399 17646 33399 17703 33400 17706 33400 17708 33400 17709 33401 17703 33401 17708 33401 17710 33402 17646 33402 17647 33402 17710 33403 17707 33403 17646 33403 17710 33404 17708 33404 17707 33404 17709 33405 17708 33405 17710 33405 17712 33406 17703 33406 17709 33406 17711 33407 17647 33407 17648 33407 17711 33408 17710 33408 17647 33408 17713 33409 17710 33409 17711 33409 17713 33410 17709 33410 17710 33410 17712 33411 17709 33411 17713 33411 17649 33412 17711 33412 17648 33412 17714 33413 17711 33413 17649 33413 17714 33414 17713 33414 17711 33414 17650 33415 17714 33415 17649 33415 17715 33416 17714 33416 17650 33416 17716 33417 17712 33417 17713 33417 17715 33418 17713 33418 17714 33418 17716 33419 17713 33419 17715 33419 17651 33420 17715 33420 17650 33420 17717 33421 17715 33421 17651 33421 17717 33422 17716 33422 17715 33422 17718 33423 17717 33423 17651 33423 17652 33424 17718 33424 17651 33424 17719 33425 17716 33425 17717 33425 17719 33426 17717 33426 17718 33426 17720 33427 17718 33427 17652 33427 17721 33428 17716 33428 17719 33428 17719 33429 17718 33429 17720 33429 17720 33430 17652 33430 17653 33430 17722 33431 17719 33431 17720 33431 17721 33432 17719 33432 17722 33432 17654 33433 17720 33433 17653 33433 17722 33434 17720 33434 17654 33434 17723 33435 17721 33435 17722 33435 17724 33436 17654 33436 17655 33436 17724 33437 17722 33437 17654 33437 17724 33438 17723 33438 17722 33438 17728 33439 17721 33439 17723 33439 17726 33440 17723 33440 17724 33440 17727 33441 17655 33441 17725 33441 17727 33442 17724 33442 17655 33442 17656 33443 17725 33443 17655 33443 17726 33444 17724 33444 17727 33444 17728 33445 17723 33445 17726 33445 17727 33446 17725 33446 17656 33446 17729 33447 17726 33447 17727 33447 17728 33448 17726 33448 17729 33448 17729 33449 17656 33449 17657 33449 17729 33450 17727 33450 17656 33450 17730 33451 17728 33451 17729 33451 17731 33452 17729 33452 17657 33452 17730 33453 17729 33453 17731 33453 17731 33454 17657 33454 17658 33454 17733 33455 17728 33455 17730 33455 17732 33456 17731 33456 17658 33456 17732 33457 17730 33457 17731 33457 17733 33458 17730 33458 17732 33458 17659 33459 17732 33459 17658 33459 17734 33460 17733 33460 17732 33460 17735 33461 17732 33461 17659 33461 17734 33462 17732 33462 17735 33462 17735 33463 17659 33463 17660 33463 17736 33464 17733 33464 17734 33464 17737 33465 17735 33465 17660 33465 17737 33466 17734 33466 17735 33466 17737 33467 17660 33467 17661 33467 17738 33468 17734 33468 17737 33468 17739 33469 17737 33469 17661 33469 17738 33470 17736 33470 17734 33470 17738 33471 17737 33471 17739 33471 17739 33472 17661 33472 17662 33472 17740 33473 17736 33473 17738 33473 17741 33474 17738 33474 17739 33474 17740 33475 17738 33475 17741 33475 17663 33476 17739 33476 17662 33476 17741 33477 17739 33477 17663 33477 17742 33478 17663 33478 17664 33478 17742 33479 17741 33479 17663 33479 17743 33480 17740 33480 17741 33480 17743 33481 17741 33481 17742 33481 17744 33482 17740 33482 17743 33482 17665 33483 17742 33483 17664 33483 17745 33484 17742 33484 17665 33484 17745 33485 17743 33485 17742 33485 17747 33486 17740 33486 17744 33486 17744 33487 17743 33487 17745 33487 17666 33488 17745 33488 17665 33488 17746 33489 17745 33489 17666 33489 17747 33490 17744 33490 17745 33490 17747 33491 17745 33491 17746 33491 17748 33492 17746 33492 17666 33492 17748 33493 17666 33493 17667 33493 17749 33494 17746 33494 17748 33494 17750 33495 17748 33495 17667 33495 17747 33496 17746 33496 17749 33496 17749 33497 17748 33497 17750 33497 17668 33498 17750 33498 17667 33498 17751 33499 17747 33499 17749 33499 17752 33500 17750 33500 17668 33500 17752 33501 17749 33501 17750 33501 17751 33502 17749 33502 17752 33502 17752 33503 17668 33503 17669 33503 17753 33504 17752 33504 17669 33504 17753 33505 17751 33505 17752 33505 17754 33506 17751 33506 17753 33506 17753 33507 17669 33507 17670 33507 17755 33508 17754 33508 17753 33508 17671 33509 17753 33509 17670 33509 17756 33510 17753 33510 17671 33510 17756 33511 17755 33511 17753 33511 17757 33512 17671 33512 17672 33512 17758 33513 17755 33513 17756 33513 17757 33514 17756 33514 17671 33514 17758 33515 17754 33515 17755 33515 17673 33516 17757 33516 17672 33516 17759 33517 17757 33517 17673 33517 17759 33518 17756 33518 17757 33518 17758 33519 17756 33519 17759 33519 17760 33520 17673 33520 17674 33520 17760 33521 17759 33521 17673 33521 17675 33522 17760 33522 17674 33522 17762 33523 17760 33523 17675 33523 17761 33524 17758 33524 17759 33524 17762 33525 17759 33525 17760 33525 17761 33526 17759 33526 17762 33526 17763 33527 17675 33527 17676 33527 17763 33528 17762 33528 17675 33528 17764 33529 17762 33529 17763 33529 17764 33530 17761 33530 17762 33530 17765 33531 17763 33531 17676 33531 17765 33532 17764 33532 17763 33532 17677 33533 17765 33533 17676 33533 17766 33534 17761 33534 17764 33534 17767 33535 17764 33535 17765 33535 17767 33536 17766 33536 17764 33536 17678 33537 17765 33537 17677 33537 17767 33538 17765 33538 17678 33538 17768 33539 17767 33539 17678 33539 17769 33540 17761 33540 17766 33540 17768 33541 17766 33541 17767 33541 17768 33542 17678 33542 17679 33542 17770 33543 17766 33543 17768 33543 17769 33544 17766 33544 17770 33544 17770 33545 17768 33545 17679 33545 17769 33546 17770 33546 17771 33546 17772 33547 17679 33547 17680 33547 17772 33548 17770 33548 17679 33548 17771 33549 17770 33549 17772 33549 17772 33550 17680 33550 17681 33550 17774 33551 17769 33551 17771 33551 17773 33552 17772 33552 17681 33552 17773 33553 17771 33553 17772 33553 17774 33554 17771 33554 17773 33554 17775 33555 17681 33555 17682 33555 17773 33556 17681 33556 17775 33556 17776 33557 17774 33557 17773 33557 17776 33558 17773 33558 17775 33558 17778 33559 17774 33559 17776 33559 17777 33560 17776 33560 17775 33560 17777 33561 17775 33561 17683 33561 17779 33562 17776 33562 17777 33562 17779 33563 17778 33563 17776 33563 17684 33564 17777 33564 17683 33564 17779 33565 17777 33565 17684 33565 17780 33566 17778 33566 17779 33566 17781 33567 17684 33567 17685 33567 17782 33568 17778 33568 17780 33568 17781 33569 17779 33569 17684 33569 17780 33570 17779 33570 17781 33570 17686 33571 17781 33571 17685 33571 17783 33572 17781 33572 17686 33572 17783 33573 17780 33573 17781 33573 17783 33574 17782 33574 17780 33574 17784 33575 17686 33575 17687 33575 17784 33576 17783 33576 17686 33576 17688 33577 17784 33577 17687 33577 17785 33578 17784 33578 17688 33578 17785 33579 17783 33579 17784 33579 17786 33580 17783 33580 17785 33580 17786 33581 17782 33581 17783 33581 17787 33582 17785 33582 17688 33582 17787 33583 17688 33583 17689 33583 17788 33584 17782 33584 17786 33584 17787 33585 17786 33585 17785 33585 17788 33586 17786 33586 17787 33586 17690 33587 17787 33587 17689 33587 17789 33588 17787 33588 17690 33588 17790 33589 17787 33589 17789 33589 17790 33590 17788 33590 17787 33590 17789 33591 17690 33591 17691 33591 17791 33592 17790 33592 17789 33592 17792 33593 17788 33593 17790 33593 17793 33594 17691 33594 17692 33594 17793 33595 17789 33595 17691 33595 17792 33596 17790 33596 17791 33596 17793 33597 17791 33597 17789 33597 17794 33598 17792 33598 17791 33598 17693 33599 17793 33599 17692 33599 17794 33600 17793 33600 17693 33600 17794 33601 17791 33601 17793 33601 17795 33602 17693 33602 17694 33602 17795 33603 17794 33603 17693 33603 17796 33604 17794 33604 17795 33604 17695 33605 17795 33605 17694 33605 17796 33606 17792 33606 17794 33606 17797 33607 17795 33607 17695 33607 17797 33608 17796 33608 17795 33608 17700 33609 17792 33609 17796 33609 17798 33610 17695 33610 17696 33610 17700 33611 17796 33611 17797 33611 17798 33612 17797 33612 17695 33612 17697 33613 17798 33613 17696 33613 17799 33614 17798 33614 17697 33614 17800 33615 17797 33615 17798 33615 17800 33616 17700 33616 17797 33616 17800 33617 17798 33617 17799 33617 17799 33618 17697 33618 17642 33618 17799 33619 17642 33619 17698 33619 17800 33620 17799 33620 17698 33620 17800 33621 17698 33621 17699 33621 17700 33622 17800 33622 17699 33622 17112 33623 17758 33623 17761 33623 17110 33624 17112 33624 17761 33624 17110 33625 17761 33625 17769 33625 17114 33626 17758 33626 17112 33626 17110 33627 17769 33627 17774 33627 17108 33628 17110 33628 17774 33628 17116 33629 17758 33629 17114 33629 17116 33630 17754 33630 17758 33630 17106 33631 17108 33631 17774 33631 17106 33632 17774 33632 17778 33632 17116 33633 17751 33633 17754 33633 17074 33634 17751 33634 17116 33634 17106 33635 17778 33635 17782 33635 17103 33636 17106 33636 17782 33636 17074 33637 17747 33637 17751 33637 17077 33638 17747 33638 17074 33638 17102 33639 17103 33639 17782 33639 17077 33640 17740 33640 17747 33640 17080 33641 17740 33641 17077 33641 17102 33642 17782 33642 17788 33642 17080 33643 17736 33643 17740 33643 17100 33644 17102 33644 17788 33644 17792 33645 17100 33645 17788 33645 17082 33646 17736 33646 17080 33646 17098 33647 17100 33647 17792 33647 17733 33648 17736 33648 17082 33648 17792 33649 17096 33649 17098 33649 17728 33650 17082 33650 17083 33650 17728 33651 17733 33651 17082 33651 17700 33652 17096 33652 17792 33652 17728 33653 17083 33653 17085 33653 17700 33654 17094 33654 17096 33654 17703 33655 17094 33655 17700 33655 17721 33656 17728 33656 17085 33656 17721 33657 17085 33657 17088 33657 17703 33658 17092 33658 17094 33658 17716 33659 17721 33659 17088 33659 17712 33660 17092 33660 17703 33660 17712 33661 17090 33661 17092 33661 17712 33662 17088 33662 17090 33662 17712 33663 17716 33663 17088 33663 17802 33664 17869 33664 17801 33664 17802 33665 17801 33665 17803 33665 17804 33666 17802 33666 17803 33666 17805 33667 17804 33667 17803 33667 17806 33668 17805 33668 17803 33668 17806 33669 17803 33669 17807 33669 17808 33670 17806 33670 17807 33670 17809 33671 17808 33671 17807 33671 17809 33672 17807 33672 17810 33672 17811 33673 17809 33673 17810 33673 17812 33674 17811 33674 17810 33674 17812 33675 17810 33675 17813 33675 18054 33676 17812 33676 17813 33676 17814 33677 18054 33677 17813 33677 17815 33678 17814 33678 17813 33678 17815 33679 17813 33679 17816 33679 17817 33680 17815 33680 17816 33680 17818 33681 17817 33681 17816 33681 17818 33682 17816 33682 17819 33682 17820 33683 17818 33683 17819 33683 17821 33684 17820 33684 17819 33684 17821 33685 17819 33685 17822 33685 17823 33686 17821 33686 17822 33686 17824 33687 17823 33687 17822 33687 17824 33688 17822 33688 17825 33688 17826 33689 17824 33689 17825 33689 17827 33690 17826 33690 17825 33690 17827 33691 17825 33691 17828 33691 17829 33692 17827 33692 17828 33692 17830 33693 17829 33693 17828 33693 17831 33694 17830 33694 17828 33694 17831 33695 17828 33695 17832 33695 17833 33696 17831 33696 17832 33696 17834 33697 17833 33697 17832 33697 17834 33698 17832 33698 17835 33698 17836 33699 17834 33699 17835 33699 17837 33700 17836 33700 17835 33700 17837 33701 17835 33701 17838 33701 17839 33702 17837 33702 17838 33702 17840 33703 17838 33703 17841 33703 17840 33704 17839 33704 17838 33704 17842 33705 17840 33705 17841 33705 17843 33706 17842 33706 17841 33706 17844 33707 17843 33707 17841 33707 17844 33708 17841 33708 17845 33708 17846 33709 17844 33709 17845 33709 17847 33710 17846 33710 17845 33710 17848 33711 17845 33711 17849 33711 17848 33712 17847 33712 17845 33712 17850 33713 17848 33713 17849 33713 17851 33714 17850 33714 17849 33714 17852 33715 17851 33715 17849 33715 17852 33716 17849 33716 17853 33716 18109 33717 17852 33717 17853 33717 17854 33718 17853 33718 17855 33718 17854 33719 18109 33719 17853 33719 17856 33720 17855 33720 17857 33720 17856 33721 17854 33721 17855 33721 17858 33722 17856 33722 17857 33722 17859 33723 17857 33723 17860 33723 17859 33724 17858 33724 17857 33724 17861 33725 17859 33725 17860 33725 17861 33726 17860 33726 17862 33726 17863 33727 17861 33727 17862 33727 17864 33728 17862 33728 17865 33728 17864 33729 17863 33729 17862 33729 17866 33730 17864 33730 17865 33730 17866 33731 17865 33731 17867 33731 17868 33732 17866 33732 17867 33732 18129 33733 17868 33733 17867 33733 17869 33734 18129 33734 17867 33734 17869 33735 17867 33735 17801 33735 17870 33736 17871 33736 17872 33736 17870 33737 17872 33737 17873 33737 17874 33738 17873 33738 18032 33738 17874 33739 17870 33739 17873 33739 17874 33740 18032 33740 17875 33740 17876 33741 17874 33741 17875 33741 17876 33742 17875 33742 17877 33742 17876 33743 17877 33743 17878 33743 17879 33744 17876 33744 17878 33744 17880 33745 17878 33745 17881 33745 17880 33746 17879 33746 17878 33746 17880 33747 17881 33747 18019 33747 17880 33748 18019 33748 17882 33748 17883 33749 17880 33749 17882 33749 17883 33750 17882 33750 17884 33750 17885 33751 17883 33751 17884 33751 17885 33752 17884 33752 17886 33752 17885 33753 17886 33753 17887 33753 17888 33754 17885 33754 17887 33754 17888 33755 17887 33755 17889 33755 17888 33756 17889 33756 18006 33756 17888 33757 18006 33757 17890 33757 17891 33758 17888 33758 17890 33758 17891 33759 17890 33759 17892 33759 17891 33760 17892 33760 17893 33760 17894 33761 17891 33761 17893 33761 17894 33762 17893 33762 17895 33762 17894 33763 17895 33763 17896 33763 17897 33764 17894 33764 17896 33764 17897 33765 17896 33765 17898 33765 17897 33766 17898 33766 17899 33766 17897 33767 17899 33767 17900 33767 17901 33768 17897 33768 17900 33768 17901 33769 17900 33769 17902 33769 17903 33770 17901 33770 17902 33770 17903 33771 17902 33771 17904 33771 17903 33772 17904 33772 17905 33772 17903 33773 17905 33773 17983 33773 17903 33774 17983 33774 17906 33774 17907 33775 17903 33775 17906 33775 17907 33776 17906 33776 17908 33776 17907 33777 17908 33777 17909 33777 17907 33778 17909 33778 17910 33778 17911 33779 17907 33779 17910 33779 17911 33780 17910 33780 17912 33780 17913 33781 17911 33781 17912 33781 17913 33782 17912 33782 17914 33782 17915 33783 17913 33783 17914 33783 17915 33784 17914 33784 17916 33784 17915 33785 17916 33785 17917 33785 17918 33786 17915 33786 17917 33786 17918 33787 17917 33787 17919 33787 17918 33788 17919 33788 17920 33788 17921 33789 17918 33789 17920 33789 17921 33790 17920 33790 17957 33790 17921 33791 17957 33791 17922 33791 17923 33792 17921 33792 17922 33792 17923 33793 17922 33793 17953 33793 17923 33794 17953 33794 17924 33794 17925 33795 17923 33795 17924 33795 17925 33796 17924 33796 17926 33796 17927 33797 17925 33797 17926 33797 17927 33798 17926 33798 17943 33798 17927 33799 17943 33799 17928 33799 17929 33800 17928 33800 17930 33800 17929 33801 17927 33801 17928 33801 17929 33802 17930 33802 17937 33802 17931 33803 17937 33803 17932 33803 17931 33804 17929 33804 17937 33804 17931 33805 17932 33805 17933 33805 17931 33806 17933 33806 17871 33806 17870 33807 17931 33807 17871 33807 17933 33808 18038 33808 17871 33808 17934 33809 18038 33809 17933 33809 17936 33810 18039 33810 17934 33810 17935 33811 17934 33811 17933 33811 17935 33812 17933 33812 17932 33812 17937 33813 17935 33813 17932 33813 17938 33814 17934 33814 17935 33814 17938 33815 17936 33815 17934 33815 17939 33816 17936 33816 17938 33816 17940 33817 17935 33817 17937 33817 17938 33818 17935 33818 17940 33818 17940 33819 17937 33819 17930 33819 17941 33820 17938 33820 17940 33820 17942 33821 17940 33821 17930 33821 17942 33822 17930 33822 17928 33822 17941 33823 17939 33823 17938 33823 17942 33824 17941 33824 17940 33824 17944 33825 17941 33825 17942 33825 17943 33826 17942 33826 17928 33826 17945 33827 17942 33827 17943 33827 17945 33828 17944 33828 17942 33828 17946 33829 17939 33829 17941 33829 17945 33830 17943 33830 17947 33830 17946 33831 17941 33831 17944 33831 17926 33832 17947 33832 17943 33832 17948 33833 17947 33833 17926 33833 17949 33834 17944 33834 17945 33834 17950 33835 17947 33835 17948 33835 17950 33836 17945 33836 17947 33836 17949 33837 17946 33837 17944 33837 17949 33838 17945 33838 17950 33838 17924 33839 17948 33839 17926 33839 17951 33840 17949 33840 17950 33840 17952 33841 17950 33841 17948 33841 17951 33842 17946 33842 17949 33842 17953 33843 17948 33843 17924 33843 17951 33844 17950 33844 17952 33844 17952 33845 17948 33845 17953 33845 17954 33846 17951 33846 17952 33846 17956 33847 17952 33847 17953 33847 17955 33848 17952 33848 17956 33848 17956 33849 17953 33849 17922 33849 17955 33850 17954 33850 17952 33850 17959 33851 17951 33851 17954 33851 17957 33852 17956 33852 17922 33852 17958 33853 17956 33853 17957 33853 17959 33854 17954 33854 17955 33854 17958 33855 17955 33855 17956 33855 17958 33856 17957 33856 17920 33856 17960 33857 17955 33857 17958 33857 17959 33858 17955 33858 17960 33858 17961 33859 17958 33859 17920 33859 17961 33860 17960 33860 17958 33860 17919 33861 17961 33861 17920 33861 17962 33862 17960 33862 17961 33862 17963 33863 17961 33863 17919 33863 17964 33864 17960 33864 17962 33864 17964 33865 17959 33865 17960 33865 17962 33866 17961 33866 17963 33866 17963 33867 17919 33867 17917 33867 17965 33868 17962 33868 17963 33868 17966 33869 17963 33869 17917 33869 17965 33870 17963 33870 17966 33870 17966 33871 17917 33871 17916 33871 17967 33872 17962 33872 17965 33872 17967 33873 17964 33873 17962 33873 17968 33874 17965 33874 17966 33874 17969 33875 17964 33875 17967 33875 17968 33876 17967 33876 17965 33876 17970 33877 17966 33877 17916 33877 17968 33878 17966 33878 17970 33878 17914 33879 17970 33879 17916 33879 17971 33880 17970 33880 17914 33880 17972 33881 17967 33881 17968 33881 17971 33882 17968 33882 17970 33882 17969 33883 17967 33883 17972 33883 17972 33884 17968 33884 17971 33884 17973 33885 17971 33885 17914 33885 17972 33886 17971 33886 17973 33886 17912 33887 17973 33887 17914 33887 17974 33888 17972 33888 17973 33888 17975 33889 17972 33889 17974 33889 17976 33890 17973 33890 17912 33890 17974 33891 17973 33891 17976 33891 17975 33892 17969 33892 17972 33892 17976 33893 17912 33893 17910 33893 17979 33894 17969 33894 17975 33894 17977 33895 17975 33895 17974 33895 17977 33896 17974 33896 17976 33896 17978 33897 17976 33897 17910 33897 17978 33898 17977 33898 17976 33898 17909 33899 17978 33899 17910 33899 17979 33900 17975 33900 17977 33900 17980 33901 17977 33901 17978 33901 17908 33902 17978 33902 17909 33902 17979 33903 17977 33903 17980 33903 17980 33904 17978 33904 17908 33904 17981 33905 17979 33905 17980 33905 17982 33906 17980 33906 17908 33906 17983 33907 17908 33907 17906 33907 17981 33908 17980 33908 17982 33908 17982 33909 17908 33909 17983 33909 17984 33910 17982 33910 17983 33910 17984 33911 17981 33911 17982 33911 17985 33912 17983 33912 17905 33912 17985 33913 17984 33913 17983 33913 17986 33914 17984 33914 17985 33914 17985 33915 17905 33915 17904 33915 17986 33916 17981 33916 17984 33916 17987 33917 17981 33917 17986 33917 17988 33918 17986 33918 17985 33918 17988 33919 17985 33919 17904 33919 17988 33920 17987 33920 17986 33920 17989 33921 17904 33921 17902 33921 17988 33922 17904 33922 17989 33922 17989 33923 17902 33923 17900 33923 17990 33924 17988 33924 17989 33924 17993 33925 17981 33925 17987 33925 17991 33926 17987 33926 17988 33926 17991 33927 17988 33927 17990 33927 17990 33928 17989 33928 17900 33928 17993 33929 17987 33929 17991 33929 17990 33930 17900 33930 17899 33930 17992 33931 17990 33931 17899 33931 17992 33932 17991 33932 17990 33932 17992 33933 17899 33933 17898 33933 17993 33934 17991 33934 17992 33934 17994 33935 17992 33935 17898 33935 17995 33936 17993 33936 17992 33936 17896 33937 17994 33937 17898 33937 17995 33938 17992 33938 17994 33938 17996 33939 17993 33939 17995 33939 17997 33940 17994 33940 17896 33940 17995 33941 17994 33941 17997 33941 17895 33942 17997 33942 17896 33942 17998 33943 17997 33943 17895 33943 17999 33944 17995 33944 17997 33944 17999 33945 17997 33945 17998 33945 17998 33946 17895 33946 17893 33946 17999 33947 17996 33947 17995 33947 18000 33948 17998 33948 17893 33948 18000 33949 17999 33949 17998 33949 18001 33950 17999 33950 18000 33950 18000 33951 17893 33951 17892 33951 18002 33952 17999 33952 18001 33952 18002 33953 17996 33953 17999 33953 17892 33954 18001 33954 18000 33954 18003 33955 17996 33955 18002 33955 18004 33956 18001 33956 17892 33956 18004 33957 18002 33957 18001 33957 18004 33958 17892 33958 17890 33958 18005 33959 18002 33959 18004 33959 18005 33960 18003 33960 18002 33960 18006 33961 18004 33961 17890 33961 18007 33962 18004 33962 18006 33962 18005 33963 18004 33963 18007 33963 17889 33964 18007 33964 18006 33964 18008 33965 18005 33965 18007 33965 18009 33966 18003 33966 18005 33966 18010 33967 17889 33967 17887 33967 18010 33968 18007 33968 17889 33968 18009 33969 18005 33969 18008 33969 18008 33970 18007 33970 18010 33970 18011 33971 18010 33971 17887 33971 18008 33972 18010 33972 18011 33972 17886 33973 18011 33973 17887 33973 18012 33974 18008 33974 18011 33974 18013 33975 18011 33975 17886 33975 18009 33976 18008 33976 18012 33976 18012 33977 18011 33977 18013 33977 18014 33978 18009 33978 18012 33978 17884 33979 18013 33979 17886 33979 18015 33980 18012 33980 18013 33980 18014 33981 18012 33981 18015 33981 18016 33982 18013 33982 17884 33982 18015 33983 18013 33983 18016 33983 18017 33984 18014 33984 18015 33984 18017 33985 18015 33985 18016 33985 18016 33986 17884 33986 17882 33986 18018 33987 18016 33987 17882 33987 18018 33988 18017 33988 18016 33988 18020 33989 18014 33989 18017 33989 18019 33990 18018 33990 17882 33990 18020 33991 18017 33991 18018 33991 18021 33992 18018 33992 18019 33992 18022 33993 18018 33993 18021 33993 18020 33994 18018 33994 18022 33994 17881 33995 18021 33995 18019 33995 18024 33996 18020 33996 18022 33996 18023 33997 18021 33997 17881 33997 18023 33998 18022 33998 18021 33998 18024 33999 18022 33999 18023 33999 18025 34000 17881 34000 17878 34000 18025 34001 18023 34001 17881 34001 18026 34002 18023 34002 18025 34002 18024 34003 18023 34003 18026 34003 17877 34004 18025 34004 17878 34004 18028 34005 18026 34005 18025 34005 18028 34006 18025 34006 17877 34006 18027 34007 18024 34007 18026 34007 18029 34008 18026 34008 18028 34008 18030 34009 18028 34009 17877 34009 18027 34010 18026 34010 18029 34010 18029 34011 18028 34011 18030 34011 18030 34012 17877 34012 17875 34012 18031 34013 18029 34013 18030 34013 18032 34014 18030 34014 17875 34014 18032 34015 18031 34015 18030 34015 18033 34016 18031 34016 18032 34016 18027 34017 18029 34017 18034 34017 18033 34018 18029 34018 18031 34018 18034 34019 18029 34019 18033 34019 18033 34020 18032 34020 18035 34020 18035 34021 18032 34021 17873 34021 18037 34022 18035 34022 17873 34022 18036 34023 18033 34023 18035 34023 18034 34024 18033 34024 18036 34024 18036 34025 18035 34025 18037 34025 17872 34026 18037 34026 17873 34026 18038 34027 18037 34027 17872 34027 18039 34028 18036 34028 18037 34028 18039 34029 18037 34029 18038 34029 18039 34030 18034 34030 18036 34030 17871 34031 18038 34031 17872 34031 18039 34032 18038 34032 17934 34032 18034 34033 18039 34033 17936 34033 17101 34034 17099 34034 17946 34034 17101 34035 17946 34035 17951 34035 17101 34036 17951 34036 17959 34036 17099 34037 17939 34037 17946 34037 17097 34038 17939 34038 17099 34038 17104 34039 17101 34039 17959 34039 17097 34040 17936 34040 17939 34040 17105 34041 17104 34041 17959 34041 17095 34042 17936 34042 17097 34042 17105 34043 17959 34043 17964 34043 17095 34044 18034 34044 17936 34044 17093 34045 18034 34045 17095 34045 17107 34046 17105 34046 17964 34046 17107 34047 17964 34047 17969 34047 17109 34048 17107 34048 17969 34048 17091 34049 18034 34049 17093 34049 17091 34050 18027 34050 18034 34050 17979 34051 17109 34051 17969 34051 17111 34052 17109 34052 17979 34052 18027 34053 17091 34053 17089 34053 17979 34054 17113 34054 17111 34054 18024 34055 17089 34055 17087 34055 18024 34056 18027 34056 17089 34056 17981 34057 17113 34057 17979 34057 17981 34058 17115 34058 17113 34058 18020 34059 17087 34059 17086 34059 18020 34060 18024 34060 17087 34060 17981 34061 17075 34061 17115 34061 18014 34062 18020 34062 17086 34062 17993 34063 17075 34063 17981 34063 18014 34064 17086 34064 17084 34064 18009 34065 18014 34065 17084 34065 17993 34066 17076 34066 17075 34066 18009 34067 17084 34067 17081 34067 17993 34068 17078 34068 17076 34068 17996 34069 17078 34069 17993 34069 18003 34070 18009 34070 17081 34070 17996 34071 17079 34071 17078 34071 18003 34072 17079 34072 17996 34072 18003 34073 17081 34073 17079 34073 17802 34074 18131 34074 17869 34074 18040 34075 18131 34075 17802 34075 18042 34076 18040 34076 17802 34076 18041 34077 18040 34077 18042 34077 18042 34078 17802 34078 17804 34078 18046 34079 18132 34079 18041 34079 18043 34080 18041 34080 18042 34080 17805 34081 18042 34081 17804 34081 18044 34082 18042 34082 17805 34082 18043 34083 18042 34083 18044 34083 18046 34084 18041 34084 18043 34084 18045 34085 17805 34085 17806 34085 18045 34086 18044 34086 17805 34086 18046 34087 18044 34087 18045 34087 18046 34088 18043 34088 18044 34088 18045 34089 17806 34089 17808 34089 18047 34090 18046 34090 18045 34090 18048 34091 18045 34091 17808 34091 18047 34092 18045 34092 18048 34092 18048 34093 17808 34093 17809 34093 18049 34094 18046 34094 18047 34094 18050 34095 18047 34095 18048 34095 18049 34096 18047 34096 18050 34096 17811 34097 18048 34097 17809 34097 18050 34098 18048 34098 17811 34098 18051 34099 18050 34099 17811 34099 18051 34100 18049 34100 18050 34100 18051 34101 17811 34101 17812 34101 18052 34102 18049 34102 18051 34102 18053 34103 18051 34103 17812 34103 18053 34104 17812 34104 18054 34104 18052 34105 18051 34105 18053 34105 18055 34106 18053 34106 18054 34106 18056 34107 18054 34107 17814 34107 18052 34108 18053 34108 18055 34108 18055 34109 18054 34109 18056 34109 18057 34110 18055 34110 18056 34110 18056 34111 17814 34111 17815 34111 18057 34112 18052 34112 18055 34112 18058 34113 18052 34113 18057 34113 18059 34114 18056 34114 17815 34114 18059 34115 18057 34115 18056 34115 18060 34116 18057 34116 18059 34116 18060 34117 18058 34117 18057 34117 18059 34118 17815 34118 17817 34118 18061 34119 18058 34119 18060 34119 17818 34120 18059 34120 17817 34120 18062 34121 18059 34121 17818 34121 18062 34122 18060 34122 18059 34122 18063 34123 18060 34123 18062 34123 18063 34124 18061 34124 18060 34124 18064 34125 18062 34125 17818 34125 18064 34126 18063 34126 18062 34126 18064 34127 17818 34127 17820 34127 18065 34128 18063 34128 18064 34128 18066 34129 18063 34129 18065 34129 18065 34130 18064 34130 17820 34130 18066 34131 18061 34131 18063 34131 18065 34132 17820 34132 17821 34132 18067 34133 18065 34133 17821 34133 18066 34134 18065 34134 18067 34134 18068 34135 18067 34135 17821 34135 18068 34136 17821 34136 17823 34136 18069 34137 18067 34137 18068 34137 18069 34138 18066 34138 18067 34138 18070 34139 18068 34139 17823 34139 18070 34140 18069 34140 18068 34140 18073 34141 18066 34141 18069 34141 17824 34142 18070 34142 17823 34142 18071 34143 18069 34143 18070 34143 18072 34144 17824 34144 17826 34144 18072 34145 18070 34145 17824 34145 18073 34146 18069 34146 18071 34146 18071 34147 18070 34147 18072 34147 18074 34148 18072 34148 17826 34148 18074 34149 18071 34149 18072 34149 18075 34150 18071 34150 18074 34150 18074 34151 17826 34151 17827 34151 18073 34152 18071 34152 18075 34152 18076 34153 18074 34153 17827 34153 18076 34154 18075 34154 18074 34154 18077 34155 18073 34155 18075 34155 18078 34156 18075 34156 18076 34156 17829 34157 18076 34157 17827 34157 18078 34158 18077 34158 18075 34158 18078 34159 18076 34159 17829 34159 18079 34160 17829 34160 17830 34160 18080 34161 18078 34161 18079 34161 18079 34162 18078 34162 17829 34162 18080 34163 18077 34163 18078 34163 18081 34164 18077 34164 18080 34164 17831 34165 18079 34165 17830 34165 18082 34166 18079 34166 17831 34166 18083 34167 18079 34167 18082 34167 18083 34168 18080 34168 18079 34168 18083 34169 18081 34169 18080 34169 17833 34170 18082 34170 17831 34170 18084 34171 18083 34171 18082 34171 18085 34172 18082 34172 17833 34172 18085 34173 18084 34173 18082 34173 18087 34174 18081 34174 18083 34174 18086 34175 18083 34175 18084 34175 18086 34176 18084 34176 18085 34176 18087 34177 18083 34177 18086 34177 18088 34178 17833 34178 17834 34178 18088 34179 18085 34179 17833 34179 18088 34180 18086 34180 18085 34180 17836 34181 18088 34181 17834 34181 18089 34182 18086 34182 18088 34182 18090 34183 18088 34183 17836 34183 18087 34184 18086 34184 18089 34184 18090 34185 18089 34185 18088 34185 18090 34186 17836 34186 17837 34186 18087 34187 18089 34187 18091 34187 18091 34188 18089 34188 18090 34188 18093 34189 18087 34189 18091 34189 17839 34190 18090 34190 17837 34190 18092 34191 18090 34191 17839 34191 18091 34192 18090 34192 18092 34192 18094 34193 18091 34193 18092 34193 18094 34194 18093 34194 18091 34194 17840 34195 18092 34195 17839 34195 18094 34196 18092 34196 17840 34196 17842 34197 18094 34197 17840 34197 18096 34198 18093 34198 18094 34198 18095 34199 18094 34199 17842 34199 18096 34200 18094 34200 18095 34200 17843 34201 18095 34201 17842 34201 18097 34202 18096 34202 18095 34202 18097 34203 18095 34203 17843 34203 18097 34204 17843 34204 17844 34204 18098 34205 18096 34205 18097 34205 18098 34206 18097 34206 18099 34206 18099 34207 18097 34207 17844 34207 18100 34208 17844 34208 17846 34208 18100 34209 18099 34209 17844 34209 17847 34210 18100 34210 17846 34210 18101 34211 18099 34211 18100 34211 18102 34212 18098 34212 18099 34212 17848 34213 18100 34213 17847 34213 18102 34214 18099 34214 18101 34214 17848 34215 18101 34215 18100 34215 18102 34216 18101 34216 18103 34216 18104 34217 18101 34217 17848 34217 18103 34218 18101 34218 18104 34218 18104 34219 17848 34219 17850 34219 18105 34220 18104 34220 17850 34220 18105 34221 17850 34221 17851 34221 18106 34222 18104 34222 18105 34222 18106 34223 18103 34223 18104 34223 18106 34224 18102 34224 18103 34224 18107 34225 17851 34225 17852 34225 18107 34226 18105 34226 17851 34226 18107 34227 18106 34227 18105 34227 18108 34228 18102 34228 18106 34228 18109 34229 18107 34229 17852 34229 18110 34230 18107 34230 18109 34230 18110 34231 18106 34231 18107 34231 18110 34232 18108 34232 18106 34232 18111 34233 18110 34233 18109 34233 18111 34234 18109 34234 17854 34234 17856 34235 18111 34235 17854 34235 18108 34236 18110 34236 18111 34236 18112 34237 18111 34237 17856 34237 18113 34238 18108 34238 18111 34238 18113 34239 18111 34239 18112 34239 18114 34240 18112 34240 17856 34240 18114 34241 17856 34241 17858 34241 18117 34242 18108 34242 18113 34242 18117 34243 18113 34243 18112 34243 18115 34244 18112 34244 18114 34244 17859 34245 18114 34245 17858 34245 18115 34246 18117 34246 18112 34246 18116 34247 18114 34247 17859 34247 18115 34248 18114 34248 18116 34248 17861 34249 18116 34249 17859 34249 18118 34250 18115 34250 18116 34250 18118 34251 18117 34251 18115 34251 18119 34252 18117 34252 18118 34252 18120 34253 18116 34253 17861 34253 18118 34254 18116 34254 18120 34254 17863 34255 18120 34255 17861 34255 18121 34256 18118 34256 18120 34256 18121 34257 18120 34257 17863 34257 18122 34258 18118 34258 18121 34258 18122 34259 18119 34259 18118 34259 18123 34260 17863 34260 17864 34260 18123 34261 18121 34261 17863 34261 18122 34262 18121 34262 18123 34262 18124 34263 18119 34263 18122 34263 18125 34264 18122 34264 18123 34264 17866 34265 18123 34265 17864 34265 18124 34266 18122 34266 18125 34266 18125 34267 18123 34267 17866 34267 18126 34268 18125 34268 17866 34268 18127 34269 18124 34269 18125 34269 18126 34270 17866 34270 17868 34270 18128 34271 18125 34271 18126 34271 18129 34272 18126 34272 17868 34272 18128 34273 18126 34273 18129 34273 18128 34274 18127 34274 18125 34274 18127 34275 18128 34275 18130 34275 18130 34276 18128 34276 18129 34276 18131 34277 18129 34277 17869 34277 18131 34278 18130 34278 18129 34278 18133 34279 18127 34279 18130 34279 18132 34280 18127 34280 18133 34280 18133 34281 18130 34281 18131 34281 18133 34282 18131 34282 18040 34282 18133 34283 18040 34283 18041 34283 18132 34284 18133 34284 18041 34284 17132 34285 18096 34285 18098 34285 17134 34286 18096 34286 17132 34286 17130 34287 17132 34287 18098 34287 17130 34288 18098 34288 18102 34288 17134 34289 18093 34289 18096 34289 17136 34290 18093 34290 17134 34290 17129 34291 17130 34291 18102 34291 17136 34292 18087 34292 18093 34292 17129 34293 18102 34293 18108 34293 17138 34294 18087 34294 17136 34294 17126 34295 17129 34295 18108 34295 17140 34296 18087 34296 17138 34296 17140 34297 18081 34297 18087 34297 17126 34298 18108 34298 18117 34298 17124 34299 17126 34299 18117 34299 17124 34300 18117 34300 18119 34300 17143 34301 18081 34301 17140 34301 17143 34302 18077 34302 18081 34302 17144 34303 18077 34303 17143 34303 17122 34304 17124 34304 18119 34304 18073 34305 18077 34305 17144 34305 18124 34306 17122 34306 18119 34306 18073 34307 17144 34307 17147 34307 18124 34308 17120 34308 17122 34308 18066 34309 18073 34309 17147 34309 18127 34310 17120 34310 18124 34310 18127 34311 17117 34311 17120 34311 18066 34312 17147 34312 17149 34312 18132 34313 17117 34313 18127 34313 18066 34314 17149 34314 17150 34314 18061 34315 18066 34315 17150 34315 18132 34316 17159 34316 17117 34316 18046 34317 17159 34317 18132 34317 18058 34318 18061 34318 17150 34318 18058 34319 17150 34319 17153 34319 18046 34320 17157 34320 17159 34320 18052 34321 18058 34321 17153 34321 18046 34322 17155 34322 17157 34322 18049 34323 17155 34323 18046 34323 18052 34324 17153 34324 17155 34324 18049 34325 18052 34325 17155 34325 18135 34326 18134 34326 18212 34326 18135 34327 18212 34327 18136 34327 18137 34328 18135 34328 18136 34328 18138 34329 18137 34329 18136 34329 18139 34330 18138 34330 18136 34330 18139 34331 18136 34331 18140 34331 18141 34332 18139 34332 18140 34332 18142 34333 18141 34333 18140 34333 18142 34334 18140 34334 18143 34334 18144 34335 18142 34335 18143 34335 18145 34336 18144 34336 18143 34336 18146 34337 18145 34337 18143 34337 18146 34338 18143 34338 18147 34338 18148 34339 18146 34339 18147 34339 18149 34340 18148 34340 18147 34340 18149 34341 18147 34341 18150 34341 18151 34342 18149 34342 18150 34342 18152 34343 18151 34343 18150 34343 18153 34344 18150 34344 18154 34344 18153 34345 18152 34345 18150 34345 18155 34346 18153 34346 18154 34346 18156 34347 18155 34347 18154 34347 18156 34348 18154 34348 18157 34348 18158 34349 18156 34349 18157 34349 18159 34350 18158 34350 18157 34350 18160 34351 18159 34351 18157 34351 18160 34352 18157 34352 18161 34352 18162 34353 18160 34353 18161 34353 18163 34354 18162 34354 18161 34354 18163 34355 18161 34355 18164 34355 18165 34356 18163 34356 18164 34356 18166 34357 18165 34357 18164 34357 18167 34358 18164 34358 18168 34358 18167 34359 18166 34359 18164 34359 18169 34360 18167 34360 18168 34360 18170 34361 18168 34361 18171 34361 18170 34362 18169 34362 18168 34362 18172 34363 18170 34363 18171 34363 18173 34364 18172 34364 18171 34364 18173 34365 18171 34365 18174 34365 18175 34366 18173 34366 18174 34366 18176 34367 18175 34367 18174 34367 18176 34368 18174 34368 18177 34368 18178 34369 18176 34369 18177 34369 18179 34370 18178 34370 18177 34370 18180 34371 18179 34371 18177 34371 18180 34372 18177 34372 18181 34372 18182 34373 18180 34373 18181 34373 18183 34374 18182 34374 18181 34374 18184 34375 18181 34375 18185 34375 18184 34376 18183 34376 18181 34376 18186 34377 18184 34377 18185 34377 18187 34378 18186 34378 18185 34378 18187 34379 18185 34379 18188 34379 18189 34380 18187 34380 18188 34380 18190 34381 18189 34381 18188 34381 18191 34382 18190 34382 18188 34382 18191 34383 18188 34383 18192 34383 18193 34384 18191 34384 18192 34384 18194 34385 18192 34385 18195 34385 18194 34386 18193 34386 18192 34386 18196 34387 18194 34387 18195 34387 18196 34388 18195 34388 18197 34388 18198 34389 18196 34389 18197 34389 18199 34390 18198 34390 18197 34390 18200 34391 18199 34391 18197 34391 18200 34392 18197 34392 18201 34392 18202 34393 18200 34393 18201 34393 18203 34394 18202 34394 18201 34394 18203 34395 18201 34395 18204 34395 18205 34396 18203 34396 18204 34396 18206 34397 18205 34397 18204 34397 18207 34398 18206 34398 18204 34398 18208 34399 18207 34399 18204 34399 18208 34400 18204 34400 18209 34400 18210 34401 18208 34401 18209 34401 18211 34402 18210 34402 18209 34402 18211 34403 18209 34403 18212 34403 18213 34404 18211 34404 18212 34404 18134 34405 18213 34405 18212 34405 18214 34406 18215 34406 18216 34406 18217 34407 18216 34407 18389 34407 18217 34408 18214 34408 18216 34408 18217 34409 18389 34409 18218 34409 18219 34410 18218 34410 18383 34410 18219 34411 18217 34411 18218 34411 18219 34412 18383 34412 18220 34412 18219 34413 18220 34413 18221 34413 18222 34414 18219 34414 18221 34414 18222 34415 18221 34415 18223 34415 18222 34416 18223 34416 18224 34416 18225 34417 18222 34417 18224 34417 18225 34418 18224 34418 18226 34418 18227 34419 18226 34419 18228 34419 18227 34420 18225 34420 18226 34420 18227 34421 18228 34421 18369 34421 18227 34422 18369 34422 18229 34422 18230 34423 18227 34423 18229 34423 18230 34424 18229 34424 18365 34424 18230 34425 18365 34425 18362 34425 18231 34426 18230 34426 18362 34426 18231 34427 18362 34427 18232 34427 18231 34428 18232 34428 18233 34428 18234 34429 18231 34429 18233 34429 18234 34430 18233 34430 18235 34430 18234 34431 18235 34431 18236 34431 18237 34432 18234 34432 18236 34432 18237 34433 18236 34433 18238 34433 18237 34434 18238 34434 18239 34434 18237 34435 18239 34435 18240 34435 18241 34436 18237 34436 18240 34436 18241 34437 18240 34437 18242 34437 18241 34438 18242 34438 18243 34438 18244 34439 18243 34439 18245 34439 18244 34440 18241 34440 18243 34440 18244 34441 18245 34441 18337 34441 18246 34442 18244 34442 18337 34442 18246 34443 18337 34443 18247 34443 18246 34444 18247 34444 18248 34444 18249 34445 18246 34445 18248 34445 18249 34446 18248 34446 18250 34446 18249 34447 18250 34447 18251 34447 18249 34448 18251 34448 18326 34448 18252 34449 18249 34449 18326 34449 18252 34450 18326 34450 18253 34450 18252 34451 18253 34451 18254 34451 18255 34452 18252 34452 18254 34452 18255 34453 18254 34453 18256 34453 18257 34454 18256 34454 18258 34454 18257 34455 18255 34455 18256 34455 18257 34456 18258 34456 18259 34456 18257 34457 18259 34457 18313 34457 18260 34458 18313 34458 18261 34458 18260 34459 18257 34459 18313 34459 18260 34460 18261 34460 18262 34460 18260 34461 18262 34461 18263 34461 18264 34462 18260 34462 18263 34462 18264 34463 18263 34463 18265 34463 18264 34464 18265 34464 18266 34464 18267 34465 18264 34465 18266 34465 18267 34466 18266 34466 18302 34466 18268 34467 18302 34467 18269 34467 18268 34468 18267 34468 18302 34468 18268 34469 18269 34469 18298 34469 18268 34470 18298 34470 18270 34470 18271 34471 18270 34471 18272 34471 18271 34472 18268 34472 18270 34472 18271 34473 18272 34473 18294 34473 18273 34474 18271 34474 18294 34474 18273 34475 18294 34475 18274 34475 18273 34476 18274 34476 18275 34476 18273 34477 18275 34477 18276 34477 18277 34478 18273 34478 18276 34478 18277 34479 18276 34479 18278 34479 18277 34480 18278 34480 18279 34480 18280 34481 18277 34481 18279 34481 18280 34482 18279 34482 18281 34482 18214 34483 18281 34483 18215 34483 18214 34484 18280 34484 18281 34484 18282 34485 18215 34485 18281 34485 18282 34486 18391 34486 18215 34486 18283 34487 18391 34487 18282 34487 18279 34488 18282 34488 18281 34488 18285 34489 18282 34489 18279 34489 18285 34490 18283 34490 18282 34490 18284 34491 18283 34491 18285 34491 18286 34492 18279 34492 18278 34492 18287 34493 18284 34493 18285 34493 18286 34494 18285 34494 18279 34494 18287 34495 18285 34495 18286 34495 18286 34496 18278 34496 18276 34496 18288 34497 18286 34497 18276 34497 18288 34498 18287 34498 18286 34498 18275 34499 18288 34499 18276 34499 18289 34500 18287 34500 18288 34500 18290 34501 18288 34501 18275 34501 18291 34502 18288 34502 18290 34502 18289 34503 18288 34503 18291 34503 18292 34504 18287 34504 18289 34504 18274 34505 18290 34505 18275 34505 18291 34506 18290 34506 18274 34506 18293 34507 18289 34507 18291 34507 18294 34508 18291 34508 18274 34508 18292 34509 18289 34509 18293 34509 18293 34510 18291 34510 18294 34510 18295 34511 18292 34511 18293 34511 18272 34512 18293 34512 18294 34512 18296 34513 18293 34513 18272 34513 18297 34514 18272 34514 18270 34514 18296 34515 18295 34515 18293 34515 18297 34516 18296 34516 18272 34516 18298 34517 18297 34517 18270 34517 18299 34518 18297 34518 18298 34518 18300 34519 18295 34519 18296 34519 18300 34520 18296 34520 18297 34520 18300 34521 18297 34521 18299 34521 18269 34522 18299 34522 18298 34522 18301 34523 18300 34523 18299 34523 18301 34524 18299 34524 18269 34524 18302 34525 18301 34525 18269 34525 18303 34526 18301 34526 18302 34526 18303 34527 18300 34527 18301 34527 18304 34528 18300 34528 18303 34528 18305 34529 18302 34529 18266 34529 18305 34530 18303 34530 18302 34530 18306 34531 18303 34531 18305 34531 18265 34532 18305 34532 18266 34532 18306 34533 18304 34533 18303 34533 18307 34534 18306 34534 18305 34534 18307 34535 18305 34535 18265 34535 18309 34536 18304 34536 18306 34536 18263 34537 18307 34537 18265 34537 18309 34538 18306 34538 18307 34538 18308 34539 18307 34539 18263 34539 18310 34540 18307 34540 18308 34540 18309 34541 18307 34541 18310 34541 18311 34542 18308 34542 18263 34542 18311 34543 18263 34543 18262 34543 18311 34544 18310 34544 18308 34544 18312 34545 18309 34545 18310 34545 18312 34546 18310 34546 18311 34546 18261 34547 18311 34547 18262 34547 18315 34548 18309 34548 18312 34548 18313 34549 18311 34549 18261 34549 18314 34550 18311 34550 18313 34550 18314 34551 18312 34551 18311 34551 18315 34552 18312 34552 18314 34552 18318 34553 18309 34553 18315 34553 18316 34554 18315 34554 18314 34554 18317 34555 18313 34555 18259 34555 18314 34556 18313 34556 18317 34556 18319 34557 18314 34557 18317 34557 18319 34558 18316 34558 18314 34558 18317 34559 18259 34559 18258 34559 18318 34560 18315 34560 18316 34560 18320 34561 18317 34561 18258 34561 18319 34562 18317 34562 18320 34562 18318 34563 18316 34563 18319 34563 18320 34564 18258 34564 18256 34564 18321 34565 18319 34565 18320 34565 18321 34566 18318 34566 18319 34566 18322 34567 18320 34567 18256 34567 18323 34568 18318 34568 18321 34568 18322 34569 18321 34569 18320 34569 18322 34570 18256 34570 18254 34570 18324 34571 18321 34571 18322 34571 18324 34572 18323 34572 18321 34572 18325 34573 18254 34573 18253 34573 18325 34574 18322 34574 18254 34574 18324 34575 18322 34575 18325 34575 18326 34576 18325 34576 18253 34576 18328 34577 18325 34577 18326 34577 18327 34578 18323 34578 18324 34578 18328 34579 18324 34579 18325 34579 18328 34580 18326 34580 18251 34580 18329 34581 18324 34581 18328 34581 18329 34582 18327 34582 18324 34582 18330 34583 18328 34583 18251 34583 18331 34584 18327 34584 18329 34584 18329 34585 18328 34585 18330 34585 18250 34586 18330 34586 18251 34586 18332 34587 18330 34587 18250 34587 18333 34588 18329 34588 18330 34588 18333 34589 18330 34589 18332 34589 18331 34590 18329 34590 18333 34590 18332 34591 18250 34591 18248 34591 18334 34592 18333 34592 18332 34592 18334 34593 18332 34593 18248 34593 18334 34594 18248 34594 18247 34594 18335 34595 18331 34595 18333 34595 18336 34596 18333 34596 18334 34596 18336 34597 18335 34597 18333 34597 18337 34598 18334 34598 18247 34598 18337 34599 18336 34599 18334 34599 18338 34600 18336 34600 18337 34600 18338 34601 18335 34601 18336 34601 18340 34602 18335 34602 18338 34602 18339 34603 18338 34603 18337 34603 18339 34604 18337 34604 18245 34604 18341 34605 18338 34605 18339 34605 18342 34606 18335 34606 18340 34606 18340 34607 18338 34607 18341 34607 18341 34608 18339 34608 18245 34608 18343 34609 18245 34609 18243 34609 18343 34610 18341 34610 18245 34610 18344 34611 18341 34611 18343 34611 18344 34612 18340 34612 18341 34612 18344 34613 18342 34613 18340 34613 18345 34614 18343 34614 18243 34614 18345 34615 18344 34615 18343 34615 18346 34616 18344 34616 18345 34616 18345 34617 18243 34617 18242 34617 18346 34618 18342 34618 18344 34618 18347 34619 18345 34619 18242 34619 18348 34620 18342 34620 18346 34620 18347 34621 18242 34621 18240 34621 18346 34622 18345 34622 18347 34622 18349 34623 18346 34623 18347 34623 18239 34624 18347 34624 18240 34624 18348 34625 18346 34625 18349 34625 18349 34626 18347 34626 18239 34626 18351 34627 18348 34627 18349 34627 18352 34628 18349 34628 18239 34628 18350 34629 18348 34629 18351 34629 18351 34630 18349 34630 18352 34630 18352 34631 18239 34631 18238 34631 18353 34632 18352 34632 18238 34632 18354 34633 18350 34633 18351 34633 18236 34634 18353 34634 18238 34634 18354 34635 18351 34635 18352 34635 18353 34636 18354 34636 18352 34636 18355 34637 18236 34637 18235 34637 18355 34638 18353 34638 18236 34638 18356 34639 18353 34639 18355 34639 18357 34640 18350 34640 18354 34640 18356 34641 18354 34641 18353 34641 18357 34642 18354 34642 18356 34642 18233 34643 18355 34643 18235 34643 18358 34644 18355 34644 18233 34644 18358 34645 18356 34645 18355 34645 18359 34646 18357 34646 18356 34646 18359 34647 18356 34647 18358 34647 18363 34648 18357 34648 18359 34648 18360 34649 18233 34649 18232 34649 18360 34650 18358 34650 18233 34650 18360 34651 18359 34651 18358 34651 18361 34652 18359 34652 18360 34652 18362 34653 18360 34653 18232 34653 18364 34654 18360 34654 18362 34654 18363 34655 18359 34655 18361 34655 18364 34656 18361 34656 18360 34656 18365 34657 18364 34657 18362 34657 18367 34658 18361 34658 18364 34658 18363 34659 18361 34659 18367 34659 18366 34660 18364 34660 18365 34660 18367 34661 18364 34661 18366 34661 18366 34662 18365 34662 18229 34662 18368 34663 18367 34663 18366 34663 18369 34664 18366 34664 18229 34664 18370 34665 18363 34665 18367 34665 18368 34666 18366 34666 18369 34666 18370 34667 18367 34667 18368 34667 18368 34668 18369 34668 18371 34668 18371 34669 18369 34669 18228 34669 18370 34670 18368 34670 18371 34670 18372 34671 18371 34671 18228 34671 18372 34672 18228 34672 18226 34672 18373 34673 18370 34673 18371 34673 18376 34674 18370 34674 18373 34674 18374 34675 18371 34675 18372 34675 18224 34676 18372 34676 18226 34676 18374 34677 18373 34677 18371 34677 18374 34678 18372 34678 18224 34678 18375 34679 18224 34679 18223 34679 18375 34680 18374 34680 18224 34680 18376 34681 18373 34681 18374 34681 18377 34682 18374 34682 18375 34682 18378 34683 18223 34683 18221 34683 18378 34684 18375 34684 18223 34684 18376 34685 18374 34685 18377 34685 18377 34686 18375 34686 18378 34686 18379 34687 18221 34687 18220 34687 18381 34688 18377 34688 18378 34688 18379 34689 18378 34689 18221 34689 18381 34690 18376 34690 18377 34690 18380 34691 18376 34691 18381 34691 18381 34692 18378 34692 18379 34692 18382 34693 18379 34693 18220 34693 18382 34694 18381 34694 18379 34694 18384 34695 18381 34695 18382 34695 18383 34696 18382 34696 18220 34696 18384 34697 18380 34697 18381 34697 18385 34698 18382 34698 18383 34698 18384 34699 18382 34699 18385 34699 18386 34700 18383 34700 18218 34700 18385 34701 18383 34701 18386 34701 18387 34702 18384 34702 18385 34702 18388 34703 18385 34703 18386 34703 18388 34704 18387 34704 18385 34704 18389 34705 18386 34705 18218 34705 18388 34706 18386 34706 18389 34706 18391 34707 18389 34707 18216 34707 18390 34708 18387 34708 18388 34708 18391 34709 18388 34709 18389 34709 18390 34710 18388 34710 18391 34710 18215 34711 18391 34711 18216 34711 18390 34712 18391 34712 18283 34712 18390 34713 18283 34713 18284 34713 18284 34714 18387 34714 18390 34714 17927 34715 18292 34715 18295 34715 17927 34716 18295 34716 17925 34716 17923 34717 17925 34717 18295 34717 17923 34718 18295 34718 18300 34718 17929 34719 18292 34719 17927 34719 17929 34720 18287 34720 18292 34720 17921 34721 17923 34721 18300 34721 17929 34722 18284 34722 18287 34722 17921 34723 18300 34723 18304 34723 17931 34724 18284 34724 17929 34724 17918 34725 17921 34725 18304 34725 17918 34726 18304 34726 18309 34726 17870 34727 18284 34727 17931 34727 17915 34728 17918 34728 18309 34728 17870 34729 18387 34729 18284 34729 18318 34730 17915 34730 18309 34730 17874 34731 18387 34731 17870 34731 17913 34732 17915 34732 18318 34732 17874 34733 18384 34733 18387 34733 17874 34734 18380 34734 18384 34734 17911 34735 17913 34735 18318 34735 17876 34736 18380 34736 17874 34736 18318 34737 17907 34737 17911 34737 18376 34738 18380 34738 17876 34738 18323 34739 17907 34739 18318 34739 18376 34740 17876 34740 17879 34740 18327 34741 17907 34741 18323 34741 18376 34742 17879 34742 17880 34742 18327 34743 17903 34743 17907 34743 18370 34744 18376 34744 17880 34744 18331 34745 17903 34745 18327 34745 18370 34746 17880 34746 17883 34746 18335 34747 17901 34747 17903 34747 18335 34748 17903 34748 18331 34748 18363 34749 18370 34749 17883 34749 18363 34750 17883 34750 17885 34750 18335 34751 17897 34751 17901 34751 18342 34752 17897 34752 18335 34752 18363 34753 17885 34753 17888 34753 18357 34754 18363 34754 17888 34754 18342 34755 17894 34755 17897 34755 18350 34756 18357 34756 17888 34756 18348 34757 17894 34757 18342 34757 18348 34758 17891 34758 17894 34758 18350 34759 17888 34759 17891 34759 18348 34760 18350 34760 17891 34760 18392 34761 18134 34761 18135 34761 18393 34762 18394 34762 18392 34762 18395 34763 18394 34763 18393 34763 18393 34764 18392 34764 18135 34764 18396 34765 18393 34765 18135 34765 18395 34766 18393 34766 18396 34766 18396 34767 18135 34767 18137 34767 18397 34768 18396 34768 18137 34768 18397 34769 18137 34769 18138 34769 18398 34770 18395 34770 18396 34770 18398 34771 18396 34771 18397 34771 18399 34772 18138 34772 18139 34772 18399 34773 18397 34773 18138 34773 18400 34774 18395 34774 18398 34774 18399 34775 18398 34775 18397 34775 18401 34776 18398 34776 18399 34776 18141 34777 18399 34777 18139 34777 18402 34778 18399 34778 18141 34778 18400 34779 18398 34779 18401 34779 18401 34780 18399 34780 18402 34780 18402 34781 18141 34781 18142 34781 18403 34782 18402 34782 18142 34782 18403 34783 18401 34783 18402 34783 18144 34784 18403 34784 18142 34784 18404 34785 18401 34785 18403 34785 18404 34786 18400 34786 18401 34786 18405 34787 18403 34787 18144 34787 18404 34788 18403 34788 18405 34788 18405 34789 18144 34789 18145 34789 18406 34790 18400 34790 18404 34790 18407 34791 18405 34791 18145 34791 18408 34792 18405 34792 18407 34792 18408 34793 18404 34793 18405 34793 18407 34794 18145 34794 18146 34794 18409 34795 18404 34795 18408 34795 18409 34796 18406 34796 18404 34796 18148 34797 18407 34797 18146 34797 18408 34798 18407 34798 18148 34798 18411 34799 18406 34799 18409 34799 18410 34800 18408 34800 18148 34800 18410 34801 18409 34801 18408 34801 18411 34802 18409 34802 18410 34802 18149 34803 18410 34803 18148 34803 18412 34804 18410 34804 18149 34804 18411 34805 18410 34805 18412 34805 18151 34806 18412 34806 18149 34806 18414 34807 18411 34807 18412 34807 18415 34808 18151 34808 18152 34808 18415 34809 18412 34809 18151 34809 18414 34810 18412 34810 18415 34810 18413 34811 18411 34811 18414 34811 18415 34812 18152 34812 18153 34812 18413 34813 18414 34813 18416 34813 18416 34814 18414 34814 18415 34814 18417 34815 18415 34815 18153 34815 18416 34816 18415 34816 18417 34816 18417 34817 18153 34817 18155 34817 18418 34818 18417 34818 18155 34818 18416 34819 18417 34819 18418 34819 18419 34820 18413 34820 18416 34820 18420 34821 18416 34821 18418 34821 18156 34822 18418 34822 18155 34822 18421 34823 18418 34823 18156 34823 18419 34824 18416 34824 18420 34824 18421 34825 18420 34825 18418 34825 18421 34826 18156 34826 18158 34826 18419 34827 18420 34827 18421 34827 18422 34828 18158 34828 18159 34828 18422 34829 18421 34829 18158 34829 18423 34830 18421 34830 18422 34830 18422 34831 18159 34831 18160 34831 18423 34832 18419 34832 18421 34832 18425 34833 18419 34833 18423 34833 18424 34834 18422 34834 18160 34834 18424 34835 18160 34835 18162 34835 18424 34836 18423 34836 18422 34836 18425 34837 18423 34837 18424 34837 18426 34838 18162 34838 18163 34838 18426 34839 18424 34839 18162 34839 18428 34840 18424 34840 18426 34840 18428 34841 18425 34841 18424 34841 18427 34842 18425 34842 18428 34842 18165 34843 18426 34843 18163 34843 18428 34844 18426 34844 18165 34844 18429 34845 18427 34845 18428 34845 18166 34846 18428 34846 18165 34846 18430 34847 18428 34847 18166 34847 18429 34848 18428 34848 18430 34848 18430 34849 18166 34849 18167 34849 18431 34850 18430 34850 18167 34850 18434 34851 18427 34851 18429 34851 18431 34852 18167 34852 18169 34852 18432 34853 18429 34853 18430 34853 18434 34854 18429 34854 18432 34854 18433 34855 18430 34855 18431 34855 18432 34856 18430 34856 18433 34856 18170 34857 18431 34857 18169 34857 18435 34858 18431 34858 18170 34858 18435 34859 18433 34859 18431 34859 18436 34860 18433 34860 18435 34860 18436 34861 18432 34861 18433 34861 18434 34862 18432 34862 18436 34862 18172 34863 18435 34863 18170 34863 18172 34864 18436 34864 18435 34864 18437 34865 18434 34865 18436 34865 18438 34866 18436 34866 18172 34866 18439 34867 18172 34867 18173 34867 18438 34868 18437 34868 18436 34868 18438 34869 18172 34869 18439 34869 18440 34870 18173 34870 18175 34870 18440 34871 18439 34871 18173 34871 18437 34872 18438 34872 18439 34872 18441 34873 18439 34873 18440 34873 18176 34874 18440 34874 18175 34874 18441 34875 18437 34875 18439 34875 18442 34876 18437 34876 18441 34876 18443 34877 18440 34877 18176 34877 18441 34878 18440 34878 18443 34878 18443 34879 18176 34879 18178 34879 18444 34880 18441 34880 18443 34880 18444 34881 18443 34881 18178 34881 18444 34882 18442 34882 18441 34882 18445 34883 18442 34883 18444 34883 18179 34884 18444 34884 18178 34884 18446 34885 18444 34885 18179 34885 18446 34886 18445 34886 18444 34886 18447 34887 18179 34887 18180 34887 18447 34888 18446 34888 18179 34888 18448 34889 18180 34889 18182 34889 18449 34890 18446 34890 18447 34890 18448 34891 18447 34891 18180 34891 18450 34892 18446 34892 18449 34892 18450 34893 18445 34893 18446 34893 18449 34894 18447 34894 18448 34894 18183 34895 18448 34895 18182 34895 18451 34896 18448 34896 18183 34896 18451 34897 18449 34897 18448 34897 18452 34898 18449 34898 18451 34898 18451 34899 18183 34899 18184 34899 18452 34900 18450 34900 18449 34900 18453 34901 18451 34901 18184 34901 18454 34902 18450 34902 18452 34902 18453 34903 18184 34903 18186 34903 18455 34904 18451 34904 18453 34904 18455 34905 18452 34905 18451 34905 18454 34906 18452 34906 18455 34906 18456 34907 18453 34907 18186 34907 18455 34908 18453 34908 18456 34908 18187 34909 18456 34909 18186 34909 18457 34910 18456 34910 18187 34910 18457 34911 18455 34911 18456 34911 18458 34912 18455 34912 18457 34912 18458 34913 18454 34913 18455 34913 18459 34914 18457 34914 18187 34914 18461 34915 18457 34915 18459 34915 18461 34916 18458 34916 18457 34916 18460 34917 18454 34917 18458 34917 18189 34918 18459 34918 18187 34918 18462 34919 18459 34919 18189 34919 18460 34920 18458 34920 18461 34920 18462 34921 18461 34921 18459 34921 18190 34922 18462 34922 18189 34922 18463 34923 18462 34923 18190 34923 18464 34924 18462 34924 18463 34924 18464 34925 18461 34925 18462 34925 18464 34926 18460 34926 18461 34926 18463 34927 18190 34927 18191 34927 18465 34928 18460 34928 18464 34928 18466 34929 18460 34929 18465 34929 18465 34930 18464 34930 18463 34930 18193 34931 18463 34931 18191 34931 18465 34932 18463 34932 18193 34932 18467 34933 18465 34933 18193 34933 18468 34934 18193 34934 18194 34934 18466 34935 18465 34935 18467 34935 18468 34936 18467 34936 18193 34936 18469 34937 18467 34937 18468 34937 18470 34938 18467 34938 18469 34938 18470 34939 18466 34939 18467 34939 18196 34940 18468 34940 18194 34940 18469 34941 18468 34941 18196 34941 18471 34942 18196 34942 18198 34942 18471 34943 18469 34943 18196 34943 18472 34944 18469 34944 18471 34944 18472 34945 18470 34945 18469 34945 18199 34946 18471 34946 18198 34946 18473 34947 18471 34947 18199 34947 18474 34948 18470 34948 18472 34948 18473 34949 18472 34949 18471 34949 18474 34950 18472 34950 18473 34950 18475 34951 18199 34951 18200 34951 18475 34952 18473 34952 18199 34952 18474 34953 18473 34953 18476 34953 18476 34954 18473 34954 18475 34954 18202 34955 18475 34955 18200 34955 18477 34956 18475 34956 18202 34956 18477 34957 18476 34957 18475 34957 18478 34958 18476 34958 18477 34958 18203 34959 18477 34959 18202 34959 18478 34960 18474 34960 18476 34960 18479 34961 18477 34961 18203 34961 18480 34962 18474 34962 18478 34962 18478 34963 18477 34963 18479 34963 18205 34964 18479 34964 18203 34964 18481 34965 18479 34965 18205 34965 18480 34966 18479 34966 18481 34966 18480 34967 18478 34967 18479 34967 18206 34968 18481 34968 18205 34968 18482 34969 18481 34969 18206 34969 18482 34970 18480 34970 18481 34970 18483 34971 18480 34971 18482 34971 18207 34972 18482 34972 18206 34972 18484 34973 18482 34973 18207 34973 18485 34974 18480 34974 18483 34974 18483 34975 18482 34975 18484 34975 18484 34976 18207 34976 18208 34976 18485 34977 18483 34977 18484 34977 18486 34978 18208 34978 18210 34978 18486 34979 18484 34979 18208 34979 18487 34980 18485 34980 18484 34980 18487 34981 18484 34981 18486 34981 18489 34982 18485 34982 18487 34982 18211 34983 18486 34983 18210 34983 18488 34984 18486 34984 18211 34984 18488 34985 18487 34985 18486 34985 18489 34986 18487 34986 18488 34986 18213 34987 18488 34987 18211 34987 18490 34988 18488 34988 18213 34988 18489 34989 18488 34989 18490 34989 18394 34990 18489 34990 18490 34990 18490 34991 18134 34991 18392 34991 18490 34992 18213 34992 18134 34992 18394 34993 18490 34993 18392 34993 18395 34994 18489 34994 18394 34994 17845 34995 17841 34995 18454 34995 17841 34996 18450 34996 18454 34996 17845 34997 18454 34997 18460 34997 17841 34998 18445 34998 18450 34998 17838 34999 18445 34999 17841 34999 17849 35000 17845 35000 18460 35000 17835 35001 18445 35001 17838 35001 17853 35002 17849 35002 18460 35002 17853 35003 18460 35003 18466 35003 17835 35004 18442 35004 18445 35004 17832 35005 18442 35005 17835 35005 17855 35006 17853 35006 18466 35006 17832 35007 18437 35007 18442 35007 17855 35008 18466 35008 18470 35008 17857 35009 17855 35009 18470 35009 17828 35010 18437 35010 17832 35010 17828 35011 18434 35011 18437 35011 17857 35012 18470 35012 18474 35012 17860 35013 17857 35013 18474 35013 17828 35014 18427 35014 18434 35014 17862 35015 17860 35015 18474 35015 17825 35016 18427 35016 17828 35016 17862 35017 18474 35017 18480 35017 18480 35018 17865 35018 17862 35018 18485 35019 17865 35019 18480 35019 17822 35020 18427 35020 17825 35020 18425 35021 18427 35021 17822 35021 17867 35022 17865 35022 18485 35022 18489 35023 17867 35023 18485 35023 18419 35024 18425 35024 17822 35024 17819 35025 18419 35025 17822 35025 18395 35026 17867 35026 18489 35026 18413 35027 18419 35027 17819 35027 18413 35028 17819 35028 17816 35028 18395 35029 17801 35029 17867 35029 18395 35030 17803 35030 17801 35030 18413 35031 17816 35031 17813 35031 18400 35032 17803 35032 18395 35032 18411 35033 18413 35033 17813 35033 18400 35034 17807 35034 17803 35034 18406 35035 18411 35035 17813 35035 18406 35036 17813 35036 17810 35036 18400 35037 18406 35037 17810 35037 18400 35038 17810 35038 17807 35038 18493 35039 18491 35039 18492 35039 18493 35040 18492 35040 18494 35040 18495 35041 18493 35041 18494 35041 18496 35042 18495 35042 18494 35042 18496 35043 18494 35043 18497 35043 18498 35044 18496 35044 18497 35044 18499 35045 18497 35045 18500 35045 18499 35046 18498 35046 18497 35046 18501 35047 18499 35047 18500 35047 18502 35048 18501 35048 18500 35048 18502 35049 18500 35049 18503 35049 18504 35050 18502 35050 18503 35050 18505 35051 18504 35051 18503 35051 18505 35052 18503 35052 18506 35052 18507 35053 18505 35053 18506 35053 18508 35054 18507 35054 18506 35054 18508 35055 18506 35055 18509 35055 18510 35056 18508 35056 18509 35056 18511 35057 18510 35057 18509 35057 18511 35058 18509 35058 18512 35058 18513 35059 18511 35059 18512 35059 18514 35060 18512 35060 18515 35060 18514 35061 18513 35061 18512 35061 18516 35062 18514 35062 18515 35062 18517 35063 18516 35063 18515 35063 18517 35064 18515 35064 18518 35064 18519 35065 18517 35065 18518 35065 18519 35066 18518 35066 18520 35066 18521 35067 18519 35067 18520 35067 18522 35068 18521 35068 18520 35068 18523 35069 18522 35069 18520 35069 18523 35070 18520 35070 18524 35070 18525 35071 18523 35071 18524 35071 18525 35072 18524 35072 18526 35072 18527 35073 18525 35073 18526 35073 18528 35074 18526 35074 18529 35074 18528 35075 18527 35075 18526 35075 18530 35076 18528 35076 18529 35076 18530 35077 18529 35077 18531 35077 18532 35078 18530 35078 18531 35078 18533 35079 18532 35079 18531 35079 18534 35080 18533 35080 18531 35080 18535 35081 18534 35081 18531 35081 18535 35082 18531 35082 18536 35082 18537 35083 18535 35083 18536 35083 18538 35084 18537 35084 18536 35084 18538 35085 18536 35085 18539 35085 18540 35086 18538 35086 18539 35086 18540 35087 18539 35087 18541 35087 18542 35088 18540 35088 18541 35088 18543 35089 18542 35089 18541 35089 18543 35090 18541 35090 18544 35090 18545 35091 18543 35091 18544 35091 18546 35092 18544 35092 18547 35092 18546 35093 18545 35093 18544 35093 18548 35094 18546 35094 18547 35094 18548 35095 18547 35095 18549 35095 18550 35096 18548 35096 18549 35096 18551 35097 18549 35097 18552 35097 18551 35098 18550 35098 18549 35098 18553 35099 18551 35099 18552 35099 18554 35100 18553 35100 18552 35100 18554 35101 18552 35101 18555 35101 18556 35102 18554 35102 18555 35102 18557 35103 18556 35103 18555 35103 18557 35104 18555 35104 18558 35104 18559 35105 18557 35105 18558 35105 18560 35106 18559 35106 18558 35106 18560 35107 18558 35107 18561 35107 18562 35108 18560 35108 18561 35108 18563 35109 18562 35109 18561 35109 18563 35110 18561 35110 18564 35110 18854 35111 18563 35111 18564 35111 18565 35112 18854 35112 18564 35112 18566 35113 18564 35113 18567 35113 18566 35114 18565 35114 18564 35114 18568 35115 18566 35115 18567 35115 18568 35116 18567 35116 18569 35116 18570 35117 18568 35117 18569 35117 18571 35118 18570 35118 18569 35118 18571 35119 18569 35119 18572 35119 18573 35120 18571 35120 18572 35120 18574 35121 18573 35121 18572 35121 18491 35122 18574 35122 18572 35122 18491 35123 18572 35123 18492 35123 18575 35124 18576 35124 18577 35124 18575 35125 18577 35125 18761 35125 18578 35126 18761 35126 18579 35126 18578 35127 18575 35127 18761 35127 18578 35128 18579 35128 18580 35128 18581 35129 18578 35129 18580 35129 18581 35130 18580 35130 18582 35130 18583 35131 18581 35131 18582 35131 18583 35132 18582 35132 18584 35132 18583 35133 18584 35133 18585 35133 18586 35134 18585 35134 18587 35134 18586 35135 18583 35135 18585 35135 18586 35136 18587 35136 18745 35136 18588 35137 18745 35137 18743 35137 18588 35138 18586 35138 18745 35138 18588 35139 18743 35139 18740 35139 18588 35140 18740 35140 18589 35140 18590 35141 18588 35141 18589 35141 18590 35142 18589 35142 18591 35142 18592 35143 18590 35143 18591 35143 18592 35144 18591 35144 18593 35144 18592 35145 18593 35145 18594 35145 18592 35146 18594 35146 18595 35146 18596 35147 18592 35147 18595 35147 18596 35148 18595 35148 18597 35148 18596 35149 18597 35149 18598 35149 18599 35150 18596 35150 18598 35150 18599 35151 18598 35151 18600 35151 18601 35152 18599 35152 18600 35152 18601 35153 18600 35153 18602 35153 18601 35154 18602 35154 18719 35154 18603 35155 18601 35155 18719 35155 18603 35156 18719 35156 18604 35156 18605 35157 18603 35157 18604 35157 18605 35158 18604 35158 18606 35158 18605 35159 18606 35159 18607 35159 18608 35160 18607 35160 18609 35160 18608 35161 18605 35161 18607 35161 18610 35162 18609 35162 18611 35162 18610 35163 18608 35163 18609 35163 18610 35164 18611 35164 18612 35164 18613 35165 18610 35165 18612 35165 18613 35166 18612 35166 18614 35166 18613 35167 18614 35167 18615 35167 18613 35168 18615 35168 18616 35168 18617 35169 18613 35169 18616 35169 18617 35170 18616 35170 18618 35170 18619 35171 18617 35171 18618 35171 18619 35172 18618 35172 18620 35172 18619 35173 18620 35173 18696 35173 18619 35174 18696 35174 18621 35174 18622 35175 18621 35175 18623 35175 18622 35176 18619 35176 18621 35176 18622 35177 18623 35177 18624 35177 18625 35178 18622 35178 18624 35178 18625 35179 18624 35179 18626 35179 18625 35180 18626 35180 18627 35180 18628 35181 18625 35181 18627 35181 18628 35182 18627 35182 18629 35182 18630 35183 18628 35183 18629 35183 18630 35184 18629 35184 18631 35184 18630 35185 18631 35185 18680 35185 18630 35186 18680 35186 18632 35186 18633 35187 18632 35187 18634 35187 18633 35188 18630 35188 18632 35188 18633 35189 18634 35189 18635 35189 18636 35190 18633 35190 18635 35190 18636 35191 18635 35191 18637 35191 18636 35192 18637 35192 18638 35192 18639 35193 18638 35193 18640 35193 18639 35194 18636 35194 18638 35194 18639 35195 18640 35195 18641 35195 18642 35196 18641 35196 18643 35196 18642 35197 18639 35197 18641 35197 18642 35198 18643 35198 18644 35198 18645 35199 18642 35199 18644 35199 18645 35200 18644 35200 18646 35200 18647 35201 18645 35201 18646 35201 18647 35202 18646 35202 18648 35202 18647 35203 18648 35203 18649 35203 18650 35204 18647 35204 18649 35204 18650 35205 18649 35205 18651 35205 18650 35206 18651 35206 18576 35206 18575 35207 18650 35207 18576 35207 18653 35208 18764 35208 18652 35208 18655 35209 18764 35209 18653 35209 18654 35210 18652 35210 18576 35210 18653 35211 18652 35211 18654 35211 18651 35212 18654 35212 18576 35212 18656 35213 18655 35213 18653 35213 18657 35214 18653 35214 18654 35214 18658 35215 18654 35215 18651 35215 18657 35216 18654 35216 18658 35216 18658 35217 18651 35217 18649 35217 18656 35218 18653 35218 18657 35218 18659 35219 18657 35219 18658 35219 18660 35220 18649 35220 18648 35220 18659 35221 18656 35221 18657 35221 18660 35222 18658 35222 18649 35222 18660 35223 18659 35223 18658 35223 18661 35224 18656 35224 18659 35224 18646 35225 18660 35225 18648 35225 18662 35226 18660 35226 18646 35226 18662 35227 18659 35227 18660 35227 18662 35228 18646 35228 18644 35228 18661 35229 18659 35229 18662 35229 18663 35230 18662 35230 18644 35230 18661 35231 18662 35231 18663 35231 18664 35232 18661 35232 18663 35232 18643 35233 18663 35233 18644 35233 18665 35234 18663 35234 18643 35234 18666 35235 18661 35235 18664 35235 18664 35236 18663 35236 18665 35236 18667 35237 18665 35237 18643 35237 18668 35238 18664 35238 18665 35238 18668 35239 18665 35239 18667 35239 18666 35240 18664 35240 18668 35240 18641 35241 18667 35241 18643 35241 18669 35242 18668 35242 18667 35242 18669 35243 18666 35243 18668 35243 18640 35244 18667 35244 18641 35244 18669 35245 18667 35245 18640 35245 18670 35246 18666 35246 18669 35246 18671 35247 18669 35247 18640 35247 18672 35248 18640 35248 18638 35248 18672 35249 18671 35249 18640 35249 18671 35250 18670 35250 18669 35250 18637 35251 18672 35251 18638 35251 18673 35252 18671 35252 18672 35252 18673 35253 18670 35253 18671 35253 18673 35254 18672 35254 18637 35254 18674 35255 18637 35255 18635 35255 18674 35256 18673 35256 18637 35256 18677 35257 18670 35257 18673 35257 18675 35258 18673 35258 18674 35258 18676 35259 18674 35259 18635 35259 18675 35260 18674 35260 18676 35260 18676 35261 18635 35261 18634 35261 18677 35262 18673 35262 18675 35262 18678 35263 18675 35263 18676 35263 18677 35264 18675 35264 18678 35264 18632 35265 18676 35265 18634 35265 18678 35266 18676 35266 18632 35266 18679 35267 18677 35267 18678 35267 18680 35268 18678 35268 18632 35268 18681 35269 18678 35269 18680 35269 18681 35270 18679 35270 18678 35270 18682 35271 18681 35271 18680 35271 18682 35272 18680 35272 18631 35272 18683 35273 18681 35273 18682 35273 18683 35274 18679 35274 18681 35274 18684 35275 18682 35275 18631 35275 18684 35276 18683 35276 18682 35276 18685 35277 18679 35277 18683 35277 18686 35278 18631 35278 18629 35278 18686 35279 18684 35279 18631 35279 18683 35280 18684 35280 18686 35280 18685 35281 18683 35281 18686 35281 18627 35282 18686 35282 18629 35282 18687 35283 18686 35283 18627 35283 18689 35284 18686 35284 18687 35284 18689 35285 18685 35285 18686 35285 18626 35286 18687 35286 18627 35286 18690 35287 18687 35287 18626 35287 18688 35288 18685 35288 18689 35288 18690 35289 18689 35289 18687 35289 18691 35290 18689 35290 18690 35290 18688 35291 18689 35291 18691 35291 18692 35292 18688 35292 18691 35292 18624 35293 18690 35293 18626 35293 18624 35294 18691 35294 18690 35294 18693 35295 18624 35295 18623 35295 18693 35296 18691 35296 18624 35296 18694 35297 18691 35297 18693 35297 18694 35298 18692 35298 18691 35298 18695 35299 18692 35299 18694 35299 18621 35300 18693 35300 18623 35300 18695 35301 18694 35301 18693 35301 18696 35302 18693 35302 18621 35302 18698 35303 18692 35303 18695 35303 18697 35304 18693 35304 18696 35304 18697 35305 18695 35305 18693 35305 18698 35306 18695 35306 18697 35306 18698 35307 18697 35307 18699 35307 18620 35308 18697 35308 18696 35308 18700 35309 18697 35309 18620 35309 18700 35310 18699 35310 18697 35310 18618 35311 18700 35311 18620 35311 18701 35312 18700 35312 18618 35312 18702 35313 18700 35313 18701 35313 18702 35314 18699 35314 18700 35314 18701 35315 18618 35315 18616 35315 18698 35316 18699 35316 18702 35316 18703 35317 18701 35317 18616 35317 18703 35318 18702 35318 18701 35318 18705 35319 18698 35319 18702 35319 18704 35320 18703 35320 18616 35320 18706 35321 18702 35321 18703 35321 18704 35322 18616 35322 18615 35322 18705 35323 18702 35323 18706 35323 18706 35324 18703 35324 18704 35324 18707 35325 18706 35325 18704 35325 18614 35326 18704 35326 18615 35326 18707 35327 18704 35327 18614 35327 18708 35328 18706 35328 18707 35328 18709 35329 18614 35329 18612 35329 18708 35330 18705 35330 18706 35330 18709 35331 18707 35331 18614 35331 18708 35332 18707 35332 18709 35332 18711 35333 18705 35333 18708 35333 18710 35334 18612 35334 18611 35334 18710 35335 18709 35335 18612 35335 18710 35336 18708 35336 18709 35336 18712 35337 18708 35337 18710 35337 18711 35338 18708 35338 18712 35338 18713 35339 18611 35339 18609 35339 18713 35340 18710 35340 18611 35340 18713 35341 18712 35341 18710 35341 18714 35342 18713 35342 18609 35342 18714 35343 18712 35343 18713 35343 18607 35344 18714 35344 18609 35344 18715 35345 18712 35345 18714 35345 18715 35346 18711 35346 18712 35346 18606 35347 18714 35347 18607 35347 18716 35348 18714 35348 18606 35348 18716 35349 18715 35349 18714 35349 18718 35350 18711 35350 18715 35350 18718 35351 18715 35351 18716 35351 18717 35352 18606 35352 18604 35352 18717 35353 18716 35353 18606 35353 18718 35354 18716 35354 18717 35354 18719 35355 18717 35355 18604 35355 18721 35356 18717 35356 18719 35356 18721 35357 18718 35357 18717 35357 18721 35358 18719 35358 18602 35358 18720 35359 18718 35359 18721 35359 18722 35360 18721 35360 18602 35360 18723 35361 18721 35361 18722 35361 18723 35362 18720 35362 18721 35362 18722 35363 18602 35363 18600 35363 18724 35364 18722 35364 18600 35364 18723 35365 18722 35365 18724 35365 18598 35366 18724 35366 18600 35366 18725 35367 18724 35367 18598 35367 18727 35368 18720 35368 18723 35368 18726 35369 18724 35369 18725 35369 18726 35370 18723 35370 18724 35370 18727 35371 18723 35371 18726 35371 18597 35372 18725 35372 18598 35372 18597 35373 18726 35373 18725 35373 18728 35374 18726 35374 18597 35374 18727 35375 18726 35375 18728 35375 18728 35376 18597 35376 18595 35376 18729 35377 18728 35377 18595 35377 18731 35378 18727 35378 18728 35378 18731 35379 18730 35379 18727 35379 18731 35380 18728 35380 18729 35380 18594 35381 18729 35381 18595 35381 18732 35382 18729 35382 18594 35382 18732 35383 18731 35383 18729 35383 18732 35384 18594 35384 18593 35384 18733 35385 18730 35385 18731 35385 18734 35386 18731 35386 18732 35386 18733 35387 18731 35387 18734 35387 18735 35388 18732 35388 18593 35388 18734 35389 18732 35389 18735 35389 18735 35390 18593 35390 18591 35390 18736 35391 18730 35391 18733 35391 18737 35392 18734 35392 18735 35392 18737 35393 18733 35393 18734 35393 18738 35394 18733 35394 18737 35394 18736 35395 18733 35395 18738 35395 18737 35396 18735 35396 18591 35396 18739 35397 18591 35397 18589 35397 18739 35398 18737 35398 18591 35398 18738 35399 18737 35399 18739 35399 18740 35400 18739 35400 18589 35400 18741 35401 18738 35401 18739 35401 18741 35402 18736 35402 18738 35402 18742 35403 18739 35403 18740 35403 18741 35404 18739 35404 18742 35404 18743 35405 18742 35405 18740 35405 18744 35406 18736 35406 18741 35406 18746 35407 18743 35407 18745 35407 18746 35408 18742 35408 18743 35408 18746 35409 18741 35409 18742 35409 18747 35410 18745 35410 18587 35410 18744 35411 18741 35411 18746 35411 18747 35412 18746 35412 18745 35412 18748 35413 18746 35413 18747 35413 18747 35414 18587 35414 18585 35414 18748 35415 18744 35415 18746 35415 18749 35416 18747 35416 18585 35416 18749 35417 18748 35417 18747 35417 18750 35418 18748 35418 18749 35418 18750 35419 18744 35419 18748 35419 18753 35420 18744 35420 18750 35420 18584 35421 18749 35421 18585 35421 18751 35422 18749 35422 18584 35422 18752 35423 18749 35423 18751 35423 18752 35424 18750 35424 18749 35424 18753 35425 18750 35425 18752 35425 18754 35426 18751 35426 18584 35426 18754 35427 18752 35427 18751 35427 18753 35428 18752 35428 18754 35428 18582 35429 18754 35429 18584 35429 18755 35430 18754 35430 18582 35430 18756 35431 18754 35431 18755 35431 18756 35432 18753 35432 18754 35432 18580 35433 18755 35433 18582 35433 18580 35434 18756 35434 18755 35434 18757 35435 18756 35435 18580 35435 18757 35436 18753 35436 18756 35436 18758 35437 18753 35437 18757 35437 18759 35438 18580 35438 18579 35438 18759 35439 18757 35439 18580 35439 18760 35440 18757 35440 18759 35440 18758 35441 18757 35441 18760 35441 18760 35442 18759 35442 18579 35442 18761 35443 18760 35443 18579 35443 18762 35444 18758 35444 18760 35444 18763 35445 18760 35445 18761 35445 18763 35446 18762 35446 18760 35446 18763 35447 18761 35447 18577 35447 18655 35448 18758 35448 18762 35448 18764 35449 18762 35449 18763 35449 18655 35450 18762 35450 18764 35450 18577 35451 18576 35451 18652 35451 18763 35452 18577 35452 18652 35452 18764 35453 18763 35453 18652 35453 18273 35454 18666 35454 18271 35454 18268 35455 18666 35455 18670 35455 18268 35456 18271 35456 18666 35456 18273 35457 18661 35457 18666 35457 18268 35458 18670 35458 18677 35458 18277 35459 18661 35459 18273 35459 18267 35460 18268 35460 18677 35460 18280 35461 18656 35461 18661 35461 18280 35462 18661 35462 18277 35462 18267 35463 18677 35463 18679 35463 18280 35464 18655 35464 18656 35464 18264 35465 18267 35465 18679 35465 18214 35466 18655 35466 18280 35466 18264 35467 18679 35467 18685 35467 18217 35468 18758 35468 18655 35468 18217 35469 18655 35469 18214 35469 18260 35470 18264 35470 18685 35470 18688 35471 18260 35471 18685 35471 18219 35472 18758 35472 18217 35472 18257 35473 18260 35473 18688 35473 18692 35474 18257 35474 18688 35474 18219 35475 18753 35475 18758 35475 18222 35476 18753 35476 18219 35476 18255 35477 18257 35477 18692 35477 18698 35478 18255 35478 18692 35478 18744 35479 18222 35479 18225 35479 18744 35480 18753 35480 18222 35480 18698 35481 18252 35481 18255 35481 18744 35482 18225 35482 18227 35482 18698 35483 18249 35483 18252 35483 18705 35484 18249 35484 18698 35484 18736 35485 18744 35485 18227 35485 18736 35486 18227 35486 18230 35486 18711 35487 18249 35487 18705 35487 18711 35488 18246 35488 18249 35488 18736 35489 18230 35489 18231 35489 18730 35490 18736 35490 18231 35490 18711 35491 18244 35491 18246 35491 18730 35492 18231 35492 18234 35492 18711 35493 18241 35493 18244 35493 18727 35494 18730 35494 18234 35494 18718 35495 18241 35495 18711 35495 18727 35496 18234 35496 18237 35496 18720 35497 18727 35497 18237 35497 18720 35498 18241 35498 18718 35498 18720 35499 18237 35499 18241 35499 18493 35500 18765 35500 18491 35500 18766 35501 18767 35501 18765 35501 18768 35502 18765 35502 18493 35502 18768 35503 18766 35503 18765 35503 18495 35504 18768 35504 18493 35504 18769 35505 18767 35505 18766 35505 18770 35506 18766 35506 18768 35506 18769 35507 18766 35507 18770 35507 18496 35508 18768 35508 18495 35508 18770 35509 18768 35509 18496 35509 18772 35510 18770 35510 18496 35510 18771 35511 18770 35511 18772 35511 18772 35512 18496 35512 18498 35512 18771 35513 18769 35513 18770 35513 18771 35514 18772 35514 18773 35514 18499 35515 18772 35515 18498 35515 18773 35516 18772 35516 18499 35516 18775 35517 18771 35517 18773 35517 18774 35518 18773 35518 18499 35518 18775 35519 18773 35519 18774 35519 18774 35520 18499 35520 18501 35520 18776 35521 18771 35521 18775 35521 18777 35522 18775 35522 18774 35522 18777 35523 18776 35523 18775 35523 18778 35524 18501 35524 18502 35524 18778 35525 18774 35525 18501 35525 18778 35526 18777 35526 18774 35526 18504 35527 18778 35527 18502 35527 18779 35528 18778 35528 18504 35528 18780 35529 18778 35529 18779 35529 18780 35530 18777 35530 18778 35530 18779 35531 18504 35531 18505 35531 18780 35532 18776 35532 18777 35532 18781 35533 18779 35533 18505 35533 18782 35534 18776 35534 18780 35534 18781 35535 18780 35535 18779 35535 18783 35536 18780 35536 18781 35536 18507 35537 18781 35537 18505 35537 18782 35538 18780 35538 18783 35538 18784 35539 18781 35539 18507 35539 18784 35540 18783 35540 18781 35540 18508 35541 18784 35541 18507 35541 18786 35542 18783 35542 18784 35542 18785 35543 18783 35543 18786 35543 18786 35544 18784 35544 18508 35544 18782 35545 18783 35545 18785 35545 18510 35546 18786 35546 18508 35546 18787 35547 18786 35547 18510 35547 18788 35548 18786 35548 18787 35548 18789 35549 18782 35549 18785 35549 18789 35550 18785 35550 18786 35550 18789 35551 18786 35551 18788 35551 18511 35552 18787 35552 18510 35552 18790 35553 18787 35553 18511 35553 18790 35554 18788 35554 18787 35554 18790 35555 18789 35555 18788 35555 18791 35556 18789 35556 18790 35556 18792 35557 18511 35557 18513 35557 18792 35558 18790 35558 18511 35558 18792 35559 18791 35559 18790 35559 18793 35560 18789 35560 18791 35560 18514 35561 18792 35561 18513 35561 18794 35562 18792 35562 18514 35562 18794 35563 18791 35563 18792 35563 18793 35564 18791 35564 18794 35564 18795 35565 18514 35565 18516 35565 18794 35566 18514 35566 18795 35566 18797 35567 18794 35567 18795 35567 18797 35568 18793 35568 18794 35568 18796 35569 18795 35569 18516 35569 18797 35570 18795 35570 18796 35570 18796 35571 18516 35571 18517 35571 18798 35572 18793 35572 18797 35572 18799 35573 18796 35573 18517 35573 18799 35574 18797 35574 18796 35574 18798 35575 18797 35575 18799 35575 18799 35576 18517 35576 18519 35576 18800 35577 18799 35577 18519 35577 18800 35578 18519 35578 18521 35578 18801 35579 18799 35579 18800 35579 18801 35580 18798 35580 18799 35580 18522 35581 18800 35581 18521 35581 18802 35582 18800 35582 18522 35582 18803 35583 18800 35583 18802 35583 18803 35584 18801 35584 18800 35584 18804 35585 18522 35585 18523 35585 18804 35586 18802 35586 18522 35586 18806 35587 18801 35587 18803 35587 18805 35588 18802 35588 18804 35588 18805 35589 18803 35589 18802 35589 18806 35590 18803 35590 18805 35590 18807 35591 18804 35591 18523 35591 18805 35592 18804 35592 18807 35592 18807 35593 18523 35593 18525 35593 18808 35594 18805 35594 18807 35594 18808 35595 18806 35595 18805 35595 18527 35596 18807 35596 18525 35596 18809 35597 18807 35597 18527 35597 18808 35598 18807 35598 18809 35598 18810 35599 18806 35599 18808 35599 18809 35600 18527 35600 18528 35600 18811 35601 18808 35601 18809 35601 18810 35602 18808 35602 18811 35602 18812 35603 18810 35603 18811 35603 18813 35604 18809 35604 18528 35604 18813 35605 18811 35605 18809 35605 18813 35606 18528 35606 18530 35606 18816 35607 18810 35607 18812 35607 18812 35608 18811 35608 18813 35608 18532 35609 18813 35609 18530 35609 18814 35610 18813 35610 18532 35610 18815 35611 18813 35611 18814 35611 18815 35612 18812 35612 18813 35612 18816 35613 18812 35613 18815 35613 18814 35614 18532 35614 18533 35614 18817 35615 18814 35615 18533 35615 18817 35616 18815 35616 18814 35616 18818 35617 18815 35617 18817 35617 18818 35618 18816 35618 18815 35618 18817 35619 18533 35619 18534 35619 18819 35620 18816 35620 18818 35620 18820 35621 18534 35621 18535 35621 18820 35622 18817 35622 18534 35622 18821 35623 18817 35623 18820 35623 18821 35624 18818 35624 18817 35624 18819 35625 18818 35625 18821 35625 18537 35626 18820 35626 18535 35626 18821 35627 18820 35627 18537 35627 18823 35628 18537 35628 18538 35628 18822 35629 18819 35629 18821 35629 18823 35630 18821 35630 18537 35630 18822 35631 18821 35631 18823 35631 18824 35632 18823 35632 18538 35632 18540 35633 18824 35633 18538 35633 18825 35634 18823 35634 18824 35634 18825 35635 18822 35635 18823 35635 18826 35636 18824 35636 18540 35636 18826 35637 18825 35637 18824 35637 18826 35638 18540 35638 18542 35638 18827 35639 18822 35639 18825 35639 18828 35640 18825 35640 18826 35640 18826 35641 18542 35641 18543 35641 18827 35642 18825 35642 18828 35642 18829 35643 18827 35643 18828 35643 18830 35644 18826 35644 18543 35644 18828 35645 18826 35645 18830 35645 18545 35646 18830 35646 18543 35646 18830 35647 18829 35647 18828 35647 18831 35648 18827 35648 18829 35648 18832 35649 18545 35649 18546 35649 18832 35650 18830 35650 18545 35650 18832 35651 18829 35651 18830 35651 18833 35652 18829 35652 18832 35652 18831 35653 18829 35653 18833 35653 18834 35654 18832 35654 18546 35654 18834 35655 18833 35655 18832 35655 18834 35656 18546 35656 18548 35656 18835 35657 18831 35657 18833 35657 18550 35658 18834 35658 18548 35658 18836 35659 18833 35659 18834 35659 18835 35660 18833 35660 18836 35660 18836 35661 18834 35661 18550 35661 18837 35662 18550 35662 18551 35662 18837 35663 18836 35663 18550 35663 18839 35664 18831 35664 18835 35664 18838 35665 18836 35665 18837 35665 18838 35666 18835 35666 18836 35666 18553 35667 18837 35667 18551 35667 18839 35668 18835 35668 18838 35668 18838 35669 18837 35669 18553 35669 18840 35670 18553 35670 18554 35670 18840 35671 18838 35671 18553 35671 18841 35672 18838 35672 18840 35672 18841 35673 18839 35673 18838 35673 18556 35674 18840 35674 18554 35674 18842 35675 18839 35675 18841 35675 18843 35676 18840 35676 18556 35676 18843 35677 18841 35677 18840 35677 18557 35678 18843 35678 18556 35678 18844 35679 18841 35679 18843 35679 18844 35680 18842 35680 18841 35680 18845 35681 18843 35681 18557 35681 18845 35682 18844 35682 18843 35682 18559 35683 18845 35683 18557 35683 18846 35684 18845 35684 18559 35684 18844 35685 18845 35685 18846 35685 18848 35686 18842 35686 18844 35686 18847 35687 18559 35687 18560 35687 18847 35688 18846 35688 18559 35688 18848 35689 18844 35689 18846 35689 18849 35690 18847 35690 18560 35690 18849 35691 18846 35691 18847 35691 18848 35692 18846 35692 18849 35692 18849 35693 18560 35693 18562 35693 18850 35694 18848 35694 18849 35694 18852 35695 18848 35695 18850 35695 18851 35696 18849 35696 18562 35696 18850 35697 18849 35697 18851 35697 18851 35698 18562 35698 18563 35698 18853 35699 18850 35699 18851 35699 18852 35700 18850 35700 18853 35700 18854 35701 18851 35701 18563 35701 18853 35702 18851 35702 18854 35702 18855 35703 18852 35703 18853 35703 18856 35704 18853 35704 18854 35704 18855 35705 18853 35705 18856 35705 18856 35706 18854 35706 18565 35706 18859 35707 18852 35707 18855 35707 18857 35708 18856 35708 18565 35708 18857 35709 18565 35709 18566 35709 18858 35710 18856 35710 18857 35710 18858 35711 18855 35711 18856 35711 18859 35712 18855 35712 18858 35712 18568 35713 18857 35713 18566 35713 18860 35714 18857 35714 18568 35714 18860 35715 18858 35715 18857 35715 18861 35716 18858 35716 18860 35716 18859 35717 18858 35717 18861 35717 18863 35718 18859 35718 18861 35718 18862 35719 18861 35719 18860 35719 18570 35720 18860 35720 18568 35720 18862 35721 18860 35721 18570 35721 18863 35722 18861 35722 18862 35722 18864 35723 18862 35723 18570 35723 18865 35724 18862 35724 18864 35724 18863 35725 18862 35725 18865 35725 18571 35726 18864 35726 18570 35726 18866 35727 18864 35727 18571 35727 18866 35728 18865 35728 18864 35728 18867 35729 18863 35729 18865 35729 18868 35730 18866 35730 18571 35730 18868 35731 18865 35731 18866 35731 18869 35732 18865 35732 18868 35732 18573 35733 18868 35733 18571 35733 18867 35734 18865 35734 18869 35734 18870 35735 18868 35735 18573 35735 18870 35736 18869 35736 18868 35736 18870 35737 18573 35737 18574 35737 18767 35738 18869 35738 18870 35738 18574 35739 18491 35739 18765 35739 18867 35740 18869 35740 18767 35740 18765 35741 18870 35741 18574 35741 18767 35742 18870 35742 18765 35742 18181 35743 18831 35743 18185 35743 18181 35744 18827 35744 18831 35744 18188 35745 18185 35745 18831 35745 18188 35746 18831 35746 18839 35746 18177 35747 18827 35747 18181 35747 18177 35748 18822 35748 18827 35748 18177 35749 18819 35749 18822 35749 18192 35750 18188 35750 18839 35750 18192 35751 18839 35751 18842 35751 18174 35752 18819 35752 18177 35752 18195 35753 18192 35753 18842 35753 18171 35754 18819 35754 18174 35754 18171 35755 18816 35755 18819 35755 18195 35756 18842 35756 18848 35756 18197 35757 18195 35757 18848 35757 18168 35758 18816 35758 18171 35758 18197 35759 18848 35759 18852 35759 18168 35760 18810 35760 18816 35760 18201 35761 18197 35761 18852 35761 18859 35762 18201 35762 18852 35762 18164 35763 18810 35763 18168 35763 18164 35764 18806 35764 18810 35764 18859 35765 18204 35765 18201 35765 18863 35766 18204 35766 18859 35766 18161 35767 18806 35767 18164 35767 18801 35768 18806 35768 18161 35768 18801 35769 18161 35769 18157 35769 18209 35770 18204 35770 18863 35770 18867 35771 18209 35771 18863 35771 18798 35772 18801 35772 18157 35772 18154 35773 18798 35773 18157 35773 18867 35774 18212 35774 18209 35774 18793 35775 18798 35775 18154 35775 18767 35776 18212 35776 18867 35776 18767 35777 18136 35777 18212 35777 18789 35778 18793 35778 18154 35778 18789 35779 18154 35779 18150 35779 18769 35780 18136 35780 18767 35780 18782 35781 18150 35781 18147 35781 18782 35782 18789 35782 18150 35782 18771 35783 18136 35783 18769 35783 18771 35784 18140 35784 18136 35784 18776 35785 18140 35785 18771 35785 18776 35786 18782 35786 18147 35786 18776 35787 18147 35787 18143 35787 18776 35788 18143 35788 18140 35788 18876 35789 19039 35789 18872 35789 18874 35790 18871 35790 18873 35790 18874 35791 18872 35791 18871 35791 18875 35792 19039 35792 18876 35792 18875 35793 19033 35793 19039 35793 18876 35794 18872 35794 18874 35794 18874 35795 18873 35795 18877 35795 18878 35796 18876 35796 18874 35796 18875 35797 18876 35797 18878 35797 18879 35798 18874 35798 18877 35798 18879 35799 18878 35799 18874 35799 18880 35800 18879 35800 18877 35800 18881 35801 18879 35801 18880 35801 18878 35802 18879 35802 18881 35802 18882 35803 18881 35803 18880 35803 18883 35804 18878 35804 18881 35804 18883 35805 18875 35805 18878 35805 18884 35806 18881 35806 18882 35806 18883 35807 18881 35807 18884 35807 18885 35808 18875 35808 18883 35808 18887 35809 18882 35809 18886 35809 18887 35810 18884 35810 18882 35810 18888 35811 18884 35811 18887 35811 18888 35812 18883 35812 18884 35812 18885 35813 18883 35813 18888 35813 18887 35814 18886 35814 18889 35814 18890 35815 18887 35815 18889 35815 18888 35816 18887 35816 18890 35816 18891 35817 18885 35817 18888 35817 18892 35818 18888 35818 18890 35818 18891 35819 18888 35819 18892 35819 18894 35820 18889 35820 18893 35820 18894 35821 18890 35821 18889 35821 18892 35822 18890 35822 18894 35822 18891 35823 18892 35823 18894 35823 18895 35824 18894 35824 18893 35824 18896 35825 18894 35825 18895 35825 18896 35826 18891 35826 18894 35826 18899 35827 18891 35827 18896 35827 18897 35828 18896 35828 18895 35828 18898 35829 18891 35829 18899 35829 18899 35830 18896 35830 18897 35830 18901 35831 18897 35831 18900 35831 18901 35832 18899 35832 18897 35832 18902 35833 18899 35833 18901 35833 18898 35834 18899 35834 18902 35834 18904 35835 18900 35835 18903 35835 18904 35836 18901 35836 18900 35836 18904 35837 18902 35837 18901 35837 18905 35838 18898 35838 18902 35838 18905 35839 18902 35839 18904 35839 18906 35840 18904 35840 18903 35840 18905 35841 18904 35841 18906 35841 18907 35842 18906 35842 18903 35842 18908 35843 18906 35843 18907 35843 18908 35844 18905 35844 18906 35844 18910 35845 18905 35845 18908 35845 18911 35846 18907 35846 18909 35846 18908 35847 18907 35847 18911 35847 18912 35848 18908 35848 18911 35848 18912 35849 18910 35849 18908 35849 18914 35850 18909 35850 18913 35850 18914 35851 18911 35851 18909 35851 18912 35852 18911 35852 18914 35852 18915 35853 18914 35853 18913 35853 18916 35854 18910 35854 18912 35854 18915 35855 18912 35855 18914 35855 18917 35856 18915 35856 18913 35856 18918 35857 18912 35857 18915 35857 18916 35858 18912 35858 18918 35858 18919 35859 18915 35859 18917 35859 18918 35860 18915 35860 18919 35860 18919 35861 18917 35861 18920 35861 18921 35862 18918 35862 18919 35862 18923 35863 18920 35863 18922 35863 18921 35864 18916 35864 18918 35864 18923 35865 18919 35865 18920 35865 18924 35866 18916 35866 18921 35866 18923 35867 18921 35867 18919 35867 18926 35868 18921 35868 18923 35868 18925 35869 18923 35869 18922 35869 18927 35870 18923 35870 18925 35870 18926 35871 18923 35871 18927 35871 18926 35872 18924 35872 18921 35872 18927 35873 18925 35873 18928 35873 18929 35874 18926 35874 18927 35874 18924 35875 18926 35875 18929 35875 18929 35876 18927 35876 18928 35876 18931 35877 18924 35877 18929 35877 18932 35878 18929 35878 18928 35878 18932 35879 18928 35879 18930 35879 18931 35880 18929 35880 18932 35880 18933 35881 18924 35881 18931 35881 18934 35882 18932 35882 18930 35882 18935 35883 18932 35883 18934 35883 18935 35884 18931 35884 18932 35884 18933 35885 18931 35885 18935 35885 18936 35886 18935 35886 18934 35886 18937 35887 18935 35887 18936 35887 18937 35888 18933 35888 18935 35888 18938 35889 18933 35889 18937 35889 18940 35890 18936 35890 18939 35890 18940 35891 18937 35891 18936 35891 18938 35892 18937 35892 18940 35892 18941 35893 18940 35893 18939 35893 18942 35894 18940 35894 18941 35894 18943 35895 18933 35895 18938 35895 18942 35896 18938 35896 18940 35896 18943 35897 18938 35897 18942 35897 18944 35898 18942 35898 18941 35898 18947 35899 18943 35899 18942 35899 18945 35900 18944 35900 18941 35900 18946 35901 18944 35901 18945 35901 18946 35902 18942 35902 18944 35902 18947 35903 18942 35903 18946 35903 18949 35904 18945 35904 18948 35904 18949 35905 18946 35905 18945 35905 18947 35906 18946 35906 18949 35906 18951 35907 18943 35907 18947 35907 18950 35908 18947 35908 18949 35908 18951 35909 18947 35909 18950 35909 18952 35910 18949 35910 18948 35910 18953 35911 18949 35911 18952 35911 18950 35912 18949 35912 18953 35912 18954 35913 18950 35913 18953 35913 18951 35914 18950 35914 18954 35914 18955 35915 18953 35915 18952 35915 18954 35916 18953 35916 18955 35916 18956 35917 18951 35917 18954 35917 18958 35918 18955 35918 18957 35918 18958 35919 18954 35919 18955 35919 18960 35920 18954 35920 18958 35920 18960 35921 18956 35921 18954 35921 18959 35922 18951 35922 18956 35922 18958 35923 18957 35923 18961 35923 18959 35924 18956 35924 18960 35924 18962 35925 18958 35925 18961 35925 18963 35926 18958 35926 18962 35926 18963 35927 18960 35927 18958 35927 18962 35928 18961 35928 18964 35928 18963 35929 18959 35929 18960 35929 18959 35930 18963 35930 18962 35930 18965 35931 18962 35931 18964 35931 18966 35932 18962 35932 18965 35932 18959 35933 18962 35933 18966 35933 18968 35934 18965 35934 18967 35934 18968 35935 18966 35935 18965 35935 18969 35936 18959 35936 18966 35936 18970 35937 18959 35937 18969 35937 18969 35938 18966 35938 18968 35938 18968 35939 18967 35939 18971 35939 18972 35940 18968 35940 18971 35940 18973 35941 18968 35941 18972 35941 18973 35942 18969 35942 18968 35942 18974 35943 18972 35943 18971 35943 18970 35944 18969 35944 18973 35944 18973 35945 18972 35945 18974 35945 18975 35946 18970 35946 18973 35946 18976 35947 18973 35947 18974 35947 18976 35948 18974 35948 18977 35948 18978 35949 18973 35949 18976 35949 18978 35950 18975 35950 18973 35950 18980 35951 18970 35951 18975 35951 18978 35952 18976 35952 18977 35952 18980 35953 18975 35953 18978 35953 18981 35954 18977 35954 18979 35954 18981 35955 18978 35955 18977 35955 18982 35956 18978 35956 18981 35956 18980 35957 18978 35957 18982 35957 18981 35958 18979 35958 18983 35958 18984 35959 18981 35959 18983 35959 18982 35960 18981 35960 18984 35960 18986 35961 18980 35961 18982 35961 18985 35962 18980 35962 18986 35962 18986 35963 18982 35963 18984 35963 18989 35964 18985 35964 18986 35964 18988 35965 18984 35965 18987 35965 18988 35966 18986 35966 18984 35966 18989 35967 18986 35967 18988 35967 18990 35968 18988 35968 18987 35968 18991 35969 18988 35969 18990 35969 18991 35970 18989 35970 18988 35970 18992 35971 18985 35971 18989 35971 18992 35972 18989 35972 18991 35972 18994 35973 18990 35973 18993 35973 18994 35974 18991 35974 18990 35974 18995 35975 18991 35975 18994 35975 18995 35976 18992 35976 18991 35976 18985 35977 18992 35977 18996 35977 18996 35978 18992 35978 18995 35978 18994 35979 18993 35979 18997 35979 18998 35980 18994 35980 18997 35980 18998 35981 18995 35981 18994 35981 18999 35982 18998 35982 18997 35982 19000 35983 18995 35983 18998 35983 19000 35984 18996 35984 18995 35984 19001 35985 18999 35985 18997 35985 19000 35986 18998 35986 18999 35986 19002 35987 19000 35987 18999 35987 19004 35988 19000 35988 19002 35988 19003 35989 18999 35989 19001 35989 19005 35990 18999 35990 19003 35990 19004 35991 18996 35991 19000 35991 19005 35992 19002 35992 18999 35992 19006 35993 19002 35993 19005 35993 19004 35994 19002 35994 19006 35994 19006 35995 19005 35995 19003 35995 19007 35996 19006 35996 19003 35996 19008 35997 19006 35997 19007 35997 19010 35998 19006 35998 19008 35998 19010 35999 19004 35999 19006 35999 19009 36000 19008 36000 19007 36000 19011 36001 19008 36001 19009 36001 19013 36002 19008 36002 19011 36002 19013 36003 19010 36003 19008 36003 19011 36004 19009 36004 19012 36004 19015 36005 19012 36005 19014 36005 19015 36006 19011 36006 19012 36006 19016 36007 19010 36007 19013 36007 19015 36008 19013 36008 19011 36008 19016 36009 19013 36009 19015 36009 19017 36010 19015 36010 19014 36010 19017 36011 19016 36011 19015 36011 19017 36012 19014 36012 19018 36012 19019 36013 19016 36013 19017 36013 19020 36014 19017 36014 19018 36014 19019 36015 19017 36015 19020 36015 19022 36016 19016 36016 19019 36016 19020 36017 19018 36017 19021 36017 19023 36018 19020 36018 19021 36018 19023 36019 19019 36019 19020 36019 19025 36020 19021 36020 19024 36020 19025 36021 19023 36021 19021 36021 19025 36022 19019 36022 19023 36022 19026 36023 19019 36023 19025 36023 19026 36024 19022 36024 19019 36024 19028 36025 19022 36025 19026 36025 19025 36026 19024 36026 19027 36026 19029 36027 19025 36027 19027 36027 19029 36028 19026 36028 19025 36028 19028 36029 19026 36029 19029 36029 19029 36030 19027 36030 19030 36030 19031 36031 19028 36031 19029 36031 19032 36032 19029 36032 19030 36032 19031 36033 19029 36033 19032 36033 19033 36034 19028 36034 19031 36034 19034 36035 19032 36035 19030 36035 19035 36036 19033 36036 19031 36036 19036 36037 19032 36037 19034 36037 19031 36038 19032 36038 19036 36038 19036 36039 19034 36039 19037 36039 19035 36040 19031 36040 19036 36040 19038 36041 19036 36041 19037 36041 19039 36042 19035 36042 19036 36042 19040 36043 19038 36043 19037 36043 19039 36044 19033 36044 19035 36044 19039 36045 19036 36045 19038 36045 19038 36046 19040 36046 18871 36046 19038 36047 18871 36047 18872 36047 19039 36048 19038 36048 18872 36048 19041 36049 18871 36049 19040 36049 19042 36050 19041 36050 19040 36050 19042 36051 19040 36051 19037 36051 19043 36052 19042 36052 19037 36052 19043 36053 19037 36053 19034 36053 19044 36054 19034 36054 19030 36054 19044 36055 19043 36055 19034 36055 19044 36056 19030 36056 19027 36056 19045 36057 19044 36057 19027 36057 19045 36058 19027 36058 19024 36058 19046 36059 19045 36059 19024 36059 19046 36060 19024 36060 19021 36060 19047 36061 19046 36061 19021 36061 19048 36062 19047 36062 19021 36062 19048 36063 19021 36063 19018 36063 19049 36064 19048 36064 19018 36064 19049 36065 19018 36065 19014 36065 19050 36066 19049 36066 19014 36066 19050 36067 19014 36067 19012 36067 19115 36068 19050 36068 19012 36068 19115 36069 19012 36069 19009 36069 19051 36070 19009 36070 19007 36070 19051 36071 19115 36071 19009 36071 19052 36072 19007 36072 19003 36072 19052 36073 19051 36073 19007 36073 19053 36074 19003 36074 19001 36074 19053 36075 19052 36075 19003 36075 19054 36076 19001 36076 18997 36076 19054 36077 19053 36077 19001 36077 19055 36078 18997 36078 18993 36078 19055 36079 19054 36079 18997 36079 19056 36080 18993 36080 18990 36080 19056 36081 19055 36081 18993 36081 19057 36082 19056 36082 18990 36082 19057 36083 18990 36083 18987 36083 19057 36084 18987 36084 18984 36084 19058 36085 18984 36085 18983 36085 19058 36086 19057 36086 18984 36086 19059 36087 18983 36087 18979 36087 19059 36088 19058 36088 18983 36088 19060 36089 18979 36089 18977 36089 19060 36090 19059 36090 18979 36090 19061 36091 18977 36091 18974 36091 19061 36092 19060 36092 18977 36092 19062 36093 19061 36093 18974 36093 19062 36094 18974 36094 18971 36094 19063 36095 18971 36095 18967 36095 19063 36096 19062 36096 18971 36096 19064 36097 19063 36097 18967 36097 19064 36098 18967 36098 18965 36098 19065 36099 19064 36099 18965 36099 19065 36100 18965 36100 18964 36100 19066 36101 19065 36101 18964 36101 19066 36102 18964 36102 18961 36102 19066 36103 18961 36103 18957 36103 19067 36104 19066 36104 18957 36104 19067 36105 18957 36105 18955 36105 19068 36106 19067 36106 18955 36106 19068 36107 18955 36107 18952 36107 19069 36108 19068 36108 18952 36108 19069 36109 18952 36109 18948 36109 19070 36110 19069 36110 18948 36110 19070 36111 18948 36111 18945 36111 19071 36112 19070 36112 18945 36112 19071 36113 18945 36113 18941 36113 19072 36114 19071 36114 18941 36114 19072 36115 18941 36115 18939 36115 19073 36116 19072 36116 18939 36116 19073 36117 18939 36117 18936 36117 19074 36118 19073 36118 18936 36118 19074 36119 18936 36119 18934 36119 19075 36120 19074 36120 18934 36120 19075 36121 18934 36121 18930 36121 19076 36122 19075 36122 18930 36122 19076 36123 18930 36123 18928 36123 19077 36124 18928 36124 18925 36124 19077 36125 19076 36125 18928 36125 19077 36126 18925 36126 18922 36126 19078 36127 19077 36127 18922 36127 19078 36128 18922 36128 18920 36128 19079 36129 19078 36129 18920 36129 19079 36130 18920 36130 18917 36130 19080 36131 19079 36131 18917 36131 19080 36132 18917 36132 18913 36132 19081 36133 19080 36133 18913 36133 19081 36134 18913 36134 18909 36134 19082 36135 19081 36135 18909 36135 19082 36136 18909 36136 18907 36136 19083 36137 19082 36137 18907 36137 19083 36138 18907 36138 18903 36138 19084 36139 19083 36139 18903 36139 19084 36140 18903 36140 18900 36140 19085 36141 19084 36141 18900 36141 19086 36142 18900 36142 18897 36142 19086 36143 19085 36143 18900 36143 19086 36144 18897 36144 18895 36144 19192 36145 19086 36145 18895 36145 19087 36146 18895 36146 18893 36146 19087 36147 19192 36147 18895 36147 19087 36148 18893 36148 18889 36148 19088 36149 19087 36149 18889 36149 19089 36150 19088 36150 18889 36150 19089 36151 18889 36151 18886 36151 19090 36152 19089 36152 18886 36152 19090 36153 18886 36153 18882 36153 19090 36154 18882 36154 18880 36154 19091 36155 19090 36155 18880 36155 19092 36156 18880 36156 18877 36156 19092 36157 19091 36157 18880 36157 19092 36158 18877 36158 18873 36158 19093 36159 19092 36159 18873 36159 19041 36160 18873 36160 18871 36160 19041 36161 19093 36161 18873 36161 18642 36162 18885 36162 18891 36162 18639 36163 18891 36163 18898 36163 18639 36164 18642 36164 18891 36164 18645 36165 18885 36165 18642 36165 18647 36166 18885 36166 18645 36166 18636 36167 18898 36167 18905 36167 18636 36168 18639 36168 18898 36168 18647 36169 18875 36169 18885 36169 18650 36170 18875 36170 18647 36170 18633 36171 18636 36171 18905 36171 18633 36172 18905 36172 18910 36172 18633 36173 18910 36173 18916 36173 18650 36174 19033 36174 18875 36174 18630 36175 18633 36175 18916 36175 18575 36176 19033 36176 18650 36176 18924 36177 18630 36177 18916 36177 18578 36178 19033 36178 18575 36178 18628 36179 18630 36179 18924 36179 18581 36180 19028 36180 19033 36180 18581 36181 19033 36181 18578 36181 18625 36182 18628 36182 18924 36182 18933 36183 18625 36183 18924 36183 18583 36184 19028 36184 18581 36184 18583 36185 19022 36185 19028 36185 18622 36186 18625 36186 18933 36186 18933 36187 18619 36187 18622 36187 18586 36188 19022 36188 18583 36188 19016 36189 19022 36189 18586 36189 18943 36190 18619 36190 18933 36190 18588 36191 19016 36191 18586 36191 19010 36192 19016 36192 18588 36192 18943 36193 18617 36193 18619 36193 18951 36194 18617 36194 18943 36194 18590 36195 19010 36195 18588 36195 18951 36196 18613 36196 18617 36196 19004 36197 19010 36197 18590 36197 18996 36198 19004 36198 18590 36198 18996 36199 18590 36199 18592 36199 18951 36200 18610 36200 18613 36200 18959 36201 18610 36201 18951 36201 18985 36202 18996 36202 18592 36202 18985 36203 18592 36203 18596 36203 18959 36204 18608 36204 18610 36204 18985 36205 18596 36205 18599 36205 18959 36206 18605 36206 18608 36206 18970 36207 18605 36207 18959 36207 18980 36208 18599 36208 18601 36208 18980 36209 18985 36209 18599 36209 18970 36210 18603 36210 18605 36210 18970 36211 18980 36211 18601 36211 18970 36212 18601 36212 18603 36212 19094 36213 19041 36213 19042 36213 19094 36214 19095 36214 19041 36214 19096 36215 19095 36215 19094 36215 19096 36216 19097 36216 19095 36216 19043 36217 19094 36217 19042 36217 19098 36218 19094 36218 19043 36218 19098 36219 19096 36219 19094 36219 19099 36220 19096 36220 19098 36220 19100 36221 19098 36221 19043 36221 19101 36222 19097 36222 19096 36222 19099 36223 19098 36223 19100 36223 19100 36224 19043 36224 19044 36224 19101 36225 19096 36225 19099 36225 19102 36226 19099 36226 19100 36226 19102 36227 19101 36227 19099 36227 19103 36228 19100 36228 19044 36228 19103 36229 19102 36229 19100 36229 19103 36230 19044 36230 19045 36230 19105 36231 19102 36231 19103 36231 19104 36232 19101 36232 19102 36232 19105 36233 19103 36233 19045 36233 19104 36234 19102 36234 19105 36234 19046 36235 19105 36235 19045 36235 19106 36236 19104 36236 19105 36236 19107 36237 19105 36237 19046 36237 19106 36238 19105 36238 19107 36238 19047 36239 19107 36239 19046 36239 19108 36240 19106 36240 19107 36240 19108 36241 19104 36241 19106 36241 19109 36242 19107 36242 19047 36242 19108 36243 19107 36243 19109 36243 19048 36244 19109 36244 19047 36244 19110 36245 19104 36245 19108 36245 19111 36246 19109 36246 19048 36246 19112 36247 19109 36247 19111 36247 19112 36248 19108 36248 19109 36248 19049 36249 19111 36249 19048 36249 19110 36250 19108 36250 19112 36250 19113 36251 19111 36251 19049 36251 19112 36252 19111 36252 19113 36252 19050 36253 19113 36253 19049 36253 19114 36254 19112 36254 19113 36254 19115 36255 19113 36255 19050 36255 19116 36256 19110 36256 19112 36256 19114 36257 19113 36257 19115 36257 19116 36258 19112 36258 19114 36258 19117 36259 19114 36259 19115 36259 19118 36260 19114 36260 19117 36260 19118 36261 19116 36261 19114 36261 19051 36262 19117 36262 19115 36262 19119 36263 19116 36263 19118 36263 19120 36264 19051 36264 19052 36264 19120 36265 19117 36265 19051 36265 19120 36266 19118 36266 19117 36266 19119 36267 19118 36267 19120 36267 19121 36268 19120 36268 19052 36268 19122 36269 19120 36269 19121 36269 19122 36270 19119 36270 19120 36270 19121 36271 19052 36271 19053 36271 19123 36272 19121 36272 19053 36272 19122 36273 19121 36273 19123 36273 19123 36274 19053 36274 19054 36274 19124 36275 19119 36275 19122 36275 19124 36276 19122 36276 19123 36276 19125 36277 19123 36277 19054 36277 19125 36278 19124 36278 19123 36278 19125 36279 19054 36279 19055 36279 19126 36280 19124 36280 19125 36280 19127 36281 19124 36281 19126 36281 19128 36282 19125 36282 19055 36282 19126 36283 19125 36283 19128 36283 19128 36284 19055 36284 19056 36284 19129 36285 19127 36285 19126 36285 19129 36286 19126 36286 19128 36286 19057 36287 19128 36287 19056 36287 19130 36288 19128 36288 19057 36288 19129 36289 19128 36289 19130 36289 19131 36290 19129 36290 19130 36290 19132 36291 19127 36291 19129 36291 19058 36292 19130 36292 19057 36292 19131 36293 19130 36293 19058 36293 19133 36294 19129 36294 19131 36294 19132 36295 19129 36295 19133 36295 19133 36296 19131 36296 19058 36296 19134 36297 19058 36297 19059 36297 19134 36298 19133 36298 19058 36298 19135 36299 19132 36299 19133 36299 19135 36300 19133 36300 19134 36300 19060 36301 19134 36301 19059 36301 19136 36302 19135 36302 19134 36302 19137 36303 19134 36303 19060 36303 19138 36304 19132 36304 19135 36304 19137 36305 19136 36305 19134 36305 19061 36306 19137 36306 19060 36306 19138 36307 19135 36307 19136 36307 19062 36308 19137 36308 19061 36308 19139 36309 19137 36309 19062 36309 19139 36310 19136 36310 19137 36310 19140 36311 19136 36311 19139 36311 19140 36312 19138 36312 19136 36312 19141 36313 19139 36313 19062 36313 19140 36314 19139 36314 19141 36314 19141 36315 19062 36315 19063 36315 19142 36316 19140 36316 19141 36316 19142 36317 19138 36317 19140 36317 19064 36318 19141 36318 19063 36318 19143 36319 19141 36319 19064 36319 19143 36320 19142 36320 19141 36320 19144 36321 19142 36321 19143 36321 19144 36322 19138 36322 19142 36322 19065 36323 19143 36323 19064 36323 19145 36324 19143 36324 19065 36324 19146 36325 19138 36325 19144 36325 19145 36326 19144 36326 19143 36326 19146 36327 19144 36327 19145 36327 19147 36328 19065 36328 19066 36328 19147 36329 19145 36329 19065 36329 19146 36330 19145 36330 19147 36330 19148 36331 19146 36331 19147 36331 19149 36332 19066 36332 19067 36332 19149 36333 19147 36333 19066 36333 19150 36334 19147 36334 19149 36334 19150 36335 19148 36335 19147 36335 19151 36336 19148 36336 19150 36336 19151 36337 19146 36337 19148 36337 19152 36338 19067 36338 19068 36338 19152 36339 19149 36339 19067 36339 19150 36340 19149 36340 19152 36340 19153 36341 19150 36341 19152 36341 19153 36342 19151 36342 19150 36342 19154 36343 19068 36343 19069 36343 19154 36344 19152 36344 19068 36344 19154 36345 19153 36345 19152 36345 19155 36346 19153 36346 19154 36346 19156 36347 19153 36347 19155 36347 19156 36348 19151 36348 19153 36348 19157 36349 19154 36349 19069 36349 19157 36350 19155 36350 19154 36350 19157 36351 19069 36351 19070 36351 19158 36352 19155 36352 19157 36352 19156 36353 19155 36353 19158 36353 19159 36354 19156 36354 19158 36354 19071 36355 19157 36355 19070 36355 19160 36356 19157 36356 19071 36356 19160 36357 19158 36357 19157 36357 19161 36358 19160 36358 19071 36358 19161 36359 19158 36359 19160 36359 19162 36360 19158 36360 19161 36360 19162 36361 19159 36361 19158 36361 19161 36362 19071 36362 19072 36362 19163 36363 19161 36363 19072 36363 19163 36364 19162 36364 19161 36364 19165 36365 19162 36365 19164 36365 19165 36366 19159 36366 19162 36366 19073 36367 19163 36367 19072 36367 19164 36368 19162 36368 19163 36368 19166 36369 19163 36369 19073 36369 19164 36370 19163 36370 19166 36370 19166 36371 19073 36371 19074 36371 19167 36372 19166 36372 19074 36372 19167 36373 19164 36373 19166 36373 19168 36374 19164 36374 19167 36374 19165 36375 19164 36375 19168 36375 19167 36376 19074 36376 19075 36376 19169 36377 19167 36377 19075 36377 19169 36378 19168 36378 19167 36378 19169 36379 19075 36379 19076 36379 19170 36380 19165 36380 19168 36380 19171 36381 19169 36381 19076 36381 19172 36382 19169 36382 19171 36382 19172 36383 19168 36383 19169 36383 19170 36384 19168 36384 19172 36384 19077 36385 19171 36385 19076 36385 19173 36386 19171 36386 19077 36386 19173 36387 19172 36387 19171 36387 19174 36388 19172 36388 19173 36388 19174 36389 19170 36389 19172 36389 19078 36390 19173 36390 19077 36390 19175 36391 19173 36391 19078 36391 19174 36392 19173 36392 19175 36392 19176 36393 19174 36393 19175 36393 19177 36394 19174 36394 19176 36394 19177 36395 19170 36395 19174 36395 19178 36396 19175 36396 19078 36396 19176 36397 19175 36397 19178 36397 19178 36398 19078 36398 19079 36398 19179 36399 19178 36399 19079 36399 19179 36400 19176 36400 19178 36400 19179 36401 19177 36401 19176 36401 19179 36402 19079 36402 19080 36402 19180 36403 19177 36403 19179 36403 19181 36404 19179 36404 19080 36404 19180 36405 19179 36405 19181 36405 19081 36406 19181 36406 19080 36406 19182 36407 19177 36407 19180 36407 19183 36408 19181 36408 19081 36408 19183 36409 19180 36409 19181 36409 19182 36410 19180 36410 19183 36410 19183 36411 19081 36411 19082 36411 19185 36412 19183 36412 19082 36412 19185 36413 19182 36413 19183 36413 19184 36414 19182 36414 19185 36414 19083 36415 19185 36415 19082 36415 19186 36416 19185 36416 19083 36416 19187 36417 19185 36417 19186 36417 19187 36418 19184 36418 19185 36418 19186 36419 19083 36419 19084 36419 19188 36420 19186 36420 19084 36420 19188 36421 19187 36421 19186 36421 19188 36422 19084 36422 19085 36422 19189 36423 19184 36423 19187 36423 19189 36424 19187 36424 19188 36424 19190 36425 19085 36425 19086 36425 19190 36426 19188 36426 19085 36426 19191 36427 19188 36427 19190 36427 19191 36428 19189 36428 19188 36428 19192 36429 19190 36429 19086 36429 19191 36430 19190 36430 19192 36430 19193 36431 19189 36431 19191 36431 19194 36432 19192 36432 19087 36432 19194 36433 19191 36433 19192 36433 19195 36434 19191 36434 19194 36434 19193 36435 19191 36435 19195 36435 19088 36436 19194 36436 19087 36436 19196 36437 19194 36437 19088 36437 19195 36438 19194 36438 19196 36438 19196 36439 19193 36439 19195 36439 19197 36440 19193 36440 19196 36440 19089 36441 19196 36441 19088 36441 19198 36442 19196 36442 19089 36442 19199 36443 19196 36443 19198 36443 19199 36444 19197 36444 19196 36444 19090 36445 19198 36445 19089 36445 19200 36446 19198 36446 19090 36446 19199 36447 19198 36447 19200 36447 19201 36448 19199 36448 19200 36448 19201 36449 19197 36449 19199 36449 19091 36450 19200 36450 19090 36450 19202 36451 19200 36451 19091 36451 19202 36452 19201 36452 19200 36452 19203 36453 19201 36453 19202 36453 19202 36454 19091 36454 19092 36454 19204 36455 19202 36455 19092 36455 19205 36456 19202 36456 19204 36456 19203 36457 19202 36457 19205 36457 19204 36458 19092 36458 19093 36458 19095 36459 19204 36459 19093 36459 19095 36460 19205 36460 19204 36460 19095 36461 19093 36461 19041 36461 19097 36462 19205 36462 19095 36462 19097 36463 19203 36463 19205 36463 18544 36464 19165 36464 18547 36464 18547 36465 19165 36465 19170 36465 18541 36466 19165 36466 18544 36466 18549 36467 18547 36467 19170 36467 18541 36468 19159 36468 19165 36468 18552 36469 18549 36469 19170 36469 18539 36470 19159 36470 18541 36470 18539 36471 19156 36471 19159 36471 18552 36472 19170 36472 19177 36472 18536 36473 19156 36473 18539 36473 18555 36474 19177 36474 19182 36474 18555 36475 18552 36475 19177 36475 18536 36476 19151 36476 19156 36476 18531 36477 19151 36477 18536 36477 18558 36478 18555 36478 19182 36478 18531 36479 19146 36479 19151 36479 18558 36480 19182 36480 19184 36480 18561 36481 18558 36481 19184 36481 18529 36482 19146 36482 18531 36482 18561 36483 19184 36483 19189 36483 18529 36484 19138 36484 19146 36484 19193 36485 18561 36485 19189 36485 18564 36486 18561 36486 19193 36486 18526 36487 19138 36487 18529 36487 18524 36488 19138 36488 18526 36488 18567 36489 18564 36489 19193 36489 19197 36490 18567 36490 19193 36490 18520 36491 19138 36491 18524 36491 18569 36492 18567 36492 19197 36492 19132 36493 19138 36493 18520 36493 18518 36494 19132 36494 18520 36494 19201 36495 18569 36495 19197 36495 19201 36496 18572 36496 18569 36496 19127 36497 18518 36497 18515 36497 19127 36498 19132 36498 18518 36498 19203 36499 18572 36499 19201 36499 19127 36500 18515 36500 18512 36500 19097 36501 18572 36501 19203 36501 19097 36502 18492 36502 18572 36502 19124 36503 19127 36503 18512 36503 19119 36504 19124 36504 18512 36504 19119 36505 18512 36505 18509 36505 19097 36506 18494 36506 18492 36506 19101 36507 18494 36507 19097 36507 19119 36508 18509 36508 18506 36508 19116 36509 19119 36509 18506 36509 19101 36510 18497 36510 18494 36510 19104 36511 18497 36511 19101 36511 19104 36512 18500 36512 18497 36512 19110 36513 19116 36513 18506 36513 19110 36514 18506 36514 18503 36514 19110 36515 18500 36515 19104 36515 19110 36516 18503 36516 18500 36516

+
+ + + +

19207 36517 19208 36517 19206 36517 19206 36518 19208 36518 19209 36518 19207 36519 19210 36519 19208 36519 19210 36520 19211 36520 19208 36520 19212 36521 19213 36521 19210 36521 19210 36522 19213 36522 19211 36522 19212 36523 19214 36523 19213 36523 19214 36524 19215 36524 19213 36524 19216 36525 19217 36525 19214 36525 19214 36526 19217 36526 19215 36526 19216 36527 19206 36527 19217 36527 19206 36528 19209 36528 19217 36528 19215 36529 19217 36529 19218 36529 19218 36530 19217 36530 19219 36530 19217 36531 19209 36531 19219 36531 19219 36532 19209 36532 19223 36532 19209 36533 19208 36533 19223 36533 19223 36534 19208 36534 19222 36534 19216 36535 19214 36535 19206 36535 19207 36536 19212 36536 19210 36536 19206 36537 19212 36537 19207 36537 19214 36538 19212 36538 19206 36538 19221 36539 20236 36539 20242 36539 19221 36540 20290 36540 20236 36540 19222 36541 19221 36541 20242 36541 19222 36542 20248 36542 20251 36542 19222 36543 20242 36543 20248 36543 19220 36544 20286 36544 20290 36544 19220 36545 20290 36545 19221 36545 20281 36546 20286 36546 19220 36546 19223 36547 19222 36547 20251 36547 19223 36548 20251 36548 20253 36548 20257 36549 19223 36549 20253 36549 20259 36550 19223 36550 20257 36550 19218 36551 20281 36551 19220 36551 20276 36552 20281 36552 19218 36552 20259 36553 19219 36553 19223 36553 20273 36554 20276 36554 19218 36554 19224 36555 19219 36555 20259 36555 20273 36556 19218 36556 19219 36556 20270 36557 20273 36557 19219 36557 20270 36558 19219 36558 19224 36558 19226 36559 19748 36559 19225 36559 19227 36560 19225 36560 19748 36560 19226 36561 19225 36561 20114 36561 19227 36562 20109 36562 19225 36562 19226 36563 20114 36563 19228 36563 19229 36564 20109 36564 19227 36564 19230 36565 19226 36565 19228 36565 19229 36566 20102 36566 20109 36566 19230 36567 19228 36567 19231 36567 19229 36568 20098 36568 20102 36568 19232 36569 20098 36569 19229 36569 19233 36570 19230 36570 19231 36570 19234 36571 19230 36571 19233 36571 19235 36572 20098 36572 19232 36572 20092 36573 20098 36573 19235 36573 20089 36574 20092 36574 19235 36574 20089 36575 19235 36575 19237 36575 20085 36576 20089 36576 19237 36576 20082 36577 20085 36577 19237 36577 20082 36578 19237 36578 19238 36578 19240 36579 19238 36579 19239 36579 19240 36580 20082 36580 19238 36580 19246 36581 19243 36581 19242 36581 19246 36582 19244 36582 19243 36582 19248 36583 19244 36583 19246 36583 19248 36584 19247 36584 19244 36584 19245 36585 19247 36585 19248 36585 19245 36586 19249 36586 19247 36586 19250 36587 19249 36587 19245 36587 19250 36588 19251 36588 19249 36588 19252 36589 19251 36589 19250 36589 19252 36590 19253 36590 19251 36590 19254 36591 19253 36591 19252 36591 19254 36592 19255 36592 19253 36592 19256 36593 19255 36593 19254 36593 19256 36594 19257 36594 19255 36594 19256 36595 19258 36595 19257 36595 19259 36596 19258 36596 19256 36596 19259 36597 19260 36597 19258 36597 19261 36598 19260 36598 19259 36598 19261 36599 19262 36599 19260 36599 19263 36600 19262 36600 19261 36600 19263 36601 19264 36601 19262 36601 19265 36602 19264 36602 19263 36602 19265 36603 19266 36603 19264 36603 19267 36604 19266 36604 19265 36604 19267 36605 19268 36605 19266 36605 19269 36606 19268 36606 19267 36606 19269 36607 19270 36607 19268 36607 19269 36608 19271 36608 19270 36608 19272 36609 19271 36609 19269 36609 19272 36610 19273 36610 19271 36610 19274 36611 19273 36611 19272 36611 19274 36612 19275 36612 19273 36612 19274 36613 19276 36613 19275 36613 19277 36614 19276 36614 19274 36614 19277 36615 19278 36615 19276 36615 19279 36616 19278 36616 19277 36616 19279 36617 19280 36617 19278 36617 19281 36618 19280 36618 19279 36618 19281 36619 19282 36619 19280 36619 19281 36620 19283 36620 19282 36620 19284 36621 19283 36621 19281 36621 19284 36622 19285 36622 19283 36622 19286 36623 19285 36623 19284 36623 19286 36624 19287 36624 19285 36624 19288 36625 19287 36625 19286 36625 19288 36626 19289 36626 19287 36626 19290 36627 19289 36627 19288 36627 19290 36628 19291 36628 19289 36628 19292 36629 19291 36629 19290 36629 19292 36630 19293 36630 19291 36630 19292 36631 19294 36631 19293 36631 19295 36632 19294 36632 19292 36632 19295 36633 19296 36633 19294 36633 19297 36634 19296 36634 19295 36634 19297 36635 19298 36635 19296 36635 19299 36636 19298 36636 19297 36636 19299 36637 19300 36637 19298 36637 19301 36638 19300 36638 19299 36638 19301 36639 19302 36639 19300 36639 19301 36640 19303 36640 19302 36640 19304 36641 19303 36641 19301 36641 19304 36642 19305 36642 19303 36642 19306 36643 19307 36643 19304 36643 19304 36644 19307 36644 19305 36644 19308 36645 19309 36645 19306 36645 19306 36646 19309 36646 19307 36646 19310 36647 19309 36647 19308 36647 19310 36648 19311 36648 19309 36648 19312 36649 19311 36649 19310 36649 19312 36650 19313 36650 19311 36650 19312 36651 19314 36651 19313 36651 19315 36652 19314 36652 19312 36652 19315 36653 19316 36653 19314 36653 19317 36654 19316 36654 19315 36654 19317 36655 19318 36655 19316 36655 19319 36656 19318 36656 19317 36656 19319 36657 19320 36657 19318 36657 19321 36658 19320 36658 19319 36658 19321 36659 19322 36659 19320 36659 19323 36660 19322 36660 19321 36660 19323 36661 19324 36661 19322 36661 19323 36662 19325 36662 19324 36662 19326 36663 19325 36663 19323 36663 19327 36664 19328 36664 19326 36664 19326 36665 19328 36665 19325 36665 19329 36666 19330 36666 19327 36666 19327 36667 19330 36667 19328 36667 19329 36668 19331 36668 19330 36668 19332 36669 19331 36669 19329 36669 19332 36670 19333 36670 19331 36670 19334 36671 19333 36671 19332 36671 19334 36672 19335 36672 19333 36672 19334 36673 19336 36673 19335 36673 19337 36674 19336 36674 19334 36674 19337 36675 19338 36675 19336 36675 19339 36676 19338 36676 19337 36676 19339 36677 19340 36677 19338 36677 19341 36678 19340 36678 19339 36678 19341 36679 19342 36679 19340 36679 19341 36680 19343 36680 19342 36680 19344 36681 19343 36681 19341 36681 19344 36682 19345 36682 19343 36682 19346 36683 19345 36683 19344 36683 19346 36684 19347 36684 19345 36684 19348 36685 19347 36685 19346 36685 19348 36686 19349 36686 19347 36686 19350 36687 19349 36687 19348 36687 19350 36688 19351 36688 19349 36688 19352 36689 19351 36689 19350 36689 19352 36690 19353 36690 19351 36690 19354 36691 19353 36691 19352 36691 19354 36692 19355 36692 19353 36692 19356 36693 19355 36693 19354 36693 19356 36694 19357 36694 19355 36694 19358 36695 19357 36695 19356 36695 19358 36696 19359 36696 19357 36696 19360 36697 19359 36697 19358 36697 19360 36698 19361 36698 19359 36698 19362 36699 19361 36699 19360 36699 19362 36700 19363 36700 19361 36700 19362 36701 19364 36701 19363 36701 19365 36702 19364 36702 19362 36702 19365 36703 19366 36703 19364 36703 19367 36704 19366 36704 19365 36704 19367 36705 19368 36705 19366 36705 19367 36706 19369 36706 19368 36706 19370 36707 19369 36707 19367 36707 19370 36708 19371 36708 19369 36708 19372 36709 19371 36709 19370 36709 19372 36710 19373 36710 19371 36710 19374 36711 19373 36711 19372 36711 19374 36712 19375 36712 19373 36712 19374 36713 19376 36713 19375 36713 19377 36714 19376 36714 19374 36714 19377 36715 19378 36715 19376 36715 19379 36716 19378 36716 19377 36716 19379 36717 19380 36717 19378 36717 19381 36718 19380 36718 19379 36718 19381 36719 19382 36719 19380 36719 19381 36720 19383 36720 19382 36720 19384 36721 19383 36721 19381 36721 19385 36722 19383 36722 19384 36722 19385 36723 19386 36723 19383 36723 19385 36724 19387 36724 19386 36724 19388 36725 19387 36725 19385 36725 19388 36726 19389 36726 19387 36726 19390 36727 19389 36727 19388 36727 19390 36728 19391 36728 19389 36728 19392 36729 19391 36729 19390 36729 19392 36730 19393 36730 19391 36730 19394 36731 19393 36731 19392 36731 19394 36732 19395 36732 19393 36732 19396 36733 19395 36733 19394 36733 19396 36734 19397 36734 19395 36734 19396 36735 19398 36735 19397 36735 19399 36736 19398 36736 19396 36736 19399 36737 19400 36737 19398 36737 19401 36738 19400 36738 19399 36738 19401 36739 19402 36739 19400 36739 19403 36740 19402 36740 19401 36740 19403 36741 19404 36741 19402 36741 19405 36742 19404 36742 19403 36742 19405 36743 19406 36743 19404 36743 19407 36744 19406 36744 19405 36744 19407 36745 19408 36745 19406 36745 19407 36746 19409 36746 19408 36746 19410 36747 19409 36747 19407 36747 19410 36748 19411 36748 19409 36748 19412 36749 19411 36749 19410 36749 19412 36750 19413 36750 19411 36750 19414 36751 19413 36751 19412 36751 19414 36752 19415 36752 19413 36752 19414 36753 19416 36753 19415 36753 19417 36754 19416 36754 19414 36754 19418 36755 19416 36755 19417 36755 19418 36756 19419 36756 19416 36756 19420 36757 19419 36757 19418 36757 19420 36758 19421 36758 19419 36758 19422 36759 19421 36759 19420 36759 19422 36760 19423 36760 19421 36760 19422 36761 19424 36761 19423 36761 19425 36762 19424 36762 19422 36762 19425 36763 19426 36763 19424 36763 19427 36764 19426 36764 19425 36764 19427 36765 19428 36765 19426 36765 19429 36766 19428 36766 19427 36766 19429 36767 19430 36767 19428 36767 19431 36768 19430 36768 19429 36768 19431 36769 19432 36769 19430 36769 19433 36770 19432 36770 19431 36770 19433 36771 19434 36771 19432 36771 19433 36772 19435 36772 19434 36772 19436 36773 19435 36773 19433 36773 19436 36774 19437 36774 19435 36774 19438 36775 19437 36775 19436 36775 19438 36776 19439 36776 19437 36776 19440 36777 19439 36777 19438 36777 19440 36778 19441 36778 19439 36778 19442 36779 19441 36779 19440 36779 19442 36780 19443 36780 19441 36780 19444 36781 19443 36781 19442 36781 19444 36782 19445 36782 19443 36782 19446 36783 19445 36783 19444 36783 19446 36784 19447 36784 19445 36784 19448 36785 19447 36785 19446 36785 19448 36786 19449 36786 19447 36786 19450 36787 19449 36787 19448 36787 19450 36788 19451 36788 19449 36788 19450 36789 19452 36789 19451 36789 19453 36790 19452 36790 19450 36790 19453 36791 19454 36791 19452 36791 19455 36792 19454 36792 19453 36792 19455 36793 19456 36793 19454 36793 19455 36794 19457 36794 19456 36794 19458 36795 19457 36795 19455 36795 19458 36796 19459 36796 19457 36796 19460 36797 19459 36797 19458 36797 19460 36798 19461 36798 19459 36798 19462 36799 19461 36799 19460 36799 19462 36800 19463 36800 19461 36800 19464 36801 19463 36801 19462 36801 19464 36802 19465 36802 19463 36802 19464 36803 19466 36803 19465 36803 19467 36804 19466 36804 19464 36804 19467 36805 19468 36805 19466 36805 19467 36806 19469 36806 19468 36806 19470 36807 19469 36807 19467 36807 19470 36808 19471 36808 19469 36808 19472 36809 19471 36809 19470 36809 19472 36810 19473 36810 19471 36810 19474 36811 19473 36811 19472 36811 19474 36812 19475 36812 19473 36812 19476 36813 19475 36813 19474 36813 19476 36814 19477 36814 19475 36814 19478 36815 19477 36815 19476 36815 19478 36816 19479 36816 19477 36816 19480 36817 19479 36817 19478 36817 19480 36818 19481 36818 19479 36818 19480 36819 19482 36819 19481 36819 19483 36820 19482 36820 19480 36820 19483 36821 19484 36821 19482 36821 19485 36822 19484 36822 19483 36822 19485 36823 19486 36823 19484 36823 19487 36824 19486 36824 19485 36824 19487 36825 19488 36825 19486 36825 19489 36826 19488 36826 19487 36826 19489 36827 19490 36827 19488 36827 19491 36828 19490 36828 19489 36828 19491 36829 19492 36829 19490 36829 19493 36830 19492 36830 19491 36830 19493 36831 19494 36831 19492 36831 19493 36832 19495 36832 19494 36832 19496 36833 19495 36833 19493 36833 19496 36834 19497 36834 19495 36834 19496 36835 19498 36835 19497 36835 19499 36836 19498 36836 19496 36836 19499 36837 19500 36837 19498 36837 19501 36838 19500 36838 19499 36838 19501 36839 19502 36839 19500 36839 19503 36840 19502 36840 19501 36840 19503 36841 19504 36841 19502 36841 19505 36842 19504 36842 19503 36842 19505 36843 19506 36843 19504 36843 19507 36844 19506 36844 19505 36844 19507 36845 19508 36845 19506 36845 19509 36846 19508 36846 19507 36846 19509 36847 19510 36847 19508 36847 19509 36848 19511 36848 19510 36848 19512 36849 19511 36849 19509 36849 19512 36850 19513 36850 19511 36850 19514 36851 19513 36851 19512 36851 19514 36852 19515 36852 19513 36852 19516 36853 19515 36853 19514 36853 19516 36854 19517 36854 19515 36854 19518 36855 19517 36855 19516 36855 19518 36856 19519 36856 19517 36856 19520 36857 19519 36857 19518 36857 19520 36858 19521 36858 19519 36858 19520 36859 19522 36859 19521 36859 19523 36860 19522 36860 19520 36860 19523 36861 19524 36861 19522 36861 19525 36862 19524 36862 19523 36862 19525 36863 19526 36863 19524 36863 19527 36864 19526 36864 19525 36864 19527 36865 19528 36865 19526 36865 19529 36866 19528 36866 19527 36866 19529 36867 19530 36867 19528 36867 19529 36868 19531 36868 19530 36868 19532 36869 19531 36869 19529 36869 19532 36870 19533 36870 19531 36870 19534 36871 19533 36871 19532 36871 19536 36872 19535 36872 19534 36872 19534 36873 19535 36873 19533 36873 19536 36874 19537 36874 19535 36874 19538 36875 19537 36875 19536 36875 19538 36876 19539 36876 19537 36876 19540 36877 19539 36877 19538 36877 19540 36878 19541 36878 19539 36878 19542 36879 19541 36879 19540 36879 19542 36880 19543 36880 19541 36880 19544 36881 19543 36881 19542 36881 19544 36882 19545 36882 19543 36882 19546 36883 19545 36883 19544 36883 19546 36884 19547 36884 19545 36884 19548 36885 19549 36885 19546 36885 19546 36886 19549 36886 19547 36886 19550 36887 19549 36887 19548 36887 19550 36888 19551 36888 19549 36888 19552 36889 19551 36889 19550 36889 19552 36890 19553 36890 19551 36890 19552 36891 19554 36891 19553 36891 19555 36892 19554 36892 19552 36892 19555 36893 19556 36893 19554 36893 19557 36894 19556 36894 19555 36894 19557 36895 19558 36895 19556 36895 19557 36896 19559 36896 19558 36896 19560 36897 19559 36897 19557 36897 19560 36898 19561 36898 19559 36898 19562 36899 19561 36899 19560 36899 19562 36900 19563 36900 19561 36900 19562 36901 19564 36901 19563 36901 19565 36902 19564 36902 19562 36902 19565 36903 19566 36903 19564 36903 19565 36904 19567 36904 19566 36904 19568 36905 19567 36905 19565 36905 19568 36906 19569 36906 19567 36906 19570 36907 19569 36907 19568 36907 19571 36908 19572 36908 19570 36908 19570 36909 19572 36909 19569 36909 19571 36910 19573 36910 19572 36910 19574 36911 19573 36911 19571 36911 19574 36912 19575 36912 19573 36912 19576 36913 19575 36913 19574 36913 19576 36914 19577 36914 19575 36914 19576 36915 19578 36915 19577 36915 19579 36916 19578 36916 19576 36916 19580 36917 19578 36917 19579 36917 19580 36918 19581 36918 19578 36918 19580 36919 19582 36919 19581 36919 19583 36920 19582 36920 19580 36920 19583 36921 19584 36921 19582 36921 19585 36922 19584 36922 19583 36922 19585 36923 19586 36923 19584 36923 19587 36924 19586 36924 19585 36924 19587 36925 19588 36925 19586 36925 19589 36926 19588 36926 19587 36926 19589 36927 19590 36927 19588 36927 19589 36928 19591 36928 19590 36928 19592 36929 19591 36929 19589 36929 19593 36930 19591 36930 19592 36930 19593 36931 19594 36931 19591 36931 19595 36932 19594 36932 19593 36932 19595 36933 19596 36933 19594 36933 19597 36934 19596 36934 19595 36934 19597 36935 19598 36935 19596 36935 19597 36936 19599 36936 19598 36936 19600 36937 19599 36937 19597 36937 19601 36938 19602 36938 19600 36938 19600 36939 19602 36939 19599 36939 19603 36940 19602 36940 19601 36940 19603 36941 19604 36941 19602 36941 19605 36942 19604 36942 19603 36942 19605 36943 19606 36943 19604 36943 19607 36944 19606 36944 19605 36944 19607 36945 19608 36945 19606 36945 19607 36946 19609 36946 19608 36946 19610 36947 19609 36947 19607 36947 19610 36948 19611 36948 19609 36948 19612 36949 19611 36949 19610 36949 19612 36950 19613 36950 19611 36950 19614 36951 19613 36951 19612 36951 19614 36952 19615 36952 19613 36952 19614 36953 19616 36953 19615 36953 19617 36954 19616 36954 19614 36954 19617 36955 19618 36955 19616 36955 19619 36956 19618 36956 19617 36956 19619 36957 19620 36957 19618 36957 19621 36958 19620 36958 19619 36958 19621 36959 19622 36959 19620 36959 19623 36960 19622 36960 19621 36960 19623 36961 19624 36961 19622 36961 19625 36962 19624 36962 19623 36962 19625 36963 19626 36963 19624 36963 19627 36964 19626 36964 19625 36964 19627 36965 19628 36965 19626 36965 19629 36966 19628 36966 19627 36966 19629 36967 19630 36967 19628 36967 19629 36968 19631 36968 19630 36968 19632 36969 19631 36969 19629 36969 19632 36970 19633 36970 19631 36970 19634 36971 19633 36971 19632 36971 19634 36972 19635 36972 19633 36972 19636 36973 19635 36973 19634 36973 19636 36974 19637 36974 19635 36974 19638 36975 19637 36975 19636 36975 19638 36976 19639 36976 19637 36976 19640 36977 19639 36977 19638 36977 19640 36978 19641 36978 19639 36978 19642 36979 19641 36979 19640 36979 19642 36980 19643 36980 19641 36980 19644 36981 19645 36981 19642 36981 19642 36982 19645 36982 19643 36982 19646 36983 19645 36983 19644 36983 19646 36984 19647 36984 19645 36984 19646 36985 19648 36985 19647 36985 19649 36986 19648 36986 19646 36986 19649 36987 19650 36987 19648 36987 19651 36988 19650 36988 19649 36988 19651 36989 19652 36989 19650 36989 19653 36990 19652 36990 19651 36990 19653 36991 19654 36991 19652 36991 19655 36992 19654 36992 19653 36992 19655 36993 19656 36993 19654 36993 19657 36994 19656 36994 19655 36994 19657 36995 19658 36995 19656 36995 19659 36996 19658 36996 19657 36996 19659 36997 19660 36997 19658 36997 19661 36998 19660 36998 19659 36998 19661 36999 19662 36999 19660 36999 19663 37000 19662 37000 19661 37000 19663 37001 19664 37001 19662 37001 19663 37002 19665 37002 19664 37002 19666 37003 19665 37003 19663 37003 19666 37004 19667 37004 19665 37004 19668 37005 19667 37005 19666 37005 19668 37006 19669 37006 19667 37006 19670 37007 19669 37007 19668 37007 19670 37008 19671 37008 19669 37008 19672 37009 19671 37009 19670 37009 19672 37010 19673 37010 19671 37010 19672 37011 19674 37011 19673 37011 19675 37012 19674 37012 19672 37012 19675 37013 19676 37013 19674 37013 19677 37014 19676 37014 19675 37014 19677 37015 19678 37015 19676 37015 19679 37016 19678 37016 19677 37016 19679 37017 19680 37017 19678 37017 19681 37018 19682 37018 19679 37018 19679 37019 19682 37019 19680 37019 19683 37020 19684 37020 19681 37020 19681 37021 19684 37021 19682 37021 19683 37022 19685 37022 19684 37022 19686 37023 19685 37023 19683 37023 19688 37024 19687 37024 19686 37024 19686 37025 19687 37025 19685 37025 19688 37026 19689 37026 19687 37026 19690 37027 19689 37027 19688 37027 19690 37028 19691 37028 19689 37028 19692 37029 19691 37029 19690 37029 19693 37030 19691 37030 19692 37030 19693 37031 19694 37031 19691 37031 19695 37032 19694 37032 19693 37032 19695 37033 19696 37033 19694 37033 19697 37034 19696 37034 19695 37034 19697 37035 19698 37035 19696 37035 19699 37036 19698 37036 19697 37036 19699 37037 19700 37037 19698 37037 19701 37038 19700 37038 19699 37038 19701 37039 19702 37039 19700 37039 19703 37040 19702 37040 19701 37040 19703 37041 19704 37041 19702 37041 19703 37042 19705 37042 19704 37042 19706 37043 19705 37043 19703 37043 19706 37044 19707 37044 19705 37044 19708 37045 19707 37045 19706 37045 19708 37046 19709 37046 19707 37046 19710 37047 19709 37047 19708 37047 19711 37048 19712 37048 19710 37048 19710 37049 19712 37049 19709 37049 19711 37050 19713 37050 19712 37050 19714 37051 19713 37051 19711 37051 19716 37052 19715 37052 19714 37052 19714 37053 19715 37053 19713 37053 19716 37054 19717 37054 19715 37054 19718 37055 19717 37055 19716 37055 19718 37056 19719 37056 19717 37056 19720 37057 19719 37057 19718 37057 19720 37058 19721 37058 19719 37058 19722 37059 19721 37059 19720 37059 19722 37060 19723 37060 19721 37060 19724 37061 19723 37061 19722 37061 19724 37062 19725 37062 19723 37062 19724 37063 19726 37063 19725 37063 19727 37064 19726 37064 19724 37064 19727 37065 19728 37065 19726 37065 19729 37066 19728 37066 19727 37066 19729 37067 19730 37067 19728 37067 19731 37068 19730 37068 19729 37068 19731 37069 19732 37069 19730 37069 19731 37070 19733 37070 19732 37070 19734 37071 19733 37071 19731 37071 19734 37072 19735 37072 19733 37072 19734 37073 19736 37073 19735 37073 19737 37074 19736 37074 19734 37074 19737 37075 19738 37075 19736 37075 19739 37076 19738 37076 19737 37076 19739 37077 19740 37077 19738 37077 19741 37078 19740 37078 19739 37078 19741 37079 19742 37079 19740 37079 19741 37080 19743 37080 19742 37080 19744 37081 19743 37081 19741 37081 19744 37082 19236 37082 19743 37082 19745 37083 19236 37083 19744 37083 19745 37084 19234 37084 19236 37084 19746 37085 19234 37085 19745 37085 19746 37086 19230 37086 19234 37086 19747 37087 19230 37087 19746 37087 19747 37088 19226 37088 19230 37088 19748 37089 19226 37089 19747 37089 19749 37090 19254 37090 19252 37090 19750 37091 19254 37091 19749 37091 19256 37092 19254 37092 19750 37092 19751 37093 19256 37093 19750 37093 19259 37094 19256 37094 19751 37094 19261 37095 19259 37095 19751 37095 19752 37096 19261 37096 19751 37096 19263 37097 19261 37097 19752 37097 19753 37098 19263 37098 19752 37098 19265 37099 19263 37099 19753 37099 19267 37100 19265 37100 19753 37100 19754 37101 19267 37101 19753 37101 19269 37102 19267 37102 19754 37102 19755 37103 19269 37103 19754 37103 19272 37104 19269 37104 19755 37104 19756 37105 19272 37105 19755 37105 19274 37106 19272 37106 19756 37106 19757 37107 19274 37107 19756 37107 19277 37108 19274 37108 19757 37108 19758 37109 19277 37109 19757 37109 19759 37110 19277 37110 19758 37110 19279 37111 19277 37111 19759 37111 19281 37112 19279 37112 19759 37112 19760 37113 19281 37113 19759 37113 19284 37114 19281 37114 19760 37114 19761 37115 19284 37115 19760 37115 19286 37116 19284 37116 19761 37116 19762 37117 19286 37117 19761 37117 19288 37118 19286 37118 19762 37118 19763 37119 19288 37119 19762 37119 19290 37120 19288 37120 19763 37120 19764 37121 19290 37121 19763 37121 19292 37122 19290 37122 19764 37122 19765 37123 19292 37123 19764 37123 19295 37124 19292 37124 19765 37124 19766 37125 19295 37125 19765 37125 19297 37126 19295 37126 19766 37126 19767 37127 19297 37127 19766 37127 19299 37128 19297 37128 19767 37128 19768 37129 19299 37129 19767 37129 19301 37130 19299 37130 19768 37130 19769 37131 19301 37131 19768 37131 19770 37132 19301 37132 19769 37132 19304 37133 19301 37133 19770 37133 19771 37134 19304 37134 19770 37134 19306 37135 19304 37135 19771 37135 19772 37136 19306 37136 19771 37136 19308 37137 19306 37137 19772 37137 19773 37138 19308 37138 19772 37138 19310 37139 19308 37139 19773 37139 19774 37140 19310 37140 19773 37140 19312 37141 19310 37141 19774 37141 19775 37142 19312 37142 19774 37142 19315 37143 19312 37143 19775 37143 19776 37144 19315 37144 19775 37144 19317 37145 19315 37145 19776 37145 19777 37146 19317 37146 19776 37146 19319 37147 19317 37147 19777 37147 19778 37148 19319 37148 19777 37148 19321 37149 19319 37149 19778 37149 19323 37150 19321 37150 19778 37150 19779 37151 19323 37151 19778 37151 19326 37152 19323 37152 19779 37152 19327 37153 19326 37153 19779 37153 19780 37154 19327 37154 19779 37154 19781 37155 19327 37155 19780 37155 19329 37156 19327 37156 19781 37156 19782 37157 19329 37157 19781 37157 19332 37158 19329 37158 19782 37158 19783 37159 19332 37159 19782 37159 19334 37160 19332 37160 19783 37160 19337 37161 19334 37161 19783 37161 19784 37162 19337 37162 19783 37162 19339 37163 19337 37163 19784 37163 19785 37164 19339 37164 19784 37164 19341 37165 19339 37165 19785 37165 19786 37166 19341 37166 19785 37166 19344 37167 19341 37167 19786 37167 19346 37168 19344 37168 19786 37168 19787 37169 19346 37169 19786 37169 19348 37170 19346 37170 19787 37170 19350 37171 19348 37171 19787 37171 19788 37172 19350 37172 19787 37172 19352 37173 19350 37173 19788 37173 19789 37174 19352 37174 19788 37174 19790 37175 19352 37175 19789 37175 19354 37176 19352 37176 19790 37176 19356 37177 19354 37177 19790 37177 19791 37178 19356 37178 19790 37178 19358 37179 19356 37179 19791 37179 19792 37180 19358 37180 19791 37180 19793 37181 19358 37181 19792 37181 19360 37182 19358 37182 19793 37182 19362 37183 19360 37183 19793 37183 19794 37184 19362 37184 19793 37184 19365 37185 19362 37185 19794 37185 19795 37186 19365 37186 19794 37186 19367 37187 19365 37187 19795 37187 19796 37188 19367 37188 19795 37188 19370 37189 19367 37189 19796 37189 19797 37190 19370 37190 19796 37190 19372 37191 19370 37191 19797 37191 19798 37192 19372 37192 19797 37192 19374 37193 19372 37193 19798 37193 19799 37194 19374 37194 19798 37194 19800 37195 19374 37195 19799 37195 19377 37196 19374 37196 19800 37196 19801 37197 19377 37197 19800 37197 19379 37198 19377 37198 19801 37198 19802 37199 19379 37199 19801 37199 19381 37200 19379 37200 19802 37200 19803 37201 19381 37201 19802 37201 19384 37202 19381 37202 19803 37202 19804 37203 19384 37203 19803 37203 19385 37204 19384 37204 19804 37204 19805 37205 19385 37205 19804 37205 19388 37206 19385 37206 19805 37206 19806 37207 19388 37207 19805 37207 19390 37208 19388 37208 19806 37208 19807 37209 19390 37209 19806 37209 19392 37210 19390 37210 19807 37210 19808 37211 19392 37211 19807 37211 19394 37212 19392 37212 19808 37212 19809 37213 19394 37213 19808 37213 19396 37214 19394 37214 19809 37214 19810 37215 19396 37215 19809 37215 19399 37216 19396 37216 19810 37216 19811 37217 19399 37217 19810 37217 19401 37218 19399 37218 19811 37218 19812 37219 19401 37219 19811 37219 19403 37220 19401 37220 19812 37220 19813 37221 19403 37221 19812 37221 19405 37222 19403 37222 19813 37222 19814 37223 19405 37223 19813 37223 19407 37224 19405 37224 19814 37224 19815 37225 19407 37225 19814 37225 19410 37226 19407 37226 19815 37226 19816 37227 19410 37227 19815 37227 19412 37228 19410 37228 19816 37228 19817 37229 19412 37229 19816 37229 19414 37230 19412 37230 19817 37230 19818 37231 19414 37231 19817 37231 19417 37232 19414 37232 19818 37232 19819 37233 19417 37233 19818 37233 19418 37234 19417 37234 19819 37234 19820 37235 19418 37235 19819 37235 19420 37236 19418 37236 19820 37236 19821 37237 19420 37237 19820 37237 19822 37238 19420 37238 19821 37238 19422 37239 19420 37239 19822 37239 19823 37240 19422 37240 19822 37240 19425 37241 19422 37241 19823 37241 19427 37242 19425 37242 19823 37242 19824 37243 19427 37243 19823 37243 19429 37244 19427 37244 19824 37244 19825 37245 19429 37245 19824 37245 19826 37246 19429 37246 19825 37246 19431 37247 19429 37247 19826 37247 19827 37248 19431 37248 19826 37248 19433 37249 19431 37249 19827 37249 19436 37250 19433 37250 19827 37250 19828 37251 19436 37251 19827 37251 19438 37252 19436 37252 19828 37252 19829 37253 19438 37253 19828 37253 19830 37254 19438 37254 19829 37254 19440 37255 19438 37255 19830 37255 19442 37256 19440 37256 19830 37256 19831 37257 19442 37257 19830 37257 19832 37258 19442 37258 19831 37258 19444 37259 19442 37259 19832 37259 19833 37260 19444 37260 19832 37260 19446 37261 19444 37261 19833 37261 19834 37262 19446 37262 19833 37262 19448 37263 19446 37263 19834 37263 19835 37264 19448 37264 19834 37264 19450 37265 19448 37265 19835 37265 19836 37266 19450 37266 19835 37266 19453 37267 19450 37267 19836 37267 19837 37268 19453 37268 19836 37268 19455 37269 19453 37269 19837 37269 19838 37270 19455 37270 19837 37270 19458 37271 19455 37271 19838 37271 19839 37272 19458 37272 19838 37272 19460 37273 19458 37273 19839 37273 19840 37274 19460 37274 19839 37274 19462 37275 19460 37275 19840 37275 19841 37276 19462 37276 19840 37276 19464 37277 19462 37277 19841 37277 19842 37278 19464 37278 19841 37278 19843 37279 19464 37279 19842 37279 19467 37280 19464 37280 19843 37280 19844 37281 19467 37281 19843 37281 19845 37282 19467 37282 19844 37282 19470 37283 19467 37283 19845 37283 19846 37284 19470 37284 19845 37284 19472 37285 19470 37285 19846 37285 19847 37286 19472 37286 19846 37286 19474 37287 19472 37287 19847 37287 19848 37288 19474 37288 19847 37288 19476 37289 19474 37289 19848 37289 19849 37290 19476 37290 19848 37290 19478 37291 19476 37291 19849 37291 19850 37292 19478 37292 19849 37292 19480 37293 19478 37293 19850 37293 19851 37294 19480 37294 19850 37294 19483 37295 19480 37295 19851 37295 19852 37296 19483 37296 19851 37296 19853 37297 19483 37297 19852 37297 19485 37298 19483 37298 19853 37298 19854 37299 19485 37299 19853 37299 19487 37300 19485 37300 19854 37300 19489 37301 19487 37301 19854 37301 19855 37302 19489 37302 19854 37302 19491 37303 19489 37303 19855 37303 19856 37304 19491 37304 19855 37304 19493 37305 19491 37305 19856 37305 19857 37306 19493 37306 19856 37306 19496 37307 19493 37307 19857 37307 19858 37308 19496 37308 19857 37308 19499 37309 19496 37309 19858 37309 19859 37310 19499 37310 19858 37310 19860 37311 19499 37311 19859 37311 19501 37312 19499 37312 19860 37312 19503 37313 19501 37313 19860 37313 19861 37314 19503 37314 19860 37314 19505 37315 19503 37315 19861 37315 19862 37316 19505 37316 19861 37316 19507 37317 19505 37317 19862 37317 19863 37318 19507 37318 19862 37318 19509 37319 19507 37319 19863 37319 19864 37320 19509 37320 19863 37320 19865 37321 19509 37321 19864 37321 19512 37322 19509 37322 19865 37322 19866 37323 19512 37323 19865 37323 19514 37324 19512 37324 19866 37324 19867 37325 19514 37325 19866 37325 19516 37326 19514 37326 19867 37326 19868 37327 19516 37327 19867 37327 19518 37328 19516 37328 19868 37328 19869 37329 19518 37329 19868 37329 19520 37330 19518 37330 19869 37330 19870 37331 19520 37331 19869 37331 19523 37332 19520 37332 19870 37332 19871 37333 19523 37333 19870 37333 19525 37334 19523 37334 19871 37334 19872 37335 19525 37335 19871 37335 19527 37336 19525 37336 19872 37336 19873 37337 19527 37337 19872 37337 19529 37338 19527 37338 19873 37338 19874 37339 19529 37339 19873 37339 19532 37340 19529 37340 19874 37340 19875 37341 19532 37341 19874 37341 19534 37342 19532 37342 19875 37342 19876 37343 19534 37343 19875 37343 19536 37344 19534 37344 19876 37344 19877 37345 19536 37345 19876 37345 19538 37346 19536 37346 19877 37346 19878 37347 19538 37347 19877 37347 19540 37348 19538 37348 19878 37348 19879 37349 19540 37349 19878 37349 19542 37350 19540 37350 19879 37350 19880 37351 19542 37351 19879 37351 19544 37352 19542 37352 19880 37352 19881 37353 19544 37353 19880 37353 19546 37354 19544 37354 19881 37354 19882 37355 19546 37355 19881 37355 19548 37356 19546 37356 19882 37356 19883 37357 19548 37357 19882 37357 19550 37358 19548 37358 19883 37358 19884 37359 19550 37359 19883 37359 19552 37360 19550 37360 19884 37360 19885 37361 19552 37361 19884 37361 19555 37362 19552 37362 19885 37362 19886 37363 19555 37363 19885 37363 19557 37364 19555 37364 19886 37364 19887 37365 19557 37365 19886 37365 19560 37366 19557 37366 19887 37366 19888 37367 19560 37367 19887 37367 19562 37368 19560 37368 19888 37368 19889 37369 19562 37369 19888 37369 19565 37370 19562 37370 19889 37370 19890 37371 19565 37371 19889 37371 19568 37372 19565 37372 19890 37372 19891 37373 19568 37373 19890 37373 19570 37374 19568 37374 19891 37374 19892 37375 19570 37375 19891 37375 19571 37376 19570 37376 19892 37376 19574 37377 19571 37377 19892 37377 19893 37378 19574 37378 19892 37378 19894 37379 19574 37379 19893 37379 19576 37380 19574 37380 19894 37380 19895 37381 19576 37381 19894 37381 19579 37382 19576 37382 19895 37382 19896 37383 19579 37383 19895 37383 19580 37384 19579 37384 19896 37384 19897 37385 19580 37385 19896 37385 19583 37386 19580 37386 19897 37386 19898 37387 19583 37387 19897 37387 19585 37388 19583 37388 19898 37388 19899 37389 19585 37389 19898 37389 19587 37390 19585 37390 19899 37390 19900 37391 19587 37391 19899 37391 19589 37392 19587 37392 19900 37392 19901 37393 19589 37393 19900 37393 19592 37394 19589 37394 19901 37394 19902 37395 19592 37395 19901 37395 19593 37396 19592 37396 19902 37396 19903 37397 19593 37397 19902 37397 19595 37398 19593 37398 19903 37398 19904 37399 19595 37399 19903 37399 19597 37400 19595 37400 19904 37400 19905 37401 19597 37401 19904 37401 19600 37402 19597 37402 19905 37402 19906 37403 19600 37403 19905 37403 19601 37404 19600 37404 19906 37404 19907 37405 19601 37405 19906 37405 19603 37406 19601 37406 19907 37406 19605 37407 19603 37407 19907 37407 19908 37408 19605 37408 19907 37408 19607 37409 19605 37409 19908 37409 19909 37410 19607 37410 19908 37410 19910 37411 19607 37411 19909 37411 19610 37412 19607 37412 19910 37412 19911 37413 19610 37413 19910 37413 19612 37414 19610 37414 19911 37414 19912 37415 19612 37415 19911 37415 19614 37416 19612 37416 19912 37416 19913 37417 19614 37417 19912 37417 19617 37418 19614 37418 19913 37418 19914 37419 19617 37419 19913 37419 19619 37420 19617 37420 19914 37420 19621 37421 19619 37421 19914 37421 19915 37422 19621 37422 19914 37422 19916 37423 19621 37423 19915 37423 19623 37424 19621 37424 19916 37424 19625 37425 19623 37425 19916 37425 19917 37426 19625 37426 19916 37426 19918 37427 19625 37427 19917 37427 19627 37428 19625 37428 19918 37428 19627 37429 19918 37429 19919 37429 19629 37430 19627 37430 19919 37430 19920 37431 19629 37431 19919 37431 19632 37432 19629 37432 19920 37432 19921 37433 19632 37433 19920 37433 19634 37434 19632 37434 19921 37434 19922 37435 19634 37435 19921 37435 19636 37436 19634 37436 19922 37436 19923 37437 19636 37437 19922 37437 19638 37438 19636 37438 19923 37438 19924 37439 19638 37439 19923 37439 19640 37440 19638 37440 19924 37440 19925 37441 19640 37441 19924 37441 19642 37442 19640 37442 19925 37442 19926 37443 19642 37443 19925 37443 19927 37444 19642 37444 19926 37444 19644 37445 19642 37445 19927 37445 19928 37446 19644 37446 19927 37446 19646 37447 19644 37447 19928 37447 19649 37448 19646 37448 19928 37448 19929 37449 19649 37449 19928 37449 19651 37450 19649 37450 19929 37450 19930 37451 19651 37451 19929 37451 19653 37452 19651 37452 19930 37452 19931 37453 19653 37453 19930 37453 19655 37454 19653 37454 19931 37454 19932 37455 19655 37455 19931 37455 19657 37456 19655 37456 19932 37456 19933 37457 19657 37457 19932 37457 19659 37458 19657 37458 19933 37458 19934 37459 19659 37459 19933 37459 19661 37460 19659 37460 19934 37460 19935 37461 19661 37461 19934 37461 19663 37462 19661 37462 19935 37462 19936 37463 19663 37463 19935 37463 19937 37464 19663 37464 19936 37464 19666 37465 19663 37465 19937 37465 19938 37466 19666 37466 19937 37466 19668 37467 19666 37467 19938 37467 19939 37468 19668 37468 19938 37468 19670 37469 19668 37469 19939 37469 19940 37470 19670 37470 19939 37470 19672 37471 19670 37471 19940 37471 19941 37472 19672 37472 19940 37472 19675 37473 19672 37473 19941 37473 19942 37474 19675 37474 19941 37474 19677 37475 19675 37475 19942 37475 19943 37476 19677 37476 19942 37476 19944 37477 19677 37477 19943 37477 19679 37478 19677 37478 19944 37478 19945 37479 19679 37479 19944 37479 19681 37480 19679 37480 19945 37480 19946 37481 19681 37481 19945 37481 19683 37482 19681 37482 19946 37482 19947 37483 19683 37483 19946 37483 19686 37484 19683 37484 19947 37484 19948 37485 19686 37485 19947 37485 19688 37486 19686 37486 19948 37486 19949 37487 19688 37487 19948 37487 19690 37488 19688 37488 19949 37488 19950 37489 19690 37489 19949 37489 19692 37490 19690 37490 19950 37490 19951 37491 19692 37491 19950 37491 19693 37492 19692 37492 19951 37492 19952 37493 19693 37493 19951 37493 19695 37494 19693 37494 19952 37494 19953 37495 19695 37495 19952 37495 19697 37496 19695 37496 19953 37496 19954 37497 19697 37497 19953 37497 19699 37498 19697 37498 19954 37498 19701 37499 19699 37499 19954 37499 19955 37500 19701 37500 19954 37500 19703 37501 19701 37501 19955 37501 19956 37502 19703 37502 19955 37502 19957 37503 19703 37503 19956 37503 19706 37504 19703 37504 19957 37504 19958 37505 19706 37505 19957 37505 19708 37506 19706 37506 19958 37506 19959 37507 19708 37507 19958 37507 19710 37508 19708 37508 19959 37508 19960 37509 19710 37509 19959 37509 19711 37510 19710 37510 19960 37510 19961 37511 19711 37511 19960 37511 19714 37512 19711 37512 19961 37512 19962 37513 19714 37513 19961 37513 19716 37514 19714 37514 19962 37514 19963 37515 19716 37515 19962 37515 19718 37516 19716 37516 19963 37516 19964 37517 19718 37517 19963 37517 19720 37518 19718 37518 19964 37518 19965 37519 19720 37519 19964 37519 19722 37520 19720 37520 19965 37520 19966 37521 19722 37521 19965 37521 19724 37522 19722 37522 19966 37522 19967 37523 19724 37523 19966 37523 19968 37524 19724 37524 19967 37524 19727 37525 19724 37525 19968 37525 19969 37526 19727 37526 19968 37526 19729 37527 19727 37527 19969 37527 19970 37528 19729 37528 19969 37528 19731 37529 19729 37529 19970 37529 19971 37530 19731 37530 19970 37530 19972 37531 19731 37531 19971 37531 19734 37532 19731 37532 19972 37532 19973 37533 19734 37533 19972 37533 19737 37534 19734 37534 19973 37534 19974 37535 19737 37535 19973 37535 19739 37536 19737 37536 19974 37536 19975 37537 19739 37537 19974 37537 19976 37538 19739 37538 19975 37538 19741 37539 19739 37539 19976 37539 19977 37540 19741 37540 19976 37540 19744 37541 19741 37541 19977 37541 19745 37542 19744 37542 19977 37542 19978 37543 19745 37543 19977 37543 19746 37544 19745 37544 19978 37544 19979 37545 19746 37545 19978 37545 19747 37546 19746 37546 19979 37546 19980 37547 19747 37547 19979 37547 19981 37548 19747 37548 19980 37548 19748 37549 19747 37549 19981 37549 19982 37550 19748 37550 19981 37550 19227 37551 19748 37551 19982 37551 19983 37552 19227 37552 19982 37552 19229 37553 19227 37553 19983 37553 19984 37554 19751 37554 19750 37554 19986 37555 19751 37555 19984 37555 19986 37556 19752 37556 19751 37556 19987 37557 19752 37557 19986 37557 19987 37558 19753 37558 19752 37558 19985 37559 19753 37559 19987 37559 19985 37560 19754 37560 19753 37560 19988 37561 19754 37561 19985 37561 19988 37562 19755 37562 19754 37562 19989 37563 19755 37563 19988 37563 19990 37564 19755 37564 19989 37564 19990 37565 19756 37565 19755 37565 19243 37566 19757 37566 19990 37566 19990 37567 19757 37567 19756 37567 19991 37568 19757 37568 19243 37568 19991 37569 19758 37569 19757 37569 19992 37570 19758 37570 19991 37570 19992 37571 19759 37571 19758 37571 19993 37572 19759 37572 19992 37572 19993 37573 19760 37573 19759 37573 19994 37574 19760 37574 19993 37574 19995 37575 19760 37575 19994 37575 19995 37576 19761 37576 19760 37576 19253 37577 19761 37577 19995 37577 19253 37578 19762 37578 19761 37578 19255 37579 19762 37579 19253 37579 19255 37580 19763 37580 19762 37580 19257 37581 19763 37581 19255 37581 19257 37582 19764 37582 19763 37582 19258 37583 19764 37583 19257 37583 19260 37584 19764 37584 19258 37584 19260 37585 19765 37585 19764 37585 19262 37586 19765 37586 19260 37586 19262 37587 19766 37587 19765 37587 19264 37588 19766 37588 19262 37588 19266 37589 19766 37589 19264 37589 19266 37590 19767 37590 19766 37590 19268 37591 19767 37591 19266 37591 19268 37592 19768 37592 19767 37592 19996 37593 19768 37593 19268 37593 19996 37594 19769 37594 19768 37594 19271 37595 19770 37595 19996 37595 19996 37596 19770 37596 19769 37596 19273 37597 19770 37597 19271 37597 19273 37598 19771 37598 19770 37598 19276 37599 19771 37599 19273 37599 19276 37600 19772 37600 19771 37600 19278 37601 19772 37601 19276 37601 19278 37602 19773 37602 19772 37602 19280 37603 19773 37603 19278 37603 19280 37604 19774 37604 19773 37604 19282 37605 19774 37605 19280 37605 19282 37606 19775 37606 19774 37606 19283 37607 19775 37607 19282 37607 19283 37608 19776 37608 19775 37608 19285 37609 19776 37609 19283 37609 19285 37610 19777 37610 19776 37610 19287 37611 19777 37611 19285 37611 19997 37612 19777 37612 19287 37612 19997 37613 19778 37613 19777 37613 19291 37614 19778 37614 19997 37614 19293 37615 19778 37615 19291 37615 19293 37616 19779 37616 19778 37616 19294 37617 19779 37617 19293 37617 19294 37618 19780 37618 19779 37618 19296 37619 19780 37619 19294 37619 19296 37620 19781 37620 19780 37620 19298 37621 19781 37621 19296 37621 19298 37622 19782 37622 19781 37622 19998 37623 19782 37623 19298 37623 19998 37624 19783 37624 19782 37624 19302 37625 19783 37625 19998 37625 19303 37626 19783 37626 19302 37626 19303 37627 19784 37627 19783 37627 19305 37628 19784 37628 19303 37628 19307 37629 19784 37629 19305 37629 19307 37630 19785 37630 19784 37630 19309 37631 19785 37631 19307 37631 19309 37632 19786 37632 19785 37632 19311 37633 19786 37633 19309 37633 19313 37634 19786 37634 19311 37634 19313 37635 19787 37635 19786 37635 19314 37636 19787 37636 19313 37636 19316 37637 19787 37637 19314 37637 19316 37638 19788 37638 19787 37638 19999 37639 19788 37639 19316 37639 19999 37640 19789 37640 19788 37640 19320 37641 19789 37641 19999 37641 19320 37642 19790 37642 19789 37642 19322 37643 19790 37643 19320 37643 19322 37644 19791 37644 19790 37644 19324 37645 19791 37645 19322 37645 19324 37646 19792 37646 19791 37646 19325 37647 19792 37647 19324 37647 19325 37648 19793 37648 19792 37648 20000 37649 19793 37649 19325 37649 19330 37650 19793 37650 20000 37650 19330 37651 19794 37651 19793 37651 19331 37652 19794 37652 19330 37652 19333 37653 19794 37653 19331 37653 19333 37654 19795 37654 19794 37654 19335 37655 19795 37655 19333 37655 19335 37656 19796 37656 19795 37656 20001 37657 19796 37657 19335 37657 20001 37658 19797 37658 19796 37658 19340 37659 19797 37659 20001 37659 19340 37660 19798 37660 19797 37660 19342 37661 19798 37661 19340 37661 19342 37662 19799 37662 19798 37662 19343 37663 19799 37663 19342 37663 19343 37664 19800 37664 19799 37664 19345 37665 19800 37665 19343 37665 19347 37666 19800 37666 19345 37666 19347 37667 19801 37667 19800 37667 19349 37668 19801 37668 19347 37668 19349 37669 19802 37669 19801 37669 19351 37670 19802 37670 19349 37670 19353 37671 19802 37671 19351 37671 19353 37672 19803 37672 19802 37672 20002 37673 19803 37673 19353 37673 20002 37674 19804 37674 19803 37674 20003 37675 19804 37675 20002 37675 20003 37676 19805 37676 19804 37676 19359 37677 19806 37677 20003 37677 20003 37678 19806 37678 19805 37678 19359 37679 19807 37679 19806 37679 19361 37680 19807 37680 19359 37680 19363 37681 19807 37681 19361 37681 19363 37682 19808 37682 19807 37682 19364 37683 19808 37683 19363 37683 19364 37684 19809 37684 19808 37684 19366 37685 19809 37685 19364 37685 19368 37686 19809 37686 19366 37686 19368 37687 19810 37687 19809 37687 19369 37688 19810 37688 19368 37688 19369 37689 19811 37689 19810 37689 19369 37690 19812 37690 19811 37690 20004 37691 19812 37691 19369 37691 20004 37692 19813 37692 19812 37692 20005 37693 19813 37693 20004 37693 20005 37694 19814 37694 19813 37694 19375 37695 19814 37695 20005 37695 19376 37696 19814 37696 19375 37696 19376 37697 19815 37697 19814 37697 19378 37698 19815 37698 19376 37698 19378 37699 19816 37699 19815 37699 19380 37700 19816 37700 19378 37700 19380 37701 19817 37701 19816 37701 19382 37702 19817 37702 19380 37702 19382 37703 19818 37703 19817 37703 20006 37704 19818 37704 19382 37704 20006 37705 19819 37705 19818 37705 19386 37706 19819 37706 20006 37706 19386 37707 19820 37707 19819 37707 19387 37708 19820 37708 19386 37708 19387 37709 19821 37709 19820 37709 19389 37710 19821 37710 19387 37710 19391 37711 19821 37711 19389 37711 19391 37712 19822 37712 19821 37712 19393 37713 19822 37713 19391 37713 19393 37714 19823 37714 19822 37714 19395 37715 19823 37715 19393 37715 19395 37716 19824 37716 19823 37716 19397 37717 19824 37717 19395 37717 19397 37718 19825 37718 19824 37718 20007 37719 19825 37719 19397 37719 20008 37720 19825 37720 20007 37720 20008 37721 19826 37721 19825 37721 19400 37722 19826 37722 20008 37722 19400 37723 19827 37723 19826 37723 19402 37724 19827 37724 19400 37724 19404 37725 19827 37725 19402 37725 19404 37726 19828 37726 19827 37726 19406 37727 19828 37727 19404 37727 19408 37728 19828 37728 19406 37728 19408 37729 19829 37729 19828 37729 19409 37730 19829 37730 19408 37730 19409 37731 19830 37731 19829 37731 19411 37732 19830 37732 19409 37732 19411 37733 19831 37733 19830 37733 19413 37734 19831 37734 19411 37734 19413 37735 19832 37735 19831 37735 19415 37736 19832 37736 19413 37736 19415 37737 19833 37737 19832 37737 20009 37738 19833 37738 19415 37738 20009 37739 19834 37739 19833 37739 20010 37740 19834 37740 20009 37740 20010 37741 19835 37741 19834 37741 19421 37742 19835 37742 20010 37742 19421 37743 19836 37743 19835 37743 19423 37744 19836 37744 19421 37744 19423 37745 19837 37745 19836 37745 19424 37746 19837 37746 19423 37746 19424 37747 19838 37747 19837 37747 19426 37748 19838 37748 19424 37748 19428 37749 19839 37749 19426 37749 19426 37750 19839 37750 19838 37750 20011 37751 19839 37751 19428 37751 20011 37752 19840 37752 19839 37752 20012 37753 19840 37753 20011 37753 20012 37754 19841 37754 19840 37754 19434 37755 19841 37755 20012 37755 19434 37756 19842 37756 19841 37756 19435 37757 19842 37757 19434 37757 19435 37758 19843 37758 19842 37758 19437 37759 19843 37759 19435 37759 19437 37760 19844 37760 19843 37760 19439 37761 19844 37761 19437 37761 19439 37762 19845 37762 19844 37762 20013 37763 19845 37763 19439 37763 20013 37764 19846 37764 19845 37764 20014 37765 19846 37765 20013 37765 20014 37766 19847 37766 19846 37766 19445 37767 19847 37767 20014 37767 19445 37768 19848 37768 19847 37768 19447 37769 19848 37769 19445 37769 19447 37770 19849 37770 19848 37770 19449 37771 19849 37771 19447 37771 19449 37772 19850 37772 19849 37772 19451 37773 19850 37773 19449 37773 19451 37774 19851 37774 19850 37774 20015 37775 19851 37775 19451 37775 19454 37776 19851 37776 20015 37776 19454 37777 19852 37777 19851 37777 19456 37778 19852 37778 19454 37778 19456 37779 19853 37779 19852 37779 20016 37780 19853 37780 19456 37780 20016 37781 19854 37781 19853 37781 19459 37782 19854 37782 20016 37782 19461 37783 19854 37783 19459 37783 19461 37784 19855 37784 19854 37784 19463 37785 19855 37785 19461 37785 19463 37786 19856 37786 19855 37786 20017 37787 19856 37787 19463 37787 20017 37788 19857 37788 19856 37788 20018 37789 19857 37789 20017 37789 20018 37790 19858 37790 19857 37790 20019 37791 19858 37791 20018 37791 20019 37792 19859 37792 19858 37792 19471 37793 19859 37793 20019 37793 19471 37794 19860 37794 19859 37794 19473 37795 19860 37795 19471 37795 19473 37796 19861 37796 19860 37796 19475 37797 19861 37797 19473 37797 19475 37798 19862 37798 19861 37798 19477 37799 19862 37799 19475 37799 19477 37800 19863 37800 19862 37800 20020 37801 19863 37801 19477 37801 20020 37802 19864 37802 19863 37802 20021 37803 19864 37803 20020 37803 20021 37804 19865 37804 19864 37804 19482 37805 19865 37805 20021 37805 19482 37806 19866 37806 19865 37806 20022 37807 19866 37807 19482 37807 20022 37808 19867 37808 19866 37808 20023 37809 19867 37809 20022 37809 20023 37810 19868 37810 19867 37810 19486 37811 19868 37811 20023 37811 19486 37812 19869 37812 19868 37812 19488 37813 19869 37813 19486 37813 19490 37814 19869 37814 19488 37814 19490 37815 19870 37815 19869 37815 19492 37816 19870 37816 19490 37816 19492 37817 19871 37817 19870 37817 19494 37818 19871 37818 19492 37818 19495 37819 19871 37819 19494 37819 19495 37820 19872 37820 19871 37820 19497 37821 19872 37821 19495 37821 19497 37822 19873 37822 19872 37822 19498 37823 19873 37823 19497 37823 19498 37824 19874 37824 19873 37824 20024 37825 19874 37825 19498 37825 19500 37826 19874 37826 20024 37826 19500 37827 19875 37827 19874 37827 19502 37828 19875 37828 19500 37828 19502 37829 19876 37829 19875 37829 19504 37830 19876 37830 19502 37830 19504 37831 19877 37831 19876 37831 19506 37832 19877 37832 19504 37832 19506 37833 19878 37833 19877 37833 19508 37834 19878 37834 19506 37834 19508 37835 19879 37835 19878 37835 20025 37836 19879 37836 19508 37836 20025 37837 19880 37837 19879 37837 19511 37838 19880 37838 20025 37838 20026 37839 19880 37839 19511 37839 20026 37840 19881 37840 19880 37840 20026 37841 19882 37841 19881 37841 20027 37842 19882 37842 20026 37842 20027 37843 19883 37843 19882 37843 19519 37844 19883 37844 20027 37844 19519 37845 19884 37845 19883 37845 19521 37846 19884 37846 19519 37846 20028 37847 19885 37847 19521 37847 19521 37848 19885 37848 19884 37848 19524 37849 19885 37849 20028 37849 19524 37850 19886 37850 19885 37850 19526 37851 19886 37851 19524 37851 20029 37852 19886 37852 19526 37852 20029 37853 19887 37853 19886 37853 20030 37854 19887 37854 20029 37854 20030 37855 19888 37855 19887 37855 20031 37856 19888 37856 20030 37856 20031 37857 19889 37857 19888 37857 19533 37858 19889 37858 20031 37858 19533 37859 19890 37859 19889 37859 19535 37860 19890 37860 19533 37860 19535 37861 19891 37861 19890 37861 19537 37862 19891 37862 19535 37862 19539 37863 19891 37863 19537 37863 19539 37864 19892 37864 19891 37864 19541 37865 19892 37865 19539 37865 20032 37866 19892 37866 19541 37866 20032 37867 19893 37867 19892 37867 20033 37868 19893 37868 20032 37868 19545 37869 19894 37869 20033 37869 20033 37870 19894 37870 19893 37870 19547 37871 19894 37871 19545 37871 19547 37872 19895 37872 19894 37872 20034 37873 19895 37873 19547 37873 20034 37874 19896 37874 19895 37874 20034 37875 19897 37875 19896 37875 19551 37876 19897 37876 20034 37876 19553 37877 19897 37877 19551 37877 19553 37878 19898 37878 19897 37878 19556 37879 19898 37879 19553 37879 19556 37880 19899 37880 19898 37880 19558 37881 19899 37881 19556 37881 19558 37882 19900 37882 19899 37882 19559 37883 19900 37883 19558 37883 19559 37884 19901 37884 19900 37884 19561 37885 19901 37885 19559 37885 19561 37886 19902 37886 19901 37886 19563 37887 19902 37887 19561 37887 19564 37888 19902 37888 19563 37888 19564 37889 19903 37889 19902 37889 19566 37890 19903 37890 19564 37890 19566 37891 19904 37891 19903 37891 19566 37892 19905 37892 19904 37892 20035 37893 19905 37893 19566 37893 19569 37894 19905 37894 20035 37894 19569 37895 19906 37895 19905 37895 19572 37896 19906 37896 19569 37896 19572 37897 19907 37897 19906 37897 19573 37898 19907 37898 19572 37898 19573 37899 19908 37899 19907 37899 19575 37900 19908 37900 19573 37900 19575 37901 19909 37901 19908 37901 19577 37902 19909 37902 19575 37902 19577 37903 19910 37903 19909 37903 20036 37904 19910 37904 19577 37904 20036 37905 19911 37905 19910 37905 19581 37906 19911 37906 20036 37906 19581 37907 19912 37907 19911 37907 19582 37908 19912 37908 19581 37908 19582 37909 19913 37909 19912 37909 19584 37910 19913 37910 19582 37910 19584 37911 19914 37911 19913 37911 19586 37912 19914 37912 19584 37912 19590 37913 19914 37913 19586 37913 19590 37914 19915 37914 19914 37914 20037 37915 19915 37915 19590 37915 20037 37916 19916 37916 19915 37916 20038 37917 19916 37917 20037 37917 20038 37918 19917 37918 19916 37918 20038 37919 19918 37919 19917 37919 19596 37920 19918 37920 20038 37920 19596 37921 19919 37921 19918 37921 19598 37922 19919 37922 19596 37922 19598 37923 19920 37923 19919 37923 19599 37924 19920 37924 19598 37924 20039 37925 19920 37925 19599 37925 20039 37926 19921 37926 19920 37926 20039 37927 19922 37927 19921 37927 19604 37928 19922 37928 20039 37928 20040 37929 19922 37929 19604 37929 20040 37930 19923 37930 19922 37930 19608 37931 19923 37931 20040 37931 19608 37932 19924 37932 19923 37932 19609 37933 19924 37933 19608 37933 19609 37934 19925 37934 19924 37934 19611 37935 19925 37935 19609 37935 19611 37936 19926 37936 19925 37936 19613 37937 19926 37937 19611 37937 19615 37938 19927 37938 19613 37938 19613 37939 19927 37939 19926 37939 19616 37940 19928 37940 19615 37940 19615 37941 19928 37941 19927 37941 19616 37942 19929 37942 19928 37942 20041 37943 19929 37943 19616 37943 20042 37944 19930 37944 20041 37944 20041 37945 19930 37945 19929 37945 19622 37946 19930 37946 20042 37946 19622 37947 19931 37947 19930 37947 19624 37948 19931 37948 19622 37948 19624 37949 19932 37949 19931 37949 20043 37950 19932 37950 19624 37950 20043 37951 19933 37951 19932 37951 20044 37952 19933 37952 20043 37952 19628 37953 19933 37953 20044 37953 19628 37954 19934 37954 19933 37954 19630 37955 19934 37955 19628 37955 19630 37956 19935 37956 19934 37956 19631 37957 19935 37957 19630 37957 19631 37958 19936 37958 19935 37958 20045 37959 19936 37959 19631 37959 20046 37960 19937 37960 20045 37960 20045 37961 19937 37961 19936 37961 20046 37962 19938 37962 19937 37962 20047 37963 19938 37963 20046 37963 20047 37964 19939 37964 19938 37964 19639 37965 19939 37965 20047 37965 19639 37966 19940 37966 19939 37966 19641 37967 19940 37967 19639 37967 19643 37968 19940 37968 19641 37968 19643 37969 19941 37969 19940 37969 19645 37970 19941 37970 19643 37970 19645 37971 19942 37971 19941 37971 19647 37972 19942 37972 19645 37972 19647 37973 19943 37973 19942 37973 19648 37974 19943 37974 19647 37974 19648 37975 19944 37975 19943 37975 20048 37976 19944 37976 19648 37976 20048 37977 19945 37977 19944 37977 19652 37978 19945 37978 20048 37978 19652 37979 19946 37979 19945 37979 19654 37980 19946 37980 19652 37980 19654 37981 19947 37981 19946 37981 19656 37982 19947 37982 19654 37982 19656 37983 19948 37983 19947 37983 19658 37984 19948 37984 19656 37984 19658 37985 19949 37985 19948 37985 20049 37986 19949 37986 19658 37986 20049 37987 19950 37987 19949 37987 19662 37988 19950 37988 20049 37988 19662 37989 19951 37989 19950 37989 19664 37990 19951 37990 19662 37990 19664 37991 19952 37991 19951 37991 19665 37992 19952 37992 19664 37992 19665 37993 19953 37993 19952 37993 19667 37994 19953 37994 19665 37994 19667 37995 19954 37995 19953 37995 20050 37996 19954 37996 19667 37996 19671 37997 19954 37997 20050 37997 19671 37998 19955 37998 19954 37998 19673 37999 19955 37999 19671 37999 19673 38000 19956 38000 19955 38000 19674 38001 19956 38001 19673 38001 19674 38002 19957 38002 19956 38002 19676 38003 19957 38003 19674 38003 19676 38004 19958 38004 19957 38004 20051 38005 19958 38005 19676 38005 20051 38006 19959 38006 19958 38006 20052 38007 19959 38007 20051 38007 20052 38008 19960 38008 19959 38008 19680 38009 19960 38009 20052 38009 19680 38010 19961 38010 19960 38010 20053 38011 19961 38011 19680 38011 20053 38012 19962 38012 19961 38012 19685 38013 19962 38013 20053 38013 19685 38014 19963 38014 19962 38014 19687 38015 19963 38015 19685 38015 19687 38016 19964 38016 19963 38016 19689 38017 19964 38017 19687 38017 19689 38018 19965 38018 19964 38018 20054 38019 19965 38019 19689 38019 20054 38020 19966 38020 19965 38020 20055 38021 19966 38021 20054 38021 20055 38022 19967 38022 19966 38022 19696 38023 19967 38023 20055 38023 19696 38024 19968 38024 19967 38024 20056 38025 19968 38025 19696 38025 20056 38026 19969 38026 19968 38026 19700 38027 19969 38027 20056 38027 19700 38028 19970 38028 19969 38028 20057 38029 19970 38029 19700 38029 20057 38030 19971 38030 19970 38030 20058 38031 19971 38031 20057 38031 20058 38032 19972 38032 19971 38032 20059 38033 19972 38033 20058 38033 19705 38034 19973 38034 20059 38034 20059 38035 19973 38035 19972 38035 20060 38036 19973 38036 19705 38036 20060 38037 19974 38037 19973 38037 20060 38038 19975 38038 19974 38038 19709 38039 19975 38039 20060 38039 20061 38040 19975 38040 19709 38040 20061 38041 19976 38041 19975 38041 20061 38042 19977 38042 19976 38042 19715 38043 19977 38043 20061 38043 19715 38044 19978 38044 19977 38044 19717 38045 19978 38045 19715 38045 19719 38046 19978 38046 19717 38046 19719 38047 19979 38047 19978 38047 20062 38048 19979 38048 19719 38048 20062 38049 19980 38049 19979 38049 20063 38050 19980 38050 20062 38050 20063 38051 19981 38051 19980 38051 19723 38052 19981 38052 20063 38052 19723 38053 19982 38053 19981 38053 19725 38054 19982 38054 19723 38054 20064 38055 19983 38055 19725 38055 19725 38056 19983 38056 19982 38056 19728 38057 19983 38057 20064 38057 19728 38058 19229 38058 19983 38058 19730 38059 19229 38059 19728 38059 19730 38060 19232 38060 19229 38060 19730 38061 19235 38061 19232 38061 19732 38062 19235 38062 19730 38062 20065 38063 19235 38063 19732 38063 20065 38064 19237 38064 19235 38064 19736 38065 19237 38065 20065 38065 19736 38066 19238 38066 19237 38066 19738 38067 19238 38067 19736 38067 19738 38068 19239 38068 19238 38068 20066 38069 19988 38069 19985 38069 19989 38070 19988 38070 20066 38070 19241 38071 19989 38071 20066 38071 19990 38072 19989 38072 19241 38072 19242 38073 19990 38073 19241 38073 19243 38074 19990 38074 19242 38074 19244 38075 19991 38075 19243 38075 19992 38076 19991 38076 19244 38076 19247 38077 19992 38077 19244 38077 19993 38078 19992 38078 19247 38078 19249 38079 19993 38079 19247 38079 19994 38080 19993 38080 19249 38080 19251 38081 19994 38081 19249 38081 19995 38082 19994 38082 19251 38082 19253 38083 19995 38083 19251 38083 19270 38084 19996 38084 19268 38084 19271 38085 19996 38085 19270 38085 19276 38086 19273 38086 19275 38086 19289 38087 19997 38087 19287 38087 19291 38088 19997 38088 19289 38088 19998 38089 19298 38089 19300 38089 19302 38090 19998 38090 19300 38090 19318 38091 19999 38091 19316 38091 19320 38092 19999 38092 19318 38092 20000 38093 19325 38093 19328 38093 19330 38094 20000 38094 19328 38094 20001 38095 19335 38095 19336 38095 19338 38096 20001 38096 19336 38096 19340 38097 20001 38097 19338 38097 19355 38098 20002 38098 19353 38098 20003 38099 20002 38099 19355 38099 19357 38100 20003 38100 19355 38100 19359 38101 20003 38101 19357 38101 20004 38102 19369 38102 19371 38102 19373 38103 20004 38103 19371 38103 20005 38104 20004 38104 19373 38104 19375 38105 20005 38105 19373 38105 20006 38106 19382 38106 19383 38106 19386 38107 20006 38107 19383 38107 19398 38108 20007 38108 19397 38108 20008 38109 20007 38109 19398 38109 19400 38110 20008 38110 19398 38110 19416 38111 20009 38111 19415 38111 20010 38112 20009 38112 19416 38112 19419 38113 20010 38113 19416 38113 19421 38114 20010 38114 19419 38114 19430 38115 20011 38115 19428 38115 20012 38116 20011 38116 19430 38116 19432 38117 20012 38117 19430 38117 19434 38118 20012 38118 19432 38118 19441 38119 20013 38119 19439 38119 20014 38120 20013 38120 19441 38120 19443 38121 20014 38121 19441 38121 19445 38122 20014 38122 19443 38122 19452 38123 20015 38123 19451 38123 19454 38124 20015 38124 19452 38124 19457 38125 20016 38125 19456 38125 19459 38126 20016 38126 19457 38126 20017 38127 19463 38127 19465 38127 19466 38128 20017 38128 19465 38128 20018 38129 20017 38129 19466 38129 19468 38130 20018 38130 19466 38130 20019 38131 20018 38131 19468 38131 19469 38132 20019 38132 19468 38132 19471 38133 20019 38133 19469 38133 20020 38134 19477 38134 19479 38134 20021 38135 20020 38135 19479 38135 19481 38136 20021 38136 19479 38136 19482 38137 20021 38137 19481 38137 19484 38138 20022 38138 19482 38138 20023 38139 20022 38139 19484 38139 19486 38140 20023 38140 19484 38140 19500 38141 20024 38141 19498 38141 20025 38142 19508 38142 19510 38142 19511 38143 20025 38143 19510 38143 20026 38144 19511 38144 19513 38144 19515 38145 20026 38145 19513 38145 20027 38146 20026 38146 19515 38146 19517 38147 20027 38147 19515 38147 19519 38148 20027 38148 19517 38148 20028 38149 19521 38149 19522 38149 19524 38150 20028 38150 19522 38150 19528 38151 20029 38151 19526 38151 20030 38152 20029 38152 19528 38152 19530 38153 20030 38153 19528 38153 20031 38154 20030 38154 19530 38154 19531 38155 20031 38155 19530 38155 19533 38156 20031 38156 19531 38156 19543 38157 20032 38157 19541 38157 20033 38158 20032 38158 19543 38158 19545 38159 20033 38159 19543 38159 19549 38160 20034 38160 19547 38160 19551 38161 20034 38161 19549 38161 19556 38162 19553 38162 19554 38162 20035 38163 19566 38163 19567 38163 19569 38164 20035 38164 19567 38164 20036 38165 19577 38165 19578 38165 19581 38166 20036 38166 19578 38166 19590 38167 19586 38167 19588 38167 19591 38168 20037 38168 19590 38168 20038 38169 20037 38169 19591 38169 19594 38170 20038 38170 19591 38170 19596 38171 20038 38171 19594 38171 20039 38172 19599 38172 19602 38172 19604 38173 20039 38173 19602 38173 20040 38174 19604 38174 19606 38174 19608 38175 20040 38175 19606 38175 20041 38176 19616 38176 19618 38176 19620 38177 20041 38177 19618 38177 20042 38178 20041 38178 19620 38178 19622 38179 20042 38179 19620 38179 19626 38180 20043 38180 19624 38180 20044 38181 20043 38181 19626 38181 19628 38182 20044 38182 19626 38182 19633 38183 20045 38183 19631 38183 20046 38184 20045 38184 19633 38184 19635 38185 20046 38185 19633 38185 20047 38186 20046 38186 19635 38186 19637 38187 20047 38187 19635 38187 19639 38188 20047 38188 19637 38188 19650 38189 20048 38189 19648 38189 19652 38190 20048 38190 19650 38190 20049 38191 19658 38191 19660 38191 19662 38192 20049 38192 19660 38192 19669 38193 20050 38193 19667 38193 19671 38194 20050 38194 19669 38194 19678 38195 20051 38195 19676 38195 20052 38196 20051 38196 19678 38196 19680 38197 20052 38197 19678 38197 20053 38198 19680 38198 19682 38198 19684 38199 20053 38199 19682 38199 19685 38200 20053 38200 19684 38200 19691 38201 20054 38201 19689 38201 20055 38202 20054 38202 19691 38202 19694 38203 20055 38203 19691 38203 19696 38204 20055 38204 19694 38204 19698 38205 20056 38205 19696 38205 19700 38206 20056 38206 19698 38206 19702 38207 20057 38207 19700 38207 20058 38208 20057 38208 19702 38208 19704 38209 20058 38209 19702 38209 20059 38210 20058 38210 19704 38210 19705 38211 20059 38211 19704 38211 20060 38212 19705 38212 19707 38212 19709 38213 20060 38213 19707 38213 20061 38214 19709 38214 19712 38214 19713 38215 20061 38215 19712 38215 19715 38216 20061 38216 19713 38216 19721 38217 20062 38217 19719 38217 20063 38218 20062 38218 19721 38218 19723 38219 20063 38219 19721 38219 19726 38220 20064 38220 19725 38220 19728 38221 20064 38221 19726 38221 20065 38222 19732 38222 19733 38222 19735 38223 20065 38223 19733 38223 19736 38224 20065 38224 19735 38224 19239 38225 19738 38225 19740 38225 20071 38226 19239 38226 19740 38226 19742 38227 20071 38227 19740 38227 19743 38228 20069 38228 19742 38228 20130 38229 20123 38229 20067 38229 20068 38230 20069 38230 20129 38230 20068 38231 20130 38231 20070 38231 20070 38232 20130 38232 20067 38232 20071 38233 20069 38233 20068 38233 20072 38234 20068 38234 20070 38234 19742 38235 20069 38235 20071 38235 20071 38236 20068 38236 20072 38236 20073 38237 20070 38237 20067 38237 20072 38238 20070 38238 20073 38238 20074 38239 20071 38239 20072 38239 19239 38240 20071 38240 20074 38240 20073 38241 20074 38241 20072 38241 20075 38242 20073 38242 20067 38242 20075 38243 20074 38243 20073 38243 20075 38244 20067 38244 20076 38244 19240 38245 19239 38245 20074 38245 20077 38246 20074 38246 20075 38246 20077 38247 19240 38247 20074 38247 20078 38248 20075 38248 20076 38248 20079 38249 20077 38249 20075 38249 19240 38250 20077 38250 20079 38250 20078 38251 20079 38251 20075 38251 20079 38252 20082 38252 19240 38252 20078 38253 20076 38253 20080 38253 20081 38254 20078 38254 20080 38254 20082 38255 20079 38255 20078 38255 20083 38256 20078 38256 20081 38256 20083 38257 20082 38257 20078 38257 20081 38258 20080 38258 20084 38258 20085 38259 20082 38259 20083 38259 20086 38260 20081 38260 20084 38260 20086 38261 20083 38261 20081 38261 20085 38262 20083 38262 20086 38262 20084 38263 20080 38263 20087 38263 20088 38264 20086 38264 20084 38264 20088 38265 20085 38265 20086 38265 20089 38266 20085 38266 20088 38266 20088 38267 20084 38267 20087 38267 20090 38268 20089 38268 20088 38268 20091 38269 20088 38269 20087 38269 20092 38270 20089 38270 20090 38270 20090 38271 20088 38271 20091 38271 20092 38272 20090 38272 20091 38272 20093 38273 20091 38273 20087 38273 20095 38274 20092 38274 20091 38274 20096 38275 20091 38275 20093 38275 20093 38276 20087 38276 20094 38276 20095 38277 20091 38277 20096 38277 20097 38278 20093 38278 20094 38278 20095 38279 20098 38279 20092 38279 20096 38280 20093 38280 20097 38280 20099 38281 20095 38281 20096 38281 20099 38282 20098 38282 20095 38282 20099 38283 20096 38283 20097 38283 20100 38284 20097 38284 20094 38284 20100 38285 20099 38285 20097 38285 20102 38286 20099 38286 20100 38286 20102 38287 20098 38287 20099 38287 20101 38288 20100 38288 20094 38288 20103 38289 20100 38289 20101 38289 20104 38290 20102 38290 20100 38290 20103 38291 20104 38291 20100 38291 20106 38292 20104 38292 20103 38292 20104 38293 20109 38293 20102 38293 20107 38294 20103 38294 20101 38294 20105 38295 20107 38295 20101 38295 20106 38296 20109 38296 20104 38296 20107 38297 20106 38297 20103 38297 20108 38298 20106 38298 20107 38298 20109 38299 20106 38299 20108 38299 20108 38300 20107 38300 20105 38300 20108 38301 19225 38301 20109 38301 20110 38302 20108 38302 20105 38302 20111 38303 20108 38303 20110 38303 19225 38304 20108 38304 20111 38304 20110 38305 20105 38305 20112 38305 20113 38306 20110 38306 20112 38306 19225 38307 20111 38307 20110 38307 20115 38308 20112 38308 20105 38308 20114 38309 19225 38309 20110 38309 20114 38310 20110 38310 20113 38310 20113 38311 20112 38311 20115 38311 20116 38312 20114 38312 20113 38312 19228 38313 20114 38313 20116 38313 20116 38314 20113 38314 20115 38314 20116 38315 20115 38315 20117 38315 20118 38316 20117 38316 20115 38316 20119 38317 20116 38317 20117 38317 20120 38318 20116 38318 20119 38318 20120 38319 19228 38319 20116 38319 20119 38320 20117 38320 20118 38320 19231 38321 19228 38321 20120 38321 20121 38322 20120 38322 20119 38322 19231 38323 20120 38323 20121 38323 20121 38324 20119 38324 20118 38324 19233 38325 19231 38325 20121 38325 20122 38326 20121 38326 20118 38326 20124 38327 20121 38327 20122 38327 19233 38328 20121 38328 20124 38328 20122 38329 20118 38329 20123 38329 20125 38330 19233 38330 20124 38330 20123 38331 20124 38331 20122 38331 19234 38332 19233 38332 20125 38332 20126 38333 20124 38333 20123 38333 20126 38334 20125 38334 20124 38334 19236 38335 19234 38335 20125 38335 20127 38336 20126 38336 20123 38336 20126 38337 19236 38337 20125 38337 20128 38338 20126 38338 20127 38338 20128 38339 19236 38339 20126 38339 20129 38340 20128 38340 20127 38340 20127 38341 20123 38341 20130 38341 20128 38342 19743 38342 19236 38342 20129 38343 20131 38343 20128 38343 20131 38344 19743 38344 20128 38344 20129 38345 20127 38345 20130 38345 20129 38346 20130 38346 20068 38346 20069 38347 20131 38347 20129 38347 19743 38348 20131 38348 20069 38348 20094 38349 20105 38349 20101 38349 20087 38350 20080 38350 20076 38350 20087 38351 20105 38351 20094 38351 20087 38352 20123 38352 20118 38352 20087 38353 20115 38353 20105 38353 20087 38354 20118 38354 20115 38354 20087 38355 20067 38355 20123 38355 20087 38356 20076 38356 20067 38356 20135 38357 20209 38357 20132 38357 20133 38358 20209 38358 20135 38358 20135 38359 20132 38359 20134 38359 20135 38360 20134 38360 20136 38360 20137 38361 20135 38361 20136 38361 20138 38362 20133 38362 20135 38362 20139 38363 20137 38363 20136 38363 20138 38364 20135 38364 20137 38364 20140 38365 20137 38365 20139 38365 20138 38366 20137 38366 20140 38366 20140 38367 20139 38367 20141 38367 20143 38368 20140 38368 20141 38368 20142 38369 20138 38369 20140 38369 20142 38370 20140 38370 20143 38370 20145 38371 20138 38371 20142 38371 20146 38372 20143 38372 20144 38372 20146 38373 20142 38373 20143 38373 20147 38374 20146 38374 20144 38374 20145 38375 20142 38375 20146 38375 20149 38376 20146 38376 20147 38376 20145 38377 20146 38377 20149 38377 20149 38378 20147 38378 20148 38378 20151 38379 20149 38379 20148 38379 20145 38380 20149 38380 20150 38380 20150 38381 20149 38381 20151 38381 20151 38382 20148 38382 20152 38382 20153 38383 20145 38383 20150 38383 20154 38384 20151 38384 20152 38384 20155 38385 20150 38385 20151 38385 20155 38386 20153 38386 20150 38386 20156 38387 20151 38387 20154 38387 20156 38388 20155 38388 20151 38388 20157 38389 20156 38389 20154 38389 20158 38390 20156 38390 20157 38390 20158 38391 20155 38391 20156 38391 20159 38392 20153 38392 20155 38392 20159 38393 20155 38393 20158 38393 20159 38394 20158 38394 20157 38394 20159 38395 20157 38395 20160 38395 20161 38396 20159 38396 20160 38396 20162 38397 20161 38397 20160 38397 20163 38398 20159 38398 20161 38398 20164 38399 20161 38399 20162 38399 20163 38400 20161 38400 20164 38400 20165 38401 20164 38401 20162 38401 20166 38402 20163 38402 20164 38402 20166 38403 20164 38403 20165 38403 20168 38404 20166 38404 20165 38404 20168 38405 20165 38405 20167 38405 20169 38406 20163 38406 20166 38406 20170 38407 20168 38407 20167 38407 20169 38408 20166 38408 20168 38408 20170 38409 20169 38409 20168 38409 20171 38410 20170 38410 20167 38410 20172 38411 20170 38411 20171 38411 20173 38412 20172 38412 20171 38412 20172 38413 20169 38413 20170 38413 20175 38414 20172 38414 20173 38414 20174 38415 20169 38415 20172 38415 20174 38416 20172 38416 20175 38416 20176 38417 20175 38417 20173 38417 20177 38418 20174 38418 20175 38418 20177 38419 20175 38419 20176 38419 20178 38420 20177 38420 20176 38420 20181 38421 20177 38421 20178 38421 20180 38422 20174 38422 20177 38422 20181 38423 20178 38423 20179 38423 20180 38424 20177 38424 20181 38424 20182 38425 20181 38425 20179 38425 20180 38426 20185 38426 20174 38426 20183 38427 20181 38427 20182 38427 20183 38428 20180 38428 20181 38428 20184 38429 20183 38429 20182 38429 20185 38430 20180 38430 20183 38430 20186 38431 20183 38431 20184 38431 20185 38432 20183 38432 20186 38432 20186 38433 20184 38433 20187 38433 20188 38434 20186 38434 20187 38434 20189 38435 20185 38435 20186 38435 20189 38436 20186 38436 20188 38436 20190 38437 20189 38437 20188 38437 20192 38438 20185 38438 20189 38438 20192 38439 20189 38439 20190 38439 20191 38440 20190 38440 20188 38440 20193 38441 20190 38441 20191 38441 20193 38442 20191 38442 20194 38442 20192 38443 20190 38443 20193 38443 20196 38444 20193 38444 20194 38444 20196 38445 20192 38445 20193 38445 20196 38446 20194 38446 20195 38446 20197 38447 20192 38447 20196 38447 20198 38448 20196 38448 20195 38448 20199 38449 20196 38449 20198 38449 20199 38450 20197 38450 20196 38450 20199 38451 20198 38451 20200 38451 20201 38452 20197 38452 20199 38452 20201 38453 20199 38453 20200 38453 20201 38454 20200 38454 20202 38454 20204 38455 20201 38455 20202 38455 20204 38456 20202 38456 20203 38456 20205 38457 20201 38457 20204 38457 20207 38458 20203 38458 20206 38458 20207 38459 20204 38459 20203 38459 20205 38460 20204 38460 20207 38460 20208 38461 20207 38461 20206 38461 20209 38462 20207 38462 20208 38462 20209 38463 20205 38463 20207 38463 20209 38464 20208 38464 20132 38464 20133 38465 20205 38465 20209 38465 20132 38466 20210 38466 20288 38466 20134 38467 20132 38467 20288 38467 20134 38468 20288 38468 20211 38468 20136 38469 20211 38469 20285 38469 20136 38470 20134 38470 20211 38470 20136 38471 20285 38471 20212 38471 20139 38472 20136 38472 20212 38472 20141 38473 20139 38473 20212 38473 20141 38474 20212 38474 20213 38474 20141 38475 20213 38475 20214 38475 20143 38476 20141 38476 20214 38476 20143 38477 20214 38477 20280 38477 20144 38478 20143 38478 20280 38478 20144 38479 20280 38479 20278 38479 20147 38480 20144 38480 20278 38480 20147 38481 20278 38481 20215 38481 20148 38482 20147 38482 20215 38482 20148 38483 20215 38483 20216 38483 20152 38484 20148 38484 20216 38484 20152 38485 20216 38485 20217 38485 20154 38486 20152 38486 20217 38486 20154 38487 20217 38487 20218 38487 20157 38488 20154 38488 20218 38488 20157 38489 20218 38489 20269 38489 20160 38490 20157 38490 20269 38490 20160 38491 20269 38491 20219 38491 20162 38492 20160 38492 20219 38492 20162 38493 20219 38493 20220 38493 20162 38494 20220 38494 20266 38494 20165 38495 20162 38495 20266 38495 20165 38496 20266 38496 20264 38496 20165 38497 20264 38497 20221 38497 20167 38498 20165 38498 20221 38498 20167 38499 20221 38499 20222 38499 20171 38500 20167 38500 20222 38500 20173 38501 20171 38501 20222 38501 20173 38502 20222 38502 20223 38502 20176 38503 20173 38503 20223 38503 20176 38504 20223 38504 20224 38504 20178 38505 20176 38505 20224 38505 20178 38506 20224 38506 20255 38506 20179 38507 20178 38507 20255 38507 20179 38508 20255 38508 20225 38508 20182 38509 20179 38509 20225 38509 20182 38510 20225 38510 20226 38510 20184 38511 20182 38511 20226 38511 20184 38512 20226 38512 20227 38512 20187 38513 20184 38513 20227 38513 20187 38514 20227 38514 20228 38514 20188 38515 20187 38515 20228 38515 20188 38516 20228 38516 20249 38516 20191 38517 20188 38517 20249 38517 20191 38518 20249 38518 20247 38518 20194 38519 20247 38519 20246 38519 20194 38520 20191 38520 20247 38520 20194 38521 20246 38521 20244 38521 20195 38522 20194 38522 20244 38522 20195 38523 20244 38523 20229 38523 20198 38524 20195 38524 20229 38524 20198 38525 20229 38525 20241 38525 20200 38526 20198 38526 20241 38526 20200 38527 20241 38527 20230 38527 20202 38528 20200 38528 20230 38528 20203 38529 20202 38529 20230 38529 20203 38530 20230 38530 20237 38530 20203 38531 20237 38531 20231 38531 20206 38532 20203 38532 20231 38532 20206 38533 20231 38533 20232 38533 20208 38534 20206 38534 20232 38534 20208 38535 20232 38535 20210 38535 20132 38536 20208 38536 20210 38536 19252 38537 20185 38537 19749 38537 19252 38538 20174 38538 20185 38538 19250 38539 20174 38539 19252 38539 19750 38540 20185 38540 20192 38540 19750 38541 19749 38541 20185 38541 19250 38542 20169 38542 20174 38542 19245 38543 20169 38543 19250 38543 19984 38544 19750 38544 20192 38544 19984 38545 20192 38545 20197 38545 19245 38546 20163 38546 20169 38546 19986 38547 19984 38547 20197 38547 19248 38548 20163 38548 19245 38548 19986 38549 20197 38549 20201 38549 19248 38550 20159 38550 20163 38550 20205 38551 19986 38551 20201 38551 20205 38552 19987 38552 19986 38552 20159 38553 19248 38553 19246 38553 20153 38554 20159 38554 19246 38554 20205 38555 19985 38555 19987 38555 20153 38556 19246 38556 19242 38556 20133 38557 19985 38557 20205 38557 20145 38558 20153 38558 19242 38558 20145 38559 19242 38559 19241 38559 20138 38560 19985 38560 20133 38560 20138 38561 20066 38561 19985 38561 20145 38562 19241 38562 20066 38562 20138 38563 20145 38563 20066 38563 20232 38564 20289 38564 20210 38564 20233 38565 20289 38565 20232 38565 20233 38566 20290 38566 20289 38566 20235 38567 20233 38567 20232 38567 20235 38568 20232 38568 20234 38568 20234 38569 20232 38569 20231 38569 20236 38570 20290 38570 20233 38570 20236 38571 20233 38571 20235 38571 20237 38572 20234 38572 20231 38572 20235 38573 20234 38573 20237 38573 20238 38574 20235 38574 20237 38574 20236 38575 20235 38575 20238 38575 20238 38576 20237 38576 20230 38576 20240 38577 20236 38577 20238 38577 20239 38578 20238 38578 20230 38578 20240 38579 20238 38579 20239 38579 20241 38580 20239 38580 20230 38580 20242 38581 20236 38581 20240 38581 20243 38582 20240 38582 20239 38582 20229 38583 20239 38583 20241 38583 20243 38584 20239 38584 20229 38584 20243 38585 20242 38585 20240 38585 20244 38586 20243 38586 20229 38586 20245 38587 20243 38587 20244 38587 20245 38588 20242 38588 20243 38588 20245 38589 20244 38589 20246 38589 20248 38590 20242 38590 20245 38590 20245 38591 20246 38591 20247 38591 20249 38592 20245 38592 20247 38592 20248 38593 20245 38593 20249 38593 20250 38594 20248 38594 20249 38594 20250 38595 20249 38595 20228 38595 20251 38596 20248 38596 20250 38596 20251 38597 20250 38597 20228 38597 20252 38598 20228 38598 20227 38598 20252 38599 20251 38599 20228 38599 20226 38600 20252 38600 20227 38600 20253 38601 20251 38601 20252 38601 20254 38602 20252 38602 20226 38602 20253 38603 20252 38603 20254 38603 20254 38604 20226 38604 20225 38604 20255 38605 20254 38605 20225 38605 20256 38606 20253 38606 20254 38606 20256 38607 20254 38607 20255 38607 20257 38608 20253 38608 20256 38608 20258 38609 20255 38609 20224 38609 20258 38610 20256 38610 20255 38610 20257 38611 20256 38611 20258 38611 20259 38612 20257 38612 20258 38612 20260 38613 20258 38613 20224 38613 20260 38614 20259 38614 20258 38614 20260 38615 20224 38615 20223 38615 20262 38616 20259 38616 20260 38616 20261 38617 20223 38617 20222 38617 20262 38618 20260 38618 20261 38618 20261 38619 20260 38619 20223 38619 19224 38620 20259 38620 20262 38620 20263 38621 20262 38621 20261 38621 20221 38622 20261 38622 20222 38622 19224 38623 20262 38623 20263 38623 20263 38624 20261 38624 20221 38624 20264 38625 20263 38625 20221 38625 20265 38626 20263 38626 20264 38626 20265 38627 19224 38627 20263 38627 20267 38628 20264 38628 20266 38628 20265 38629 20264 38629 20267 38629 20267 38630 20266 38630 20220 38630 20268 38631 20265 38631 20267 38631 20268 38632 19224 38632 20265 38632 20219 38633 20267 38633 20220 38633 20268 38634 20267 38634 20219 38634 20270 38635 19224 38635 20268 38635 20270 38636 20268 38636 20219 38636 20271 38637 20219 38637 20269 38637 20270 38638 20219 38638 20271 38638 20272 38639 20269 38639 20218 38639 20272 38640 20271 38640 20269 38640 20274 38641 20271 38641 20272 38641 20274 38642 20270 38642 20271 38642 20273 38643 20270 38643 20274 38643 20217 38644 20272 38644 20218 38644 20274 38645 20272 38645 20217 38645 20275 38646 20274 38646 20217 38646 20275 38647 20273 38647 20274 38647 20275 38648 20217 38648 20216 38648 20276 38649 20273 38649 20275 38649 20215 38650 20275 38650 20216 38650 20277 38651 20275 38651 20215 38651 20277 38652 20276 38652 20275 38652 20278 38653 20277 38653 20215 38653 20281 38654 20276 38654 20277 38654 20279 38655 20278 38655 20280 38655 20279 38656 20277 38656 20278 38656 20281 38657 20277 38657 20279 38657 20282 38658 20279 38658 20280 38658 20282 38659 20280 38659 20214 38659 20281 38660 20279 38660 20282 38660 20213 38661 20282 38661 20214 38661 20283 38662 20281 38662 20282 38662 20283 38663 20282 38663 20213 38663 20283 38664 20213 38664 20212 38664 20286 38665 20281 38665 20283 38665 20285 38666 20283 38666 20212 38666 20286 38667 20283 38667 20284 38667 20284 38668 20283 38668 20285 38668 20211 38669 20284 38669 20285 38669 20287 38670 20284 38670 20211 38670 20287 38671 20286 38671 20284 38671 20290 38672 20286 38672 20287 38672 20288 38673 20287 38673 20211 38673 20289 38674 20290 38674 20287 38674 20289 38675 20287 38675 20288 38675 20288 38676 20210 38676 20289 38676 19213 38677 19215 38677 19220 38677 19220 38678 19215 38678 19218 38678 19211 38679 19220 38679 19221 38679 19211 38680 19213 38680 19220 38680 19208 38681 19211 38681 19222 38681 19222 38682 19211 38682 19221 38682

+
+ + + +

20292 38683 20293 38683 20291 38683 20291 38684 20293 38684 20294 38684 20292 38685 20295 38685 20293 38685 20295 38686 20296 38686 20293 38686 20295 38687 20297 38687 20296 38687 20297 38688 20298 38688 20296 38688 20299 38689 20300 38689 20297 38689 20297 38690 20300 38690 20298 38690 20299 38691 20301 38691 20300 38691 20301 38692 20302 38692 20300 38692 20291 38693 20294 38693 20301 38693 20301 38694 20294 38694 20302 38694 20300 38695 20302 38695 20303 38695 20303 38696 20302 38696 20304 38696 20302 38697 20294 38697 20304 38697 20304 38698 20294 38698 20308 38698 20294 38699 20293 38699 20308 38699 20308 38700 20293 38700 20307 38700 20292 38701 20299 38701 20295 38701 20301 38702 20299 38702 20291 38702 20291 38703 20299 38703 20292 38703 20299 38704 20297 38704 20295 38704 20306 38705 21300 38705 21306 38705 20307 38706 20306 38706 21306 38706 20307 38707 21306 38707 21311 38707 20307 38708 21311 38708 21316 38708 21317 38709 20307 38709 21316 38709 20305 38710 21351 38710 21300 38710 20305 38711 21349 38711 21351 38711 20305 38712 21300 38712 20306 38712 21346 38713 21349 38713 20305 38713 20308 38714 20307 38714 21317 38714 20308 38715 21317 38715 21323 38715 21325 38716 20308 38716 21323 38716 20303 38717 21342 38717 21346 38717 20303 38718 21346 38718 20305 38718 21339 38719 21342 38719 20303 38719 21325 38720 20304 38720 20308 38720 21331 38721 20304 38721 21325 38721 21336 38722 21339 38722 20303 38722 21336 38723 20303 38723 20304 38723 21334 38724 20304 38724 21331 38724 21334 38725 21336 38725 20304 38725 20311 38726 20309 38726 20310 38726 20311 38727 20310 38727 20312 38727 20309 38728 21172 38728 20310 38728 20313 38729 21169 38729 21172 38729 20313 38730 21172 38730 20309 38730 20311 38731 20312 38731 20314 38731 20313 38732 21166 38732 21169 38732 20315 38733 20311 38733 20314 38733 20315 38734 20314 38734 20316 38734 20317 38735 21166 38735 20313 38735 20318 38736 20315 38736 20316 38736 20319 38737 20315 38737 20318 38737 20317 38738 20320 38738 21166 38738 20321 38739 20320 38739 20317 38739 21158 38740 20320 38740 20321 38740 20323 38741 21158 38741 20321 38741 20323 38742 20321 38742 20324 38742 20325 38743 20323 38743 20324 38743 21149 38744 20325 38744 20324 38744 21149 38745 20324 38745 20326 38745 21145 38746 21149 38746 20326 38746 21145 38747 20326 38747 20328 38747 20334 38748 20331 38748 20330 38748 20334 38749 20332 38749 20331 38749 20336 38750 20332 38750 20334 38750 20336 38751 20335 38751 20332 38751 20333 38752 20335 38752 20336 38752 20333 38753 20337 38753 20335 38753 20338 38754 20337 38754 20333 38754 20338 38755 20339 38755 20337 38755 20340 38756 20339 38756 20338 38756 20340 38757 20341 38757 20339 38757 20342 38758 20341 38758 20340 38758 20342 38759 20343 38759 20341 38759 20344 38760 20343 38760 20342 38760 20344 38761 20345 38761 20343 38761 20346 38762 20345 38762 20344 38762 20346 38763 20347 38763 20345 38763 20348 38764 20347 38764 20346 38764 20348 38765 20349 38765 20347 38765 20350 38766 20349 38766 20348 38766 20350 38767 20351 38767 20349 38767 20352 38768 20351 38768 20350 38768 20352 38769 20353 38769 20351 38769 20354 38770 20353 38770 20352 38770 20354 38771 20355 38771 20353 38771 20356 38772 20355 38772 20354 38772 20356 38773 20357 38773 20355 38773 20358 38774 20357 38774 20356 38774 20358 38775 20359 38775 20357 38775 20358 38776 20360 38776 20359 38776 20361 38777 20360 38777 20358 38777 20361 38778 20362 38778 20360 38778 20363 38779 20362 38779 20361 38779 20363 38780 20364 38780 20362 38780 20363 38781 20365 38781 20364 38781 20366 38782 20365 38782 20363 38782 20366 38783 20367 38783 20365 38783 20368 38784 20367 38784 20366 38784 20368 38785 20369 38785 20367 38785 20370 38786 20369 38786 20368 38786 20370 38787 20371 38787 20369 38787 20370 38788 20372 38788 20371 38788 20373 38789 20372 38789 20370 38789 20373 38790 20374 38790 20372 38790 20375 38791 20374 38791 20373 38791 20375 38792 20376 38792 20374 38792 20377 38793 20376 38793 20375 38793 20377 38794 20378 38794 20376 38794 20379 38795 20378 38795 20377 38795 20379 38796 20380 38796 20378 38796 20381 38797 20380 38797 20379 38797 20381 38798 20382 38798 20380 38798 20381 38799 20383 38799 20382 38799 20384 38800 20383 38800 20381 38800 20385 38801 20383 38801 20384 38801 20385 38802 20386 38802 20383 38802 20385 38803 20387 38803 20386 38803 20388 38804 20387 38804 20385 38804 20388 38805 20389 38805 20387 38805 20388 38806 20390 38806 20389 38806 20391 38807 20390 38807 20388 38807 20391 38808 20392 38808 20390 38808 20393 38809 20392 38809 20391 38809 20393 38810 20394 38810 20392 38810 20395 38811 20394 38811 20393 38811 20395 38812 20396 38812 20394 38812 20397 38813 20396 38813 20395 38813 20397 38814 20398 38814 20396 38814 20399 38815 20398 38815 20397 38815 20399 38816 20400 38816 20398 38816 20401 38817 20400 38817 20399 38817 20401 38818 20402 38818 20400 38818 20401 38819 20403 38819 20402 38819 20404 38820 20403 38820 20401 38820 20404 38821 20405 38821 20403 38821 20406 38822 20405 38822 20404 38822 20406 38823 20407 38823 20405 38823 20408 38824 20407 38824 20406 38824 20408 38825 20409 38825 20407 38825 20408 38826 20410 38826 20409 38826 20411 38827 20410 38827 20408 38827 20411 38828 20412 38828 20410 38828 20413 38829 20412 38829 20411 38829 20413 38830 20414 38830 20412 38830 20415 38831 20414 38831 20413 38831 20415 38832 20416 38832 20414 38832 20417 38833 20416 38833 20415 38833 20417 38834 20418 38834 20416 38834 20417 38835 20419 38835 20418 38835 20420 38836 20419 38836 20417 38836 20420 38837 20421 38837 20419 38837 20422 38838 20421 38838 20420 38838 20422 38839 20423 38839 20421 38839 20422 38840 20424 38840 20423 38840 20425 38841 20424 38841 20422 38841 20425 38842 20426 38842 20424 38842 20427 38843 20426 38843 20425 38843 20427 38844 20428 38844 20426 38844 20429 38845 20428 38845 20427 38845 20429 38846 20430 38846 20428 38846 20431 38847 20430 38847 20429 38847 20431 38848 20432 38848 20430 38848 20433 38849 20432 38849 20431 38849 20433 38850 20434 38850 20432 38850 20433 38851 20435 38851 20434 38851 20436 38852 20435 38852 20433 38852 20436 38853 20437 38853 20435 38853 20438 38854 20437 38854 20436 38854 20438 38855 20439 38855 20437 38855 20440 38856 20439 38856 20438 38856 20440 38857 20441 38857 20439 38857 20442 38858 20441 38858 20440 38858 20444 38859 20443 38859 20442 38859 20442 38860 20443 38860 20441 38860 20444 38861 20445 38861 20443 38861 20446 38862 20445 38862 20444 38862 20446 38863 20447 38863 20445 38863 20446 38864 20448 38864 20447 38864 20449 38865 20448 38865 20446 38865 20449 38866 20450 38866 20448 38866 20451 38867 20450 38867 20449 38867 20451 38868 20452 38868 20450 38868 20453 38869 20452 38869 20451 38869 20453 38870 20454 38870 20452 38870 20453 38871 20455 38871 20454 38871 20456 38872 20455 38872 20453 38872 20456 38873 20457 38873 20455 38873 20458 38874 20457 38874 20456 38874 20458 38875 20459 38875 20457 38875 20458 38876 20460 38876 20459 38876 20461 38877 20460 38877 20458 38877 20461 38878 20462 38878 20460 38878 20463 38879 20462 38879 20461 38879 20463 38880 20464 38880 20462 38880 20465 38881 20464 38881 20463 38881 20465 38882 20466 38882 20464 38882 20467 38883 20466 38883 20465 38883 20467 38884 20468 38884 20466 38884 20469 38885 20468 38885 20467 38885 20469 38886 20470 38886 20468 38886 20469 38887 20471 38887 20470 38887 20472 38888 20471 38888 20469 38888 20472 38889 20473 38889 20471 38889 20474 38890 20473 38890 20472 38890 20474 38891 20475 38891 20473 38891 20476 38892 20475 38892 20474 38892 20476 38893 20477 38893 20475 38893 20478 38894 20477 38894 20476 38894 20478 38895 20479 38895 20477 38895 20480 38896 20479 38896 20478 38896 20480 38897 20481 38897 20479 38897 20482 38898 20481 38898 20480 38898 20482 38899 20483 38899 20481 38899 20484 38900 20483 38900 20482 38900 20484 38901 20485 38901 20483 38901 20486 38902 20487 38902 20484 38902 20484 38903 20487 38903 20485 38903 20486 38904 20488 38904 20487 38904 20486 38905 20489 38905 20488 38905 20490 38906 20489 38906 20486 38906 20490 38907 20491 38907 20489 38907 20492 38908 20491 38908 20490 38908 20492 38909 20493 38909 20491 38909 20492 38910 20494 38910 20493 38910 20495 38911 20494 38911 20492 38911 20496 38912 20494 38912 20495 38912 20496 38913 20497 38913 20494 38913 20496 38914 20498 38914 20497 38914 20499 38915 20498 38915 20496 38915 20499 38916 20500 38916 20498 38916 20501 38917 20500 38917 20499 38917 20501 38918 20502 38918 20500 38918 20503 38919 20502 38919 20501 38919 20503 38920 20504 38920 20502 38920 20505 38921 20504 38921 20503 38921 20505 38922 20506 38922 20504 38922 20507 38923 20508 38923 20505 38923 20505 38924 20508 38924 20506 38924 20509 38925 20508 38925 20507 38925 20509 38926 20510 38926 20508 38926 20509 38927 20511 38927 20510 38927 20512 38928 20511 38928 20509 38928 20512 38929 20513 38929 20511 38929 20514 38930 20513 38930 20512 38930 20514 38931 20515 38931 20513 38931 20516 38932 20515 38932 20514 38932 20516 38933 20517 38933 20515 38933 20518 38934 20517 38934 20516 38934 20518 38935 20519 38935 20517 38935 20518 38936 20520 38936 20519 38936 20521 38937 20520 38937 20518 38937 20521 38938 20522 38938 20520 38938 20523 38939 20522 38939 20521 38939 20523 38940 20524 38940 20522 38940 20523 38941 20525 38941 20524 38941 20526 38942 20525 38942 20523 38942 20526 38943 20527 38943 20525 38943 20528 38944 20527 38944 20526 38944 20528 38945 20529 38945 20527 38945 20530 38946 20531 38946 20528 38946 20528 38947 20531 38947 20529 38947 20532 38948 20533 38948 20530 38948 20530 38949 20533 38949 20531 38949 20534 38950 20533 38950 20532 38950 20534 38951 20535 38951 20533 38951 20534 38952 20536 38952 20535 38952 20537 38953 20536 38953 20534 38953 20537 38954 20538 38954 20536 38954 20539 38955 20538 38955 20537 38955 20539 38956 20540 38956 20538 38956 20541 38957 20540 38957 20539 38957 20541 38958 20542 38958 20540 38958 20543 38959 20542 38959 20541 38959 20543 38960 20544 38960 20542 38960 20543 38961 20545 38961 20544 38961 20546 38962 20545 38962 20543 38962 20546 38963 20547 38963 20545 38963 20548 38964 20547 38964 20546 38964 20548 38965 20549 38965 20547 38965 20550 38966 20549 38966 20548 38966 20550 38967 20551 38967 20549 38967 20552 38968 20551 38968 20550 38968 20552 38969 20553 38969 20551 38969 20552 38970 20554 38970 20553 38970 20555 38971 20554 38971 20552 38971 20555 38972 20556 38972 20554 38972 20557 38973 20556 38973 20555 38973 20557 38974 20558 38974 20556 38974 20557 38975 20559 38975 20558 38975 20560 38976 20559 38976 20557 38976 20560 38977 20561 38977 20559 38977 20562 38978 20561 38978 20560 38978 20563 38979 20561 38979 20562 38979 20563 38980 20564 38980 20561 38980 20565 38981 20564 38981 20563 38981 20565 38982 20566 38982 20564 38982 20567 38983 20566 38983 20565 38983 20567 38984 20568 38984 20566 38984 20567 38985 20569 38985 20568 38985 20570 38986 20569 38986 20567 38986 20570 38987 20571 38987 20569 38987 20570 38988 20572 38988 20571 38988 20573 38989 20572 38989 20570 38989 20573 38990 20574 38990 20572 38990 20575 38991 20574 38991 20573 38991 20576 38992 20574 38992 20575 38992 20576 38993 20577 38993 20574 38993 20576 38994 20578 38994 20577 38994 20579 38995 20578 38995 20576 38995 20580 38996 20578 38996 20579 38996 20580 38997 20581 38997 20578 38997 20580 38998 20582 38998 20581 38998 20583 38999 20582 38999 20580 38999 20584 39000 20582 39000 20583 39000 20584 39001 20585 39001 20582 39001 20584 39002 20586 39002 20585 39002 20587 39003 20586 39003 20584 39003 20587 39004 20588 39004 20586 39004 20589 39005 20588 39005 20587 39005 20589 39006 20590 39006 20588 39006 20589 39007 20591 39007 20590 39007 20592 39008 20591 39008 20589 39008 20592 39009 20593 39009 20591 39009 20594 39010 20593 39010 20592 39010 20594 39011 20595 39011 20593 39011 20596 39012 20595 39012 20594 39012 20596 39013 20597 39013 20595 39013 20598 39014 20597 39014 20596 39014 20598 39015 20599 39015 20597 39015 20598 39016 20600 39016 20599 39016 20601 39017 20600 39017 20598 39017 20602 39018 20600 39018 20601 39018 20602 39019 20603 39019 20600 39019 20602 39020 20604 39020 20603 39020 20605 39021 20604 39021 20602 39021 20605 39022 20606 39022 20604 39022 20607 39023 20606 39023 20605 39023 20607 39024 20608 39024 20606 39024 20607 39025 20609 39025 20608 39025 20610 39026 20609 39026 20607 39026 20610 39027 20611 39027 20609 39027 20612 39028 20611 39028 20610 39028 20612 39029 20613 39029 20611 39029 20614 39030 20613 39030 20612 39030 20614 39031 20615 39031 20613 39031 20616 39032 20615 39032 20614 39032 20616 39033 20617 39033 20615 39033 20618 39034 20617 39034 20616 39034 20618 39035 20619 39035 20617 39035 20618 39036 20620 39036 20619 39036 20621 39037 20620 39037 20618 39037 20622 39038 20620 39038 20621 39038 20622 39039 20623 39039 20620 39039 20622 39040 20624 39040 20623 39040 20625 39041 20624 39041 20622 39041 20626 39042 20624 39042 20625 39042 20626 39043 20627 39043 20624 39043 20628 39044 20627 39044 20626 39044 20628 39045 20629 39045 20627 39045 20630 39046 20629 39046 20628 39046 20630 39047 20631 39047 20629 39047 20630 39048 20632 39048 20631 39048 20633 39049 20632 39049 20630 39049 20633 39050 20634 39050 20632 39050 20635 39051 20634 39051 20633 39051 20635 39052 20636 39052 20634 39052 20637 39053 20636 39053 20635 39053 20637 39054 20638 39054 20636 39054 20637 39055 20639 39055 20638 39055 20640 39056 20639 39056 20637 39056 20640 39057 20641 39057 20639 39057 20640 39058 20642 39058 20641 39058 20643 39059 20642 39059 20640 39059 20643 39060 20644 39060 20642 39060 20645 39061 20644 39061 20643 39061 20645 39062 20646 39062 20644 39062 20647 39063 20646 39063 20645 39063 20647 39064 20648 39064 20646 39064 20649 39065 20648 39065 20647 39065 20649 39066 20650 39066 20648 39066 20651 39067 20650 39067 20649 39067 20651 39068 20652 39068 20650 39068 20653 39069 20652 39069 20651 39069 20654 39070 20652 39070 20653 39070 20654 39071 20655 39071 20652 39071 20654 39072 20656 39072 20655 39072 20657 39073 20656 39073 20654 39073 20657 39074 20658 39074 20656 39074 20657 39075 20659 39075 20658 39075 20660 39076 20659 39076 20657 39076 20660 39077 20661 39077 20659 39077 20662 39078 20661 39078 20660 39078 20662 39079 20663 39079 20661 39079 20664 39080 20663 39080 20662 39080 20664 39081 20665 39081 20663 39081 20666 39082 20665 39082 20664 39082 20666 39083 20667 39083 20665 39083 20666 39084 20668 39084 20667 39084 20669 39085 20668 39085 20666 39085 20669 39086 20670 39086 20668 39086 20671 39087 20670 39087 20669 39087 20671 39088 20672 39088 20670 39088 20673 39089 20672 39089 20671 39089 20673 39090 20674 39090 20672 39090 20675 39091 20674 39091 20673 39091 20675 39092 20676 39092 20674 39092 20677 39093 20676 39093 20675 39093 20677 39094 20678 39094 20676 39094 20679 39095 20678 39095 20677 39095 20679 39096 20680 39096 20678 39096 20679 39097 20681 39097 20680 39097 20682 39098 20681 39098 20679 39098 20682 39099 20683 39099 20681 39099 20682 39100 20684 39100 20683 39100 20685 39101 20684 39101 20682 39101 20685 39102 20686 39102 20684 39102 20687 39103 20686 39103 20685 39103 20687 39104 20688 39104 20686 39104 20687 39105 20689 39105 20688 39105 20690 39106 20689 39106 20687 39106 20690 39107 20691 39107 20689 39107 20692 39108 20691 39108 20690 39108 20692 39109 20693 39109 20691 39109 20692 39110 20694 39110 20693 39110 20695 39111 20694 39111 20692 39111 20695 39112 20696 39112 20694 39112 20697 39113 20696 39113 20695 39113 20697 39114 20698 39114 20696 39114 20699 39115 20698 39115 20697 39115 20699 39116 20700 39116 20698 39116 20701 39117 20700 39117 20699 39117 20701 39118 20702 39118 20700 39118 20701 39119 20703 39119 20702 39119 20704 39120 20703 39120 20701 39120 20704 39121 20705 39121 20703 39121 20706 39122 20705 39122 20704 39122 20706 39123 20707 39123 20705 39123 20708 39124 20707 39124 20706 39124 20708 39125 20709 39125 20707 39125 20710 39126 20709 39126 20708 39126 20710 39127 20711 39127 20709 39127 20712 39128 20711 39128 20710 39128 20712 39129 20713 39129 20711 39129 20714 39130 20715 39130 20712 39130 20712 39131 20715 39131 20713 39131 20716 39132 20715 39132 20714 39132 20716 39133 20717 39133 20715 39133 20718 39134 20717 39134 20716 39134 20718 39135 20719 39135 20717 39135 20720 39136 20719 39136 20718 39136 20720 39137 20721 39137 20719 39137 20722 39138 20721 39138 20720 39138 20722 39139 20723 39139 20721 39139 20724 39140 20723 39140 20722 39140 20724 39141 20725 39141 20723 39141 20726 39142 20725 39142 20724 39142 20726 39143 20727 39143 20725 39143 20728 39144 20727 39144 20726 39144 20728 39145 20729 39145 20727 39145 20730 39146 20729 39146 20728 39146 20730 39147 20731 39147 20729 39147 20730 39148 20732 39148 20731 39148 20733 39149 20732 39149 20730 39149 20733 39150 20734 39150 20732 39150 20735 39151 20734 39151 20733 39151 20735 39152 20736 39152 20734 39152 20735 39153 20737 39153 20736 39153 20738 39154 20737 39154 20735 39154 20738 39155 20739 39155 20737 39155 20740 39156 20739 39156 20738 39156 20740 39157 20741 39157 20739 39157 20740 39158 20742 39158 20741 39158 20743 39159 20742 39159 20740 39159 20743 39160 20744 39160 20742 39160 20745 39161 20744 39161 20743 39161 20745 39162 20746 39162 20744 39162 20745 39163 20747 39163 20746 39163 20748 39164 20747 39164 20745 39164 20748 39165 20749 39165 20747 39165 20750 39166 20749 39166 20748 39166 20750 39167 20751 39167 20749 39167 20752 39168 20751 39168 20750 39168 20752 39169 20753 39169 20751 39169 20754 39170 20753 39170 20752 39170 20754 39171 20755 39171 20753 39171 20756 39172 20755 39172 20754 39172 20756 39173 20757 39173 20755 39173 20756 39174 20758 39174 20757 39174 20759 39175 20758 39175 20756 39175 20759 39176 20760 39176 20758 39176 20761 39177 20760 39177 20759 39177 20761 39178 20762 39178 20760 39178 20763 39179 20762 39179 20761 39179 20763 39180 20764 39180 20762 39180 20765 39181 20764 39181 20763 39181 20765 39182 20766 39182 20764 39182 20765 39183 20767 39183 20766 39183 20768 39184 20767 39184 20765 39184 20768 39185 20769 39185 20767 39185 20770 39186 20769 39186 20768 39186 20770 39187 20771 39187 20769 39187 20772 39188 20771 39188 20770 39188 20772 39189 20773 39189 20771 39189 20774 39190 20773 39190 20772 39190 20775 39191 20773 39191 20774 39191 20775 39192 20776 39192 20773 39192 20777 39193 20776 39193 20775 39193 20777 39194 20778 39194 20776 39194 20777 39195 20779 39195 20778 39195 20780 39196 20779 39196 20777 39196 20780 39197 20781 39197 20779 39197 20782 39198 20781 39198 20780 39198 20782 39199 20783 39199 20781 39199 20784 39200 20783 39200 20782 39200 20784 39201 20785 39201 20783 39201 20786 39202 20785 39202 20784 39202 20786 39203 20787 39203 20785 39203 20788 39204 20787 39204 20786 39204 20788 39205 20789 39205 20787 39205 20790 39206 20789 39206 20788 39206 20790 39207 20791 39207 20789 39207 20792 39208 20791 39208 20790 39208 20792 39209 20793 39209 20791 39209 20794 39210 20793 39210 20792 39210 20794 39211 20795 39211 20793 39211 20794 39212 20796 39212 20795 39212 20797 39213 20796 39213 20794 39213 20797 39214 20798 39214 20796 39214 20797 39215 20799 39215 20798 39215 20800 39216 20799 39216 20797 39216 20800 39217 20801 39217 20799 39217 20802 39218 20801 39218 20800 39218 20802 39219 20803 39219 20801 39219 20802 39220 20804 39220 20803 39220 20805 39221 20804 39221 20802 39221 20805 39222 20806 39222 20804 39222 20807 39223 20806 39223 20805 39223 20807 39224 20808 39224 20806 39224 20809 39225 20808 39225 20807 39225 20811 39226 20810 39226 20809 39226 20809 39227 20810 39227 20808 39227 20811 39228 20812 39228 20810 39228 20813 39229 20812 39229 20811 39229 20813 39230 20814 39230 20812 39230 20813 39231 20815 39231 20814 39231 20816 39232 20815 39232 20813 39232 20817 39233 20815 39233 20816 39233 20817 39234 20818 39234 20815 39234 20819 39235 20818 39235 20817 39235 20819 39236 20820 39236 20818 39236 20821 39237 20820 39237 20819 39237 20821 39238 20822 39238 20820 39238 20821 39239 20823 39239 20822 39239 20824 39240 20823 39240 20821 39240 20824 39241 20825 39241 20823 39241 20824 39242 20826 39242 20825 39242 20827 39243 20826 39243 20824 39243 20827 39244 20828 39244 20826 39244 20829 39245 20828 39245 20827 39245 20829 39246 20830 39246 20828 39246 20829 39247 20831 39247 20830 39247 20832 39248 20831 39248 20829 39248 20832 39249 20833 39249 20831 39249 20834 39250 20833 39250 20832 39250 20834 39251 20835 39251 20833 39251 20834 39252 20836 39252 20835 39252 20837 39253 20836 39253 20834 39253 20838 39254 20836 39254 20837 39254 20838 39255 20839 39255 20836 39255 20840 39256 20839 39256 20838 39256 20840 39257 20841 39257 20839 39257 20840 39258 20322 39258 20841 39258 20842 39259 20322 39259 20840 39259 20842 39260 20319 39260 20322 39260 20843 39261 20319 39261 20842 39261 20843 39262 20315 39262 20319 39262 20844 39263 20315 39263 20843 39263 20844 39264 20311 39264 20315 39264 20845 39265 20311 39265 20844 39265 20309 39266 20311 39266 20845 39266 20846 39267 20342 39267 20340 39267 20344 39268 20342 39268 20846 39268 20847 39269 20344 39269 20846 39269 20346 39270 20344 39270 20847 39270 20848 39271 20346 39271 20847 39271 20348 39272 20346 39272 20848 39272 20350 39273 20348 39273 20848 39273 20849 39274 20350 39274 20848 39274 20352 39275 20350 39275 20849 39275 20850 39276 20352 39276 20849 39276 20354 39277 20352 39277 20850 39277 20851 39278 20354 39278 20850 39278 20356 39279 20354 39279 20851 39279 20852 39280 20356 39280 20851 39280 20358 39281 20356 39281 20852 39281 20853 39282 20358 39282 20852 39282 20854 39283 20358 39283 20853 39283 20361 39284 20358 39284 20854 39284 20363 39285 20361 39285 20854 39285 20855 39286 20363 39286 20854 39286 20366 39287 20363 39287 20855 39287 20856 39288 20366 39288 20855 39288 20857 39289 20366 39289 20856 39289 20368 39290 20366 39290 20857 39290 20370 39291 20368 39291 20857 39291 20858 39292 20370 39292 20857 39292 20373 39293 20370 39293 20858 39293 20859 39294 20373 39294 20858 39294 20375 39295 20373 39295 20859 39295 20860 39296 20375 39296 20859 39296 20377 39297 20375 39297 20860 39297 20861 39298 20377 39298 20860 39298 20379 39299 20377 39299 20861 39299 20862 39300 20379 39300 20861 39300 20381 39301 20379 39301 20862 39301 20863 39302 20381 39302 20862 39302 20384 39303 20381 39303 20863 39303 20864 39304 20384 39304 20863 39304 20385 39305 20384 39305 20864 39305 20865 39306 20385 39306 20864 39306 20388 39307 20385 39307 20865 39307 20866 39308 20388 39308 20865 39308 20867 39309 20388 39309 20866 39309 20391 39310 20388 39310 20867 39310 20393 39311 20391 39311 20867 39311 20868 39312 20393 39312 20867 39312 20869 39313 20393 39313 20868 39313 20395 39314 20393 39314 20869 39314 20870 39315 20395 39315 20869 39315 20397 39316 20395 39316 20870 39316 20871 39317 20397 39317 20870 39317 20399 39318 20397 39318 20871 39318 20872 39319 20399 39319 20871 39319 20401 39320 20399 39320 20872 39320 20873 39321 20401 39321 20872 39321 20404 39322 20401 39322 20873 39322 20874 39323 20404 39323 20873 39323 20406 39324 20404 39324 20874 39324 20408 39325 20406 39325 20874 39325 20875 39326 20408 39326 20874 39326 20408 39327 20875 39327 20876 39327 20411 39328 20408 39328 20876 39328 20877 39329 20411 39329 20876 39329 20413 39330 20411 39330 20877 39330 20415 39331 20413 39331 20877 39331 20878 39332 20415 39332 20877 39332 20417 39333 20415 39333 20878 39333 20879 39334 20417 39334 20878 39334 20880 39335 20417 39335 20879 39335 20420 39336 20417 39336 20880 39336 20881 39337 20420 39337 20880 39337 20422 39338 20420 39338 20881 39338 20425 39339 20422 39339 20881 39339 20882 39340 20425 39340 20881 39340 20427 39341 20425 39341 20882 39341 20883 39342 20427 39342 20882 39342 20429 39343 20427 39343 20883 39343 20884 39344 20429 39344 20883 39344 20431 39345 20429 39345 20884 39345 20885 39346 20431 39346 20884 39346 20433 39347 20431 39347 20885 39347 20886 39348 20433 39348 20885 39348 20436 39349 20433 39349 20886 39349 20887 39350 20436 39350 20886 39350 20888 39351 20436 39351 20887 39351 20438 39352 20436 39352 20888 39352 20889 39353 20438 39353 20888 39353 20440 39354 20438 39354 20889 39354 20442 39355 20440 39355 20889 39355 20890 39356 20442 39356 20889 39356 20444 39357 20442 39357 20890 39357 20891 39358 20444 39358 20890 39358 20446 39359 20444 39359 20891 39359 20892 39360 20446 39360 20891 39360 20893 39361 20446 39361 20892 39361 20449 39362 20446 39362 20893 39362 20894 39363 20449 39363 20893 39363 20451 39364 20449 39364 20894 39364 20453 39365 20451 39365 20894 39365 20895 39366 20453 39366 20894 39366 20896 39367 20453 39367 20895 39367 20456 39368 20453 39368 20896 39368 20458 39369 20456 39369 20896 39369 20897 39370 20458 39370 20896 39370 20461 39371 20458 39371 20897 39371 20898 39372 20461 39372 20897 39372 20463 39373 20461 39373 20898 39373 20899 39374 20463 39374 20898 39374 20900 39375 20463 39375 20899 39375 20465 39376 20463 39376 20900 39376 20467 39377 20465 39377 20900 39377 20901 39378 20467 39378 20900 39378 20469 39379 20467 39379 20901 39379 20902 39380 20469 39380 20901 39380 20472 39381 20469 39381 20902 39381 20474 39382 20472 39382 20902 39382 20903 39383 20474 39383 20902 39383 20476 39384 20474 39384 20903 39384 20904 39385 20476 39385 20903 39385 20478 39386 20476 39386 20904 39386 20905 39387 20478 39387 20904 39387 20480 39388 20478 39388 20905 39388 20906 39389 20480 39389 20905 39389 20482 39390 20480 39390 20906 39390 20907 39391 20482 39391 20906 39391 20484 39392 20482 39392 20907 39392 20908 39393 20484 39393 20907 39393 20486 39394 20484 39394 20908 39394 20909 39395 20486 39395 20908 39395 20490 39396 20486 39396 20909 39396 20910 39397 20490 39397 20909 39397 20911 39398 20490 39398 20910 39398 20492 39399 20490 39399 20911 39399 20912 39400 20492 39400 20911 39400 20495 39401 20492 39401 20912 39401 20496 39402 20495 39402 20912 39402 20913 39403 20496 39403 20912 39403 20499 39404 20496 39404 20913 39404 20914 39405 20499 39405 20913 39405 20501 39406 20499 39406 20914 39406 20915 39407 20501 39407 20914 39407 20503 39408 20501 39408 20915 39408 20916 39409 20503 39409 20915 39409 20505 39410 20503 39410 20916 39410 20917 39411 20505 39411 20916 39411 20507 39412 20505 39412 20917 39412 20918 39413 20507 39413 20917 39413 20509 39414 20507 39414 20918 39414 20919 39415 20509 39415 20918 39415 20512 39416 20509 39416 20919 39416 20920 39417 20512 39417 20919 39417 20514 39418 20512 39418 20920 39418 20516 39419 20514 39419 20920 39419 20921 39420 20516 39420 20920 39420 20518 39421 20516 39421 20921 39421 20922 39422 20518 39422 20921 39422 20923 39423 20518 39423 20922 39423 20521 39424 20518 39424 20923 39424 20924 39425 20521 39425 20923 39425 20523 39426 20521 39426 20924 39426 20526 39427 20523 39427 20924 39427 20925 39428 20526 39428 20924 39428 20528 39429 20526 39429 20925 39429 20926 39430 20528 39430 20925 39430 20530 39431 20528 39431 20926 39431 20927 39432 20530 39432 20926 39432 20532 39433 20530 39433 20927 39433 20928 39434 20532 39434 20927 39434 20534 39435 20532 39435 20928 39435 20929 39436 20534 39436 20928 39436 20537 39437 20534 39437 20929 39437 20539 39438 20537 39438 20929 39438 20930 39439 20539 39439 20929 39439 20931 39440 20539 39440 20930 39440 20541 39441 20539 39441 20931 39441 20932 39442 20541 39442 20931 39442 20543 39443 20541 39443 20932 39443 20933 39444 20543 39444 20932 39444 20546 39445 20543 39445 20933 39445 20934 39446 20546 39446 20933 39446 20548 39447 20546 39447 20934 39447 20935 39448 20548 39448 20934 39448 20550 39449 20548 39449 20935 39449 20936 39450 20550 39450 20935 39450 20552 39451 20550 39451 20936 39451 20552 39452 20936 39452 20937 39452 20555 39453 20552 39453 20937 39453 20938 39454 20555 39454 20937 39454 20557 39455 20555 39455 20938 39455 20939 39456 20557 39456 20938 39456 20940 39457 20557 39457 20939 39457 20560 39458 20557 39458 20940 39458 20941 39459 20560 39459 20940 39459 20562 39460 20560 39460 20941 39460 20942 39461 20562 39461 20941 39461 20563 39462 20562 39462 20942 39462 20565 39463 20563 39463 20942 39463 20943 39464 20565 39464 20942 39464 20567 39465 20565 39465 20943 39465 20944 39466 20567 39466 20943 39466 20945 39467 20567 39467 20944 39467 20570 39468 20567 39468 20945 39468 20946 39469 20570 39469 20945 39469 20573 39470 20570 39470 20946 39470 20947 39471 20573 39471 20946 39471 20575 39472 20573 39472 20947 39472 20948 39473 20575 39473 20947 39473 20576 39474 20575 39474 20948 39474 20949 39475 20576 39475 20948 39475 20579 39476 20576 39476 20949 39476 20950 39477 20579 39477 20949 39477 20580 39478 20579 39478 20950 39478 20583 39479 20580 39479 20950 39479 20951 39480 20583 39480 20950 39480 20584 39481 20583 39481 20951 39481 20952 39482 20584 39482 20951 39482 20587 39483 20584 39483 20952 39483 20953 39484 20587 39484 20952 39484 20589 39485 20587 39485 20953 39485 20954 39486 20589 39486 20953 39486 20955 39487 20589 39487 20954 39487 20592 39488 20589 39488 20955 39488 20956 39489 20592 39489 20955 39489 20594 39490 20592 39490 20956 39490 20596 39491 20594 39491 20956 39491 20957 39492 20596 39492 20956 39492 20598 39493 20596 39493 20957 39493 20958 39494 20598 39494 20957 39494 20959 39495 20598 39495 20958 39495 20601 39496 20598 39496 20959 39496 20960 39497 20601 39497 20959 39497 20602 39498 20601 39498 20960 39498 20961 39499 20602 39499 20960 39499 20605 39500 20602 39500 20961 39500 20962 39501 20605 39501 20961 39501 20607 39502 20605 39502 20962 39502 20963 39503 20607 39503 20962 39503 20610 39504 20607 39504 20963 39504 20964 39505 20610 39505 20963 39505 20612 39506 20610 39506 20964 39506 20965 39507 20612 39507 20964 39507 20614 39508 20612 39508 20965 39508 20616 39509 20614 39509 20965 39509 20966 39510 20616 39510 20965 39510 20967 39511 20616 39511 20966 39511 20618 39512 20616 39512 20967 39512 20968 39513 20618 39513 20967 39513 20969 39514 20618 39514 20968 39514 20621 39515 20618 39515 20969 39515 20622 39516 20621 39516 20969 39516 20970 39517 20622 39517 20969 39517 20625 39518 20622 39518 20970 39518 20971 39519 20625 39519 20970 39519 20626 39520 20625 39520 20971 39520 20628 39521 20626 39521 20971 39521 20972 39522 20628 39522 20971 39522 20630 39523 20628 39523 20972 39523 20973 39524 20630 39524 20972 39524 20633 39525 20630 39525 20973 39525 20974 39526 20633 39526 20973 39526 20635 39527 20633 39527 20974 39527 20975 39528 20635 39528 20974 39528 20635 39529 20975 39529 20976 39529 20637 39530 20635 39530 20976 39530 20977 39531 20637 39531 20976 39531 20640 39532 20637 39532 20977 39532 20978 39533 20640 39533 20977 39533 20643 39534 20640 39534 20978 39534 20979 39535 20643 39535 20978 39535 20645 39536 20643 39536 20979 39536 20980 39537 20645 39537 20979 39537 20981 39538 20645 39538 20980 39538 20647 39539 20645 39539 20981 39539 20649 39540 20647 39540 20981 39540 20649 39541 20981 39541 20982 39541 20651 39542 20649 39542 20982 39542 20983 39543 20651 39543 20982 39543 20653 39544 20651 39544 20983 39544 20984 39545 20653 39545 20983 39545 20654 39546 20653 39546 20984 39546 20985 39547 20654 39547 20984 39547 20657 39548 20654 39548 20985 39548 20986 39549 20657 39549 20985 39549 20660 39550 20657 39550 20986 39550 20987 39551 20660 39551 20986 39551 20662 39552 20660 39552 20987 39552 20988 39553 20662 39553 20987 39553 20664 39554 20662 39554 20988 39554 20666 39555 20664 39555 20988 39555 20989 39556 20666 39556 20988 39556 20669 39557 20666 39557 20989 39557 20990 39558 20669 39558 20989 39558 20671 39559 20669 39559 20990 39559 20991 39560 20671 39560 20990 39560 20673 39561 20671 39561 20991 39561 20992 39562 20673 39562 20991 39562 20675 39563 20673 39563 20992 39563 20993 39564 20675 39564 20992 39564 20677 39565 20675 39565 20993 39565 20679 39566 20677 39566 20993 39566 20994 39567 20679 39567 20993 39567 20682 39568 20679 39568 20994 39568 20995 39569 20682 39569 20994 39569 20996 39570 20682 39570 20995 39570 20685 39571 20682 39571 20996 39571 20997 39572 20685 39572 20996 39572 20687 39573 20685 39573 20997 39573 20998 39574 20687 39574 20997 39574 20690 39575 20687 39575 20998 39575 20999 39576 20690 39576 20998 39576 20692 39577 20690 39577 20999 39577 21000 39578 20692 39578 20999 39578 20695 39579 20692 39579 21000 39579 21001 39580 20695 39580 21000 39580 20697 39581 20695 39581 21001 39581 21002 39582 20697 39582 21001 39582 20699 39583 20697 39583 21002 39583 21003 39584 20699 39584 21002 39584 20701 39585 20699 39585 21003 39585 21004 39586 20701 39586 21003 39586 21005 39587 20701 39587 21004 39587 20704 39588 20701 39588 21005 39588 21006 39589 20704 39589 21005 39589 20706 39590 20704 39590 21006 39590 21007 39591 20706 39591 21006 39591 20708 39592 20706 39592 21007 39592 21008 39593 20708 39593 21007 39593 20710 39594 20708 39594 21008 39594 21009 39595 20710 39595 21008 39595 20712 39596 20710 39596 21009 39596 21010 39597 20712 39597 21009 39597 20714 39598 20712 39598 21010 39598 20716 39599 20714 39599 21010 39599 21011 39600 20716 39600 21010 39600 20718 39601 20716 39601 21011 39601 21012 39602 20718 39602 21011 39602 20720 39603 20718 39603 21012 39603 20720 39604 21012 39604 21013 39604 20722 39605 20720 39605 21013 39605 21014 39606 20722 39606 21013 39606 20724 39607 20722 39607 21014 39607 21015 39608 20724 39608 21014 39608 20726 39609 20724 39609 21015 39609 21016 39610 20726 39610 21015 39610 20728 39611 20726 39611 21016 39611 21017 39612 20728 39612 21016 39612 20730 39613 20728 39613 21017 39613 21018 39614 20730 39614 21017 39614 20733 39615 20730 39615 21018 39615 21019 39616 20733 39616 21018 39616 20735 39617 20733 39617 21019 39617 21020 39618 20735 39618 21019 39618 20738 39619 20735 39619 21020 39619 21021 39620 20738 39620 21020 39620 20740 39621 20738 39621 21021 39621 21022 39622 20740 39622 21021 39622 21023 39623 20740 39623 21022 39623 20743 39624 20740 39624 21023 39624 21024 39625 20743 39625 21023 39625 20745 39626 20743 39626 21024 39626 21025 39627 20745 39627 21024 39627 20748 39628 20745 39628 21025 39628 21026 39629 20748 39629 21025 39629 20750 39630 20748 39630 21026 39630 21027 39631 20750 39631 21026 39631 20752 39632 20750 39632 21027 39632 21028 39633 20752 39633 21027 39633 20754 39634 20752 39634 21028 39634 21029 39635 20754 39635 21028 39635 20756 39636 20754 39636 21029 39636 20759 39637 20756 39637 21029 39637 21030 39638 20759 39638 21029 39638 21031 39639 20759 39639 21030 39639 20761 39640 20759 39640 21031 39640 20763 39641 20761 39641 21031 39641 21032 39642 20763 39642 21031 39642 20765 39643 20763 39643 21032 39643 21033 39644 20765 39644 21032 39644 20768 39645 20765 39645 21033 39645 20770 39646 20768 39646 21033 39646 21034 39647 20770 39647 21033 39647 20772 39648 20770 39648 21034 39648 21035 39649 20772 39649 21034 39649 20774 39650 20772 39650 21035 39650 21036 39651 20774 39651 21035 39651 20775 39652 20774 39652 21036 39652 20777 39653 20775 39653 21036 39653 21037 39654 20777 39654 21036 39654 20780 39655 20777 39655 21037 39655 21038 39656 20780 39656 21037 39656 20782 39657 20780 39657 21038 39657 21039 39658 20782 39658 21038 39658 20784 39659 20782 39659 21039 39659 20786 39660 20784 39660 21039 39660 21040 39661 20786 39661 21039 39661 20788 39662 20786 39662 21040 39662 21041 39663 20788 39663 21040 39663 20790 39664 20788 39664 21041 39664 21042 39665 20790 39665 21041 39665 20792 39666 20790 39666 21042 39666 21043 39667 20792 39667 21042 39667 20794 39668 20792 39668 21043 39668 21044 39669 20794 39669 21043 39669 20797 39670 20794 39670 21044 39670 21045 39671 20797 39671 21044 39671 21046 39672 20797 39672 21045 39672 20800 39673 20797 39673 21046 39673 21047 39674 20800 39674 21046 39674 20802 39675 20800 39675 21047 39675 21048 39676 20802 39676 21047 39676 20805 39677 20802 39677 21048 39677 21049 39678 20805 39678 21048 39678 20807 39679 20805 39679 21049 39679 21050 39680 20807 39680 21049 39680 20809 39681 20807 39681 21050 39681 21051 39682 20809 39682 21050 39682 20811 39683 20809 39683 21051 39683 21052 39684 20811 39684 21051 39684 20813 39685 20811 39685 21052 39685 21053 39686 20813 39686 21052 39686 20816 39687 20813 39687 21053 39687 21054 39688 20816 39688 21053 39688 20817 39689 20816 39689 21054 39689 21055 39690 20817 39690 21054 39690 20819 39691 20817 39691 21055 39691 20819 39692 21055 39692 21056 39692 20821 39693 20819 39693 21056 39693 21057 39694 20821 39694 21056 39694 20824 39695 20821 39695 21057 39695 21058 39696 20824 39696 21057 39696 20827 39697 20824 39697 21058 39697 21059 39698 20827 39698 21058 39698 20829 39699 20827 39699 21059 39699 21060 39700 20829 39700 21059 39700 21061 39701 20829 39701 21060 39701 20832 39702 20829 39702 21061 39702 20834 39703 20832 39703 21061 39703 21062 39704 20834 39704 21061 39704 20837 39705 20834 39705 21062 39705 21063 39706 20837 39706 21062 39706 20838 39707 20837 39707 21063 39707 21064 39708 20838 39708 21063 39708 20840 39709 20838 39709 21064 39709 21065 39710 20840 39710 21064 39710 20842 39711 20840 39711 21065 39711 21066 39712 20842 39712 21065 39712 20843 39713 20842 39713 21066 39713 21067 39714 20843 39714 21066 39714 20844 39715 20843 39715 21067 39715 21068 39716 20844 39716 21067 39716 20845 39717 20844 39717 21068 39717 21069 39718 20845 39718 21068 39718 20309 39719 20845 39719 21069 39719 21070 39720 20309 39720 21069 39720 20313 39721 20309 39721 21070 39721 21071 39722 20848 39722 20847 39722 21073 39723 20848 39723 21071 39723 21073 39724 20849 39724 20848 39724 21074 39725 20849 39725 21073 39725 21074 39726 20850 39726 20849 39726 21072 39727 20851 39727 21074 39727 21074 39728 20851 39728 20850 39728 21075 39729 20851 39729 21072 39729 21075 39730 20852 39730 20851 39730 21076 39731 20852 39731 21075 39731 21076 39732 20853 39732 20852 39732 21076 39733 20854 39733 20853 39733 21077 39734 20854 39734 21076 39734 20331 39735 20855 39735 21077 39735 21077 39736 20855 39736 20854 39736 21078 39737 20855 39737 20331 39737 21078 39738 20856 39738 20855 39738 20335 39739 20856 39739 21078 39739 20335 39740 20857 39740 20856 39740 21079 39741 20857 39741 20335 39741 21079 39742 20858 39742 20857 39742 21080 39743 20858 39743 21079 39743 21080 39744 20859 39744 20858 39744 21081 39745 20859 39745 21080 39745 21081 39746 20860 39746 20859 39746 20343 39747 20860 39747 21081 39747 20343 39748 20861 39748 20860 39748 20345 39749 20861 39749 20343 39749 20345 39750 20862 39750 20861 39750 20347 39751 20862 39751 20345 39751 20349 39752 20862 39752 20347 39752 20349 39753 20863 39753 20862 39753 20351 39754 20863 39754 20349 39754 20351 39755 20864 39755 20863 39755 20353 39756 20864 39756 20351 39756 20353 39757 20865 39757 20864 39757 20355 39758 20865 39758 20353 39758 20355 39759 20866 39759 20865 39759 20357 39760 20866 39760 20355 39760 20357 39761 20867 39761 20866 39761 20359 39762 20867 39762 20357 39762 20360 39763 20867 39763 20359 39763 20360 39764 20868 39764 20867 39764 20362 39765 20868 39765 20360 39765 20364 39766 20868 39766 20362 39766 20364 39767 20869 39767 20868 39767 20365 39768 20869 39768 20364 39768 20365 39769 20870 39769 20869 39769 20367 39770 20870 39770 20365 39770 20367 39771 20871 39771 20870 39771 20369 39772 20871 39772 20367 39772 20369 39773 20872 39773 20871 39773 20371 39774 20872 39774 20369 39774 20371 39775 20873 39775 20872 39775 20372 39776 20873 39776 20371 39776 20374 39777 20873 39777 20372 39777 20374 39778 20874 39778 20873 39778 20376 39779 20874 39779 20374 39779 20376 39780 20875 39780 20874 39780 21082 39781 20875 39781 20376 39781 21082 39782 20876 39782 20875 39782 20380 39783 20876 39783 21082 39783 20382 39784 20876 39784 20380 39784 20382 39785 20877 39785 20876 39785 20383 39786 20877 39786 20382 39786 20386 39787 20878 39787 20383 39787 20383 39788 20878 39788 20877 39788 20387 39789 20879 39789 20386 39789 20386 39790 20879 39790 20878 39790 20389 39791 20879 39791 20387 39791 20389 39792 20880 39792 20879 39792 20390 39793 20880 39793 20389 39793 20390 39794 20881 39794 20880 39794 21083 39795 20881 39795 20390 39795 21083 39796 20882 39796 20881 39796 20394 39797 20882 39797 21083 39797 20394 39798 20883 39798 20882 39798 20396 39799 20883 39799 20394 39799 20398 39800 20883 39800 20396 39800 20398 39801 20884 39801 20883 39801 20400 39802 20884 39802 20398 39802 20402 39803 20884 39803 20400 39803 20402 39804 20885 39804 20884 39804 20403 39805 20885 39805 20402 39805 20403 39806 20886 39806 20885 39806 20405 39807 20886 39807 20403 39807 20405 39808 20887 39808 20886 39808 20407 39809 20887 39809 20405 39809 20409 39810 20887 39810 20407 39810 20409 39811 20888 39811 20887 39811 20410 39812 20889 39812 20409 39812 20409 39813 20889 39813 20888 39813 21084 39814 20889 39814 20410 39814 21084 39815 20890 39815 20889 39815 21084 39816 20891 39816 20890 39816 20414 39817 20891 39817 21084 39817 20414 39818 20892 39818 20891 39818 20416 39819 20892 39819 20414 39819 20418 39820 20893 39820 20416 39820 20416 39821 20893 39821 20892 39821 20419 39822 20893 39822 20418 39822 20419 39823 20894 39823 20893 39823 20421 39824 20894 39824 20419 39824 20423 39825 20894 39825 20421 39825 20423 39826 20895 39826 20894 39826 20424 39827 20895 39827 20423 39827 20426 39828 20895 39828 20424 39828 20426 39829 20896 39829 20895 39829 21085 39830 20896 39830 20426 39830 21085 39831 20897 39831 20896 39831 21086 39832 20897 39832 21085 39832 21086 39833 20898 39833 20897 39833 20430 39834 20898 39834 21086 39834 20432 39835 20898 39835 20430 39835 20432 39836 20899 39836 20898 39836 20434 39837 20899 39837 20432 39837 20434 39838 20900 39838 20899 39838 20435 39839 20900 39839 20434 39839 20435 39840 20901 39840 20900 39840 21087 39841 20901 39841 20435 39841 21087 39842 20902 39842 20901 39842 21088 39843 20902 39843 21087 39843 21088 39844 20903 39844 20902 39844 20443 39845 20903 39845 21088 39845 20445 39846 20904 39846 20443 39846 20443 39847 20904 39847 20903 39847 20445 39848 20905 39848 20904 39848 20447 39849 20905 39849 20445 39849 20448 39850 20905 39850 20447 39850 20448 39851 20906 39851 20905 39851 20450 39852 20906 39852 20448 39852 20450 39853 20907 39853 20906 39853 20452 39854 20907 39854 20450 39854 20454 39855 20907 39855 20452 39855 20454 39856 20908 39856 20907 39856 20455 39857 20908 39857 20454 39857 20455 39858 20909 39858 20908 39858 20457 39859 20909 39859 20455 39859 20457 39860 20910 39860 20909 39860 20459 39861 20910 39861 20457 39861 20459 39862 20911 39862 20910 39862 21089 39863 20911 39863 20459 39863 21089 39864 20912 39864 20911 39864 20462 39865 20912 39865 21089 39865 20462 39866 20913 39866 20912 39866 20464 39867 20913 39867 20462 39867 20464 39868 20914 39868 20913 39868 20466 39869 20914 39869 20464 39869 20466 39870 20915 39870 20914 39870 20468 39871 20915 39871 20466 39871 20468 39872 20916 39872 20915 39872 21090 39873 20916 39873 20468 39873 21090 39874 20917 39874 20916 39874 20473 39875 20917 39875 21090 39875 20473 39876 20918 39876 20917 39876 20475 39877 20918 39877 20473 39877 20477 39878 20918 39878 20475 39878 20477 39879 20919 39879 20918 39879 20479 39880 20919 39880 20477 39880 20479 39881 20920 39881 20919 39881 20481 39882 20920 39882 20479 39882 20485 39883 20920 39883 20481 39883 20485 39884 20921 39884 20920 39884 20487 39885 20921 39885 20485 39885 20487 39886 20922 39886 20921 39886 20488 39887 20922 39887 20487 39887 20488 39888 20923 39888 20922 39888 20489 39889 20923 39889 20488 39889 20489 39890 20924 39890 20923 39890 20491 39891 20924 39891 20489 39891 20493 39892 20924 39892 20491 39892 20493 39893 20925 39893 20924 39893 20494 39894 20925 39894 20493 39894 20494 39895 20926 39895 20925 39895 20497 39896 20926 39896 20494 39896 20498 39897 20926 39897 20497 39897 20500 39898 20927 39898 20498 39898 20498 39899 20927 39899 20926 39899 20502 39900 20927 39900 20500 39900 20502 39901 20928 39901 20927 39901 20504 39902 20928 39902 20502 39902 20504 39903 20929 39903 20928 39903 21091 39904 20929 39904 20504 39904 21091 39905 20930 39905 20929 39905 21092 39906 20930 39906 21091 39906 21092 39907 20931 39907 20930 39907 20510 39908 20931 39908 21092 39908 20510 39909 20932 39909 20931 39909 20511 39910 20932 39910 20510 39910 20511 39911 20933 39911 20932 39911 20513 39912 20933 39912 20511 39912 20513 39913 20934 39913 20933 39913 20515 39914 20934 39914 20513 39914 20517 39915 20934 39915 20515 39915 20517 39916 20935 39916 20934 39916 20519 39917 20935 39917 20517 39917 20519 39918 20936 39918 20935 39918 21093 39919 20936 39919 20519 39919 21093 39920 20937 39920 20936 39920 20524 39921 20937 39921 21093 39921 20524 39922 20938 39922 20937 39922 20525 39923 20938 39923 20524 39923 20525 39924 20939 39924 20938 39924 20527 39925 20939 39925 20525 39925 20527 39926 20940 39926 20939 39926 20529 39927 20940 39927 20527 39927 20529 39928 20941 39928 20940 39928 20531 39929 20941 39929 20529 39929 20531 39930 20942 39930 20941 39930 20533 39931 20942 39931 20531 39931 20533 39932 20943 39932 20942 39932 20535 39933 20943 39933 20533 39933 20536 39934 20943 39934 20535 39934 20536 39935 20944 39935 20943 39935 20538 39936 20944 39936 20536 39936 20538 39937 20945 39937 20944 39937 20540 39938 20945 39938 20538 39938 20542 39939 20945 39939 20540 39939 20542 39940 20946 39940 20945 39940 20544 39941 20946 39941 20542 39941 20544 39942 20947 39942 20946 39942 20545 39943 20948 39943 20544 39943 20544 39944 20948 39944 20947 39944 20545 39945 20949 39945 20948 39945 21094 39946 20949 39946 20545 39946 20549 39947 20949 39947 21094 39947 20549 39948 20950 39948 20949 39948 20551 39949 20950 39949 20549 39949 20551 39950 20951 39950 20950 39950 20553 39951 20951 39951 20551 39951 20554 39952 20951 39952 20553 39952 20556 39953 20951 39953 20554 39953 20556 39954 20952 39954 20951 39954 20558 39955 20952 39955 20556 39955 20558 39956 20953 39956 20952 39956 20559 39957 20953 39957 20558 39957 20559 39958 20954 39958 20953 39958 21095 39959 20954 39959 20559 39959 21095 39960 20955 39960 20954 39960 21096 39961 20955 39961 21095 39961 21096 39962 20956 39962 20955 39962 21097 39963 20956 39963 21096 39963 21097 39964 20957 39964 20956 39964 20568 39965 20957 39965 21097 39965 20568 39966 20958 39966 20957 39966 20569 39967 20958 39967 20568 39967 20569 39968 20959 39968 20958 39968 20571 39969 20959 39969 20569 39969 20571 39970 20960 39970 20959 39970 20572 39971 20960 39971 20571 39971 20572 39972 20961 39972 20960 39972 21098 39973 20961 39973 20572 39973 21098 39974 20962 39974 20961 39974 21099 39975 20962 39975 21098 39975 21099 39976 20963 39976 20962 39976 21100 39977 20963 39977 21099 39977 21100 39978 20964 39978 20963 39978 21101 39979 20964 39979 21100 39979 21101 39980 20965 39980 20964 39980 21102 39981 20965 39981 21101 39981 20585 39982 20965 39982 21102 39982 20585 39983 20966 39983 20965 39983 20586 39984 20966 39984 20585 39984 20586 39985 20967 39985 20966 39985 20588 39986 20967 39986 20586 39986 20588 39987 20968 39987 20967 39987 20590 39988 20968 39988 20588 39988 20590 39989 20969 39989 20968 39989 20591 39990 20969 39990 20590 39990 20593 39991 20969 39991 20591 39991 20593 39992 20970 39992 20969 39992 21103 39993 20970 39993 20593 39993 21103 39994 20971 39994 20970 39994 21104 39995 20971 39995 21103 39995 21104 39996 20972 39996 20971 39996 20599 39997 20972 39997 21104 39997 21105 39998 20973 39998 20599 39998 20599 39999 20973 39999 20972 39999 20603 40000 20973 40000 21105 40000 20603 40001 20974 40001 20973 40001 20604 40002 20974 40002 20603 40002 20604 40003 20975 40003 20974 40003 20606 40004 20975 40004 20604 40004 20606 40005 20976 40005 20975 40005 20608 40006 20976 40006 20606 40006 20609 40007 20976 40007 20608 40007 20609 40008 20977 40008 20976 40008 20611 40009 20977 40009 20609 40009 20611 40010 20978 40010 20977 40010 21106 40011 20978 40011 20611 40011 21106 40012 20979 40012 20978 40012 21107 40013 20979 40013 21106 40013 21107 40014 20980 40014 20979 40014 21108 40015 20980 40015 21107 40015 21108 40016 20981 40016 20980 40016 21109 40017 20981 40017 21108 40017 21109 40018 20982 40018 20981 40018 20619 40019 20982 40019 21109 40019 21110 40020 20982 40020 20619 40020 21110 40021 20983 40021 20982 40021 20623 40022 20983 40022 21110 40022 20623 40023 20984 40023 20983 40023 21111 40024 20984 40024 20623 40024 21111 40025 20985 40025 20984 40025 21112 40026 20985 40026 21111 40026 21112 40027 20986 40027 20985 40027 20629 40028 20986 40028 21112 40028 20631 40029 20986 40029 20629 40029 20631 40030 20987 40030 20986 40030 20632 40031 20987 40031 20631 40031 20632 40032 20988 40032 20987 40032 20634 40033 20988 40033 20632 40033 20636 40034 20988 40034 20634 40034 20636 40035 20989 40035 20988 40035 20638 40036 20989 40036 20636 40036 20638 40037 20990 40037 20989 40037 20639 40038 20990 40038 20638 40038 20641 40039 20990 40039 20639 40039 20641 40040 20991 40040 20990 40040 21113 40041 20991 40041 20641 40041 21113 40042 20992 40042 20991 40042 20644 40043 20992 40043 21113 40043 20644 40044 20993 40044 20992 40044 20646 40045 20993 40045 20644 40045 20648 40046 20993 40046 20646 40046 20648 40047 20994 40047 20993 40047 20650 40048 20994 40048 20648 40048 20650 40049 20995 40049 20994 40049 21114 40050 20995 40050 20650 40050 21114 40051 20996 40051 20995 40051 21115 40052 20996 40052 21114 40052 21115 40053 20997 40053 20996 40053 20656 40054 20997 40054 21115 40054 20658 40055 20997 40055 20656 40055 20658 40056 20998 40056 20997 40056 20659 40057 20999 40057 20658 40057 20658 40058 20999 40058 20998 40058 20661 40059 20999 40059 20659 40059 20661 40060 21000 40060 20999 40060 20663 40061 21000 40061 20661 40061 20663 40062 21001 40062 21000 40062 20665 40063 21001 40063 20663 40063 20665 40064 21002 40064 21001 40064 20667 40065 21002 40065 20665 40065 20667 40066 21003 40066 21002 40066 20668 40067 21003 40067 20667 40067 20670 40068 21003 40068 20668 40068 20670 40069 21004 40069 21003 40069 20672 40070 21004 40070 20670 40070 20672 40071 21005 40071 21004 40071 20674 40072 21005 40072 20672 40072 20674 40073 21006 40073 21005 40073 21116 40074 21006 40074 20674 40074 21116 40075 21007 40075 21006 40075 20676 40076 21007 40076 21116 40076 20676 40077 21008 40077 21007 40077 20678 40078 21008 40078 20676 40078 20680 40079 21008 40079 20678 40079 20681 40080 21008 40080 20680 40080 20681 40081 21009 40081 21008 40081 20683 40082 21009 40082 20681 40082 20683 40083 21010 40083 21009 40083 20684 40084 21010 40084 20683 40084 20684 40085 21011 40085 21010 40085 20686 40086 21011 40086 20684 40086 20686 40087 21012 40087 21011 40087 20688 40088 21012 40088 20686 40088 20688 40089 21013 40089 21012 40089 20689 40090 21013 40090 20688 40090 20691 40091 21013 40091 20689 40091 20693 40092 21013 40092 20691 40092 20693 40093 21014 40093 21013 40093 20694 40094 21014 40094 20693 40094 20694 40095 21015 40095 21014 40095 20696 40096 21015 40096 20694 40096 20696 40097 21016 40097 21015 40097 20698 40098 21016 40098 20696 40098 20698 40099 21017 40099 21016 40099 20700 40100 21017 40100 20698 40100 20702 40101 21017 40101 20700 40101 20702 40102 21018 40102 21017 40102 21117 40103 21018 40103 20702 40103 21117 40104 21019 40104 21018 40104 20705 40105 21019 40105 21117 40105 20705 40106 21020 40106 21019 40106 20707 40107 21020 40107 20705 40107 20707 40108 21021 40108 21020 40108 21118 40109 21021 40109 20707 40109 21118 40110 21022 40110 21021 40110 20711 40111 21022 40111 21118 40111 20713 40112 21023 40112 20711 40112 20711 40113 21023 40113 21022 40113 21119 40114 21023 40114 20713 40114 21119 40115 21024 40115 21023 40115 21120 40116 21024 40116 21119 40116 21120 40117 21025 40117 21024 40117 20717 40118 21025 40118 21120 40118 20719 40119 21025 40119 20717 40119 20719 40120 21026 40120 21025 40120 20721 40121 21026 40121 20719 40121 20721 40122 21027 40122 21026 40122 20723 40123 21027 40123 20721 40123 21121 40124 21027 40124 20723 40124 21121 40125 21028 40125 21027 40125 20725 40126 21028 40126 21121 40126 20725 40127 21029 40127 21028 40127 21122 40128 21029 40128 20725 40128 21122 40129 21030 40129 21029 40129 20731 40130 21030 40130 21122 40130 20731 40131 21031 40131 21030 40131 21123 40132 21031 40132 20731 40132 21124 40133 21031 40133 21123 40133 21124 40134 21032 40134 21031 40134 20734 40135 21032 40135 21124 40135 20734 40136 21033 40136 21032 40136 20736 40137 21033 40137 20734 40137 21125 40138 21033 40138 20736 40138 21125 40139 21034 40139 21033 40139 21125 40140 21035 40140 21034 40140 20741 40141 21035 40141 21125 40141 20742 40142 21035 40142 20741 40142 20742 40143 21036 40143 21035 40143 20744 40144 21036 40144 20742 40144 20744 40145 21037 40145 21036 40145 20746 40146 21037 40146 20744 40146 20747 40147 21037 40147 20746 40147 20747 40148 21038 40148 21037 40148 20749 40149 21038 40149 20747 40149 20749 40150 21039 40150 21038 40150 20751 40151 21039 40151 20749 40151 20753 40152 21040 40152 20751 40152 20751 40153 21040 40153 21039 40153 20753 40154 21041 40154 21040 40154 20755 40155 21041 40155 20753 40155 20757 40156 21041 40156 20755 40156 20757 40157 21042 40157 21041 40157 20758 40158 21042 40158 20757 40158 20760 40159 21042 40159 20758 40159 20760 40160 21043 40160 21042 40160 20762 40161 21043 40161 20760 40161 20762 40162 21044 40162 21043 40162 20764 40163 21044 40163 20762 40163 20764 40164 21045 40164 21044 40164 20766 40165 21045 40165 20764 40165 20767 40166 21045 40166 20766 40166 20767 40167 21046 40167 21045 40167 20769 40168 21046 40168 20767 40168 20769 40169 21047 40169 21046 40169 21126 40170 21047 40170 20769 40170 21126 40171 21048 40171 21047 40171 21127 40172 21048 40172 21126 40172 21127 40173 21049 40173 21048 40173 20776 40174 21049 40174 21127 40174 20776 40175 21050 40175 21049 40175 20776 40176 21051 40176 21050 40176 20778 40177 21051 40177 20776 40177 20779 40178 21051 40178 20778 40178 20779 40179 21052 40179 21051 40179 20781 40180 21052 40180 20779 40180 20781 40181 21053 40181 21052 40181 21128 40182 21053 40182 20781 40182 21128 40183 21054 40183 21053 40183 21128 40184 21055 40184 21054 40184 21129 40185 21055 40185 21128 40185 21130 40186 21055 40186 21129 40186 21130 40187 21056 40187 21055 40187 20789 40188 21056 40188 21130 40188 20789 40189 21057 40189 21056 40189 20791 40190 21057 40190 20789 40190 20793 40191 21057 40191 20791 40191 20793 40192 21058 40192 21057 40192 20795 40193 21058 40193 20793 40193 20796 40194 21059 40194 20795 40194 20795 40195 21059 40195 21058 40195 20798 40196 21059 40196 20796 40196 20798 40197 21060 40197 21059 40197 20799 40198 21060 40198 20798 40198 20799 40199 21061 40199 21060 40199 20801 40200 21061 40200 20799 40200 20803 40201 21061 40201 20801 40201 20803 40202 21062 40202 21061 40202 20804 40203 21062 40203 20803 40203 20804 40204 21063 40204 21062 40204 21131 40205 21063 40205 20804 40205 21131 40206 21064 40206 21063 40206 20810 40207 21064 40207 21131 40207 20810 40208 21065 40208 21064 40208 20812 40209 21065 40209 20810 40209 20812 40210 21066 40210 21065 40210 20814 40211 21066 40211 20812 40211 21132 40212 21066 40212 20814 40212 21132 40213 21067 40213 21066 40213 21133 40214 21067 40214 21132 40214 21133 40215 21068 40215 21067 40215 20818 40216 21068 40216 21133 40216 20818 40217 21069 40217 21068 40217 20820 40218 21069 40218 20818 40218 20822 40219 21069 40219 20820 40219 20822 40220 21070 40220 21069 40220 20823 40221 20313 40221 20822 40221 20822 40222 20313 40222 21070 40222 20825 40223 20313 40223 20823 40223 20825 40224 20317 40224 20313 40224 20826 40225 20317 40225 20825 40225 20826 40226 20321 40226 20317 40226 20828 40227 20321 40227 20826 40227 20830 40228 20321 40228 20828 40228 20830 40229 20324 40229 20321 40229 20831 40230 20324 40230 20830 40230 20833 40231 20324 40231 20831 40231 20833 40232 20326 40232 20324 40232 20835 40233 20326 40233 20833 40233 20835 40234 20328 40234 20326 40234 20327 40235 20328 40235 20835 40235 21076 40236 21075 40236 21134 40236 20329 40237 21076 40237 21134 40237 21077 40238 21076 40238 20329 40238 20330 40239 21077 40239 20329 40239 20331 40240 21077 40240 20330 40240 21078 40241 20331 40241 20332 40241 20335 40242 21078 40242 20332 40242 20337 40243 21079 40243 20335 40243 21080 40244 21079 40244 20337 40244 20339 40245 21080 40245 20337 40245 21081 40246 21080 40246 20339 40246 20341 40247 21081 40247 20339 40247 20343 40248 21081 40248 20341 40248 20378 40249 21082 40249 20376 40249 20380 40250 21082 40250 20378 40250 20392 40251 21083 40251 20390 40251 20394 40252 21083 40252 20392 40252 20412 40253 21084 40253 20410 40253 20414 40254 21084 40254 20412 40254 20428 40255 21085 40255 20426 40255 21086 40256 21085 40256 20428 40256 20430 40257 21086 40257 20428 40257 21087 40258 20435 40258 20437 40258 20439 40259 21087 40259 20437 40259 21088 40260 21087 40260 20439 40260 20441 40261 21088 40261 20439 40261 20443 40262 21088 40262 20441 40262 20460 40263 21089 40263 20459 40263 20462 40264 21089 40264 20460 40264 21090 40265 20468 40265 20470 40265 20471 40266 21090 40266 20470 40266 20473 40267 21090 40267 20471 40267 20485 40268 20481 40268 20483 40268 20506 40269 21091 40269 20504 40269 21092 40270 21091 40270 20506 40270 20508 40271 21092 40271 20506 40271 20510 40272 21092 40272 20508 40272 21093 40273 20519 40273 20520 40273 20522 40274 21093 40274 20520 40274 20524 40275 21093 40275 20522 40275 21094 40276 20545 40276 20547 40276 20549 40277 21094 40277 20547 40277 20561 40278 21095 40278 20559 40278 21096 40279 21095 40279 20561 40279 20564 40280 21096 40280 20561 40280 21097 40281 21096 40281 20564 40281 20566 40282 21097 40282 20564 40282 20568 40283 21097 40283 20566 40283 21098 40284 20572 40284 20574 40284 21099 40285 21098 40285 20574 40285 20577 40286 21099 40286 20574 40286 21100 40287 21099 40287 20577 40287 20578 40288 21100 40288 20577 40288 21101 40289 21100 40289 20578 40289 20581 40290 21101 40290 20578 40290 21102 40291 21101 40291 20581 40291 20582 40292 21102 40292 20581 40292 20585 40293 21102 40293 20582 40293 20595 40294 21103 40294 20593 40294 20597 40295 21103 40295 20595 40295 21104 40296 21103 40296 20597 40296 20599 40297 21104 40297 20597 40297 21105 40298 20599 40298 20600 40298 20603 40299 21105 40299 20600 40299 20613 40300 21106 40300 20611 40300 21107 40301 21106 40301 20613 40301 20615 40302 21107 40302 20613 40302 21108 40303 21107 40303 20615 40303 20617 40304 21108 40304 20615 40304 21109 40305 21108 40305 20617 40305 20619 40306 21109 40306 20617 40306 21110 40307 20619 40307 20620 40307 20623 40308 21110 40308 20620 40308 21111 40309 20623 40309 20624 40309 20627 40310 21111 40310 20624 40310 21112 40311 21111 40311 20627 40311 20629 40312 21112 40312 20627 40312 20642 40313 21113 40313 20641 40313 20644 40314 21113 40314 20642 40314 21114 40315 20650 40315 20652 40315 21115 40316 21114 40316 20652 40316 20655 40317 21115 40317 20652 40317 20656 40318 21115 40318 20655 40318 20676 40319 21116 40319 20674 40319 20703 40320 21117 40320 20702 40320 20705 40321 21117 40321 20703 40321 20709 40322 21118 40322 20707 40322 20711 40323 21118 40323 20709 40323 20715 40324 21119 40324 20713 40324 21120 40325 21119 40325 20715 40325 20717 40326 21120 40326 20715 40326 20725 40327 21121 40327 20723 40327 21122 40328 20725 40328 20727 40328 20729 40329 21122 40329 20727 40329 20731 40330 21122 40330 20729 40330 20732 40331 21123 40331 20731 40331 21124 40332 21123 40332 20732 40332 20734 40333 21124 40333 20732 40333 21125 40334 20736 40334 20737 40334 20739 40335 21125 40335 20737 40335 20741 40336 21125 40336 20739 40336 21126 40337 20769 40337 20771 40337 20773 40338 21126 40338 20771 40338 21127 40339 21126 40339 20773 40339 20776 40340 21127 40340 20773 40340 21128 40341 20781 40341 20783 40341 20785 40342 21128 40342 20783 40342 21129 40343 21128 40343 20785 40343 20787 40344 21129 40344 20785 40344 21130 40345 21129 40345 20787 40345 20789 40346 21130 40346 20787 40346 21131 40347 20804 40347 20806 40347 20808 40348 21131 40348 20806 40348 20810 40349 21131 40349 20808 40349 20815 40350 21132 40350 20814 40350 21133 40351 21132 40351 20815 40351 20818 40352 21133 40352 20815 40352 20836 40353 20327 40353 20835 40353 21139 40354 20327 40354 20836 40354 20839 40355 21138 40355 20836 40355 21136 40356 21192 40356 21135 40356 21137 40357 21192 40357 21136 40357 21138 40358 21192 40358 21137 40358 21139 40359 21138 40359 21137 40359 20836 40360 21138 40360 21139 40360 21139 40361 21137 40361 21136 40361 21140 40362 21136 40362 21135 40362 21140 40363 21139 40363 21136 40363 21143 40364 21139 40364 21140 40364 21142 40365 21140 40365 21135 40365 20327 40366 21139 40366 21143 40366 21142 40367 21135 40367 21141 40367 21144 40368 21143 40368 21140 40368 21144 40369 21140 40369 21142 40369 21143 40370 20328 40370 20327 40370 20328 40371 21143 40371 21144 40371 21146 40372 21144 40372 21142 40372 21145 40373 20328 40373 21144 40373 21146 40374 21142 40374 21141 40374 21146 40375 21145 40375 21144 40375 21149 40376 21145 40376 21146 40376 21148 40377 21146 40377 21141 40377 21149 40378 21146 40378 21148 40378 21150 40379 21148 40379 21141 40379 21150 40380 21141 40380 21147 40380 21151 40381 21148 40381 21150 40381 21151 40382 21149 40382 21148 40382 20325 40383 21149 40383 21151 40383 21153 40384 21150 40384 21147 40384 21151 40385 21150 40385 21153 40385 21154 40386 21153 40386 21147 40386 20325 40387 21151 40387 21153 40387 21155 40388 21153 40388 21154 40388 20323 40389 20325 40389 21153 40389 21152 40390 21154 40390 21147 40390 21155 40391 20323 40391 21153 40391 21156 40392 21155 40392 21154 40392 21158 40393 21155 40393 21156 40393 21157 40394 21154 40394 21152 40394 21156 40395 21154 40395 21157 40395 21158 40396 20323 40396 21155 40396 21159 40397 21158 40397 21156 40397 21159 40398 21156 40398 21157 40398 21159 40399 20320 40399 21158 40399 21157 40400 21152 40400 21161 40400 21160 40401 21159 40401 21157 40401 21161 40402 21160 40402 21157 40402 21160 40403 20320 40403 21159 40403 21163 40404 21160 40404 21161 40404 21163 40405 21161 40405 21165 40405 21162 40406 21160 40406 21163 40406 21162 40407 20320 40407 21160 40407 21162 40408 21166 40408 20320 40408 21165 40409 21161 40409 21164 40409 21166 40410 21162 40410 21163 40410 21167 40411 21166 40411 21163 40411 21167 40412 21163 40412 21165 40412 21167 40413 21165 40413 21168 40413 21169 40414 21166 40414 21167 40414 21164 40415 21168 40415 21165 40415 21169 40416 21167 40416 21168 40416 21170 40417 21169 40417 21168 40417 21168 40418 21164 40418 21171 40418 21172 40419 21169 40419 21170 40419 21173 40420 21170 40420 21168 40420 21173 40421 21168 40421 21171 40421 21172 40422 21170 40422 21173 40422 21174 40423 21173 40423 21171 40423 21175 40424 21173 40424 21174 40424 21175 40425 21172 40425 21173 40425 21176 40426 21171 40426 21164 40426 21174 40427 21171 40427 21176 40427 20310 40428 21172 40428 21175 40428 21177 40429 21175 40429 21174 40429 20310 40430 21175 40430 21177 40430 21178 40431 21174 40431 21176 40431 21177 40432 21174 40432 21178 40432 21178 40433 21176 40433 21179 40433 20312 40434 20310 40434 21177 40434 21180 40435 21177 40435 21178 40435 20312 40436 21177 40436 21180 40436 21180 40437 21178 40437 21181 40437 21181 40438 21178 40438 21179 40438 20314 40439 20312 40439 21180 40439 21184 40440 21180 40440 21181 40440 20314 40441 21180 40441 21184 40441 21182 40442 21181 40442 21179 40442 21182 40443 21179 40443 21183 40443 21184 40444 21181 40444 21182 40444 20316 40445 20314 40445 21184 40445 21185 40446 21182 40446 21183 40446 21186 40447 21184 40447 21182 40447 20316 40448 21184 40448 21186 40448 21186 40449 21182 40449 21185 40449 20318 40450 20316 40450 21186 40450 21187 40451 21186 40451 21185 40451 21189 40452 21185 40452 21183 40452 21187 40453 20318 40453 21186 40453 21189 40454 21187 40454 21185 40454 21187 40455 20319 40455 20318 40455 21189 40456 21183 40456 21190 40456 21190 40457 21183 40457 21188 40457 20319 40458 21187 40458 21189 40458 20322 40459 20319 40459 21189 40459 21191 40460 21189 40460 21190 40460 21191 40461 20322 40461 21189 40461 21193 40462 21191 40462 21190 40462 21191 40463 20841 40463 20322 40463 21192 40464 21190 40464 21188 40464 21193 40465 21190 40465 21192 40465 20841 40466 21191 40466 21193 40466 21192 40467 21188 40467 21135 40467 20841 40468 21192 40468 21138 40468 20841 40469 21193 40469 21192 40469 20841 40470 21138 40470 20839 40470 21141 40471 21135 40471 21188 40471 21164 40472 21179 40472 21176 40472 21164 40473 21183 40473 21179 40473 21152 40474 21164 40474 21161 40474 21152 40475 21188 40475 21183 40475 21152 40476 21147 40476 21141 40476 21152 40477 21183 40477 21164 40477 21152 40478 21141 40478 21188 40478 21195 40479 21194 40479 21196 40479 21198 40480 21270 40480 21195 40480 21198 40481 21195 40481 21196 40481 21199 40482 21196 40482 21197 40482 21198 40483 21196 40483 21199 40483 21201 40484 21198 40484 21199 40484 21199 40485 21197 40485 21200 40485 21203 40486 21199 40486 21200 40486 21201 40487 21199 40487 21203 40487 21203 40488 21200 40488 21202 40488 21201 40489 21206 40489 21198 40489 21204 40490 21203 40490 21202 40490 21205 40491 21203 40491 21204 40491 21206 40492 21201 40492 21203 40492 21206 40493 21203 40493 21205 40493 21205 40494 21204 40494 21207 40494 21209 40495 21205 40495 21207 40495 21209 40496 21206 40496 21205 40496 21209 40497 21207 40497 21208 40497 21206 40498 21209 40498 21210 40498 21211 40499 21209 40499 21208 40499 21210 40500 21209 40500 21211 40500 21211 40501 21208 40501 21212 40501 21213 40502 21211 40502 21212 40502 21215 40503 21211 40503 21213 40503 21214 40504 21210 40504 21211 40504 21214 40505 21211 40505 21215 40505 21216 40506 21215 40506 21213 40506 21214 40507 21218 40507 21210 40507 21217 40508 21215 40508 21216 40508 21218 40509 21214 40509 21215 40509 21218 40510 21215 40510 21217 40510 21220 40511 21217 40511 21219 40511 21220 40512 21218 40512 21217 40512 21221 40513 21220 40513 21219 40513 21223 40514 21218 40514 21220 40514 21221 40515 21219 40515 21222 40515 21223 40516 21220 40516 21221 40516 21224 40517 21221 40517 21222 40517 21224 40518 21222 40518 21225 40518 21226 40519 21221 40519 21224 40519 21226 40520 21223 40520 21221 40520 21227 40521 21224 40521 21225 40521 21226 40522 21224 40522 21227 40522 21229 40523 21226 40523 21227 40523 21229 40524 21227 40524 21228 40524 21230 40525 21229 40525 21228 40525 21231 40526 21226 40526 21229 40526 21232 40527 21226 40527 21231 40527 21233 40528 21229 40528 21230 40528 21231 40529 21229 40529 21233 40529 21233 40530 21230 40530 21234 40530 21232 40531 21231 40531 21233 40531 21236 40532 21233 40532 21234 40532 21235 40533 21233 40533 21236 40533 21232 40534 21233 40534 21235 40534 21238 40535 21232 40535 21235 40535 21237 40536 21235 40536 21236 40536 21239 40537 21235 40537 21237 40537 21239 40538 21238 40538 21235 40538 21239 40539 21237 40539 21240 40539 21242 40540 21239 40540 21240 40540 21242 40541 21238 40541 21239 40541 21243 40542 21240 40542 21241 40542 21243 40543 21242 40543 21240 40543 21238 40544 21242 40544 21245 40544 21243 40545 21241 40545 21244 40545 21245 40546 21242 40546 21243 40546 21246 40547 21243 40547 21244 40547 21246 40548 21244 40548 21247 40548 21246 40549 21245 40549 21243 40549 21249 40550 21245 40550 21246 40550 21249 40551 21246 40551 21247 40551 21249 40552 21247 40552 21248 40552 21249 40553 21248 40553 21250 40553 21252 40554 21250 40554 21248 40554 21251 40555 21249 40555 21250 40555 21255 40556 21249 40556 21251 40556 21253 40557 21250 40557 21252 40557 21251 40558 21250 40558 21253 40558 21254 40559 21253 40559 21252 40559 21253 40560 21255 40560 21251 40560 21257 40561 21253 40561 21254 40561 21257 40562 21254 40562 21256 40562 21255 40563 21253 40563 21257 40563 21258 40564 21257 40564 21256 40564 21259 40565 21255 40565 21257 40565 21259 40566 21257 40566 21258 40566 21259 40567 21258 40567 21260 40567 21262 40568 21255 40568 21259 40568 21261 40569 21259 40569 21260 40569 21263 40570 21259 40570 21261 40570 21262 40571 21259 40571 21263 40571 21264 40572 21263 40572 21261 40572 21265 40573 21263 40573 21264 40573 21262 40574 21263 40574 21265 40574 21266 40575 21265 40575 21264 40575 21267 40576 21265 40576 21266 40576 21267 40577 21262 40577 21265 40577 21268 40578 21267 40578 21266 40578 21269 40579 21267 40579 21268 40579 21270 40580 21262 40580 21267 40580 21269 40581 21268 40581 21271 40581 21272 40582 21269 40582 21271 40582 21270 40583 21267 40583 21269 40583 21270 40584 21269 40584 21272 40584 21272 40585 21271 40585 21194 40585 21195 40586 21272 40586 21194 40586 21195 40587 21270 40587 21272 40587 21194 40588 21273 40588 21274 40588 21196 40589 21194 40589 21274 40589 21196 40590 21274 40590 21275 40590 21197 40591 21196 40591 21275 40591 21197 40592 21275 40592 21348 40592 21200 40593 21197 40593 21348 40593 21200 40594 21348 40594 21276 40594 21202 40595 21200 40595 21276 40595 21202 40596 21276 40596 21277 40596 21204 40597 21202 40597 21277 40597 21204 40598 21277 40598 21278 40598 21207 40599 21204 40599 21278 40599 21208 40600 21278 40600 21279 40600 21208 40601 21207 40601 21278 40601 21208 40602 21279 40602 21341 40602 21212 40603 21208 40603 21341 40603 21212 40604 21341 40604 21280 40604 21213 40605 21212 40605 21280 40605 21213 40606 21280 40606 21340 40606 21213 40607 21340 40607 21281 40607 21216 40608 21213 40608 21281 40608 21216 40609 21281 40609 21282 40609 21217 40610 21216 40610 21282 40610 21219 40611 21217 40611 21282 40611 21219 40612 21282 40612 21283 40612 21222 40613 21219 40613 21283 40613 21222 40614 21283 40614 21284 40614 21225 40615 21222 40615 21284 40615 21225 40616 21284 40616 21285 40616 21225 40617 21285 40617 21286 40617 21227 40618 21225 40618 21286 40618 21228 40619 21286 40619 21287 40619 21228 40620 21227 40620 21286 40620 21230 40621 21287 40621 21288 40621 21230 40622 21228 40622 21287 40622 21234 40623 21288 40623 21328 40623 21234 40624 21230 40624 21288 40624 21236 40625 21234 40625 21328 40625 21236 40626 21328 40626 21289 40626 21237 40627 21236 40627 21289 40627 21237 40628 21289 40628 21326 40628 21237 40629 21326 40629 21290 40629 21240 40630 21237 40630 21290 40630 21241 40631 21240 40631 21290 40631 21241 40632 21290 40632 21320 40632 21244 40633 21241 40633 21320 40633 21244 40634 21320 40634 21319 40634 21244 40635 21319 40635 21291 40635 21247 40636 21244 40636 21291 40636 21248 40637 21247 40637 21291 40637 21248 40638 21291 40638 21315 40638 21248 40639 21315 40639 21292 40639 21252 40640 21248 40640 21292 40640 21252 40641 21292 40641 21293 40641 21254 40642 21252 40642 21293 40642 21256 40643 21293 40643 21312 40643 21256 40644 21254 40644 21293 40644 21256 40645 21312 40645 21294 40645 21258 40646 21256 40646 21294 40646 21260 40647 21258 40647 21294 40647 21260 40648 21294 40648 21295 40648 21261 40649 21260 40649 21295 40649 21261 40650 21295 40650 21296 40650 21264 40651 21261 40651 21296 40651 21266 40652 21264 40652 21296 40652 21266 40653 21296 40653 21297 40653 21266 40654 21297 40654 21304 40654 21268 40655 21266 40655 21304 40655 21268 40656 21304 40656 21302 40656 21271 40657 21268 40657 21302 40657 21271 40658 21302 40658 21298 40658 21194 40659 21298 40659 21273 40659 21194 40660 21271 40660 21298 40660 20340 40661 21245 40661 20846 40661 20846 40662 21245 40662 21249 40662 20340 40663 21238 40663 21245 40663 20847 40664 20846 40664 21249 40664 20847 40665 21249 40665 21255 40665 20338 40666 21238 40666 20340 40666 20338 40667 21232 40667 21238 40667 21071 40668 20847 40668 21255 40668 20333 40669 21232 40669 20338 40669 20333 40670 21226 40670 21232 40670 21073 40671 21071 40671 21255 40671 21073 40672 21255 40672 21262 40672 20336 40673 21226 40673 20333 40673 21223 40674 21226 40674 20336 40674 21262 40675 21074 40675 21073 40675 21223 40676 20336 40676 20334 40676 21270 40677 21074 40677 21262 40677 21218 40678 21223 40678 20334 40678 21270 40679 21072 40679 21074 40679 21218 40680 20334 40680 20330 40680 21198 40681 21072 40681 21270 40681 21210 40682 21218 40682 20330 40682 21198 40683 21075 40683 21072 40683 21210 40684 20330 40684 20329 40684 21206 40685 21210 40685 20329 40685 21198 40686 21134 40686 21075 40686 21206 40687 21134 40687 21198 40687 21206 40688 20329 40688 21134 40688 21299 40689 21352 40689 21273 40689 21300 40690 21351 40690 21299 40690 21298 40691 21299 40691 21273 40691 21302 40692 21299 40692 21298 40692 21301 40693 21299 40693 21302 40693 21300 40694 21299 40694 21301 40694 21300 40695 21301 40695 21303 40695 21304 40696 21301 40696 21302 40696 21303 40697 21301 40697 21304 40697 21306 40698 21300 40698 21303 40698 21297 40699 21303 40699 21304 40699 21305 40700 21303 40700 21297 40700 21306 40701 21303 40701 21305 40701 21306 40702 21305 40702 21297 40702 21307 40703 21297 40703 21296 40703 21307 40704 21306 40704 21297 40704 21307 40705 21296 40705 21295 40705 21308 40706 21306 40706 21307 40706 21309 40707 21307 40707 21295 40707 21309 40708 21295 40708 21294 40708 21308 40709 21307 40709 21309 40709 21310 40710 21308 40710 21309 40710 21310 40711 21309 40711 21294 40711 21306 40712 21308 40712 21311 40712 21311 40713 21308 40713 21310 40713 21310 40714 21294 40714 21312 40714 21293 40715 21310 40715 21312 40715 21313 40716 21310 40716 21293 40716 21313 40717 21311 40717 21310 40717 21314 40718 21313 40718 21293 40718 21292 40719 21314 40719 21293 40719 21316 40720 21311 40720 21313 40720 21315 40721 21314 40721 21292 40721 21316 40722 21313 40722 21314 40722 21316 40723 21314 40723 21315 40723 21317 40724 21316 40724 21315 40724 21318 40725 21315 40725 21291 40725 21317 40726 21315 40726 21318 40726 21319 40727 21318 40727 21291 40727 21320 40728 21318 40728 21319 40728 21321 40729 21317 40729 21318 40729 21321 40730 21318 40730 21320 40730 21322 40731 21321 40731 21320 40731 21323 40732 21317 40732 21321 40732 21322 40733 21320 40733 21290 40733 21323 40734 21321 40734 21322 40734 21324 40735 21322 40735 21290 40735 21324 40736 21323 40736 21322 40736 21325 40737 21323 40737 21324 40737 21324 40738 21290 40738 21326 40738 21324 40739 21326 40739 21289 40739 21327 40740 21324 40740 21289 40740 21328 40741 21327 40741 21289 40741 21329 40742 21324 40742 21327 40742 21329 40743 21325 40743 21324 40743 21331 40744 21325 40744 21329 40744 21288 40745 21327 40745 21328 40745 21329 40746 21327 40746 21288 40746 21330 40747 21329 40747 21288 40747 21330 40748 21288 40748 21287 40748 21330 40749 21331 40749 21329 40749 21332 40750 21330 40750 21287 40750 21332 40751 21331 40751 21330 40751 21332 40752 21287 40752 21286 40752 21334 40753 21331 40753 21332 40753 21285 40754 21332 40754 21286 40754 21333 40755 21332 40755 21285 40755 21334 40756 21332 40756 21333 40756 21284 40757 21333 40757 21285 40757 21335 40758 21333 40758 21284 40758 21334 40759 21333 40759 21335 40759 21335 40760 21284 40760 21283 40760 21282 40761 21335 40761 21283 40761 21336 40762 21334 40762 21335 40762 21336 40763 21335 40763 21282 40763 21336 40764 21282 40764 21337 40764 21281 40765 21337 40765 21282 40765 21339 40766 21336 40766 21337 40766 21338 40767 21337 40767 21281 40767 21339 40768 21337 40768 21338 40768 21338 40769 21281 40769 21340 40769 21341 40770 21340 40770 21280 40770 21342 40771 21339 40771 21338 40771 21338 40772 21340 40772 21341 40772 21343 40773 21338 40773 21341 40773 21343 40774 21342 40774 21338 40774 21343 40775 21341 40775 21279 40775 21344 40776 21343 40776 21279 40776 21344 40777 21342 40777 21343 40777 21278 40778 21344 40778 21279 40778 21346 40779 21342 40779 21344 40779 21345 40780 21278 40780 21277 40780 21346 40781 21344 40781 21278 40781 21346 40782 21278 40782 21345 40782 21276 40783 21345 40783 21277 40783 21347 40784 21346 40784 21345 40784 21347 40785 21345 40785 21276 40785 21349 40786 21346 40786 21347 40786 21348 40787 21347 40787 21276 40787 21350 40788 21347 40788 21348 40788 21349 40789 21347 40789 21350 40789 21350 40790 21348 40790 21275 40790 21351 40791 21349 40791 21350 40791 21352 40792 21350 40792 21275 40792 21351 40793 21350 40793 21352 40793 21274 40794 21352 40794 21275 40794 21352 40795 21274 40795 21273 40795 21352 40796 21299 40796 21351 40796 20298 40797 20303 40797 20305 40797 20298 40798 20300 40798 20303 40798 20296 40799 20305 40799 20306 40799 20296 40800 20298 40800 20305 40800 20293 40801 20296 40801 20307 40801 20307 40802 20296 40802 20306 40802

+
+ + + +

21353 40803 21354 40803 21355 40803 21354 40804 21356 40804 21355 40804 21357 40805 21358 40805 21354 40805 21354 40806 21358 40806 21356 40806 21357 40807 21359 40807 21358 40807 21359 40808 21360 40808 21358 40808 21361 40809 21362 40809 21359 40809 21359 40810 21362 40810 21360 40810 21363 40811 21364 40811 21361 40811 21361 40812 21364 40812 21362 40812 21363 40813 21353 40813 21364 40813 21353 40814 21355 40814 21364 40814 21362 40815 21364 40815 21365 40815 21365 40816 21364 40816 21366 40816 21364 40817 21370 40817 21366 40817 21364 40818 21355 40818 21370 40818 21355 40819 21356 40819 21370 40819 21370 40820 21356 40820 21369 40820 21363 40821 21361 40821 21353 40821 21354 40822 21359 40822 21357 40822 21353 40823 21359 40823 21354 40823 21361 40824 21359 40824 21353 40824 21368 40825 22386 40825 22391 40825 21368 40826 22382 40826 22386 40826 21368 40827 22380 40827 22382 40827 21369 40828 22391 40828 22395 40828 21369 40829 21368 40829 22391 40829 22399 40830 21369 40830 22395 40830 22402 40831 21369 40831 22399 40831 21367 40832 22432 40832 22380 40832 21367 40833 22380 40833 21368 40833 22430 40834 22432 40834 21367 40834 22426 40835 22430 40835 21367 40835 21370 40836 21369 40836 22402 40836 22407 40837 21370 40837 22402 40837 21365 40838 22426 40838 21367 40838 22421 40839 22426 40839 21365 40839 22410 40840 21370 40840 22407 40840 22410 40841 21366 40841 21370 40841 22420 40842 22421 40842 21365 40842 22413 40843 21366 40843 22410 40843 22420 40844 21365 40844 21366 40844 22417 40845 21366 40845 22413 40845 22417 40846 22420 40846 21366 40846 21371 40847 21372 40847 22257 40847 21371 40848 22257 40848 21373 40848 21374 40849 21372 40849 21371 40849 21375 40850 21371 40850 21373 40850 21374 40851 22249 40851 21372 40851 21375 40852 21373 40852 21376 40852 21377 40853 22249 40853 21374 40853 21378 40854 21375 40854 21376 40854 21377 40855 22244 40855 22249 40855 21378 40856 21376 40856 21379 40856 21380 40857 22244 40857 21377 40857 21381 40858 21379 40858 22269 40858 21381 40859 21378 40859 21379 40859 21380 40860 21382 40860 22244 40860 21383 40861 21382 40861 21380 40861 22239 40862 21382 40862 21383 40862 21385 40863 22239 40863 21383 40863 21385 40864 21383 40864 21386 40864 22234 40865 21385 40865 21386 40865 21388 40866 22234 40866 21386 40866 21388 40867 21386 40867 21387 40867 21394 40868 21392 40868 21391 40868 21394 40869 21393 40869 21392 40869 21397 40870 21395 40870 21394 40870 21394 40871 21395 40871 21393 40871 21397 40872 21398 40872 21395 40872 21400 40873 21398 40873 21397 40873 21400 40874 21399 40874 21398 40874 21396 40875 21399 40875 21400 40875 21396 40876 21401 40876 21399 40876 21402 40877 21401 40877 21396 40877 21402 40878 21403 40878 21401 40878 21404 40879 21403 40879 21402 40879 21404 40880 21405 40880 21403 40880 21406 40881 21405 40881 21404 40881 21406 40882 21407 40882 21405 40882 21408 40883 21407 40883 21406 40883 21408 40884 21409 40884 21407 40884 21408 40885 21410 40885 21409 40885 21411 40886 21410 40886 21408 40886 21411 40887 21412 40887 21410 40887 21413 40888 21412 40888 21411 40888 21413 40889 21414 40889 21412 40889 21413 40890 21415 40890 21414 40890 21416 40891 21415 40891 21413 40891 21416 40892 21417 40892 21415 40892 21418 40893 21417 40893 21416 40893 21418 40894 21419 40894 21417 40894 21418 40895 21420 40895 21419 40895 21421 40896 21420 40896 21418 40896 21421 40897 21422 40897 21420 40897 21423 40898 21422 40898 21421 40898 21423 40899 21424 40899 21422 40899 21425 40900 21424 40900 21423 40900 21425 40901 21426 40901 21424 40901 21425 40902 21427 40902 21426 40902 21428 40903 21427 40903 21425 40903 21428 40904 21429 40904 21427 40904 21430 40905 21429 40905 21428 40905 21430 40906 21431 40906 21429 40906 21432 40907 21431 40907 21430 40907 21432 40908 21433 40908 21431 40908 21432 40909 21434 40909 21433 40909 21435 40910 21434 40910 21432 40910 21435 40911 21436 40911 21434 40911 21435 40912 21437 40912 21436 40912 21438 40913 21437 40913 21435 40913 21438 40914 21439 40914 21437 40914 21440 40915 21439 40915 21438 40915 21440 40916 21441 40916 21439 40916 21442 40917 21441 40917 21440 40917 21442 40918 21443 40918 21441 40918 21444 40919 21443 40919 21442 40919 21444 40920 21445 40920 21443 40920 21446 40921 21445 40921 21444 40921 21446 40922 21447 40922 21445 40922 21446 40923 21448 40923 21447 40923 21449 40924 21448 40924 21446 40924 21449 40925 21450 40925 21448 40925 21449 40926 21451 40926 21450 40926 21452 40927 21451 40927 21449 40927 21452 40928 21453 40928 21451 40928 21454 40929 21453 40929 21452 40929 21454 40930 21455 40930 21453 40930 21454 40931 21456 40931 21455 40931 21457 40932 21456 40932 21454 40932 21457 40933 21458 40933 21456 40933 21459 40934 21458 40934 21457 40934 21459 40935 21460 40935 21458 40935 21461 40936 21460 40936 21459 40936 21461 40937 21462 40937 21460 40937 21463 40938 21462 40938 21461 40938 21463 40939 21464 40939 21462 40939 21465 40940 21464 40940 21463 40940 21465 40941 21466 40941 21464 40941 21465 40942 21467 40942 21466 40942 21468 40943 21467 40943 21465 40943 21468 40944 21469 40944 21467 40944 21470 40945 21469 40945 21468 40945 21470 40946 21471 40946 21469 40946 21472 40947 21471 40947 21470 40947 21472 40948 21473 40948 21471 40948 21474 40949 21473 40949 21472 40949 21474 40950 21475 40950 21473 40950 21476 40951 21475 40951 21474 40951 21476 40952 21477 40952 21475 40952 21478 40953 21477 40953 21476 40953 21478 40954 21479 40954 21477 40954 21478 40955 21480 40955 21479 40955 21481 40956 21480 40956 21478 40956 21481 40957 21482 40957 21480 40957 21483 40958 21482 40958 21481 40958 21483 40959 21484 40959 21482 40959 21485 40960 21486 40960 21483 40960 21483 40961 21486 40961 21484 40961 21485 40962 21487 40962 21486 40962 21488 40963 21487 40963 21485 40963 21488 40964 21489 40964 21487 40964 21490 40965 21489 40965 21488 40965 21490 40966 21491 40966 21489 40966 21492 40967 21491 40967 21490 40967 21492 40968 21493 40968 21491 40968 21492 40969 21494 40969 21493 40969 21495 40970 21494 40970 21492 40970 21495 40971 21496 40971 21494 40971 21497 40972 21496 40972 21495 40972 21497 40973 21498 40973 21496 40973 21499 40974 21498 40974 21497 40974 21499 40975 21500 40975 21498 40975 21501 40976 21500 40976 21499 40976 21501 40977 21502 40977 21500 40977 21503 40978 21502 40978 21501 40978 21503 40979 21504 40979 21502 40979 21503 40980 21505 40980 21504 40980 21506 40981 21505 40981 21503 40981 21506 40982 21507 40982 21505 40982 21508 40983 21507 40983 21506 40983 21508 40984 21509 40984 21507 40984 21508 40985 21510 40985 21509 40985 21511 40986 21510 40986 21508 40986 21511 40987 21512 40987 21510 40987 21513 40988 21512 40988 21511 40988 21513 40989 21514 40989 21512 40989 21515 40990 21514 40990 21513 40990 21515 40991 21516 40991 21514 40991 21517 40992 21516 40992 21515 40992 21517 40993 21518 40993 21516 40993 21519 40994 21518 40994 21517 40994 21519 40995 21520 40995 21518 40995 21519 40996 21521 40996 21520 40996 21522 40997 21521 40997 21519 40997 21522 40998 21523 40998 21521 40998 21524 40999 21523 40999 21522 40999 21524 41000 21525 41000 21523 41000 21524 41001 21526 41001 21525 41001 21527 41002 21526 41002 21524 41002 21527 41003 21528 41003 21526 41003 21529 41004 21528 41004 21527 41004 21529 41005 21530 41005 21528 41005 21531 41006 21530 41006 21529 41006 21531 41007 21532 41007 21530 41007 21533 41008 21532 41008 21531 41008 21533 41009 21534 41009 21532 41009 21533 41010 21535 41010 21534 41010 21536 41011 21535 41011 21533 41011 21536 41012 21537 41012 21535 41012 21538 41013 21537 41013 21536 41013 21538 41014 21539 41014 21537 41014 21540 41015 21541 41015 21538 41015 21538 41016 21541 41016 21539 41016 21542 41017 21541 41017 21540 41017 21542 41018 21543 41018 21541 41018 21542 41019 21544 41019 21543 41019 21545 41020 21544 41020 21542 41020 21546 41021 21547 41021 21545 41021 21545 41022 21547 41022 21544 41022 21548 41023 21547 41023 21546 41023 21548 41024 21549 41024 21547 41024 21548 41025 21550 41025 21549 41025 21551 41026 21550 41026 21548 41026 21551 41027 21552 41027 21550 41027 21551 41028 21553 41028 21552 41028 21554 41029 21553 41029 21551 41029 21554 41030 21555 41030 21553 41030 21556 41031 21555 41031 21554 41031 21556 41032 21557 41032 21555 41032 21558 41033 21557 41033 21556 41033 21558 41034 21559 41034 21557 41034 21560 41035 21559 41035 21558 41035 21560 41036 21561 41036 21559 41036 21562 41037 21561 41037 21560 41037 21562 41038 21563 41038 21561 41038 21564 41039 21563 41039 21562 41039 21564 41040 21565 41040 21563 41040 21564 41041 21566 41041 21565 41041 21567 41042 21566 41042 21564 41042 21567 41043 21568 41043 21566 41043 21569 41044 21568 41044 21567 41044 21569 41045 21570 41045 21568 41045 21571 41046 21570 41046 21569 41046 21571 41047 21572 41047 21570 41047 21573 41048 21572 41048 21571 41048 21573 41049 21574 41049 21572 41049 21575 41050 21574 41050 21573 41050 21575 41051 21576 41051 21574 41051 21575 41052 21577 41052 21576 41052 21578 41053 21577 41053 21575 41053 21578 41054 21579 41054 21577 41054 21580 41055 21579 41055 21578 41055 21580 41056 21581 41056 21579 41056 21580 41057 21582 41057 21581 41057 21583 41058 21582 41058 21580 41058 21583 41059 21584 41059 21582 41059 21585 41060 21584 41060 21583 41060 21585 41061 21586 41061 21584 41061 21587 41062 21586 41062 21585 41062 21587 41063 21588 41063 21586 41063 21589 41064 21588 41064 21587 41064 21589 41065 21590 41065 21588 41065 21591 41066 21590 41066 21589 41066 21591 41067 21592 41067 21590 41067 21593 41068 21592 41068 21591 41068 21593 41069 21594 41069 21592 41069 21595 41070 21594 41070 21593 41070 21595 41071 21596 41071 21594 41071 21597 41072 21596 41072 21595 41072 21597 41073 21598 41073 21596 41073 21599 41074 21598 41074 21597 41074 21599 41075 21600 41075 21598 41075 21599 41076 21601 41076 21600 41076 21602 41077 21601 41077 21599 41077 21602 41078 21603 41078 21601 41078 21604 41079 21603 41079 21602 41079 21604 41080 21605 41080 21603 41080 21604 41081 21606 41081 21605 41081 21607 41082 21606 41082 21604 41082 21607 41083 21608 41083 21606 41083 21609 41084 21608 41084 21607 41084 21609 41085 21610 41085 21608 41085 21611 41086 21610 41086 21609 41086 21611 41087 21612 41087 21610 41087 21613 41088 21612 41088 21611 41088 21613 41089 21614 41089 21612 41089 21613 41090 21615 41090 21614 41090 21616 41091 21615 41091 21613 41091 21617 41092 21618 41092 21616 41092 21616 41093 21618 41093 21615 41093 21617 41094 21619 41094 21618 41094 21620 41095 21619 41095 21617 41095 21620 41096 21621 41096 21619 41096 21622 41097 21621 41097 21620 41097 21622 41098 21623 41098 21621 41098 21624 41099 21625 41099 21622 41099 21622 41100 21625 41100 21623 41100 21626 41101 21625 41101 21624 41101 21626 41102 21627 41102 21625 41102 21628 41103 21627 41103 21626 41103 21628 41104 21629 41104 21627 41104 21630 41105 21631 41105 21628 41105 21628 41106 21631 41106 21629 41106 21630 41107 21632 41107 21631 41107 21633 41108 21632 41108 21630 41108 21633 41109 21634 41109 21632 41109 21635 41110 21634 41110 21633 41110 21635 41111 21636 41111 21634 41111 21637 41112 21636 41112 21635 41112 21637 41113 21638 41113 21636 41113 21639 41114 21638 41114 21637 41114 21639 41115 21640 41115 21638 41115 21641 41116 21640 41116 21639 41116 21641 41117 21642 41117 21640 41117 21643 41118 21642 41118 21641 41118 21643 41119 21644 41119 21642 41119 21645 41120 21644 41120 21643 41120 21645 41121 21646 41121 21644 41121 21647 41122 21646 41122 21645 41122 21647 41123 21648 41123 21646 41123 21649 41124 21648 41124 21647 41124 21649 41125 21650 41125 21648 41125 21651 41126 21650 41126 21649 41126 21651 41127 21652 41127 21650 41127 21651 41128 21653 41128 21652 41128 21654 41129 21653 41129 21651 41129 21655 41130 21653 41130 21654 41130 21655 41131 21656 41131 21653 41131 21657 41132 21656 41132 21655 41132 21657 41133 21658 41133 21656 41133 21659 41134 21658 41134 21657 41134 21659 41135 21660 41135 21658 41135 21661 41136 21662 41136 21659 41136 21659 41137 21662 41137 21660 41137 21663 41138 21664 41138 21661 41138 21661 41139 21664 41139 21662 41139 21663 41140 21665 41140 21664 41140 21666 41141 21665 41141 21663 41141 21666 41142 21667 41142 21665 41142 21668 41143 21667 41143 21666 41143 21668 41144 21669 41144 21667 41144 21670 41145 21669 41145 21668 41145 21670 41146 21671 41146 21669 41146 21672 41147 21671 41147 21670 41147 21672 41148 21673 41148 21671 41148 21674 41149 21673 41149 21672 41149 21674 41150 21675 41150 21673 41150 21676 41151 21675 41151 21674 41151 21676 41152 21677 41152 21675 41152 21678 41153 21677 41153 21676 41153 21678 41154 21679 41154 21677 41154 21680 41155 21679 41155 21678 41155 21680 41156 21681 41156 21679 41156 21680 41157 21682 41157 21681 41157 21683 41158 21682 41158 21680 41158 21683 41159 21684 41159 21682 41159 21683 41160 21685 41160 21684 41160 21686 41161 21685 41161 21683 41161 21687 41162 21685 41162 21686 41162 21687 41163 21688 41163 21685 41163 21687 41164 21689 41164 21688 41164 21690 41165 21689 41165 21687 41165 21690 41166 21691 41166 21689 41166 21692 41167 21691 41167 21690 41167 21692 41168 21693 41168 21691 41168 21694 41169 21693 41169 21692 41169 21694 41170 21695 41170 21693 41170 21696 41171 21695 41171 21694 41171 21696 41172 21697 41172 21695 41172 21698 41173 21697 41173 21696 41173 21698 41174 21699 41174 21697 41174 21698 41175 21700 41175 21699 41175 21701 41176 21700 41176 21698 41176 21701 41177 21702 41177 21700 41177 21703 41178 21702 41178 21701 41178 21703 41179 21704 41179 21702 41179 21703 41180 21705 41180 21704 41180 21703 41181 21706 41181 21705 41181 21707 41182 21706 41182 21703 41182 21708 41183 21709 41183 21707 41183 21707 41184 21709 41184 21706 41184 21708 41185 21710 41185 21709 41185 21711 41186 21710 41186 21708 41186 21711 41187 21712 41187 21710 41187 21713 41188 21712 41188 21711 41188 21713 41189 21714 41189 21712 41189 21715 41190 21714 41190 21713 41190 21715 41191 21716 41191 21714 41191 21717 41192 21716 41192 21715 41192 21717 41193 21718 41193 21716 41193 21717 41194 21719 41194 21718 41194 21720 41195 21719 41195 21717 41195 21721 41196 21719 41196 21720 41196 21721 41197 21722 41197 21719 41197 21723 41198 21724 41198 21721 41198 21721 41199 21724 41199 21722 41199 21725 41200 21724 41200 21723 41200 21725 41201 21726 41201 21724 41201 21725 41202 21727 41202 21726 41202 21728 41203 21727 41203 21725 41203 21728 41204 21729 41204 21727 41204 21730 41205 21729 41205 21728 41205 21730 41206 21731 41206 21729 41206 21732 41207 21731 41207 21730 41207 21732 41208 21733 41208 21731 41208 21732 41209 21734 41209 21733 41209 21735 41210 21734 41210 21732 41210 21736 41211 21734 41211 21735 41211 21736 41212 21737 41212 21734 41212 21736 41213 21738 41213 21737 41213 21739 41214 21738 41214 21736 41214 21739 41215 21740 41215 21738 41215 21741 41216 21740 41216 21739 41216 21741 41217 21742 41217 21740 41217 21743 41218 21742 41218 21741 41218 21743 41219 21744 41219 21742 41219 21745 41220 21744 41220 21743 41220 21745 41221 21746 41221 21744 41221 21747 41222 21746 41222 21745 41222 21747 41223 21748 41223 21746 41223 21749 41224 21748 41224 21747 41224 21749 41225 21750 41225 21748 41225 21749 41226 21751 41226 21750 41226 21752 41227 21751 41227 21749 41227 21752 41228 21753 41228 21751 41228 21754 41229 21753 41229 21752 41229 21754 41230 21755 41230 21753 41230 21756 41231 21755 41231 21754 41231 21756 41232 21757 41232 21755 41232 21756 41233 21758 41233 21757 41233 21759 41234 21758 41234 21756 41234 21759 41235 21760 41235 21758 41235 21761 41236 21760 41236 21759 41236 21761 41237 21762 41237 21760 41237 21763 41238 21762 41238 21761 41238 21763 41239 21764 41239 21762 41239 21763 41240 21765 41240 21764 41240 21766 41241 21765 41241 21763 41241 21766 41242 21767 41242 21765 41242 21766 41243 21768 41243 21767 41243 21769 41244 21768 41244 21766 41244 21769 41245 21770 41245 21768 41245 21769 41246 21771 41246 21770 41246 21772 41247 21771 41247 21769 41247 21772 41248 21773 41248 21771 41248 21774 41249 21773 41249 21772 41249 21775 41250 21773 41250 21774 41250 21775 41251 21776 41251 21773 41251 21777 41252 21778 41252 21775 41252 21775 41253 21778 41253 21776 41253 21777 41254 21779 41254 21778 41254 21780 41255 21779 41255 21777 41255 21780 41256 21781 41256 21779 41256 21782 41257 21781 41257 21780 41257 21782 41258 21783 41258 21781 41258 21784 41259 21783 41259 21782 41259 21784 41260 21785 41260 21783 41260 21786 41261 21785 41261 21784 41261 21786 41262 21787 41262 21785 41262 21786 41263 21788 41263 21787 41263 21789 41264 21788 41264 21786 41264 21789 41265 21790 41265 21788 41265 21791 41266 21790 41266 21789 41266 21792 41267 21790 41267 21791 41267 21792 41268 21793 41268 21790 41268 21792 41269 21794 41269 21793 41269 21795 41270 21794 41270 21792 41270 21795 41271 21796 41271 21794 41271 21797 41272 21796 41272 21795 41272 21797 41273 21798 41273 21796 41273 21799 41274 21798 41274 21797 41274 21799 41275 21800 41275 21798 41275 21801 41276 21800 41276 21799 41276 21801 41277 21802 41277 21800 41277 21801 41278 21803 41278 21802 41278 21804 41279 21803 41279 21801 41279 21804 41280 21805 41280 21803 41280 21804 41281 21806 41281 21805 41281 21807 41282 21806 41282 21804 41282 21807 41283 21808 41283 21806 41283 21809 41284 21808 41284 21807 41284 21809 41285 21810 41285 21808 41285 21811 41286 21810 41286 21809 41286 21811 41287 21812 41287 21810 41287 21813 41288 21812 41288 21811 41288 21813 41289 21814 41289 21812 41289 21815 41290 21814 41290 21813 41290 21815 41291 21816 41291 21814 41291 21817 41292 21816 41292 21815 41292 21817 41293 21818 41293 21816 41293 21817 41294 21819 41294 21818 41294 21820 41295 21821 41295 21817 41295 21817 41296 21821 41296 21819 41296 21820 41297 21822 41297 21821 41297 21823 41298 21822 41298 21820 41298 21823 41299 21824 41299 21822 41299 21825 41300 21824 41300 21823 41300 21825 41301 21826 41301 21824 41301 21825 41302 21827 41302 21826 41302 21828 41303 21827 41303 21825 41303 21828 41304 21829 41304 21827 41304 21830 41305 21829 41305 21828 41305 21831 41306 21832 41306 21830 41306 21830 41307 21832 41307 21829 41307 21831 41308 21833 41308 21832 41308 21834 41309 21833 41309 21831 41309 21834 41310 21835 41310 21833 41310 21836 41311 21835 41311 21834 41311 21836 41312 21837 41312 21835 41312 21838 41313 21837 41313 21836 41313 21838 41314 21839 41314 21837 41314 21840 41315 21839 41315 21838 41315 21840 41316 21841 41316 21839 41316 21842 41317 21841 41317 21840 41317 21842 41318 21843 41318 21841 41318 21844 41319 21843 41319 21842 41319 21844 41320 21845 41320 21843 41320 21844 41321 21846 41321 21845 41321 21847 41322 21846 41322 21844 41322 21848 41323 21849 41323 21847 41323 21847 41324 21849 41324 21846 41324 21848 41325 21850 41325 21849 41325 21851 41326 21850 41326 21848 41326 21852 41327 21850 41327 21851 41327 21852 41328 21853 41328 21850 41328 21854 41329 21853 41329 21852 41329 21854 41330 21855 41330 21853 41330 21856 41331 21855 41331 21854 41331 21856 41332 21857 41332 21855 41332 21858 41333 21857 41333 21856 41333 21858 41334 21859 41334 21857 41334 21858 41335 21860 41335 21859 41335 21861 41336 21860 41336 21858 41336 21861 41337 21862 41337 21860 41337 21863 41338 21862 41338 21861 41338 21863 41339 21864 41339 21862 41339 21865 41340 21864 41340 21863 41340 21865 41341 21866 41341 21864 41341 21865 41342 21867 41342 21866 41342 21868 41343 21867 41343 21865 41343 21868 41344 21869 41344 21867 41344 21870 41345 21869 41345 21868 41345 21871 41346 21869 41346 21870 41346 21871 41347 21872 41347 21869 41347 21871 41348 21873 41348 21872 41348 21874 41349 21873 41349 21871 41349 21874 41350 21875 41350 21873 41350 21876 41351 21875 41351 21874 41351 21876 41352 21877 41352 21875 41352 21878 41353 21877 41353 21876 41353 21878 41354 21879 41354 21877 41354 21880 41355 21879 41355 21878 41355 21880 41356 21881 41356 21879 41356 21882 41357 21881 41357 21880 41357 21882 41358 21883 41358 21881 41358 21884 41359 21883 41359 21882 41359 21884 41360 21885 41360 21883 41360 21884 41361 21886 41361 21885 41361 21887 41362 21886 41362 21884 41362 21887 41363 21888 41363 21886 41363 21889 41364 21888 41364 21887 41364 21889 41365 21890 41365 21888 41365 21891 41366 21890 41366 21889 41366 21891 41367 21892 41367 21890 41367 21891 41368 21893 41368 21892 41368 21894 41369 21893 41369 21891 41369 21894 41370 21895 41370 21893 41370 21896 41371 21895 41371 21894 41371 21897 41372 21895 41372 21896 41372 21897 41373 21898 41373 21895 41373 21899 41374 21898 41374 21897 41374 21899 41375 21900 41375 21898 41375 21901 41376 21900 41376 21899 41376 21901 41377 21902 41377 21900 41377 21903 41378 21902 41378 21901 41378 21903 41379 21904 41379 21902 41379 21903 41380 21905 41380 21904 41380 21906 41381 21905 41381 21903 41381 21907 41382 21905 41382 21906 41382 21907 41383 21908 41383 21905 41383 21907 41384 21384 41384 21908 41384 21907 41385 21381 41385 21384 41385 21909 41386 21381 41386 21907 41386 21909 41387 21378 41387 21381 41387 21910 41388 21378 41388 21909 41388 21375 41389 21378 41389 21910 41389 21911 41390 21406 41390 21404 41390 21912 41391 21406 41391 21911 41391 21408 41392 21406 41392 21912 41392 21913 41393 21408 41393 21912 41393 21411 41394 21408 41394 21913 41394 21413 41395 21411 41395 21913 41395 21914 41396 21413 41396 21913 41396 21915 41397 21413 41397 21914 41397 21416 41398 21413 41398 21915 41398 21418 41399 21416 41399 21915 41399 21916 41400 21418 41400 21915 41400 21917 41401 21418 41401 21916 41401 21421 41402 21418 41402 21917 41402 21423 41403 21421 41403 21917 41403 21918 41404 21423 41404 21917 41404 21425 41405 21423 41405 21918 41405 21919 41406 21425 41406 21918 41406 21428 41407 21425 41407 21919 41407 21920 41408 21428 41408 21919 41408 21921 41409 21428 41409 21920 41409 21430 41410 21428 41410 21921 41410 21922 41411 21430 41411 21921 41411 21432 41412 21430 41412 21922 41412 21923 41413 21432 41413 21922 41413 21435 41414 21432 41414 21923 41414 21924 41415 21435 41415 21923 41415 21438 41416 21435 41416 21924 41416 21925 41417 21438 41417 21924 41417 21926 41418 21438 41418 21925 41418 21440 41419 21438 41419 21926 41419 21442 41420 21440 41420 21926 41420 21927 41421 21442 41421 21926 41421 21444 41422 21442 41422 21927 41422 21928 41423 21444 41423 21927 41423 21446 41424 21444 41424 21928 41424 21929 41425 21446 41425 21928 41425 21449 41426 21446 41426 21929 41426 21930 41427 21449 41427 21929 41427 21931 41428 21449 41428 21930 41428 21452 41429 21449 41429 21931 41429 21454 41430 21452 41430 21931 41430 21932 41431 21454 41431 21931 41431 21933 41432 21454 41432 21932 41432 21457 41433 21454 41433 21933 41433 21459 41434 21457 41434 21933 41434 21934 41435 21459 41435 21933 41435 21461 41436 21459 41436 21934 41436 21935 41437 21461 41437 21934 41437 21463 41438 21461 41438 21935 41438 21936 41439 21463 41439 21935 41439 21465 41440 21463 41440 21936 41440 21937 41441 21465 41441 21936 41441 21938 41442 21465 41442 21937 41442 21468 41443 21465 41443 21938 41443 21939 41444 21468 41444 21938 41444 21470 41445 21468 41445 21939 41445 21940 41446 21470 41446 21939 41446 21472 41447 21470 41447 21940 41447 21941 41448 21472 41448 21940 41448 21474 41449 21472 41449 21941 41449 21942 41450 21474 41450 21941 41450 21476 41451 21474 41451 21942 41451 21478 41452 21476 41452 21942 41452 21943 41453 21478 41453 21942 41453 21944 41454 21478 41454 21943 41454 21481 41455 21478 41455 21944 41455 21945 41456 21481 41456 21944 41456 21483 41457 21481 41457 21945 41457 21946 41458 21483 41458 21945 41458 21485 41459 21483 41459 21946 41459 21488 41460 21485 41460 21946 41460 21947 41461 21488 41461 21946 41461 21490 41462 21488 41462 21947 41462 21948 41463 21490 41463 21947 41463 21492 41464 21490 41464 21948 41464 21949 41465 21492 41465 21948 41465 21495 41466 21492 41466 21949 41466 21950 41467 21495 41467 21949 41467 21497 41468 21495 41468 21950 41468 21951 41469 21497 41469 21950 41469 21499 41470 21497 41470 21951 41470 21952 41471 21499 41471 21951 41471 21501 41472 21499 41472 21952 41472 21953 41473 21501 41473 21952 41473 21503 41474 21501 41474 21953 41474 21506 41475 21503 41475 21953 41475 21954 41476 21506 41476 21953 41476 21508 41477 21506 41477 21954 41477 21955 41478 21508 41478 21954 41478 21956 41479 21508 41479 21955 41479 21511 41480 21508 41480 21956 41480 21957 41481 21511 41481 21956 41481 21513 41482 21511 41482 21957 41482 21958 41483 21513 41483 21957 41483 21515 41484 21513 41484 21958 41484 21959 41485 21515 41485 21958 41485 21517 41486 21515 41486 21959 41486 21960 41487 21517 41487 21959 41487 21519 41488 21517 41488 21960 41488 21961 41489 21519 41489 21960 41489 21522 41490 21519 41490 21961 41490 21524 41491 21522 41491 21961 41491 21962 41492 21524 41492 21961 41492 21527 41493 21524 41493 21962 41493 21963 41494 21527 41494 21962 41494 21529 41495 21527 41495 21963 41495 21964 41496 21529 41496 21963 41496 21531 41497 21529 41497 21964 41497 21965 41498 21531 41498 21964 41498 21533 41499 21531 41499 21965 41499 21966 41500 21533 41500 21965 41500 21536 41501 21533 41501 21966 41501 21967 41502 21536 41502 21966 41502 21538 41503 21536 41503 21967 41503 21968 41504 21538 41504 21967 41504 21540 41505 21538 41505 21968 41505 21969 41506 21540 41506 21968 41506 21542 41507 21540 41507 21969 41507 21970 41508 21542 41508 21969 41508 21545 41509 21542 41509 21970 41509 21971 41510 21545 41510 21970 41510 21546 41511 21545 41511 21971 41511 21548 41512 21546 41512 21971 41512 21972 41513 21548 41513 21971 41513 21551 41514 21548 41514 21972 41514 21973 41515 21551 41515 21972 41515 21974 41516 21551 41516 21973 41516 21554 41517 21551 41517 21974 41517 21975 41518 21554 41518 21974 41518 21556 41519 21554 41519 21975 41519 21976 41520 21556 41520 21975 41520 21558 41521 21556 41521 21976 41521 21977 41522 21558 41522 21976 41522 21560 41523 21558 41523 21977 41523 21978 41524 21560 41524 21977 41524 21562 41525 21560 41525 21978 41525 21564 41526 21562 41526 21978 41526 21979 41527 21564 41527 21978 41527 21980 41528 21564 41528 21979 41528 21567 41529 21564 41529 21980 41529 21981 41530 21567 41530 21980 41530 21569 41531 21567 41531 21981 41531 21982 41532 21569 41532 21981 41532 21571 41533 21569 41533 21982 41533 21573 41534 21571 41534 21982 41534 21983 41535 21573 41535 21982 41535 21575 41536 21573 41536 21983 41536 21984 41537 21575 41537 21983 41537 21578 41538 21575 41538 21984 41538 21985 41539 21578 41539 21984 41539 21580 41540 21578 41540 21985 41540 21986 41541 21580 41541 21985 41541 21987 41542 21580 41542 21986 41542 21583 41543 21580 41543 21987 41543 21585 41544 21583 41544 21987 41544 21988 41545 21585 41545 21987 41545 21989 41546 21585 41546 21988 41546 21587 41547 21585 41547 21989 41547 21589 41548 21587 41548 21989 41548 21990 41549 21589 41549 21989 41549 21591 41550 21589 41550 21990 41550 21593 41551 21591 41551 21990 41551 21991 41552 21593 41552 21990 41552 21595 41553 21593 41553 21991 41553 21992 41554 21595 41554 21991 41554 21597 41555 21595 41555 21992 41555 21993 41556 21597 41556 21992 41556 21599 41557 21597 41557 21993 41557 21994 41558 21599 41558 21993 41558 21602 41559 21599 41559 21994 41559 21995 41560 21602 41560 21994 41560 21604 41561 21602 41561 21995 41561 21996 41562 21604 41562 21995 41562 21607 41563 21604 41563 21996 41563 21997 41564 21607 41564 21996 41564 21998 41565 21607 41565 21997 41565 21609 41566 21607 41566 21998 41566 21999 41567 21609 41567 21998 41567 21611 41568 21609 41568 21999 41568 22000 41569 21611 41569 21999 41569 21613 41570 21611 41570 22000 41570 22001 41571 21613 41571 22000 41571 21616 41572 21613 41572 22001 41572 22002 41573 21616 41573 22001 41573 21617 41574 21616 41574 22002 41574 22003 41575 21617 41575 22002 41575 21620 41576 21617 41576 22003 41576 22004 41577 21620 41577 22003 41577 21622 41578 21620 41578 22004 41578 22005 41579 21622 41579 22004 41579 21624 41580 21622 41580 22005 41580 22006 41581 21624 41581 22005 41581 21626 41582 21624 41582 22006 41582 22007 41583 21626 41583 22006 41583 21628 41584 21626 41584 22007 41584 22008 41585 21628 41585 22007 41585 21630 41586 21628 41586 22008 41586 22009 41587 21630 41587 22008 41587 21633 41588 21630 41588 22009 41588 22010 41589 21633 41589 22009 41589 21635 41590 21633 41590 22010 41590 22011 41591 21635 41591 22010 41591 21637 41592 21635 41592 22011 41592 22012 41593 21637 41593 22011 41593 21639 41594 21637 41594 22012 41594 21641 41595 21639 41595 22012 41595 22013 41596 21641 41596 22012 41596 22014 41597 21641 41597 22013 41597 21643 41598 21641 41598 22014 41598 21645 41599 21643 41599 22014 41599 22015 41600 21645 41600 22014 41600 21647 41601 21645 41601 22015 41601 22016 41602 21647 41602 22015 41602 21649 41603 21647 41603 22016 41603 22017 41604 21649 41604 22016 41604 21651 41605 21649 41605 22017 41605 22018 41606 21651 41606 22017 41606 21654 41607 21651 41607 22018 41607 22019 41608 21654 41608 22018 41608 21655 41609 21654 41609 22019 41609 22020 41610 21655 41610 22019 41610 21657 41611 21655 41611 22020 41611 22021 41612 21657 41612 22020 41612 22022 41613 21657 41613 22021 41613 21659 41614 21657 41614 22022 41614 22023 41615 21659 41615 22022 41615 21661 41616 21659 41616 22023 41616 21663 41617 21661 41617 22023 41617 22024 41618 21663 41618 22023 41618 21666 41619 21663 41619 22024 41619 22025 41620 21666 41620 22024 41620 21668 41621 21666 41621 22025 41621 22026 41622 21668 41622 22025 41622 21670 41623 21668 41623 22026 41623 22027 41624 21670 41624 22026 41624 21672 41625 21670 41625 22027 41625 22028 41626 21672 41626 22027 41626 21674 41627 21672 41627 22028 41627 22029 41628 21674 41628 22028 41628 21676 41629 21674 41629 22029 41629 22030 41630 21676 41630 22029 41630 21678 41631 21676 41631 22030 41631 22031 41632 21678 41632 22030 41632 21680 41633 21678 41633 22031 41633 22032 41634 21680 41634 22031 41634 21683 41635 21680 41635 22032 41635 22033 41636 21683 41636 22032 41636 21686 41637 21683 41637 22033 41637 22034 41638 21686 41638 22033 41638 21687 41639 21686 41639 22034 41639 22035 41640 21687 41640 22034 41640 22036 41641 21687 41641 22035 41641 21690 41642 21687 41642 22036 41642 22037 41643 21690 41643 22036 41643 21692 41644 21690 41644 22037 41644 22038 41645 21692 41645 22037 41645 21694 41646 21692 41646 22038 41646 22039 41647 21694 41647 22038 41647 21696 41648 21694 41648 22039 41648 22040 41649 21696 41649 22039 41649 21698 41650 21696 41650 22040 41650 22041 41651 21698 41651 22040 41651 21701 41652 21698 41652 22041 41652 22042 41653 21701 41653 22041 41653 21703 41654 21701 41654 22042 41654 22043 41655 21703 41655 22042 41655 21707 41656 21703 41656 22043 41656 22044 41657 21707 41657 22043 41657 21708 41658 21707 41658 22044 41658 22045 41659 21708 41659 22044 41659 21711 41660 21708 41660 22045 41660 22046 41661 21711 41661 22045 41661 21713 41662 21711 41662 22046 41662 21713 41663 22046 41663 22047 41663 21715 41664 21713 41664 22047 41664 22048 41665 21715 41665 22047 41665 21717 41666 21715 41666 22048 41666 22049 41667 21717 41667 22048 41667 22050 41668 21717 41668 22049 41668 21720 41669 21717 41669 22050 41669 22051 41670 21720 41670 22050 41670 21721 41671 21720 41671 22051 41671 22052 41672 21721 41672 22051 41672 21723 41673 21721 41673 22052 41673 22053 41674 21723 41674 22052 41674 21725 41675 21723 41675 22053 41675 22054 41676 21725 41676 22053 41676 21728 41677 21725 41677 22054 41677 22055 41678 21728 41678 22054 41678 21730 41679 21728 41679 22055 41679 22056 41680 21730 41680 22055 41680 21732 41681 21730 41681 22056 41681 22057 41682 21732 41682 22056 41682 21735 41683 21732 41683 22057 41683 22058 41684 21735 41684 22057 41684 21736 41685 21735 41685 22058 41685 22059 41686 21736 41686 22058 41686 21739 41687 21736 41687 22059 41687 22060 41688 21739 41688 22059 41688 21741 41689 21739 41689 22060 41689 22061 41690 21741 41690 22060 41690 21743 41691 21741 41691 22061 41691 22062 41692 21743 41692 22061 41692 21745 41693 21743 41693 22062 41693 22063 41694 21745 41694 22062 41694 21747 41695 21745 41695 22063 41695 22064 41696 21747 41696 22063 41696 22065 41697 21747 41697 22064 41697 21749 41698 21747 41698 22065 41698 22066 41699 21749 41699 22065 41699 21752 41700 21749 41700 22066 41700 22067 41701 21752 41701 22066 41701 21754 41702 21752 41702 22067 41702 22068 41703 21754 41703 22067 41703 21756 41704 21754 41704 22068 41704 22069 41705 21756 41705 22068 41705 21759 41706 21756 41706 22069 41706 22070 41707 21759 41707 22069 41707 21761 41708 21759 41708 22070 41708 22071 41709 21761 41709 22070 41709 21763 41710 21761 41710 22071 41710 22072 41711 21763 41711 22071 41711 21766 41712 21763 41712 22072 41712 22073 41713 21766 41713 22072 41713 21769 41714 21766 41714 22073 41714 22074 41715 21769 41715 22073 41715 21772 41716 21769 41716 22074 41716 22075 41717 21772 41717 22074 41717 21774 41718 21772 41718 22075 41718 22076 41719 21774 41719 22075 41719 21775 41720 21774 41720 22076 41720 22077 41721 21775 41721 22076 41721 21777 41722 21775 41722 22077 41722 22078 41723 21777 41723 22077 41723 22079 41724 21777 41724 22078 41724 21780 41725 21777 41725 22079 41725 21782 41726 21780 41726 22079 41726 22080 41727 21782 41727 22079 41727 21784 41728 21782 41728 22080 41728 22081 41729 21784 41729 22080 41729 21786 41730 21784 41730 22081 41730 22082 41731 21786 41731 22081 41731 22083 41732 21786 41732 22082 41732 21789 41733 21786 41733 22083 41733 22084 41734 21789 41734 22083 41734 21791 41735 21789 41735 22084 41735 22085 41736 21791 41736 22084 41736 21792 41737 21791 41737 22085 41737 22086 41738 21792 41738 22085 41738 21795 41739 21792 41739 22086 41739 22087 41740 21795 41740 22086 41740 21797 41741 21795 41741 22087 41741 22088 41742 21797 41742 22087 41742 22089 41743 21797 41743 22088 41743 21799 41744 21797 41744 22089 41744 22090 41745 21799 41745 22089 41745 21801 41746 21799 41746 22090 41746 22091 41747 21801 41747 22090 41747 21804 41748 21801 41748 22091 41748 22092 41749 21804 41749 22091 41749 21807 41750 21804 41750 22092 41750 22093 41751 21807 41751 22092 41751 21809 41752 21807 41752 22093 41752 22094 41753 21809 41753 22093 41753 21811 41754 21809 41754 22094 41754 22095 41755 21811 41755 22094 41755 21813 41756 21811 41756 22095 41756 22096 41757 21813 41757 22095 41757 21815 41758 21813 41758 22096 41758 22097 41759 21815 41759 22096 41759 21817 41760 21815 41760 22097 41760 22098 41761 21817 41761 22097 41761 21820 41762 21817 41762 22098 41762 22099 41763 21820 41763 22098 41763 22100 41764 21820 41764 22099 41764 21823 41765 21820 41765 22100 41765 22101 41766 21823 41766 22100 41766 21825 41767 21823 41767 22101 41767 22102 41768 21825 41768 22101 41768 21828 41769 21825 41769 22102 41769 22103 41770 21828 41770 22102 41770 21830 41771 21828 41771 22103 41771 22104 41772 21830 41772 22103 41772 21831 41773 21830 41773 22104 41773 22105 41774 21831 41774 22104 41774 21834 41775 21831 41775 22105 41775 22106 41776 21834 41776 22105 41776 21836 41777 21834 41777 22106 41777 21838 41778 21836 41778 22106 41778 22107 41779 21838 41779 22106 41779 21840 41780 21838 41780 22107 41780 22108 41781 21840 41781 22107 41781 21842 41782 21840 41782 22108 41782 22109 41783 21842 41783 22108 41783 21844 41784 21842 41784 22109 41784 22110 41785 21844 41785 22109 41785 21847 41786 21844 41786 22110 41786 21848 41787 21847 41787 22110 41787 22111 41788 21848 41788 22110 41788 21851 41789 21848 41789 22111 41789 22112 41790 21851 41790 22111 41790 21852 41791 21851 41791 22112 41791 22113 41792 21852 41792 22112 41792 21854 41793 21852 41793 22113 41793 22114 41794 21854 41794 22113 41794 21856 41795 21854 41795 22114 41795 21858 41796 22114 41796 22115 41796 21858 41797 21856 41797 22114 41797 22116 41798 21858 41798 22115 41798 21861 41799 21858 41799 22116 41799 21863 41800 21861 41800 22116 41800 22117 41801 21863 41801 22116 41801 21865 41802 21863 41802 22117 41802 22118 41803 21865 41803 22117 41803 21868 41804 21865 41804 22118 41804 22119 41805 21868 41805 22118 41805 21870 41806 21868 41806 22119 41806 22120 41807 21870 41807 22119 41807 21871 41808 21870 41808 22120 41808 22121 41809 21871 41809 22120 41809 21874 41810 21871 41810 22121 41810 22122 41811 21874 41811 22121 41811 21876 41812 21874 41812 22122 41812 21878 41813 21876 41813 22122 41813 22123 41814 21878 41814 22122 41814 21880 41815 21878 41815 22123 41815 22124 41816 21880 41816 22123 41816 21882 41817 21880 41817 22124 41817 22125 41818 21882 41818 22124 41818 21884 41819 21882 41819 22125 41819 22126 41820 21884 41820 22125 41820 21887 41821 21884 41821 22126 41821 22127 41822 21887 41822 22126 41822 21889 41823 21887 41823 22127 41823 22128 41824 21889 41824 22127 41824 21891 41825 21889 41825 22128 41825 22129 41826 21891 41826 22128 41826 21894 41827 21891 41827 22129 41827 22130 41828 21894 41828 22129 41828 21896 41829 21894 41829 22130 41829 22131 41830 21896 41830 22130 41830 21897 41831 21896 41831 22131 41831 22132 41832 21897 41832 22131 41832 21899 41833 21897 41833 22132 41833 22133 41834 21899 41834 22132 41834 21901 41835 21899 41835 22133 41835 22134 41836 21901 41836 22133 41836 21903 41837 21901 41837 22134 41837 22135 41838 21903 41838 22134 41838 21906 41839 21903 41839 22135 41839 22136 41840 21906 41840 22135 41840 21907 41841 21906 41841 22136 41841 22137 41842 21907 41842 22136 41842 21909 41843 21907 41843 22137 41843 22138 41844 21909 41844 22137 41844 22139 41845 21909 41845 22138 41845 21910 41846 21909 41846 22139 41846 21375 41847 21910 41847 22139 41847 22140 41848 21375 41848 22139 41848 21371 41849 21375 41849 22140 41849 22141 41850 21371 41850 22140 41850 21374 41851 21371 41851 22141 41851 22142 41852 21374 41852 22141 41852 21377 41853 21374 41853 22142 41853 22144 41854 21913 41854 21912 41854 22144 41855 21914 41855 21913 41855 22145 41856 21914 41856 22144 41856 22145 41857 21915 41857 21914 41857 22143 41858 21915 41858 22145 41858 22143 41859 21916 41859 21915 41859 22146 41860 21916 41860 22143 41860 22146 41861 21917 41861 21916 41861 22147 41862 21917 41862 22146 41862 22147 41863 21918 41863 21917 41863 21392 41864 21918 41864 22147 41864 21392 41865 21919 41865 21918 41865 21393 41866 21919 41866 21392 41866 22148 41867 21919 41867 21393 41867 22148 41868 21920 41868 21919 41868 22149 41869 21920 41869 22148 41869 22149 41870 21921 41870 21920 41870 22149 41871 21922 41871 21921 41871 21401 41872 21922 41872 22149 41872 21401 41873 21923 41873 21922 41873 21403 41874 21923 41874 21401 41874 21403 41875 21924 41875 21923 41875 22150 41876 21924 41876 21403 41876 22151 41877 21924 41877 22150 41877 22151 41878 21925 41878 21924 41878 21409 41879 21925 41879 22151 41879 21409 41880 21926 41880 21925 41880 21410 41881 21926 41881 21409 41881 21412 41882 21926 41882 21410 41882 21412 41883 21927 41883 21926 41883 21414 41884 21927 41884 21412 41884 21414 41885 21928 41885 21927 41885 21415 41886 21928 41886 21414 41886 21417 41887 21928 41887 21415 41887 21417 41888 21929 41888 21928 41888 21417 41889 21930 41889 21929 41889 21419 41890 21930 41890 21417 41890 21420 41891 21930 41891 21419 41891 21420 41892 21931 41892 21930 41892 21422 41893 21931 41893 21420 41893 21424 41894 21931 41894 21422 41894 21424 41895 21932 41895 21931 41895 21426 41896 21932 41896 21424 41896 21426 41897 21933 41897 21932 41897 21427 41898 21933 41898 21426 41898 21427 41899 21934 41899 21933 41899 21429 41900 21934 41900 21427 41900 21429 41901 21935 41901 21934 41901 21431 41902 21935 41902 21429 41902 21431 41903 21936 41903 21935 41903 21433 41904 21936 41904 21431 41904 21433 41905 21937 41905 21936 41905 21434 41906 21937 41906 21433 41906 21434 41907 21938 41907 21937 41907 21436 41908 21938 41908 21434 41908 21436 41909 21939 41909 21938 41909 21437 41910 21939 41910 21436 41910 21437 41911 21940 41911 21939 41911 21439 41912 21940 41912 21437 41912 21441 41913 21940 41913 21439 41913 21441 41914 21941 41914 21940 41914 21443 41915 21941 41915 21441 41915 21443 41916 21942 41916 21941 41916 21445 41917 21942 41917 21443 41917 21447 41918 21943 41918 21445 41918 21445 41919 21943 41919 21942 41919 21448 41920 21944 41920 21447 41920 21447 41921 21944 41921 21943 41921 21450 41922 21944 41922 21448 41922 21450 41923 21945 41923 21944 41923 21451 41924 21945 41924 21450 41924 21451 41925 21946 41925 21945 41925 21453 41926 21946 41926 21451 41926 21455 41927 21946 41927 21453 41927 21455 41928 21947 41928 21946 41928 21456 41929 21947 41929 21455 41929 21458 41930 21947 41930 21456 41930 21458 41931 21948 41931 21947 41931 21460 41932 21948 41932 21458 41932 21462 41933 21948 41933 21460 41933 21462 41934 21949 41934 21948 41934 21464 41935 21949 41935 21462 41935 21464 41936 21950 41936 21949 41936 21466 41937 21950 41937 21464 41937 21466 41938 21951 41938 21950 41938 22152 41939 21951 41939 21466 41939 22152 41940 21952 41940 21951 41940 22153 41941 21953 41941 22152 41941 22152 41942 21953 41942 21952 41942 22154 41943 21953 41943 22153 41943 22154 41944 21954 41944 21953 41944 22155 41945 21954 41945 22154 41945 22155 41946 21955 41946 21954 41946 21477 41947 21955 41947 22155 41947 21477 41948 21956 41948 21955 41948 21479 41949 21956 41949 21477 41949 21479 41950 21957 41950 21956 41950 22156 41951 21957 41951 21479 41951 22156 41952 21958 41952 21957 41952 21482 41953 21958 41953 22156 41953 21482 41954 21959 41954 21958 41954 22157 41955 21959 41955 21482 41955 21487 41956 21959 41956 22157 41956 21487 41957 21960 41957 21959 41957 22158 41958 21960 41958 21487 41958 22158 41959 21961 41959 21960 41959 21491 41960 21961 41960 22158 41960 21491 41961 21962 41961 21961 41961 21493 41962 21962 41962 21491 41962 21494 41963 21962 41963 21493 41963 21494 41964 21963 41964 21962 41964 21496 41965 21963 41965 21494 41965 21498 41966 21963 41966 21496 41966 21498 41967 21964 41967 21963 41967 21500 41968 21964 41968 21498 41968 21500 41969 21965 41969 21964 41969 21502 41970 21965 41970 21500 41970 21502 41971 21966 41971 21965 41971 21504 41972 21966 41972 21502 41972 21504 41973 21967 41973 21966 41973 21505 41974 21967 41974 21504 41974 21507 41975 21967 41975 21505 41975 21507 41976 21968 41976 21967 41976 21509 41977 21968 41977 21507 41977 21509 41978 21969 41978 21968 41978 21510 41979 21969 41979 21509 41979 21512 41980 21969 41980 21510 41980 21512 41981 21970 41981 21969 41981 22159 41982 21970 41982 21512 41982 22160 41983 21970 41983 22159 41983 22160 41984 21971 41984 21970 41984 21516 41985 21971 41985 22160 41985 21516 41986 21972 41986 21971 41986 21518 41987 21972 41987 21516 41987 21520 41988 21973 41988 21518 41988 21518 41989 21973 41989 21972 41989 21521 41990 21973 41990 21520 41990 21521 41991 21974 41991 21973 41991 22161 41992 21974 41992 21521 41992 22161 41993 21975 41993 21974 41993 22161 41994 21976 41994 21975 41994 21526 41995 21976 41995 22161 41995 21528 41996 21976 41996 21526 41996 21528 41997 21977 41997 21976 41997 21530 41998 21977 41998 21528 41998 21530 41999 21978 41999 21977 41999 21532 42000 21978 42000 21530 42000 21532 42001 21979 42001 21978 42001 21534 42002 21979 42002 21532 42002 21534 42003 21980 42003 21979 42003 21535 42004 21980 42004 21534 42004 21535 42005 21981 42005 21980 42005 21537 42006 21981 42006 21535 42006 21537 42007 21982 42007 21981 42007 21539 42008 21982 42008 21537 42008 21541 42009 21982 42009 21539 42009 21541 42010 21983 42010 21982 42010 21543 42011 21983 42011 21541 42011 21544 42012 21983 42012 21543 42012 21544 42013 21984 42013 21983 42013 21544 42014 21985 42014 21984 42014 21547 42015 21985 42015 21544 42015 22162 42016 21985 42016 21547 42016 22162 42017 21986 42017 21985 42017 21552 42018 21986 42018 22162 42018 21552 42019 21987 42019 21986 42019 21553 42020 21987 42020 21552 42020 22163 42021 21988 42021 21553 42021 21553 42022 21988 42022 21987 42022 22164 42023 21988 42023 22163 42023 22164 42024 21989 42024 21988 42024 21557 42025 21989 42025 22164 42025 21557 42026 21990 42026 21989 42026 21559 42027 21990 42027 21557 42027 21561 42028 21990 42028 21559 42028 21561 42029 21991 42029 21990 42029 21563 42030 21991 42030 21561 42030 21565 42031 21991 42031 21563 42031 21565 42032 21992 42032 21991 42032 21566 42033 21992 42033 21565 42033 21566 42034 21993 42034 21992 42034 21566 42035 21994 42035 21993 42035 21568 42036 21994 42036 21566 42036 22165 42037 21994 42037 21568 42037 22165 42038 21995 42038 21994 42038 22165 42039 21996 42039 21995 42039 21574 42040 21996 42040 22165 42040 21574 42041 21997 42041 21996 42041 22166 42042 21997 42042 21574 42042 22166 42043 21998 42043 21997 42043 22167 42044 21998 42044 22166 42044 21579 42045 21999 42045 22167 42045 22167 42046 21999 42046 21998 42046 21579 42047 22000 42047 21999 42047 21581 42048 22000 42048 21579 42048 21581 42049 22001 42049 22000 42049 21582 42050 22001 42050 21581 42050 21584 42051 22001 42051 21582 42051 21584 42052 22002 42052 22001 42052 21586 42053 22002 42053 21584 42053 22168 42054 22002 42054 21586 42054 22168 42055 22003 42055 22002 42055 21588 42056 22003 42056 22168 42056 21588 42057 22004 42057 22003 42057 22169 42058 22004 42058 21588 42058 22169 42059 22005 42059 22004 42059 21592 42060 22005 42060 22169 42060 21592 42061 22006 42061 22005 42061 21594 42062 22006 42062 21592 42062 21594 42063 22007 42063 22006 42063 21596 42064 22007 42064 21594 42064 21598 42065 22007 42065 21596 42065 21598 42066 22008 42066 22007 42066 21600 42067 22008 42067 21598 42067 21600 42068 22009 42068 22008 42068 21601 42069 22009 42069 21600 42069 21601 42070 22010 42070 22009 42070 22170 42071 22010 42071 21601 42071 22170 42072 22011 42072 22010 42072 21605 42073 22011 42073 22170 42073 22171 42074 22011 42074 21605 42074 22171 42075 22012 42075 22011 42075 22172 42076 22012 42076 22171 42076 22172 42077 22013 42077 22012 42077 22173 42078 22013 42078 22172 42078 22173 42079 22014 42079 22013 42079 21612 42080 22014 42080 22173 42080 21612 42081 22015 42081 22014 42081 21614 42082 22015 42082 21612 42082 21614 42083 22016 42083 22015 42083 21615 42084 22016 42084 21614 42084 21615 42085 22017 42085 22016 42085 21618 42086 22017 42086 21615 42086 21618 42087 22018 42087 22017 42087 21619 42088 22018 42088 21618 42088 21619 42089 22019 42089 22018 42089 22174 42090 22019 42090 21619 42090 22174 42091 22020 42091 22019 42091 21623 42092 22020 42092 22174 42092 22175 42093 22020 42093 21623 42093 22175 42094 22021 42094 22020 42094 21627 42095 22021 42095 22175 42095 21627 42096 22022 42096 22021 42096 21629 42097 22022 42097 21627 42097 21629 42098 22023 42098 22022 42098 21631 42099 22023 42099 21629 42099 21632 42100 22023 42100 21631 42100 21632 42101 22024 42101 22023 42101 21634 42102 22024 42102 21632 42102 21634 42103 22025 42103 22024 42103 21636 42104 22025 42104 21634 42104 21636 42105 22026 42105 22025 42105 21638 42106 22026 42106 21636 42106 21638 42107 22027 42107 22026 42107 22176 42108 22027 42108 21638 42108 22176 42109 22028 42109 22027 42109 22177 42110 22028 42110 22176 42110 22177 42111 22029 42111 22028 42111 21642 42112 22029 42112 22177 42112 21642 42113 22030 42113 22029 42113 21644 42114 22030 42114 21642 42114 21646 42115 22030 42115 21644 42115 21646 42116 22031 42116 22030 42116 21648 42117 22031 42117 21646 42117 21648 42118 22032 42118 22031 42118 21650 42119 22032 42119 21648 42119 21652 42120 22032 42120 21650 42120 22178 42121 22033 42121 21652 42121 21652 42122 22033 42122 22032 42122 22178 42123 22034 42123 22033 42123 22179 42124 22034 42124 22178 42124 22180 42125 22035 42125 22179 42125 22179 42126 22035 42126 22034 42126 22180 42127 22036 42127 22035 42127 21660 42128 22036 42128 22180 42128 21660 42129 22037 42129 22036 42129 21662 42130 22037 42130 21660 42130 21662 42131 22038 42131 22037 42131 21664 42132 22038 42132 21662 42132 21665 42133 22038 42133 21664 42133 21665 42134 22039 42134 22038 42134 22181 42135 22039 42135 21665 42135 22181 42136 22040 42136 22039 42136 21669 42137 22040 42137 22181 42137 21671 42138 22040 42138 21669 42138 21671 42139 22041 42139 22040 42139 21673 42140 22041 42140 21671 42140 21673 42141 22042 42141 22041 42141 21675 42142 22042 42142 21673 42142 21675 42143 22043 42143 22042 42143 21677 42144 22043 42144 21675 42144 21677 42145 22044 42145 22043 42145 21679 42146 22044 42146 21677 42146 21679 42147 22045 42147 22044 42147 21681 42148 22045 42148 21679 42148 21681 42149 22046 42149 22045 42149 21682 42150 22046 42150 21681 42150 21684 42151 22046 42151 21682 42151 21684 42152 22047 42152 22046 42152 22182 42153 22047 42153 21684 42153 22182 42154 22048 42154 22047 42154 22183 42155 22048 42155 22182 42155 22183 42156 22049 42156 22048 42156 21688 42157 22049 42157 22183 42157 21688 42158 22050 42158 22049 42158 21689 42159 22050 42159 21688 42159 21689 42160 22051 42160 22050 42160 22184 42161 22051 42161 21689 42161 22184 42162 22052 42162 22051 42162 22185 42163 22052 42163 22184 42163 22185 42164 22053 42164 22052 42164 21693 42165 22053 42165 22185 42165 21695 42166 22053 42166 21693 42166 21695 42167 22054 42167 22053 42167 21697 42168 22054 42168 21695 42168 21697 42169 22055 42169 22054 42169 21699 42170 22055 42170 21697 42170 21699 42171 22056 42171 22055 42171 21700 42172 22056 42172 21699 42172 21700 42173 22057 42173 22056 42173 21702 42174 22057 42174 21700 42174 21702 42175 22058 42175 22057 42175 21704 42176 22058 42176 21702 42176 21705 42177 22058 42177 21704 42177 21705 42178 22059 42178 22058 42178 21706 42179 22059 42179 21705 42179 21709 42180 22059 42180 21706 42180 21709 42181 22060 42181 22059 42181 21710 42182 22060 42182 21709 42182 21710 42183 22061 42183 22060 42183 22186 42184 22061 42184 21710 42184 22186 42185 22062 42185 22061 42185 22186 42186 22063 42186 22062 42186 21716 42187 22063 42187 22186 42187 21716 42188 22064 42188 22063 42188 21718 42189 22064 42189 21716 42189 21718 42190 22065 42190 22064 42190 22187 42191 22065 42191 21718 42191 22187 42192 22066 42192 22065 42192 21722 42193 22066 42193 22187 42193 21722 42194 22067 42194 22066 42194 21724 42195 22067 42195 21722 42195 21726 42196 22067 42196 21724 42196 21726 42197 22068 42197 22067 42197 21727 42198 22068 42198 21726 42198 21727 42199 22069 42199 22068 42199 21729 42200 22069 42200 21727 42200 21729 42201 22070 42201 22069 42201 21731 42202 22070 42202 21729 42202 21731 42203 22071 42203 22070 42203 21733 42204 22071 42204 21731 42204 21733 42205 22072 42205 22071 42205 22188 42206 22072 42206 21733 42206 22189 42207 22072 42207 22188 42207 22189 42208 22073 42208 22072 42208 21737 42209 22073 42209 22189 42209 21737 42210 22074 42210 22073 42210 21738 42211 22074 42211 21737 42211 21740 42212 22074 42212 21738 42212 21740 42213 22075 42213 22074 42213 22190 42214 22075 42214 21740 42214 22190 42215 22076 42215 22075 42215 22191 42216 22076 42216 22190 42216 22191 42217 22077 42217 22076 42217 21746 42218 22077 42218 22191 42218 21746 42219 22078 42219 22077 42219 21748 42220 22078 42220 21746 42220 21748 42221 22079 42221 22078 42221 21750 42222 22079 42222 21748 42222 21750 42223 22080 42223 22079 42223 21751 42224 22080 42224 21750 42224 21751 42225 22081 42225 22080 42225 21753 42226 22081 42226 21751 42226 21753 42227 22082 42227 22081 42227 21755 42228 22082 42228 21753 42228 21757 42229 22082 42229 21755 42229 21757 42230 22083 42230 22082 42230 21758 42231 22083 42231 21757 42231 21758 42232 22084 42232 22083 42232 21760 42233 22084 42233 21758 42233 21760 42234 22085 42234 22084 42234 21762 42235 22085 42235 21760 42235 21762 42236 22086 42236 22085 42236 21764 42237 22086 42237 21762 42237 21764 42238 22087 42238 22086 42238 21765 42239 22087 42239 21764 42239 21765 42240 22088 42240 22087 42240 21767 42241 22088 42241 21765 42241 21767 42242 22089 42242 22088 42242 21768 42243 22089 42243 21767 42243 21768 42244 22090 42244 22089 42244 21770 42245 22090 42245 21768 42245 21771 42246 22090 42246 21770 42246 21771 42247 22091 42247 22090 42247 22192 42248 22091 42248 21771 42248 22192 42249 22092 42249 22091 42249 22192 42250 22093 42250 22092 42250 21776 42251 22093 42251 22192 42251 22193 42252 22094 42252 21776 42252 21776 42253 22094 42253 22093 42253 22193 42254 22095 42254 22094 42254 21779 42255 22095 42255 22193 42255 21781 42256 22095 42256 21779 42256 21781 42257 22096 42257 22095 42257 21783 42258 22096 42258 21781 42258 21783 42259 22097 42259 22096 42259 21785 42260 22097 42260 21783 42260 21787 42261 22097 42261 21785 42261 21787 42262 22098 42262 22097 42262 22194 42263 22098 42263 21787 42263 22194 42264 22099 42264 22098 42264 22195 42265 22099 42265 22194 42265 22195 42266 22100 42266 22099 42266 22195 42267 22101 42267 22100 42267 21793 42268 22101 42268 22195 42268 21794 42269 22101 42269 21793 42269 21794 42270 22102 42270 22101 42270 21796 42271 22102 42271 21794 42271 21796 42272 22103 42272 22102 42272 21798 42273 22103 42273 21796 42273 21798 42274 22104 42274 22103 42274 21800 42275 22104 42275 21798 42275 21800 42276 22105 42276 22104 42276 21802 42277 22105 42277 21800 42277 21802 42278 22106 42278 22105 42278 21803 42279 22106 42279 21802 42279 21805 42280 22106 42280 21803 42280 21805 42281 22107 42281 22106 42281 22196 42282 22107 42282 21805 42282 22196 42283 22108 42283 22107 42283 22197 42284 22108 42284 22196 42284 22197 42285 22109 42285 22108 42285 21812 42286 22109 42286 22197 42286 21812 42287 22110 42287 22109 42287 21814 42288 22110 42288 21812 42288 21816 42289 22110 42289 21814 42289 21818 42290 22111 42290 21816 42290 21816 42291 22111 42291 22110 42291 21819 42292 22112 42292 21818 42292 21818 42293 22112 42293 22111 42293 21821 42294 22112 42294 21819 42294 21821 42295 22113 42295 22112 42295 21822 42296 22113 42296 21821 42296 21822 42297 22114 42297 22113 42297 22198 42298 22114 42298 21822 42298 22198 42299 22115 42299 22114 42299 21826 42300 22115 42300 22198 42300 21826 42301 22116 42301 22115 42301 22199 42302 22116 42302 21826 42302 21832 42303 22116 42303 22199 42303 21832 42304 22117 42304 22116 42304 21833 42305 22117 42305 21832 42305 21833 42306 22118 42306 22117 42306 21835 42307 22118 42307 21833 42307 21835 42308 22119 42308 22118 42308 21837 42309 22119 42309 21835 42309 21837 42310 22120 42310 22119 42310 22200 42311 22120 42311 21837 42311 21843 42312 22121 42312 22200 42312 22200 42313 22121 42313 22120 42313 21845 42314 22121 42314 21843 42314 21845 42315 22122 42315 22121 42315 21846 42316 22122 42316 21845 42316 21846 42317 22123 42317 22122 42317 21849 42318 22123 42318 21846 42318 22201 42319 22123 42319 21849 42319 22201 42320 22124 42320 22123 42320 22202 42321 22124 42321 22201 42321 22202 42322 22125 42322 22124 42322 21855 42323 22125 42323 22202 42323 21855 42324 22126 42324 22125 42324 22203 42325 22126 42325 21855 42325 22203 42326 22127 42326 22126 42326 21859 42327 22127 42327 22203 42327 21859 42328 22128 42328 22127 42328 22204 42329 22128 42329 21859 42329 22204 42330 22129 42330 22128 42330 22205 42331 22129 42331 22204 42331 22205 42332 22130 42332 22129 42332 22206 42333 22130 42333 22205 42333 22206 42334 22131 42334 22130 42334 22207 42335 22131 42335 22206 42335 22207 42336 22132 42336 22131 42336 22208 42337 22132 42337 22207 42337 22208 42338 22133 42338 22132 42338 22209 42339 22133 42339 22208 42339 22209 42340 22134 42340 22133 42340 21872 42341 22134 42341 22209 42341 21872 42342 22135 42342 22134 42342 21873 42343 22135 42343 21872 42343 21873 42344 22136 42344 22135 42344 21875 42345 22136 42345 21873 42345 21877 42346 22136 42346 21875 42346 21877 42347 22137 42347 22136 42347 22210 42348 22137 42348 21877 42348 22210 42349 22138 42349 22137 42349 22211 42350 22138 42350 22210 42350 22211 42351 22139 42351 22138 42351 22212 42352 22139 42352 22211 42352 22212 42353 22140 42353 22139 42353 22213 42354 22140 42354 22212 42354 22213 42355 22141 42355 22140 42355 21888 42356 22141 42356 22213 42356 21888 42357 22142 42357 22141 42357 21890 42358 22142 42358 21888 42358 21892 42359 21377 42359 21890 42359 21890 42360 21377 42360 22142 42360 22214 42361 21377 42361 21892 42361 22214 42362 21380 42362 21377 42362 22214 42363 21383 42363 21380 42363 22215 42364 21383 42364 22214 42364 22216 42365 21383 42365 22215 42365 22216 42366 21386 42366 21383 42366 21900 42367 21386 42367 22216 42367 21900 42368 21387 42368 21386 42368 21902 42369 21387 42369 21900 42369 21902 42370 21390 42370 21387 42370 21389 42371 21390 42371 21902 42371 21391 42372 22147 42372 22146 42372 21392 42373 22147 42373 21391 42373 22148 42374 21393 42374 21395 42374 21398 42375 22148 42375 21395 42375 22149 42376 22148 42376 21398 42376 21399 42377 22149 42377 21398 42377 21401 42378 22149 42378 21399 42378 21405 42379 22150 42379 21403 42379 22151 42380 22150 42380 21405 42380 21407 42381 22151 42381 21405 42381 21409 42382 22151 42382 21407 42382 22152 42383 21466 42383 21467 42383 21469 42384 22152 42384 21467 42384 22153 42385 22152 42385 21469 42385 21471 42386 22153 42386 21469 42386 22154 42387 22153 42387 21471 42387 21473 42388 22154 42388 21471 42388 22155 42389 22154 42389 21473 42389 21475 42390 22155 42390 21473 42390 21477 42391 22155 42391 21475 42391 22156 42392 21479 42392 21480 42392 21482 42393 22156 42393 21480 42393 22157 42394 21482 42394 21484 42394 21486 42395 22157 42395 21484 42395 21487 42396 22157 42396 21486 42396 21489 42397 22158 42397 21487 42397 21491 42398 22158 42398 21489 42398 21514 42399 22159 42399 21512 42399 22160 42400 22159 42400 21514 42400 21516 42401 22160 42401 21514 42401 22161 42402 21521 42402 21523 42402 21525 42403 22161 42403 21523 42403 21526 42404 22161 42404 21525 42404 22162 42405 21547 42405 21549 42405 21550 42406 22162 42406 21549 42406 21552 42407 22162 42407 21550 42407 21555 42408 22163 42408 21553 42408 22164 42409 22163 42409 21555 42409 21557 42410 22164 42410 21555 42410 22165 42411 21568 42411 21570 42411 21572 42412 22165 42412 21570 42412 21574 42413 22165 42413 21572 42413 22166 42414 21574 42414 21576 42414 21577 42415 22166 42415 21576 42415 22167 42416 22166 42416 21577 42416 21579 42417 22167 42417 21577 42417 21588 42418 22168 42418 21586 42418 22169 42419 21588 42419 21590 42419 21592 42420 22169 42420 21590 42420 21603 42421 22170 42421 21601 42421 21605 42422 22170 42422 21603 42422 21606 42423 22171 42423 21605 42423 22172 42424 22171 42424 21606 42424 21608 42425 22172 42425 21606 42425 22173 42426 22172 42426 21608 42426 21610 42427 22173 42427 21608 42427 21612 42428 22173 42428 21610 42428 22174 42429 21619 42429 21621 42429 21623 42430 22174 42430 21621 42430 22175 42431 21623 42431 21625 42431 21627 42432 22175 42432 21625 42432 21640 42433 22176 42433 21638 42433 22177 42434 22176 42434 21640 42434 21642 42435 22177 42435 21640 42435 21653 42436 22178 42436 21652 42436 22179 42437 22178 42437 21653 42437 21656 42438 22179 42438 21653 42438 22180 42439 22179 42439 21656 42439 21658 42440 22180 42440 21656 42440 21660 42441 22180 42441 21658 42441 22181 42442 21665 42442 21667 42442 21669 42443 22181 42443 21667 42443 21685 42444 22182 42444 21684 42444 22183 42445 22182 42445 21685 42445 21688 42446 22183 42446 21685 42446 21691 42447 22184 42447 21689 42447 22185 42448 22184 42448 21691 42448 21693 42449 22185 42449 21691 42449 22186 42450 21710 42450 21712 42450 21714 42451 22186 42451 21712 42451 21716 42452 22186 42452 21714 42452 21719 42453 22187 42453 21718 42453 21722 42454 22187 42454 21719 42454 21734 42455 22188 42455 21733 42455 22189 42456 22188 42456 21734 42456 21737 42457 22189 42457 21734 42457 21742 42458 22190 42458 21740 42458 22191 42459 22190 42459 21742 42459 21744 42460 22191 42460 21742 42460 21746 42461 22191 42461 21744 42461 22192 42462 21771 42462 21773 42462 21776 42463 22192 42463 21773 42463 22193 42464 21776 42464 21778 42464 21779 42465 22193 42465 21778 42465 21788 42466 22194 42466 21787 42466 22195 42467 22194 42467 21788 42467 21790 42468 22195 42468 21788 42468 21793 42469 22195 42469 21790 42469 22196 42470 21805 42470 21806 42470 21808 42471 22196 42471 21806 42471 22197 42472 22196 42472 21808 42472 21810 42473 22197 42473 21808 42473 21812 42474 22197 42474 21810 42474 21824 42475 22198 42475 21822 42475 21826 42476 22198 42476 21824 42476 22199 42477 21826 42477 21827 42477 21829 42478 22199 42478 21827 42478 21832 42479 22199 42479 21829 42479 22200 42480 21837 42480 21839 42480 21841 42481 22200 42481 21839 42481 21843 42482 22200 42482 21841 42482 21850 42483 22201 42483 21849 42483 22202 42484 22201 42484 21850 42484 21853 42485 22202 42485 21850 42485 21855 42486 22202 42486 21853 42486 21857 42487 22203 42487 21855 42487 21859 42488 22203 42488 21857 42488 22204 42489 21859 42489 21860 42489 21862 42490 22204 42490 21860 42490 22205 42491 22204 42491 21862 42491 21864 42492 22205 42492 21862 42492 22206 42493 22205 42493 21864 42493 21866 42494 22206 42494 21864 42494 22207 42495 22206 42495 21866 42495 21867 42496 22207 42496 21866 42496 22208 42497 22207 42497 21867 42497 21869 42498 22208 42498 21867 42498 22209 42499 22208 42499 21869 42499 21872 42500 22209 42500 21869 42500 22210 42501 21877 42501 21879 42501 21881 42502 22210 42502 21879 42502 22211 42503 22210 42503 21881 42503 21883 42504 22211 42504 21881 42504 22212 42505 22211 42505 21883 42505 21885 42506 22212 42506 21883 42506 22213 42507 22212 42507 21885 42507 21886 42508 22213 42508 21885 42508 21888 42509 22213 42509 21886 42509 21893 42510 22214 42510 21892 42510 22215 42511 22214 42511 21893 42511 21895 42512 22215 42512 21893 42512 22216 42513 22215 42513 21895 42513 21898 42514 22216 42514 21895 42514 21900 42515 22216 42515 21898 42515 21389 42516 21902 42516 21904 42516 22222 42517 21389 42517 21904 42517 21905 42518 22222 42518 21904 42518 22220 42519 22219 42519 22218 42519 22217 42520 22218 42520 22274 42520 21905 42521 22219 42521 22220 42521 22221 42522 22220 42522 22218 42522 22221 42523 22218 42523 22217 42523 22222 42524 22220 42524 22221 42524 21905 42525 22220 42525 22222 42525 22223 42526 22222 42526 22221 42526 21389 42527 22222 42527 22223 42527 22223 42528 22221 42528 22217 42528 22223 42529 21390 42529 21389 42529 22224 42530 22223 42530 22217 42530 22225 42531 22223 42531 22224 42531 22224 42532 22217 42532 22226 42532 21390 42533 22223 42533 22225 42533 22225 42534 22224 42534 22227 42534 22228 42535 22225 42535 22227 42535 21387 42536 21390 42536 22225 42536 22228 42537 21387 42537 22225 42537 22229 42538 22224 42538 22226 42538 22229 42539 22227 42539 22224 42539 21388 42540 21387 42540 22228 42540 22230 42541 22228 42541 22227 42541 22230 42542 22227 42542 22229 42542 21388 42543 22228 42543 22230 42543 22231 42544 22230 42544 22229 42544 22231 42545 22234 42545 21388 42545 22231 42546 21388 42546 22230 42546 22232 42547 22231 42547 22229 42547 22233 42548 22229 42548 22226 42548 22233 42549 22232 42549 22229 42549 22235 42550 22231 42550 22232 42550 22235 42551 22234 42551 22231 42551 21385 42552 22234 42552 22235 42552 22237 42553 22235 42553 22232 42553 22236 42554 22233 42554 22226 42554 21385 42555 22235 42555 22237 42555 22238 42556 22232 42556 22233 42556 22238 42557 22233 42557 22236 42557 22237 42558 22232 42558 22238 42558 22239 42559 21385 42559 22237 42559 22239 42560 22237 42560 22238 42560 22240 42561 22238 42561 22236 42561 22241 42562 22238 42562 22240 42562 22241 42563 22239 42563 22238 42563 22242 42564 22241 42564 22240 42564 21382 42565 22239 42565 22241 42565 21382 42566 22241 42566 22242 42566 22242 42567 22240 42567 22245 42567 22243 42568 22242 42568 22245 42568 22244 42569 21382 42569 22242 42569 22244 42570 22242 42570 22243 42570 22245 42571 22240 42571 22246 42571 22246 42572 22240 42572 22247 42572 22243 42573 22245 42573 22246 42573 22248 42574 22243 42574 22246 42574 22249 42575 22244 42575 22243 42575 22249 42576 22243 42576 22248 42576 22250 42577 22248 42577 22246 42577 22250 42578 22246 42578 22247 42578 22251 42579 22248 42579 22250 42579 22252 42580 22250 42580 22247 42580 22251 42581 22250 42581 22252 42581 22251 42582 22249 42582 22248 42582 22253 42583 22251 42583 22252 42583 22251 42584 21372 42584 22249 42584 22253 42585 21372 42585 22251 42585 22254 42586 22253 42586 22252 42586 22255 42587 22252 42587 22247 42587 22255 42588 22254 42588 22252 42588 21372 42589 22253 42589 22254 42589 22255 42590 22247 42590 22261 42590 22256 42591 22254 42591 22255 42591 22257 42592 21372 42592 22254 42592 22256 42593 22257 42593 22254 42593 22258 42594 22256 42594 22255 42594 22261 42595 22258 42595 22255 42595 22259 42596 22257 42596 22256 42596 22260 42597 22256 42597 22258 42597 22259 42598 22256 42598 22260 42598 22259 42599 21373 42599 22257 42599 22260 42600 22258 42600 22261 42600 21373 42601 22259 42601 22260 42601 22262 42602 22260 42602 22261 42602 22263 42603 21373 42603 22260 42603 22263 42604 22260 42604 22262 42604 21376 42605 21373 42605 22263 42605 22262 42606 22261 42606 22264 42606 21376 42607 22263 42607 22262 42607 22266 42608 21376 42608 22262 42608 22266 42609 22262 42609 22264 42609 22266 42610 21379 42610 21376 42610 22267 42611 21379 42611 22266 42611 22268 42612 22264 42612 22265 42612 22267 42613 22266 42613 22264 42613 22268 42614 22267 42614 22264 42614 22267 42615 22269 42615 21379 42615 22269 42616 22267 42616 22268 42616 22272 42617 22268 42617 22265 42617 22271 42618 22269 42618 22268 42618 22271 42619 22268 42619 22272 42619 22270 42620 22272 42620 22265 42620 22271 42621 21381 42621 22269 42621 22270 42622 22273 42622 22272 42622 22273 42623 22271 42623 22272 42623 22273 42624 21381 42624 22271 42624 22273 42625 21384 42625 21381 42625 22275 42626 22270 42626 22274 42626 22276 42627 22273 42627 22270 42627 22276 42628 22270 42628 22275 42628 22276 42629 21384 42629 22273 42629 21908 42630 21384 42630 22276 42630 22275 42631 22274 42631 22218 42631 22219 42632 22276 42632 22275 42632 22219 42633 22275 42633 22218 42633 21908 42634 22276 42634 22219 42634 22219 42635 21905 42635 21908 42635 22261 42636 22265 42636 22264 42636 22226 42637 22274 42637 22270 42637 22226 42638 22217 42638 22274 42638 22236 42639 22247 42639 22240 42639 22236 42640 22261 42640 22247 42640 22236 42641 22265 42641 22261 42641 22236 42642 22270 42642 22265 42642 22236 42643 22226 42643 22270 42643 22279 42644 22354 42644 22277 42644 22279 42645 22277 42645 22278 42645 22279 42646 22281 42646 22354 42646 22280 42647 22279 42647 22278 42647 22281 42648 22279 42648 22280 42648 22281 42649 22280 42649 22282 42649 22284 42650 22281 42650 22282 42650 22284 42651 22282 42651 22283 42651 22286 42652 22283 42652 22285 42652 22284 42653 22283 42653 22286 42653 22287 42654 22286 42654 22285 42654 22288 42655 22284 42655 22286 42655 22288 42656 22286 42656 22289 42656 22289 42657 22286 42657 22287 42657 22289 42658 22287 42658 22290 42658 22291 42659 22289 42659 22290 42659 22292 42660 22289 42660 22291 42660 22292 42661 22288 42661 22289 42661 22294 42662 22292 42662 22291 42662 22293 42663 22294 42663 22291 42663 22296 42664 22288 42664 22292 42664 22296 42665 22292 42665 22294 42665 22297 42666 22293 42666 22295 42666 22297 42667 22294 42667 22293 42667 22297 42668 22295 42668 22298 42668 22297 42669 22296 42669 22294 42669 22299 42670 22296 42670 22297 42670 22300 42671 22297 42671 22298 42671 22299 42672 22297 42672 22300 42672 22300 42673 22298 42673 22301 42673 22303 42674 22296 42674 22299 42674 22303 42675 22299 42675 22300 42675 22300 42676 22301 42676 22302 42676 22304 42677 22300 42677 22302 42677 22303 42678 22300 42678 22304 42678 22305 42679 22304 42679 22302 42679 22303 42680 22304 42680 22306 42680 22306 42681 22304 42681 22305 42681 22307 42682 22306 42682 22305 42682 22310 42683 22303 42683 22306 42683 22309 42684 22306 42684 22307 42684 22309 42685 22307 42685 22308 42685 22310 42686 22306 42686 22309 42686 22312 42687 22309 42687 22308 42687 22312 42688 22308 42688 22311 42688 22312 42689 22310 42689 22309 42689 22313 42690 22310 42690 22312 42690 22314 42691 22312 42691 22311 42691 22314 42692 22313 42692 22312 42692 22310 42693 22313 42693 22316 42693 22315 42694 22313 42694 22314 42694 22317 42695 22313 42695 22315 42695 22316 42696 22313 42696 22317 42696 22318 42697 22317 42697 22315 42697 22319 42698 22317 42698 22318 42698 22319 42699 22316 42699 22317 42699 22320 42700 22319 42700 22318 42700 22322 42701 22316 42701 22319 42701 22323 42702 22319 42702 22320 42702 22323 42703 22320 42703 22321 42703 22322 42704 22319 42704 22323 42704 22325 42705 22321 42705 22324 42705 22325 42706 22323 42706 22321 42706 22322 42707 22323 42707 22325 42707 22327 42708 22325 42708 22324 42708 22327 42709 22322 42709 22325 42709 22326 42710 22327 42710 22324 42710 22328 42711 22322 42711 22327 42711 22330 42712 22327 42712 22326 42712 22329 42713 22328 42713 22327 42713 22329 42714 22327 42714 22330 42714 22331 42715 22329 42715 22330 42715 22329 42716 22331 42716 22332 42716 22332 42717 22331 42717 22333 42717 22334 42718 22329 42718 22332 42718 22334 42719 22328 42719 22329 42719 22336 42720 22332 42720 22333 42720 22336 42721 22333 42721 22335 42721 22334 42722 22332 42722 22336 42722 22337 42723 22336 42723 22335 42723 22338 42724 22334 42724 22336 42724 22338 42725 22336 42725 22337 42725 22339 42726 22334 42726 22338 42726 22338 42727 22337 42727 22340 42727 22342 42728 22338 42728 22340 42728 22339 42729 22338 42729 22342 42729 22342 42730 22340 42730 22341 42730 22343 42731 22342 42731 22341 42731 22344 42732 22342 42732 22343 42732 22346 42733 22339 42733 22342 42733 22346 42734 22342 42734 22344 42734 22344 42735 22343 42735 22345 42735 22347 42736 22344 42736 22345 42736 22346 42737 22344 42737 22347 42737 22349 42738 22347 42738 22348 42738 22349 42739 22346 42739 22347 42739 22348 42740 22347 42740 22350 42740 22352 42741 22346 42741 22349 42741 22352 42742 22348 42742 22350 42742 22352 42743 22349 42743 22348 42743 22352 42744 22350 42744 22353 42744 22353 42745 22350 42745 22351 42745 22354 42746 22352 42746 22353 42746 22354 42747 22353 42747 22351 42747 22354 42748 22351 42748 22277 42748 22281 42749 22352 42749 22354 42749 22278 42750 22277 42750 22355 42750 22278 42751 22355 42751 22435 42751 22280 42752 22278 42752 22435 42752 22280 42753 22435 42753 22356 42753 22282 42754 22280 42754 22356 42754 22283 42755 22356 42755 22357 42755 22283 42756 22282 42756 22356 42756 22285 42757 22283 42757 22357 42757 22285 42758 22357 42758 22427 42758 22287 42759 22285 42759 22427 42759 22287 42760 22427 42760 22358 42760 22290 42761 22287 42761 22358 42761 22290 42762 22358 42762 22359 42762 22291 42763 22290 42763 22359 42763 22291 42764 22359 42764 22360 42764 22293 42765 22291 42765 22360 42765 22295 42766 22293 42766 22360 42766 22295 42767 22360 42767 22423 42767 22298 42768 22295 42768 22423 42768 22298 42769 22423 42769 22361 42769 22298 42770 22361 42770 22362 42770 22301 42771 22298 42771 22362 42771 22301 42772 22362 42772 22363 42772 22302 42773 22301 42773 22363 42773 22302 42774 22363 42774 22364 42774 22305 42775 22302 42775 22364 42775 22305 42776 22364 42776 22416 42776 22305 42777 22416 42777 22365 42777 22307 42778 22305 42778 22365 42778 22307 42779 22365 42779 22366 42779 22308 42780 22307 42780 22366 42780 22308 42781 22366 42781 22367 42781 22311 42782 22308 42782 22367 42782 22311 42783 22367 42783 22412 42783 22314 42784 22311 42784 22412 42784 22314 42785 22412 42785 22368 42785 22315 42786 22368 42786 22369 42786 22315 42787 22314 42787 22368 42787 22318 42788 22315 42788 22369 42788 22318 42789 22369 42789 22370 42789 22320 42790 22318 42790 22370 42790 22320 42791 22370 42791 22405 42791 22321 42792 22320 42792 22405 42792 22321 42793 22405 42793 22403 42793 22324 42794 22403 42794 22400 42794 22324 42795 22321 42795 22403 42795 22326 42796 22400 42796 22371 42796 22326 42797 22324 42797 22400 42797 22326 42798 22371 42798 22372 42798 22330 42799 22326 42799 22372 42799 22331 42800 22330 42800 22372 42800 22331 42801 22372 42801 22396 42801 22333 42802 22331 42802 22396 42802 22333 42803 22396 42803 22373 42803 22335 42804 22333 42804 22373 42804 22335 42805 22373 42805 22374 42805 22337 42806 22335 42806 22374 42806 22340 42807 22337 42807 22374 42807 22340 42808 22374 42808 22375 42808 22341 42809 22340 42809 22375 42809 22343 42810 22341 42810 22375 42810 22343 42811 22375 42811 22390 42811 22343 42812 22390 42812 22388 42812 22345 42813 22388 42813 22387 42813 22345 42814 22343 42814 22388 42814 22347 42815 22387 42815 22385 42815 22347 42816 22345 42816 22387 42816 22347 42817 22385 42817 22376 42817 22350 42818 22347 42818 22376 42818 22350 42819 22376 42819 22377 42819 22351 42820 22350 42820 22377 42820 22351 42821 22377 42821 22378 42821 22351 42822 22378 42822 22379 42822 22277 42823 22351 42823 22379 42823 22277 42824 22379 42824 22355 42824 21404 42825 22328 42825 21911 42825 21404 42826 22322 42826 22328 42826 21911 42827 22328 42827 22334 42827 21402 42828 22322 42828 21404 42828 21402 42829 22316 42829 22322 42829 21912 42830 21911 42830 22334 42830 21912 42831 22334 42831 22339 42831 21396 42832 22316 42832 21402 42832 21396 42833 22310 42833 22316 42833 22144 42834 21912 42834 22339 42834 22144 42835 22339 42835 22346 42835 21400 42836 22310 42836 21396 42836 22145 42837 22144 42837 22346 42837 22303 42838 22310 42838 21400 42838 22352 42839 22145 42839 22346 42839 22303 42840 21400 42840 21397 42840 22296 42841 22303 42841 21397 42841 22281 42842 22143 42842 22145 42842 22281 42843 22145 42843 22352 42843 22296 42844 21397 42844 21394 42844 22281 42845 22146 42845 22143 42845 22296 42846 21394 42846 21391 42846 22288 42847 22296 42847 21391 42847 22284 42848 22146 42848 22281 42848 22284 42849 21391 42849 22146 42849 22288 42850 21391 42850 22284 42850 22381 42851 22436 42851 22379 42851 22380 42852 22436 42852 22381 42852 22382 42853 22380 42853 22381 42853 22378 42854 22381 42854 22379 42854 22382 42855 22381 42855 22378 42855 22383 42856 22378 42856 22377 42856 22383 42857 22382 42857 22378 42857 22383 42858 22377 42858 22376 42858 22384 42859 22382 42859 22383 42859 22385 42860 22383 42860 22376 42860 22384 42861 22383 42861 22385 42861 22386 42862 22382 42862 22384 42862 22386 42863 22384 42863 22385 42863 22386 42864 22385 42864 22387 42864 22389 42865 22386 42865 22387 42865 22388 42866 22389 42866 22387 42866 22391 42867 22386 42867 22389 42867 22392 42868 22388 42868 22390 42868 22392 42869 22389 42869 22388 42869 22392 42870 22391 42870 22389 42870 22392 42871 22390 42871 22375 42871 22393 42872 22392 42872 22375 42872 22393 42873 22375 42873 22374 42873 22393 42874 22391 42874 22392 42874 22394 42875 22393 42875 22374 42875 22394 42876 22374 42876 22373 42876 22395 42877 22393 42877 22394 42877 22395 42878 22391 42878 22393 42878 22396 42879 22394 42879 22373 42879 22397 42880 22394 42880 22396 42880 22395 42881 22394 42881 22397 42881 22372 42882 22397 42882 22396 42882 22398 42883 22397 42883 22372 42883 22399 42884 22395 42884 22397 42884 22399 42885 22397 42885 22398 42885 22398 42886 22372 42886 22371 42886 22401 42887 22399 42887 22398 42887 22400 42888 22398 42888 22371 42888 22401 42889 22398 42889 22400 42889 22402 42890 22399 42890 22401 42890 22403 42891 22401 42891 22400 42891 22404 42892 22402 42892 22401 42892 22404 42893 22401 42893 22403 42893 22405 42894 22404 42894 22403 42894 22406 42895 22402 42895 22404 42895 22406 42896 22404 42896 22405 42896 22370 42897 22406 42897 22405 42897 22407 42898 22402 42898 22406 42898 22408 42899 22406 42899 22370 42899 22408 42900 22407 42900 22406 42900 22408 42901 22370 42901 22369 42901 22409 42902 22408 42902 22369 42902 22409 42903 22407 42903 22408 42903 22368 42904 22409 42904 22369 42904 22410 42905 22407 42905 22409 42905 22411 42906 22409 42906 22368 42906 22410 42907 22409 42907 22411 42907 22411 42908 22368 42908 22412 42908 22413 42909 22410 42909 22411 42909 22367 42910 22411 42910 22412 42910 22414 42911 22413 42911 22411 42911 22414 42912 22411 42912 22367 42912 22366 42913 22414 42913 22367 42913 22365 42914 22414 42914 22366 42914 22417 42915 22413 42915 22414 42915 22415 42916 22414 42916 22365 42916 22415 42917 22365 42917 22416 42917 22417 42918 22414 42918 22415 42918 22417 42919 22415 42919 22416 42919 22418 42920 22417 42920 22416 42920 22418 42921 22416 42921 22364 42921 22363 42922 22418 42922 22364 42922 22420 42923 22417 42923 22418 42923 22419 42924 22418 42924 22363 42924 22420 42925 22418 42925 22419 42925 22421 42926 22420 42926 22419 42926 22362 42927 22419 42927 22363 42927 22361 42928 22419 42928 22362 42928 22421 42929 22419 42929 22361 42929 22422 42930 22421 42930 22361 42930 22422 42931 22361 42931 22423 42931 22424 42932 22421 42932 22422 42932 22424 42933 22422 42933 22423 42933 22360 42934 22424 42934 22423 42934 22426 42935 22421 42935 22424 42935 22425 42936 22360 42936 22359 42936 22425 42937 22424 42937 22360 42937 22426 42938 22424 42938 22425 42938 22427 42939 22359 42939 22358 42939 22427 42940 22425 42940 22359 42940 22428 42941 22426 42941 22425 42941 22428 42942 22425 42942 22427 42942 22430 42943 22426 42943 22428 42943 22428 42944 22427 42944 22429 42944 22429 42945 22427 42945 22357 42945 22429 42946 22430 42946 22428 42946 22431 42947 22429 42947 22357 42947 22431 42948 22430 42948 22429 42948 22432 42949 22430 42949 22431 42949 22432 42950 22431 42950 22433 42950 22433 42951 22357 42951 22356 42951 22433 42952 22431 42952 22357 42952 22434 42953 22432 42953 22433 42953 22435 42954 22433 42954 22356 42954 22435 42955 22434 42955 22433 42955 22436 42956 22435 42956 22355 42956 22436 42957 22434 42957 22435 42957 22380 42958 22432 42958 22434 42958 22436 42959 22355 42959 22379 42959 22380 42960 22434 42960 22436 42960 21360 42961 21365 42961 21367 42961 21360 42962 21362 42962 21365 42962 21358 42963 21367 42963 21368 42963 21358 42964 21360 42964 21367 42964 21356 42965 21358 42965 21369 42965 21369 42966 21358 42966 21368 42966

+
+ + + +

22437 42967 22439 42967 22440 42967 22438 42968 22439 42968 22437 42968 22441 42969 22442 42969 22438 42969 22438 42970 22442 42970 22439 42970 22441 42971 22443 42971 22442 42971 22443 42972 22444 42972 22442 42972 22445 42973 22446 42973 22443 42973 22443 42974 22446 42974 22444 42974 22445 42975 22447 42975 22446 42975 22447 42976 22448 42976 22446 42976 22447 42977 22437 42977 22448 42977 22437 42978 22440 42978 22448 42978 22446 42979 22450 42979 22449 42979 22446 42980 22448 42980 22450 42980 22448 42981 22440 42981 22450 42981 22450 42982 22440 42982 22454 42982 22440 42983 22439 42983 22454 42983 22454 42984 22439 42984 22453 42984 22437 42985 22447 42985 22438 42985 22447 42986 22441 42986 22438 42986 22447 42987 22445 42987 22441 42987 22445 42988 22443 42988 22441 42988 22452 42989 23468 42989 23470 42989 22452 42990 23465 42990 23468 42990 22452 42991 23463 42991 23465 42991 22453 42992 22452 42992 23470 42992 22453 42993 23473 42993 23476 42993 22453 42994 23470 42994 23473 42994 22451 42995 23520 42995 23463 42995 22451 42996 23516 42996 23520 42996 22451 42997 23463 42997 22452 42997 23511 42998 23516 42998 22451 42998 22454 42999 22453 42999 23476 42999 22454 43000 23476 43000 23486 43000 22449 43001 23511 43001 22451 43001 23487 43002 22454 43002 23486 43002 23503 43003 23511 43003 22449 43003 23493 43004 22450 43004 22454 43004 23493 43005 22454 43005 23487 43005 23503 43006 22449 43006 22450 43006 23496 43007 22450 43007 23493 43007 23500 43008 23503 43008 22450 43008 23500 43009 22450 43009 23496 43009 22992 43010 23329 43010 23334 43010 22455 43011 23329 43011 22992 43011 22455 43012 23326 43012 23329 43012 22456 43013 22992 43013 23334 43013 22455 43014 23324 43014 23326 43014 22456 43015 23334 43015 22457 43015 22458 43016 23324 43016 22455 43016 22458 43017 23321 43017 23324 43017 22456 43018 22457 43018 22459 43018 22460 43019 22461 43019 23321 43019 22460 43020 23321 43020 22458 43020 22462 43021 22456 43021 22459 43021 22463 43022 22462 43022 22459 43022 22460 43023 22464 43023 22461 43023 22465 43024 22464 43024 22460 43024 22467 43025 22464 43025 22465 43025 22467 43026 22465 43026 22468 43026 22469 43027 22467 43027 22468 43027 22469 43028 22468 43028 22470 43028 22471 43029 22470 43029 22472 43029 22477 43030 22475 43030 22474 43030 22477 43031 22476 43031 22475 43031 22481 43032 22476 43032 22477 43032 22481 43033 22479 43033 22476 43033 22481 43034 22480 43034 22479 43034 22478 43035 22480 43035 22481 43035 22478 43036 22482 43036 22480 43036 22483 43037 22482 43037 22478 43037 22483 43038 22484 43038 22482 43038 22485 43039 22484 43039 22483 43039 22485 43040 22486 43040 22484 43040 22487 43041 22486 43041 22485 43041 22487 43042 22488 43042 22486 43042 22489 43043 22488 43043 22487 43043 22489 43044 22490 43044 22488 43044 22489 43045 22491 43045 22490 43045 22492 43046 22491 43046 22489 43046 22492 43047 22493 43047 22491 43047 22492 43048 22494 43048 22493 43048 22495 43049 22494 43049 22492 43049 22495 43050 22496 43050 22494 43050 22497 43051 22496 43051 22495 43051 22497 43052 22498 43052 22496 43052 22499 43053 22498 43053 22497 43053 22499 43054 22500 43054 22498 43054 22499 43055 22501 43055 22500 43055 22502 43056 22501 43056 22499 43056 22502 43057 22503 43057 22501 43057 22504 43058 22503 43058 22502 43058 22504 43059 22505 43059 22503 43059 22506 43060 22505 43060 22504 43060 22506 43061 22507 43061 22505 43061 22506 43062 22508 43062 22507 43062 22509 43063 22508 43063 22506 43063 22509 43064 22510 43064 22508 43064 22511 43065 22510 43065 22509 43065 22511 43066 22512 43066 22510 43066 22513 43067 22512 43067 22511 43067 22513 43068 22514 43068 22512 43068 22513 43069 22515 43069 22514 43069 22516 43070 22515 43070 22513 43070 22516 43071 22517 43071 22515 43071 22518 43072 22517 43072 22516 43072 22518 43073 22519 43073 22517 43073 22520 43074 22519 43074 22518 43074 22520 43075 22521 43075 22519 43075 22522 43076 22521 43076 22520 43076 22522 43077 22523 43077 22521 43077 22524 43078 22523 43078 22522 43078 22524 43079 22525 43079 22523 43079 22526 43080 22527 43080 22524 43080 22524 43081 22527 43081 22525 43081 22528 43082 22529 43082 22526 43082 22526 43083 22529 43083 22527 43083 22528 43084 22530 43084 22529 43084 22531 43085 22530 43085 22528 43085 22531 43086 22532 43086 22530 43086 22533 43087 22532 43087 22531 43087 22533 43088 22534 43088 22532 43088 22535 43089 22534 43089 22533 43089 22535 43090 22536 43090 22534 43090 22537 43091 22536 43091 22535 43091 22537 43092 22538 43092 22536 43092 22539 43093 22538 43093 22537 43093 22539 43094 22540 43094 22538 43094 22541 43095 22540 43095 22539 43095 22541 43096 22542 43096 22540 43096 22543 43097 22542 43097 22541 43097 22543 43098 22544 43098 22542 43098 22545 43099 22544 43099 22543 43099 22545 43100 22546 43100 22544 43100 22547 43101 22546 43101 22545 43101 22547 43102 22548 43102 22546 43102 22549 43103 22548 43103 22547 43103 22549 43104 22550 43104 22548 43104 22551 43105 22550 43105 22549 43105 22551 43106 22552 43106 22550 43106 22553 43107 22552 43107 22551 43107 22553 43108 22554 43108 22552 43108 22555 43109 22554 43109 22553 43109 22555 43110 22556 43110 22554 43110 22557 43111 22556 43111 22555 43111 22557 43112 22558 43112 22556 43112 22557 43113 22559 43113 22558 43113 22560 43114 22559 43114 22557 43114 22560 43115 22561 43115 22559 43115 22562 43116 22561 43116 22560 43116 22562 43117 22563 43117 22561 43117 22564 43118 22563 43118 22562 43118 22564 43119 22565 43119 22563 43119 22564 43120 22566 43120 22565 43120 22567 43121 22566 43121 22564 43121 22568 43122 22566 43122 22567 43122 22568 43123 22569 43123 22566 43123 22570 43124 22569 43124 22568 43124 22570 43125 22571 43125 22569 43125 22570 43126 22572 43126 22571 43126 22573 43127 22572 43127 22570 43127 22573 43128 22574 43128 22572 43128 22575 43129 22574 43129 22573 43129 22575 43130 22576 43130 22574 43130 22577 43131 22576 43131 22575 43131 22577 43132 22578 43132 22576 43132 22579 43133 22578 43133 22577 43133 22579 43134 22580 43134 22578 43134 22581 43135 22580 43135 22579 43135 22581 43136 22582 43136 22580 43136 22583 43137 22582 43137 22581 43137 22583 43138 22584 43138 22582 43138 22585 43139 22584 43139 22583 43139 22585 43140 22586 43140 22584 43140 22587 43141 22586 43141 22585 43141 22587 43142 22588 43142 22586 43142 22587 43143 22589 43143 22588 43143 22590 43144 22589 43144 22587 43144 22590 43145 22591 43145 22589 43145 22592 43146 22591 43146 22590 43146 22592 43147 22593 43147 22591 43147 22594 43148 22593 43148 22592 43148 22594 43149 22595 43149 22593 43149 22596 43150 22595 43150 22594 43150 22596 43151 22597 43151 22595 43151 22598 43152 22597 43152 22596 43152 22598 43153 22599 43153 22597 43153 22600 43154 22599 43154 22598 43154 22600 43155 22601 43155 22599 43155 22602 43156 22601 43156 22600 43156 22602 43157 22603 43157 22601 43157 22604 43158 22603 43158 22602 43158 22604 43159 22605 43159 22603 43159 22606 43160 22605 43160 22604 43160 22606 43161 22607 43161 22605 43161 22606 43162 22608 43162 22607 43162 22609 43163 22608 43163 22606 43163 22609 43164 22610 43164 22608 43164 22611 43165 22610 43165 22609 43165 22612 43166 22613 43166 22611 43166 22611 43167 22613 43167 22610 43167 22614 43168 22613 43168 22612 43168 22614 43169 22615 43169 22613 43169 22614 43170 22616 43170 22615 43170 22617 43171 22616 43171 22614 43171 22617 43172 22618 43172 22616 43172 22619 43173 22618 43173 22617 43173 22619 43174 22620 43174 22618 43174 22621 43175 22620 43175 22619 43175 22621 43176 22622 43176 22620 43176 22623 43177 22622 43177 22621 43177 22623 43178 22624 43178 22622 43178 22623 43179 22625 43179 22624 43179 22626 43180 22625 43180 22623 43180 22626 43181 22627 43181 22625 43181 22626 43182 22628 43182 22627 43182 22629 43183 22628 43183 22626 43183 22629 43184 22630 43184 22628 43184 22631 43185 22630 43185 22629 43185 22631 43186 22632 43186 22630 43186 22631 43187 22633 43187 22632 43187 22634 43188 22633 43188 22631 43188 22634 43189 22635 43189 22633 43189 22636 43190 22635 43190 22634 43190 22636 43191 22637 43191 22635 43191 22636 43192 22638 43192 22637 43192 22639 43193 22638 43193 22636 43193 22639 43194 22640 43194 22638 43194 22641 43195 22640 43195 22639 43195 22641 43196 22642 43196 22640 43196 22643 43197 22642 43197 22641 43197 22643 43198 22644 43198 22642 43198 22645 43199 22644 43199 22643 43199 22645 43200 22646 43200 22644 43200 22647 43201 22646 43201 22645 43201 22647 43202 22648 43202 22646 43202 22649 43203 22648 43203 22647 43203 22649 43204 22650 43204 22648 43204 22651 43205 22650 43205 22649 43205 22651 43206 22652 43206 22650 43206 22651 43207 22653 43207 22652 43207 22654 43208 22653 43208 22651 43208 22655 43209 22656 43209 22654 43209 22654 43210 22656 43210 22653 43210 22657 43211 22656 43211 22655 43211 22657 43212 22658 43212 22656 43212 22659 43213 22658 43213 22657 43213 22659 43214 22660 43214 22658 43214 22661 43215 22660 43215 22659 43215 22661 43216 22662 43216 22660 43216 22661 43217 22663 43217 22662 43217 22664 43218 22663 43218 22661 43218 22664 43219 22665 43219 22663 43219 22666 43220 22665 43220 22664 43220 22666 43221 22667 43221 22665 43221 22668 43222 22667 43222 22666 43222 22669 43223 22667 43223 22668 43223 22669 43224 22670 43224 22667 43224 22669 43225 22671 43225 22670 43225 22672 43226 22671 43226 22669 43226 22672 43227 22673 43227 22671 43227 22674 43228 22673 43228 22672 43228 22674 43229 22675 43229 22673 43229 22676 43230 22675 43230 22674 43230 22676 43231 22677 43231 22675 43231 22678 43232 22677 43232 22676 43232 22678 43233 22679 43233 22677 43233 22680 43234 22679 43234 22678 43234 22680 43235 22681 43235 22679 43235 22682 43236 22681 43236 22680 43236 22682 43237 22683 43237 22681 43237 22682 43238 22684 43238 22683 43238 22685 43239 22684 43239 22682 43239 22685 43240 22686 43240 22684 43240 22687 43241 22686 43241 22685 43241 22687 43242 22688 43242 22686 43242 22689 43243 22688 43243 22687 43243 22689 43244 22690 43244 22688 43244 22691 43245 22690 43245 22689 43245 22691 43246 22692 43246 22690 43246 22691 43247 22693 43247 22692 43247 22694 43248 22693 43248 22691 43248 22694 43249 22695 43249 22693 43249 22696 43250 22695 43250 22694 43250 22696 43251 22697 43251 22695 43251 22698 43252 22697 43252 22696 43252 22698 43253 22699 43253 22697 43253 22700 43254 22699 43254 22698 43254 22700 43255 22701 43255 22699 43255 22702 43256 22701 43256 22700 43256 22702 43257 22703 43257 22701 43257 22702 43258 22704 43258 22703 43258 22705 43259 22704 43259 22702 43259 22705 43260 22706 43260 22704 43260 22707 43261 22706 43261 22705 43261 22707 43262 22708 43262 22706 43262 22709 43263 22708 43263 22707 43263 22709 43264 22710 43264 22708 43264 22711 43265 22710 43265 22709 43265 22711 43266 22712 43266 22710 43266 22711 43267 22713 43267 22712 43267 22714 43268 22713 43268 22711 43268 22714 43269 22715 43269 22713 43269 22716 43270 22715 43270 22714 43270 22716 43271 22717 43271 22715 43271 22718 43272 22717 43272 22716 43272 22718 43273 22719 43273 22717 43273 22720 43274 22719 43274 22718 43274 22720 43275 22721 43275 22719 43275 22722 43276 22721 43276 22720 43276 22722 43277 22723 43277 22721 43277 22724 43278 22723 43278 22722 43278 22724 43279 22725 43279 22723 43279 22726 43280 22725 43280 22724 43280 22726 43281 22727 43281 22725 43281 22726 43282 22728 43282 22727 43282 22729 43283 22728 43283 22726 43283 22729 43284 22730 43284 22728 43284 22729 43285 22731 43285 22730 43285 22732 43286 22731 43286 22729 43286 22732 43287 22733 43287 22731 43287 22732 43288 22734 43288 22733 43288 22735 43289 22734 43289 22732 43289 22735 43290 22736 43290 22734 43290 22737 43291 22736 43291 22735 43291 22737 43292 22738 43292 22736 43292 22739 43293 22738 43293 22737 43293 22739 43294 22740 43294 22738 43294 22741 43295 22740 43295 22739 43295 22741 43296 22742 43296 22740 43296 22743 43297 22742 43297 22741 43297 22743 43298 22744 43298 22742 43298 22745 43299 22744 43299 22743 43299 22745 43300 22746 43300 22744 43300 22747 43301 22748 43301 22745 43301 22745 43302 22748 43302 22746 43302 22749 43303 22748 43303 22747 43303 22749 43304 22750 43304 22748 43304 22751 43305 22750 43305 22749 43305 22751 43306 22752 43306 22750 43306 22751 43307 22753 43307 22752 43307 22754 43308 22753 43308 22751 43308 22754 43309 22755 43309 22753 43309 22756 43310 22755 43310 22754 43310 22756 43311 22757 43311 22755 43311 22758 43312 22757 43312 22756 43312 22758 43313 22759 43313 22757 43313 22760 43314 22759 43314 22758 43314 22760 43315 22761 43315 22759 43315 22760 43316 22762 43316 22761 43316 22763 43317 22762 43317 22760 43317 22763 43318 22764 43318 22762 43318 22765 43319 22764 43319 22763 43319 22765 43320 22766 43320 22764 43320 22767 43321 22766 43321 22765 43321 22767 43322 22768 43322 22766 43322 22769 43323 22768 43323 22767 43323 22769 43324 22770 43324 22768 43324 22769 43325 22771 43325 22770 43325 22772 43326 22771 43326 22769 43326 22772 43327 22773 43327 22771 43327 22774 43328 22773 43328 22772 43328 22774 43329 22775 43329 22773 43329 22774 43330 22776 43330 22775 43330 22777 43331 22776 43331 22774 43331 22777 43332 22778 43332 22776 43332 22779 43333 22778 43333 22777 43333 22779 43334 22780 43334 22778 43334 22781 43335 22780 43335 22779 43335 22781 43336 22782 43336 22780 43336 22781 43337 22783 43337 22782 43337 22784 43338 22783 43338 22781 43338 22784 43339 22785 43339 22783 43339 22784 43340 22786 43340 22785 43340 22787 43341 22786 43341 22784 43341 22787 43342 22788 43342 22786 43342 22789 43343 22788 43343 22787 43343 22790 43344 22788 43344 22789 43344 22790 43345 22791 43345 22788 43345 22790 43346 22792 43346 22791 43346 22793 43347 22792 43347 22790 43347 22793 43348 22794 43348 22792 43348 22795 43349 22794 43349 22793 43349 22795 43350 22796 43350 22794 43350 22797 43351 22798 43351 22795 43351 22795 43352 22798 43352 22796 43352 22799 43353 22800 43353 22797 43353 22797 43354 22800 43354 22798 43354 22799 43355 22801 43355 22800 43355 22802 43356 22801 43356 22799 43356 22802 43357 22803 43357 22801 43357 22802 43358 22804 43358 22803 43358 22805 43359 22804 43359 22802 43359 22805 43360 22806 43360 22804 43360 22807 43361 22806 43361 22805 43361 22807 43362 22808 43362 22806 43362 22809 43363 22808 43363 22807 43363 22809 43364 22810 43364 22808 43364 22811 43365 22810 43365 22809 43365 22812 43366 22810 43366 22811 43366 22812 43367 22813 43367 22810 43367 22814 43368 22813 43368 22812 43368 22814 43369 22815 43369 22813 43369 22814 43370 22816 43370 22815 43370 22817 43371 22816 43371 22814 43371 22817 43372 22818 43372 22816 43372 22817 43373 22819 43373 22818 43373 22820 43374 22819 43374 22817 43374 22821 43375 22819 43375 22820 43375 22821 43376 22822 43376 22819 43376 22823 43377 22822 43377 22821 43377 22823 43378 22824 43378 22822 43378 22825 43379 22824 43379 22823 43379 22825 43380 22826 43380 22824 43380 22825 43381 22827 43381 22826 43381 22828 43382 22827 43382 22825 43382 22828 43383 22829 43383 22827 43383 22830 43384 22829 43384 22828 43384 22830 43385 22831 43385 22829 43385 22832 43386 22831 43386 22830 43386 22832 43387 22833 43387 22831 43387 22834 43388 22833 43388 22832 43388 22834 43389 22835 43389 22833 43389 22836 43390 22835 43390 22834 43390 22836 43391 22837 43391 22835 43391 22838 43392 22837 43392 22836 43392 22838 43393 22839 43393 22837 43393 22840 43394 22839 43394 22838 43394 22840 43395 22841 43395 22839 43395 22842 43396 22841 43396 22840 43396 22842 43397 22843 43397 22841 43397 22844 43398 22843 43398 22842 43398 22844 43399 22845 43399 22843 43399 22846 43400 22845 43400 22844 43400 22846 43401 22847 43401 22845 43401 22846 43402 22848 43402 22847 43402 22849 43403 22848 43403 22846 43403 22849 43404 22850 43404 22848 43404 22851 43405 22850 43405 22849 43405 22851 43406 22852 43406 22850 43406 22853 43407 22852 43407 22851 43407 22853 43408 22854 43408 22852 43408 22855 43409 22854 43409 22853 43409 22855 43410 22856 43410 22854 43410 22855 43411 22857 43411 22856 43411 22858 43412 22857 43412 22855 43412 22858 43413 22859 43413 22857 43413 22861 43414 22860 43414 22858 43414 22858 43415 22860 43415 22859 43415 22861 43416 22862 43416 22860 43416 22863 43417 22862 43417 22861 43417 22863 43418 22864 43418 22862 43418 22865 43419 22864 43419 22863 43419 22865 43420 22866 43420 22864 43420 22867 43421 22866 43421 22865 43421 22867 43422 22868 43422 22866 43422 22869 43423 22868 43423 22867 43423 22869 43424 22870 43424 22868 43424 22869 43425 22871 43425 22870 43425 22872 43426 22871 43426 22869 43426 22872 43427 22873 43427 22871 43427 22874 43428 22873 43428 22872 43428 22874 43429 22875 43429 22873 43429 22874 43430 22876 43430 22875 43430 22877 43431 22876 43431 22874 43431 22877 43432 22878 43432 22876 43432 22879 43433 22878 43433 22877 43433 22879 43434 22880 43434 22878 43434 22881 43435 22880 43435 22879 43435 22881 43436 22882 43436 22880 43436 22883 43437 22882 43437 22881 43437 22883 43438 22884 43438 22882 43438 22883 43439 22885 43439 22884 43439 22886 43440 22885 43440 22883 43440 22886 43441 22887 43441 22885 43441 22888 43442 22887 43442 22886 43442 22888 43443 22889 43443 22887 43443 22890 43444 22889 43444 22888 43444 22890 43445 22891 43445 22889 43445 22892 43446 22891 43446 22890 43446 22892 43447 22893 43447 22891 43447 22892 43448 22894 43448 22893 43448 22895 43449 22894 43449 22892 43449 22896 43450 22897 43450 22895 43450 22895 43451 22897 43451 22894 43451 22896 43452 22898 43452 22897 43452 22899 43453 22898 43453 22896 43453 22899 43454 22900 43454 22898 43454 22901 43455 22900 43455 22899 43455 22901 43456 22902 43456 22900 43456 22903 43457 22902 43457 22901 43457 22903 43458 22904 43458 22902 43458 22903 43459 22905 43459 22904 43459 22906 43460 22905 43460 22903 43460 22906 43461 22907 43461 22905 43461 22906 43462 22908 43462 22907 43462 22909 43463 22908 43463 22906 43463 22909 43464 22910 43464 22908 43464 22909 43465 22911 43465 22910 43465 22912 43466 22911 43466 22909 43466 22912 43467 22913 43467 22911 43467 22914 43468 22913 43468 22912 43468 22914 43469 22915 43469 22913 43469 22916 43470 22915 43470 22914 43470 22916 43471 22917 43471 22915 43471 22916 43472 22918 43472 22917 43472 22919 43473 22918 43473 22916 43473 22919 43474 22920 43474 22918 43474 22921 43475 22920 43475 22919 43475 22921 43476 22922 43476 22920 43476 22921 43477 22923 43477 22922 43477 22924 43478 22923 43478 22921 43478 22924 43479 22925 43479 22923 43479 22924 43480 22926 43480 22925 43480 22927 43481 22926 43481 22924 43481 22927 43482 22928 43482 22926 43482 22929 43483 22928 43483 22927 43483 22929 43484 22930 43484 22928 43484 22931 43485 22932 43485 22929 43485 22929 43486 22932 43486 22930 43486 22931 43487 22933 43487 22932 43487 22934 43488 22933 43488 22931 43488 22934 43489 22935 43489 22933 43489 22936 43490 22935 43490 22934 43490 22936 43491 22937 43491 22935 43491 22936 43492 22938 43492 22937 43492 22939 43493 22938 43493 22936 43493 22939 43494 22940 43494 22938 43494 22941 43495 22940 43495 22939 43495 22941 43496 22942 43496 22940 43496 22943 43497 22942 43497 22941 43497 22943 43498 22944 43498 22942 43498 22943 43499 22945 43499 22944 43499 22946 43500 22945 43500 22943 43500 22946 43501 22947 43501 22945 43501 22948 43502 22947 43502 22946 43502 22948 43503 22949 43503 22947 43503 22950 43504 22949 43504 22948 43504 22950 43505 22951 43505 22949 43505 22950 43506 22952 43506 22951 43506 22953 43507 22952 43507 22950 43507 22953 43508 22954 43508 22952 43508 22955 43509 22954 43509 22953 43509 22955 43510 22956 43510 22954 43510 22955 43511 22957 43511 22956 43511 22958 43512 22957 43512 22955 43512 22958 43513 22959 43513 22957 43513 22960 43514 22959 43514 22958 43514 22960 43515 22961 43515 22959 43515 22962 43516 22961 43516 22960 43516 22962 43517 22963 43517 22961 43517 22964 43518 22963 43518 22962 43518 22964 43519 22965 43519 22963 43519 22966 43520 22965 43520 22964 43520 22966 43521 22967 43521 22965 43521 22968 43522 22967 43522 22966 43522 22968 43523 22969 43523 22967 43523 22970 43524 22969 43524 22968 43524 22970 43525 22971 43525 22969 43525 22972 43526 22973 43526 22970 43526 22970 43527 22973 43527 22971 43527 22972 43528 22974 43528 22973 43528 22975 43529 22974 43529 22972 43529 22975 43530 22976 43530 22974 43530 22977 43531 22976 43531 22975 43531 22977 43532 22978 43532 22976 43532 22977 43533 22979 43533 22978 43533 22980 43534 22979 43534 22977 43534 22980 43535 22981 43535 22979 43535 22982 43536 22981 43536 22980 43536 22982 43537 22983 43537 22981 43537 22982 43538 22984 43538 22983 43538 22985 43539 22984 43539 22982 43539 22985 43540 22986 43540 22984 43540 22987 43541 22986 43541 22985 43541 22987 43542 23353 43542 22986 43542 22988 43543 23353 43543 22987 43543 22988 43544 22466 43544 23353 43544 22989 43545 22466 43545 22988 43545 22989 43546 22462 43546 22466 43546 22990 43547 22462 43547 22989 43547 22990 43548 22456 43548 22462 43548 22991 43549 22456 43549 22990 43549 22992 43550 22456 43550 22991 43550 22993 43551 22487 43551 22485 43551 22994 43552 22487 43552 22993 43552 22489 43553 22487 43553 22994 43553 22995 43554 22489 43554 22994 43554 22492 43555 22489 43555 22995 43555 22996 43556 22492 43556 22995 43556 22495 43557 22492 43557 22996 43557 22997 43558 22495 43558 22996 43558 22497 43559 22495 43559 22997 43559 22998 43560 22497 43560 22997 43560 22499 43561 22497 43561 22998 43561 22999 43562 22499 43562 22998 43562 22502 43563 22499 43563 22999 43563 23000 43564 22502 43564 22999 43564 22504 43565 22502 43565 23000 43565 23001 43566 22504 43566 23000 43566 22506 43567 22504 43567 23001 43567 23002 43568 22506 43568 23001 43568 23003 43569 22506 43569 23002 43569 22509 43570 22506 43570 23003 43570 23004 43571 22509 43571 23003 43571 22511 43572 22509 43572 23004 43572 22513 43573 22511 43573 23004 43573 23005 43574 22513 43574 23004 43574 23006 43575 22513 43575 23005 43575 22516 43576 22513 43576 23006 43576 23007 43577 22516 43577 23006 43577 22518 43578 22516 43578 23007 43578 23008 43579 22518 43579 23007 43579 22520 43580 22518 43580 23008 43580 22522 43581 22520 43581 23008 43581 23009 43582 22522 43582 23008 43582 22524 43583 22522 43583 23009 43583 23010 43584 22524 43584 23009 43584 22526 43585 22524 43585 23010 43585 23011 43586 22526 43586 23010 43586 22528 43587 22526 43587 23011 43587 23012 43588 22528 43588 23011 43588 22531 43589 22528 43589 23012 43589 23013 43590 22531 43590 23012 43590 22533 43591 22531 43591 23013 43591 23014 43592 22533 43592 23013 43592 22535 43593 22533 43593 23014 43593 23015 43594 22535 43594 23014 43594 22537 43595 22535 43595 23015 43595 23016 43596 22537 43596 23015 43596 22539 43597 22537 43597 23016 43597 22541 43598 22539 43598 23016 43598 23017 43599 22541 43599 23016 43599 22543 43600 22541 43600 23017 43600 22545 43601 22543 43601 23017 43601 23018 43602 22545 43602 23017 43602 22547 43603 22545 43603 23018 43603 23019 43604 22547 43604 23018 43604 22549 43605 22547 43605 23019 43605 23020 43606 22549 43606 23019 43606 22551 43607 22549 43607 23020 43607 23021 43608 22551 43608 23020 43608 22553 43609 22551 43609 23021 43609 23022 43610 22553 43610 23021 43610 22555 43611 22553 43611 23022 43611 23023 43612 22555 43612 23022 43612 22557 43613 22555 43613 23023 43613 23024 43614 22557 43614 23023 43614 22560 43615 22557 43615 23024 43615 23025 43616 22560 43616 23024 43616 22562 43617 22560 43617 23025 43617 23026 43618 22562 43618 23025 43618 22564 43619 22562 43619 23026 43619 23027 43620 22564 43620 23026 43620 22567 43621 22564 43621 23027 43621 23028 43622 22567 43622 23027 43622 22568 43623 22567 43623 23028 43623 23029 43624 22568 43624 23028 43624 22570 43625 22568 43625 23029 43625 23030 43626 22570 43626 23029 43626 22573 43627 22570 43627 23030 43627 23031 43628 22573 43628 23030 43628 22575 43629 22573 43629 23031 43629 22577 43630 22575 43630 23031 43630 23032 43631 22577 43631 23031 43631 22579 43632 22577 43632 23032 43632 23033 43633 22579 43633 23032 43633 22581 43634 22579 43634 23033 43634 23034 43635 22581 43635 23033 43635 22583 43636 22581 43636 23034 43636 23035 43637 22583 43637 23034 43637 22585 43638 22583 43638 23035 43638 23036 43639 22585 43639 23035 43639 22587 43640 22585 43640 23036 43640 23037 43641 22587 43641 23036 43641 23038 43642 22587 43642 23037 43642 22590 43643 22587 43643 23038 43643 23039 43644 22590 43644 23038 43644 22592 43645 22590 43645 23039 43645 23040 43646 22592 43646 23039 43646 22594 43647 22592 43647 23040 43647 23041 43648 22594 43648 23040 43648 22596 43649 22594 43649 23041 43649 23042 43650 22596 43650 23041 43650 22598 43651 22596 43651 23042 43651 23043 43652 22598 43652 23042 43652 22600 43653 22598 43653 23043 43653 23044 43654 22600 43654 23043 43654 22602 43655 22600 43655 23044 43655 23045 43656 22602 43656 23044 43656 22604 43657 22602 43657 23045 43657 23046 43658 22604 43658 23045 43658 22606 43659 22604 43659 23046 43659 23047 43660 22606 43660 23046 43660 22609 43661 22606 43661 23047 43661 23048 43662 22609 43662 23047 43662 22611 43663 22609 43663 23048 43663 23049 43664 22611 43664 23048 43664 22612 43665 22611 43665 23049 43665 23050 43666 22612 43666 23049 43666 22614 43667 22612 43667 23050 43667 23051 43668 22614 43668 23050 43668 22617 43669 22614 43669 23051 43669 23052 43670 22617 43670 23051 43670 22619 43671 22617 43671 23052 43671 23053 43672 22619 43672 23052 43672 23054 43673 22619 43673 23053 43673 22621 43674 22619 43674 23054 43674 23055 43675 22621 43675 23054 43675 22623 43676 22621 43676 23055 43676 23056 43677 22623 43677 23055 43677 22626 43678 22623 43678 23056 43678 23057 43679 22626 43679 23056 43679 22629 43680 22626 43680 23057 43680 23058 43681 22629 43681 23057 43681 22631 43682 22629 43682 23058 43682 23059 43683 22631 43683 23058 43683 23060 43684 22631 43684 23059 43684 22634 43685 22631 43685 23060 43685 23061 43686 22634 43686 23060 43686 22636 43687 22634 43687 23061 43687 23062 43688 22636 43688 23061 43688 22639 43689 22636 43689 23062 43689 23063 43690 22639 43690 23062 43690 22641 43691 22639 43691 23063 43691 23064 43692 22641 43692 23063 43692 22643 43693 22641 43693 23064 43693 22645 43694 22643 43694 23064 43694 23065 43695 22645 43695 23064 43695 22647 43696 22645 43696 23065 43696 23066 43697 22647 43697 23065 43697 22649 43698 22647 43698 23066 43698 23067 43699 22649 43699 23066 43699 22651 43700 22649 43700 23067 43700 23068 43701 22651 43701 23067 43701 22654 43702 22651 43702 23068 43702 22655 43703 22654 43703 23068 43703 23069 43704 22655 43704 23068 43704 22657 43705 22655 43705 23069 43705 23070 43706 22657 43706 23069 43706 22659 43707 22657 43707 23070 43707 23071 43708 22659 43708 23070 43708 22661 43709 22659 43709 23071 43709 23072 43710 22661 43710 23071 43710 22664 43711 22661 43711 23072 43711 23073 43712 22664 43712 23072 43712 22666 43713 22664 43713 23073 43713 22668 43714 22666 43714 23073 43714 23074 43715 22668 43715 23073 43715 22669 43716 22668 43716 23074 43716 23075 43717 22669 43717 23074 43717 23076 43718 22669 43718 23075 43718 22672 43719 22669 43719 23076 43719 22674 43720 22672 43720 23076 43720 23077 43721 22674 43721 23076 43721 22676 43722 22674 43722 23077 43722 23078 43723 22676 43723 23077 43723 22678 43724 22676 43724 23078 43724 23079 43725 22678 43725 23078 43725 22680 43726 22678 43726 23079 43726 23080 43727 22680 43727 23079 43727 22682 43728 22680 43728 23080 43728 22682 43729 23080 43729 23081 43729 23082 43730 22682 43730 23081 43730 22685 43731 22682 43731 23082 43731 23083 43732 22685 43732 23082 43732 22687 43733 22685 43733 23083 43733 23084 43734 22687 43734 23083 43734 22689 43735 22687 43735 23084 43735 22691 43736 22689 43736 23084 43736 23085 43737 22691 43737 23084 43737 22694 43738 22691 43738 23085 43738 23086 43739 22694 43739 23085 43739 22696 43740 22694 43740 23086 43740 23087 43741 22696 43741 23086 43741 22698 43742 22696 43742 23087 43742 23088 43743 22698 43743 23087 43743 22700 43744 22698 43744 23088 43744 23089 43745 22700 43745 23088 43745 22702 43746 22700 43746 23089 43746 23090 43747 22702 43747 23089 43747 22705 43748 22702 43748 23090 43748 23091 43749 22705 43749 23090 43749 22707 43750 22705 43750 23091 43750 23092 43751 22707 43751 23091 43751 22709 43752 22707 43752 23092 43752 23093 43753 22709 43753 23092 43753 22711 43754 22709 43754 23093 43754 23094 43755 22711 43755 23093 43755 22714 43756 22711 43756 23094 43756 23095 43757 22714 43757 23094 43757 22716 43758 22714 43758 23095 43758 23096 43759 22716 43759 23095 43759 22718 43760 22716 43760 23096 43760 23097 43761 22718 43761 23096 43761 22720 43762 22718 43762 23097 43762 23098 43763 22720 43763 23097 43763 22722 43764 22720 43764 23098 43764 23099 43765 22722 43765 23098 43765 22724 43766 22722 43766 23099 43766 22724 43767 23099 43767 23100 43767 22726 43768 22724 43768 23100 43768 23101 43769 22726 43769 23100 43769 23102 43770 22726 43770 23101 43770 22729 43771 22726 43771 23102 43771 23103 43772 22729 43772 23102 43772 22732 43773 22729 43773 23103 43773 23104 43774 22732 43774 23103 43774 22735 43775 22732 43775 23104 43775 23105 43776 22735 43776 23104 43776 22737 43777 22735 43777 23105 43777 23106 43778 22737 43778 23105 43778 22739 43779 22737 43779 23106 43779 23107 43780 22739 43780 23106 43780 22741 43781 22739 43781 23107 43781 23108 43782 22741 43782 23107 43782 22743 43783 22741 43783 23108 43783 22745 43784 22743 43784 23108 43784 23109 43785 22745 43785 23108 43785 22747 43786 22745 43786 23109 43786 23110 43787 22747 43787 23109 43787 22749 43788 22747 43788 23110 43788 23111 43789 22749 43789 23110 43789 22751 43790 22749 43790 23111 43790 23112 43791 22751 43791 23111 43791 23113 43792 22751 43792 23112 43792 22754 43793 22751 43793 23113 43793 22756 43794 22754 43794 23113 43794 23114 43795 22756 43795 23113 43795 22758 43796 22756 43796 23114 43796 22760 43797 22758 43797 23114 43797 23115 43798 22760 43798 23114 43798 23116 43799 22760 43799 23115 43799 22763 43800 22760 43800 23116 43800 22765 43801 22763 43801 23116 43801 23117 43802 22765 43802 23116 43802 23118 43803 22765 43803 23117 43803 22767 43804 22765 43804 23118 43804 23119 43805 22767 43805 23118 43805 22769 43806 22767 43806 23119 43806 23120 43807 22769 43807 23119 43807 22772 43808 22769 43808 23120 43808 23121 43809 22772 43809 23120 43809 22774 43810 22772 43810 23121 43810 23122 43811 22774 43811 23121 43811 22777 43812 22774 43812 23122 43812 23123 43813 22777 43813 23122 43813 22779 43814 22777 43814 23123 43814 23124 43815 22779 43815 23123 43815 22781 43816 22779 43816 23124 43816 23125 43817 22781 43817 23124 43817 22784 43818 22781 43818 23125 43818 23126 43819 22784 43819 23125 43819 23127 43820 22784 43820 23126 43820 22787 43821 22784 43821 23127 43821 22789 43822 22787 43822 23127 43822 23128 43823 22789 43823 23127 43823 22790 43824 22789 43824 23128 43824 23129 43825 22790 43825 23128 43825 22793 43826 22790 43826 23129 43826 22793 43827 23129 43827 23130 43827 22795 43828 22793 43828 23130 43828 23131 43829 22795 43829 23130 43829 22797 43830 22795 43830 23131 43830 23132 43831 22797 43831 23131 43831 22799 43832 22797 43832 23132 43832 22802 43833 22799 43833 23132 43833 23133 43834 22802 43834 23132 43834 23134 43835 22802 43835 23133 43835 22805 43836 22802 43836 23134 43836 22807 43837 22805 43837 23134 43837 23135 43838 22807 43838 23134 43838 22809 43839 22807 43839 23135 43839 23136 43840 22809 43840 23135 43840 22811 43841 22809 43841 23136 43841 23137 43842 22811 43842 23136 43842 22812 43843 22811 43843 23137 43843 23138 43844 22812 43844 23137 43844 22814 43845 22812 43845 23138 43845 23139 43846 22814 43846 23138 43846 23140 43847 22814 43847 23139 43847 22817 43848 22814 43848 23140 43848 23141 43849 22817 43849 23140 43849 22820 43850 22817 43850 23141 43850 23142 43851 22820 43851 23141 43851 22821 43852 22820 43852 23142 43852 23143 43853 22821 43853 23142 43853 22823 43854 22821 43854 23143 43854 22825 43855 22823 43855 23143 43855 23144 43856 22825 43856 23143 43856 22828 43857 22825 43857 23144 43857 23145 43858 22828 43858 23144 43858 22830 43859 22828 43859 23145 43859 23146 43860 22830 43860 23145 43860 22832 43861 22830 43861 23146 43861 23147 43862 22832 43862 23146 43862 22834 43863 22832 43863 23147 43863 23148 43864 22834 43864 23147 43864 22836 43865 22834 43865 23148 43865 23149 43866 22836 43866 23148 43866 23150 43867 22836 43867 23149 43867 22838 43868 22836 43868 23150 43868 22840 43869 22838 43869 23150 43869 23151 43870 22840 43870 23150 43870 22842 43871 22840 43871 23151 43871 23152 43872 22842 43872 23151 43872 22844 43873 22842 43873 23152 43873 23153 43874 22844 43874 23152 43874 22846 43875 22844 43875 23153 43875 23154 43876 22846 43876 23153 43876 23155 43877 22846 43877 23154 43877 22849 43878 22846 43878 23155 43878 23156 43879 22849 43879 23155 43879 22851 43880 22849 43880 23156 43880 22853 43881 22851 43881 23156 43881 23157 43882 22853 43882 23156 43882 23158 43883 22853 43883 23157 43883 22855 43884 22853 43884 23158 43884 23159 43885 22855 43885 23158 43885 22858 43886 22855 43886 23159 43886 23160 43887 22858 43887 23159 43887 22861 43888 22858 43888 23160 43888 23161 43889 22861 43889 23160 43889 22863 43890 22861 43890 23161 43890 23162 43891 22863 43891 23161 43891 22865 43892 22863 43892 23162 43892 23163 43893 22865 43893 23162 43893 22867 43894 22865 43894 23163 43894 23164 43895 22867 43895 23163 43895 22869 43896 22867 43896 23164 43896 23165 43897 22869 43897 23164 43897 22872 43898 22869 43898 23165 43898 23166 43899 22872 43899 23165 43899 22874 43900 22872 43900 23166 43900 23167 43901 22874 43901 23166 43901 23168 43902 22874 43902 23167 43902 22877 43903 22874 43903 23168 43903 22879 43904 22877 43904 23168 43904 22879 43905 23168 43905 23169 43905 22881 43906 22879 43906 23169 43906 23170 43907 22881 43907 23169 43907 22883 43908 22881 43908 23170 43908 23171 43909 22883 43909 23170 43909 22886 43910 22883 43910 23171 43910 23172 43911 22886 43911 23171 43911 23173 43912 22886 43912 23172 43912 22888 43913 22886 43913 23173 43913 22890 43914 22888 43914 23173 43914 23174 43915 22890 43915 23173 43915 22892 43916 22890 43916 23174 43916 23175 43917 22892 43917 23174 43917 22895 43918 22892 43918 23175 43918 23176 43919 22895 43919 23175 43919 22896 43920 22895 43920 23176 43920 23177 43921 22896 43921 23176 43921 22899 43922 22896 43922 23177 43922 23178 43923 22899 43923 23177 43923 22901 43924 22899 43924 23178 43924 23179 43925 22901 43925 23178 43925 22903 43926 22901 43926 23179 43926 23180 43927 22903 43927 23179 43927 22906 43928 22903 43928 23180 43928 23181 43929 22906 43929 23180 43929 22909 43930 22906 43930 23181 43930 22909 43931 23181 43931 23182 43931 23183 43932 22909 43932 23182 43932 22912 43933 22909 43933 23183 43933 23184 43934 22912 43934 23183 43934 23185 43935 22912 43935 23184 43935 22914 43936 22912 43936 23185 43936 23186 43937 22914 43937 23185 43937 22916 43938 22914 43938 23186 43938 23187 43939 22916 43939 23186 43939 22919 43940 22916 43940 23187 43940 23188 43941 22919 43941 23187 43941 22921 43942 22919 43942 23188 43942 23189 43943 22921 43943 23188 43943 22924 43944 22921 43944 23189 43944 23190 43945 22924 43945 23189 43945 23191 43946 22924 43946 23190 43946 22927 43947 22924 43947 23191 43947 22929 43948 22927 43948 23191 43948 23192 43949 22929 43949 23191 43949 23193 43950 22929 43950 23192 43950 22931 43951 22929 43951 23193 43951 23194 43952 22931 43952 23193 43952 22934 43953 22931 43953 23194 43953 23195 43954 22934 43954 23194 43954 22936 43955 22934 43955 23195 43955 22936 43956 23195 43956 23196 43956 22939 43957 22936 43957 23196 43957 23197 43958 22939 43958 23196 43958 22941 43959 22939 43959 23197 43959 23198 43960 22941 43960 23197 43960 22943 43961 22941 43961 23198 43961 23199 43962 22943 43962 23198 43962 22946 43963 22943 43963 23199 43963 23200 43964 22946 43964 23199 43964 22948 43965 22946 43965 23200 43965 23201 43966 22948 43966 23200 43966 22950 43967 22948 43967 23201 43967 23202 43968 22950 43968 23201 43968 22953 43969 22950 43969 23202 43969 23203 43970 22953 43970 23202 43970 22955 43971 22953 43971 23203 43971 23204 43972 22955 43972 23203 43972 22958 43973 22955 43973 23204 43973 23205 43974 22958 43974 23204 43974 23206 43975 22958 43975 23205 43975 22960 43976 22958 43976 23206 43976 23207 43977 22960 43977 23206 43977 22962 43978 22960 43978 23207 43978 22964 43979 22962 43979 23207 43979 23208 43980 22964 43980 23207 43980 22966 43981 22964 43981 23208 43981 23209 43982 22966 43982 23208 43982 22968 43983 22966 43983 23209 43983 23210 43984 22968 43984 23209 43984 22970 43985 22968 43985 23210 43985 23211 43986 22970 43986 23210 43986 22972 43987 22970 43987 23211 43987 23212 43988 22972 43988 23211 43988 22975 43989 22972 43989 23212 43989 23213 43990 22975 43990 23212 43990 22977 43991 22975 43991 23213 43991 23214 43992 22977 43992 23213 43992 23215 43993 22977 43993 23214 43993 22980 43994 22977 43994 23215 43994 23216 43995 22980 43995 23215 43995 22982 43996 22980 43996 23216 43996 23217 43997 22982 43997 23216 43997 22985 43998 22982 43998 23217 43998 23218 43999 22985 43999 23217 43999 22987 44000 22985 44000 23218 44000 23219 44001 22987 44001 23218 44001 22988 44002 22987 44002 23219 44002 23220 44003 22988 44003 23219 44003 22989 44004 22988 44004 23220 44004 22990 44005 22989 44005 23220 44005 23221 44006 22990 44006 23220 44006 22991 44007 22990 44007 23221 44007 23222 44008 22991 44008 23221 44008 22992 44009 22991 44009 23222 44009 23223 44010 22992 44010 23222 44010 22455 44011 22992 44011 23223 44011 23224 44012 22455 44012 23223 44012 22458 44013 22455 44013 23224 44013 23226 44014 22995 44014 22994 44014 23226 44015 22996 44015 22995 44015 23227 44016 22996 44016 23226 44016 23227 44017 22997 44017 22996 44017 23227 44018 22998 44018 22997 44018 23225 44019 22998 44019 23227 44019 23228 44020 22999 44020 23225 44020 23225 44021 22999 44021 22998 44021 23228 44022 23000 44022 22999 44022 22473 44023 23000 44023 23228 44023 22473 44024 23001 44024 23000 44024 23229 44025 23001 44025 22473 44025 23229 44026 23002 44026 23001 44026 22475 44027 23002 44027 23229 44027 22476 44028 23002 44028 22475 44028 22476 44029 23003 44029 23002 44029 22479 44030 23003 44030 22476 44030 22479 44031 23004 44031 23003 44031 22480 44032 23004 44032 22479 44032 22482 44033 23004 44033 22480 44033 22482 44034 23005 44034 23004 44034 22484 44035 23006 44035 22482 44035 22482 44036 23006 44036 23005 44036 23230 44037 23006 44037 22484 44037 23230 44038 23007 44038 23006 44038 23231 44039 23007 44039 23230 44039 23231 44040 23008 44040 23007 44040 22490 44041 23008 44041 23231 44041 22490 44042 23009 44042 23008 44042 22491 44043 23009 44043 22490 44043 22493 44044 23009 44044 22491 44044 22493 44045 23010 44045 23009 44045 22494 44046 23010 44046 22493 44046 22494 44047 23011 44047 23010 44047 22496 44048 23011 44048 22494 44048 22496 44049 23012 44049 23011 44049 22498 44050 23012 44050 22496 44050 22498 44051 23013 44051 23012 44051 22500 44052 23013 44052 22498 44052 22501 44053 23013 44053 22500 44053 22501 44054 23014 44054 23013 44054 22503 44055 23014 44055 22501 44055 22503 44056 23015 44056 23014 44056 22505 44057 23015 44057 22503 44057 22507 44058 23015 44058 22505 44058 22507 44059 23016 44059 23015 44059 22508 44060 23016 44060 22507 44060 22510 44061 23016 44061 22508 44061 22510 44062 23017 44062 23016 44062 22512 44063 23017 44063 22510 44063 22512 44064 23018 44064 23017 44064 22514 44065 23018 44065 22512 44065 22515 44066 23019 44066 22514 44066 22514 44067 23019 44067 23018 44067 22517 44068 23019 44068 22515 44068 22517 44069 23020 44069 23019 44069 22519 44070 23020 44070 22517 44070 22519 44071 23021 44071 23020 44071 22521 44072 23021 44072 22519 44072 22521 44073 23022 44073 23021 44073 23232 44074 23022 44074 22521 44074 23232 44075 23023 44075 23022 44075 22523 44076 23023 44076 23232 44076 22523 44077 23024 44077 23023 44077 22525 44078 23024 44078 22523 44078 22527 44079 23025 44079 22525 44079 22525 44080 23025 44080 23024 44080 22529 44081 23025 44081 22527 44081 22529 44082 23026 44082 23025 44082 22530 44083 23026 44083 22529 44083 22530 44084 23027 44084 23026 44084 23233 44085 23027 44085 22530 44085 23233 44086 23028 44086 23027 44086 22536 44087 23028 44087 23233 44087 22536 44088 23029 44088 23028 44088 22538 44089 23029 44089 22536 44089 23234 44090 23030 44090 22538 44090 22538 44091 23030 44091 23029 44091 23234 44092 23031 44092 23030 44092 23235 44093 23031 44093 23234 44093 22542 44094 23031 44094 23235 44094 22544 44095 23032 44095 22542 44095 22542 44096 23032 44096 23031 44096 22546 44097 23032 44097 22544 44097 22546 44098 23033 44098 23032 44098 22548 44099 23033 44099 22546 44099 22548 44100 23034 44100 23033 44100 22550 44101 23034 44101 22548 44101 22550 44102 23035 44102 23034 44102 22552 44103 23035 44103 22550 44103 22552 44104 23036 44104 23035 44104 22554 44105 23036 44105 22552 44105 22556 44106 23037 44106 22554 44106 22554 44107 23037 44107 23036 44107 22556 44108 23038 44108 23037 44108 22558 44109 23038 44109 22556 44109 22559 44110 23038 44110 22558 44110 22559 44111 23039 44111 23038 44111 22561 44112 23039 44112 22559 44112 22561 44113 23040 44113 23039 44113 22563 44114 23040 44114 22561 44114 22563 44115 23041 44115 23040 44115 22565 44116 23041 44116 22563 44116 23236 44117 23041 44117 22565 44117 23236 44118 23042 44118 23041 44118 23237 44119 23042 44119 23236 44119 23237 44120 23043 44120 23042 44120 23238 44121 23043 44121 23237 44121 23238 44122 23044 44122 23043 44122 22572 44123 23044 44123 23238 44123 22572 44124 23045 44124 23044 44124 22574 44125 23045 44125 22572 44125 22574 44126 23046 44126 23045 44126 23239 44127 23046 44127 22574 44127 23239 44128 23047 44128 23046 44128 22580 44129 23047 44129 23239 44129 22580 44130 23048 44130 23047 44130 23240 44131 23048 44131 22580 44131 23240 44132 23049 44132 23048 44132 23241 44133 23049 44133 23240 44133 23241 44134 23050 44134 23049 44134 22584 44135 23050 44135 23241 44135 22584 44136 23051 44136 23050 44136 22586 44137 23051 44137 22584 44137 22586 44138 23052 44138 23051 44138 23242 44139 23052 44139 22586 44139 23242 44140 23053 44140 23052 44140 22589 44141 23053 44141 23242 44141 23243 44142 23054 44142 22589 44142 22589 44143 23054 44143 23053 44143 22593 44144 23054 44144 23243 44144 22593 44145 23055 44145 23054 44145 22595 44146 23055 44146 22593 44146 22595 44147 23056 44147 23055 44147 22597 44148 23056 44148 22595 44148 22597 44149 23057 44149 23056 44149 22599 44150 23057 44150 22597 44150 22599 44151 23058 44151 23057 44151 23244 44152 23058 44152 22599 44152 23244 44153 23059 44153 23058 44153 22603 44154 23059 44154 23244 44154 22603 44155 23060 44155 23059 44155 22605 44156 23060 44156 22603 44156 22605 44157 23061 44157 23060 44157 22607 44158 23061 44158 22605 44158 22607 44159 23062 44159 23061 44159 22608 44160 23062 44160 22607 44160 23245 44161 23063 44161 22608 44161 22608 44162 23063 44162 23062 44162 23246 44163 23063 44163 23245 44163 23246 44164 23064 44164 23063 44164 22613 44165 23064 44165 23246 44165 22613 44166 23065 44166 23064 44166 22615 44167 23065 44167 22613 44167 22615 44168 23066 44168 23065 44168 23247 44169 23066 44169 22615 44169 23248 44170 23066 44170 23247 44170 23248 44171 23067 44171 23066 44171 22618 44172 23067 44172 23248 44172 22618 44173 23068 44173 23067 44173 22620 44174 23068 44174 22618 44174 22622 44175 23068 44175 22620 44175 22622 44176 23069 44176 23068 44176 22624 44177 23069 44177 22622 44177 22624 44178 23070 44178 23069 44178 22625 44179 23070 44179 22624 44179 22627 44180 23070 44180 22625 44180 22627 44181 23071 44181 23070 44181 22628 44182 23071 44182 22627 44182 22628 44183 23072 44183 23071 44183 22630 44184 23072 44184 22628 44184 22630 44185 23073 44185 23072 44185 22632 44186 23073 44186 22630 44186 22633 44187 23073 44187 22632 44187 22633 44188 23074 44188 23073 44188 22635 44189 23074 44189 22633 44189 22637 44190 23075 44190 22635 44190 22635 44191 23075 44191 23074 44191 22637 44192 23076 44192 23075 44192 22638 44193 23076 44193 22637 44193 22640 44194 23076 44194 22638 44194 22642 44195 23076 44195 22640 44195 22642 44196 23077 44196 23076 44196 22644 44197 23077 44197 22642 44197 22644 44198 23078 44198 23077 44198 22646 44199 23078 44199 22644 44199 22646 44200 23079 44200 23078 44200 23249 44201 23079 44201 22646 44201 23249 44202 23080 44202 23079 44202 23249 44203 23081 44203 23080 44203 22650 44204 23081 44204 23249 44204 22650 44205 23082 44205 23081 44205 22652 44206 23082 44206 22650 44206 23250 44207 23082 44207 22652 44207 23250 44208 23083 44208 23082 44208 23251 44209 23083 44209 23250 44209 23251 44210 23084 44210 23083 44210 22658 44211 23084 44211 23251 44211 22658 44212 23085 44212 23084 44212 22660 44213 23085 44213 22658 44213 22662 44214 23085 44214 22660 44214 22662 44215 23086 44215 23085 44215 23252 44216 23086 44216 22662 44216 23252 44217 23087 44217 23086 44217 23253 44218 23087 44218 23252 44218 23253 44219 23088 44219 23087 44219 23254 44220 23088 44220 23253 44220 23254 44221 23089 44221 23088 44221 22670 44222 23089 44222 23254 44222 22670 44223 23090 44223 23089 44223 22671 44224 23090 44224 22670 44224 22673 44225 23090 44225 22671 44225 22673 44226 23091 44226 23090 44226 22675 44227 23091 44227 22673 44227 22675 44228 23092 44228 23091 44228 22677 44229 23092 44229 22675 44229 22679 44230 23092 44230 22677 44230 22679 44231 23093 44231 23092 44231 22681 44232 23093 44232 22679 44232 22681 44233 23094 44233 23093 44233 22683 44234 23094 44234 22681 44234 22683 44235 23095 44235 23094 44235 22684 44236 23095 44236 22683 44236 22684 44237 23096 44237 23095 44237 23255 44238 23096 44238 22684 44238 23255 44239 23097 44239 23096 44239 23256 44240 23097 44240 23255 44240 23256 44241 23098 44241 23097 44241 22690 44242 23098 44242 23256 44242 22692 44243 23098 44243 22690 44243 22692 44244 23099 44244 23098 44244 22693 44245 23099 44245 22692 44245 22693 44246 23100 44246 23099 44246 22695 44247 23100 44247 22693 44247 22695 44248 23101 44248 23100 44248 22697 44249 23101 44249 22695 44249 22697 44250 23102 44250 23101 44250 23257 44251 23102 44251 22697 44251 23257 44252 23103 44252 23102 44252 22701 44253 23103 44253 23257 44253 22701 44254 23104 44254 23103 44254 22703 44255 23104 44255 22701 44255 22703 44256 23105 44256 23104 44256 23258 44257 23105 44257 22703 44257 23258 44258 23106 44258 23105 44258 22706 44259 23106 44259 23258 44259 22708 44260 23106 44260 22706 44260 22708 44261 23107 44261 23106 44261 22710 44262 23107 44262 22708 44262 22712 44263 23107 44263 22710 44263 22712 44264 23108 44264 23107 44264 23259 44265 23108 44265 22712 44265 23259 44266 23109 44266 23108 44266 23260 44267 23109 44267 23259 44267 23260 44268 23110 44268 23109 44268 23261 44269 23110 44269 23260 44269 23261 44270 23111 44270 23110 44270 22719 44271 23111 44271 23261 44271 22719 44272 23112 44272 23111 44272 22721 44273 23112 44273 22719 44273 22721 44274 23113 44274 23112 44274 22723 44275 23113 44275 22721 44275 22725 44276 23113 44276 22723 44276 22727 44277 23113 44277 22725 44277 22727 44278 23114 44278 23113 44278 22728 44279 23114 44279 22727 44279 22728 44280 23115 44280 23114 44280 22730 44281 23115 44281 22728 44281 22731 44282 23115 44282 22730 44282 22731 44283 23116 44283 23115 44283 22733 44284 23116 44284 22731 44284 22733 44285 23117 44285 23116 44285 22734 44286 23117 44286 22733 44286 23262 44287 23117 44287 22734 44287 23262 44288 23118 44288 23117 44288 23263 44289 23118 44289 23262 44289 23263 44290 23119 44290 23118 44290 23264 44291 23119 44291 23263 44291 23264 44292 23120 44292 23119 44292 22742 44293 23120 44293 23264 44293 22742 44294 23121 44294 23120 44294 22744 44295 23121 44295 22742 44295 22744 44296 23122 44296 23121 44296 22746 44297 23122 44297 22744 44297 22746 44298 23123 44298 23122 44298 23265 44299 23123 44299 22746 44299 23265 44300 23124 44300 23123 44300 22750 44301 23124 44301 23265 44301 22750 44302 23125 44302 23124 44302 22752 44303 23125 44303 22750 44303 22752 44304 23126 44304 23125 44304 22753 44305 23126 44305 22752 44305 22753 44306 23127 44306 23126 44306 22757 44307 23127 44307 22753 44307 22757 44308 23128 44308 23127 44308 22759 44309 23128 44309 22757 44309 22759 44310 23129 44310 23128 44310 22761 44311 23129 44311 22759 44311 22762 44312 23129 44312 22761 44312 22762 44313 23130 44313 23129 44313 22764 44314 23130 44314 22762 44314 23266 44315 23130 44315 22764 44315 23266 44316 23131 44316 23130 44316 23267 44317 23131 44317 23266 44317 23267 44318 23132 44318 23131 44318 22768 44319 23132 44319 23267 44319 22768 44320 23133 44320 23132 44320 22770 44321 23133 44321 22768 44321 22770 44322 23134 44322 23133 44322 22771 44323 23134 44323 22770 44323 23268 44324 23134 44324 22771 44324 23268 44325 23135 44325 23134 44325 23268 44326 23136 44326 23135 44326 22776 44327 23136 44327 23268 44327 22778 44328 23136 44328 22776 44328 22778 44329 23137 44329 23136 44329 22780 44330 23137 44330 22778 44330 22780 44331 23138 44331 23137 44331 22782 44332 23138 44332 22780 44332 22782 44333 23139 44333 23138 44333 22783 44334 23139 44334 22782 44334 22783 44335 23140 44335 23139 44335 23269 44336 23140 44336 22783 44336 23269 44337 23141 44337 23140 44337 22788 44338 23141 44338 23269 44338 22788 44339 23142 44339 23141 44339 22791 44340 23142 44340 22788 44340 23270 44341 23142 44341 22791 44341 23270 44342 23143 44342 23142 44342 22794 44343 23143 44343 23270 44343 22794 44344 23144 44344 23143 44344 22796 44345 23144 44345 22794 44345 22796 44346 23145 44346 23144 44346 22798 44347 23145 44347 22796 44347 22800 44348 23145 44348 22798 44348 22800 44349 23146 44349 23145 44349 22801 44350 23146 44350 22800 44350 22801 44351 23147 44351 23146 44351 22803 44352 23147 44352 22801 44352 22803 44353 23148 44353 23147 44353 22804 44354 23148 44354 22803 44354 22804 44355 23149 44355 23148 44355 22806 44356 23149 44356 22804 44356 22806 44357 23150 44357 23149 44357 22808 44358 23150 44358 22806 44358 22808 44359 23151 44359 23150 44359 23271 44360 23151 44360 22808 44360 23271 44361 23152 44361 23151 44361 22813 44362 23152 44362 23271 44362 22813 44363 23153 44363 23152 44363 22815 44364 23153 44364 22813 44364 22815 44365 23154 44365 23153 44365 23272 44366 23154 44366 22815 44366 23272 44367 23155 44367 23154 44367 22818 44368 23155 44368 23272 44368 23273 44369 23155 44369 22818 44369 23273 44370 23156 44370 23155 44370 23274 44371 23156 44371 23273 44371 23274 44372 23157 44372 23156 44372 22822 44373 23157 44373 23274 44373 22822 44374 23158 44374 23157 44374 22824 44375 23158 44375 22822 44375 22826 44376 23158 44376 22824 44376 22826 44377 23159 44377 23158 44377 22827 44378 23159 44378 22826 44378 22827 44379 23160 44379 23159 44379 22829 44380 23160 44380 22827 44380 22829 44381 23161 44381 23160 44381 22831 44382 23161 44382 22829 44382 22831 44383 23162 44383 23161 44383 22833 44384 23162 44384 22831 44384 23275 44385 23162 44385 22833 44385 23275 44386 23163 44386 23162 44386 23276 44387 23163 44387 23275 44387 23276 44388 23164 44388 23163 44388 22839 44389 23164 44389 23276 44389 22839 44390 23165 44390 23164 44390 22841 44391 23165 44391 22839 44391 22841 44392 23166 44392 23165 44392 22843 44393 23166 44393 22841 44393 22843 44394 23167 44394 23166 44394 22845 44395 23167 44395 22843 44395 22845 44396 23168 44396 23167 44396 22847 44397 23168 44397 22845 44397 23277 44398 23168 44398 22847 44398 23277 44399 23169 44399 23168 44399 22850 44400 23169 44400 23277 44400 22850 44401 23170 44401 23169 44401 22852 44402 23170 44402 22850 44402 22852 44403 23171 44403 23170 44403 22854 44404 23171 44404 22852 44404 22854 44405 23172 44405 23171 44405 22856 44406 23172 44406 22854 44406 22856 44407 23173 44407 23172 44407 22859 44408 23173 44408 22856 44408 22859 44409 23174 44409 23173 44409 22860 44410 23174 44410 22859 44410 22862 44411 23174 44411 22860 44411 22862 44412 23175 44412 23174 44412 22864 44413 23175 44413 22862 44413 22864 44414 23176 44414 23175 44414 22866 44415 23176 44415 22864 44415 22866 44416 23177 44416 23176 44416 23278 44417 23177 44417 22866 44417 23278 44418 23178 44418 23177 44418 23279 44419 23178 44419 23278 44419 23279 44420 23179 44420 23178 44420 23280 44421 23179 44421 23279 44421 23280 44422 23180 44422 23179 44422 23281 44423 23180 44423 23280 44423 23281 44424 23181 44424 23180 44424 23282 44425 23181 44425 23281 44425 23282 44426 23182 44426 23181 44426 22878 44427 23182 44427 23282 44427 22878 44428 23183 44428 23182 44428 22880 44429 23183 44429 22878 44429 22880 44430 23184 44430 23183 44430 22882 44431 23184 44431 22880 44431 22882 44432 23185 44432 23184 44432 22884 44433 23185 44433 22882 44433 22884 44434 23186 44434 23185 44434 22885 44435 23186 44435 22884 44435 22885 44436 23187 44436 23186 44436 22887 44437 23187 44437 22885 44437 22887 44438 23188 44438 23187 44438 22889 44439 23188 44439 22887 44439 22889 44440 23189 44440 23188 44440 22891 44441 23189 44441 22889 44441 22891 44442 23190 44442 23189 44442 22893 44443 23190 44443 22891 44443 22894 44444 23190 44444 22893 44444 22894 44445 23191 44445 23190 44445 22897 44446 23191 44446 22894 44446 22897 44447 23192 44447 23191 44447 22898 44448 23192 44448 22897 44448 22898 44449 23193 44449 23192 44449 22900 44450 23193 44450 22898 44450 22902 44451 23193 44451 22900 44451 22902 44452 23194 44452 23193 44452 22904 44453 23194 44453 22902 44453 22904 44454 23195 44454 23194 44454 22905 44455 23195 44455 22904 44455 22905 44456 23196 44456 23195 44456 22907 44457 23196 44457 22905 44457 22907 44458 23197 44458 23196 44458 22908 44459 23197 44459 22907 44459 22908 44460 23198 44460 23197 44460 23283 44461 23198 44461 22908 44461 23283 44462 23199 44462 23198 44462 22913 44463 23199 44463 23283 44463 23284 44464 23200 44464 22913 44464 22913 44465 23200 44465 23199 44465 22917 44466 23200 44466 23284 44466 22917 44467 23201 44467 23200 44467 23285 44468 23201 44468 22917 44468 23285 44469 23202 44469 23201 44469 22920 44470 23202 44470 23285 44470 22922 44471 23202 44471 22920 44471 22923 44472 23203 44472 22922 44472 22922 44473 23203 44473 23202 44473 22925 44474 23203 44474 22923 44474 22925 44475 23204 44475 23203 44475 22926 44476 23204 44476 22925 44476 22926 44477 23205 44477 23204 44477 22928 44478 23205 44478 22926 44478 22928 44479 23206 44479 23205 44479 22930 44480 23206 44480 22928 44480 22930 44481 23207 44481 23206 44481 22932 44482 23207 44482 22930 44482 22933 44483 23207 44483 22932 44483 22933 44484 23208 44484 23207 44484 23286 44485 23208 44485 22933 44485 23286 44486 23209 44486 23208 44486 23286 44487 23210 44487 23209 44487 22938 44488 23210 44488 23286 44488 22938 44489 23211 44489 23210 44489 22940 44490 23211 44490 22938 44490 22942 44491 23211 44491 22940 44491 22942 44492 23212 44492 23211 44492 22944 44493 23212 44493 22942 44493 22944 44494 23213 44494 23212 44494 23287 44495 23213 44495 22944 44495 23287 44496 23214 44496 23213 44496 22949 44497 23214 44497 23287 44497 22949 44498 23215 44498 23214 44498 23288 44499 23215 44499 22949 44499 23288 44500 23216 44500 23215 44500 23289 44501 23216 44501 23288 44501 23289 44502 23217 44502 23216 44502 22952 44503 23217 44503 23289 44503 22952 44504 23218 44504 23217 44504 22954 44505 23218 44505 22952 44505 22954 44506 23219 44506 23218 44506 22956 44507 23219 44507 22954 44507 22957 44508 23219 44508 22956 44508 22957 44509 23220 44509 23219 44509 22959 44510 23220 44510 22957 44510 22961 44511 23220 44511 22959 44511 22961 44512 23221 44512 23220 44512 22963 44513 23221 44513 22961 44513 23290 44514 23221 44514 22963 44514 23290 44515 23222 44515 23221 44515 23291 44516 23222 44516 23290 44516 23291 44517 23223 44517 23222 44517 22967 44518 23223 44518 23291 44518 22967 44519 23224 44519 23223 44519 22969 44520 23224 44520 22967 44520 22971 44521 23224 44521 22969 44521 22973 44522 22458 44522 22971 44522 22971 44523 22458 44523 23224 44523 22973 44524 22460 44524 22458 44524 23292 44525 22460 44525 22973 44525 23292 44526 22465 44526 22460 44526 22976 44527 22465 44527 23292 44527 22978 44528 22465 44528 22976 44528 22978 44529 22468 44529 22465 44529 22979 44530 22468 44530 22978 44530 22981 44531 22468 44531 22979 44531 22981 44532 22470 44532 22468 44532 22983 44533 22470 44533 22981 44533 22983 44534 22472 44534 22470 44534 23229 44535 22473 44535 22474 44535 22475 44536 23229 44536 22474 44536 22486 44537 23230 44537 22484 44537 23231 44538 23230 44538 22486 44538 22488 44539 23231 44539 22486 44539 22490 44540 23231 44540 22488 44540 22523 44541 23232 44541 22521 44541 23233 44542 22530 44542 22532 44542 22534 44543 23233 44543 22532 44543 22536 44544 23233 44544 22534 44544 22540 44545 23234 44545 22538 44545 23235 44546 23234 44546 22540 44546 22542 44547 23235 44547 22540 44547 22566 44548 23236 44548 22565 44548 23237 44549 23236 44549 22566 44549 22569 44550 23237 44550 22566 44550 23238 44551 23237 44551 22569 44551 22571 44552 23238 44552 22569 44552 22572 44553 23238 44553 22571 44553 23239 44554 22574 44554 22576 44554 22578 44555 23239 44555 22576 44555 22580 44556 23239 44556 22578 44556 22582 44557 23240 44557 22580 44557 23241 44558 23240 44558 22582 44558 22584 44559 23241 44559 22582 44559 23242 44560 22586 44560 22588 44560 22589 44561 23242 44561 22588 44561 23243 44562 22589 44562 22591 44562 22593 44563 23243 44563 22591 44563 22601 44564 23244 44564 22599 44564 22603 44565 23244 44565 22601 44565 22610 44566 23245 44566 22608 44566 23246 44567 23245 44567 22610 44567 22613 44568 23246 44568 22610 44568 22616 44569 23247 44569 22615 44569 23248 44570 23247 44570 22616 44570 22618 44571 23248 44571 22616 44571 23249 44572 22646 44572 22648 44572 22650 44573 23249 44573 22648 44573 23250 44574 22652 44574 22653 44574 22656 44575 23250 44575 22653 44575 23251 44576 23250 44576 22656 44576 22658 44577 23251 44577 22656 44577 23252 44578 22662 44578 22663 44578 22665 44579 23252 44579 22663 44579 23253 44580 23252 44580 22665 44580 22667 44581 23253 44581 22665 44581 23254 44582 23253 44582 22667 44582 22670 44583 23254 44583 22667 44583 23255 44584 22684 44584 22686 44584 23256 44585 23255 44585 22686 44585 22688 44586 23256 44586 22686 44586 22690 44587 23256 44587 22688 44587 22699 44588 23257 44588 22697 44588 22701 44589 23257 44589 22699 44589 22704 44590 23258 44590 22703 44590 22706 44591 23258 44591 22704 44591 23259 44592 22712 44592 22713 44592 22715 44593 23259 44593 22713 44593 23260 44594 23259 44594 22715 44594 22717 44595 23260 44595 22715 44595 23261 44596 23260 44596 22717 44596 22719 44597 23261 44597 22717 44597 22736 44598 23262 44598 22734 44598 23263 44599 23262 44599 22736 44599 22738 44600 23263 44600 22736 44600 23264 44601 23263 44601 22738 44601 22740 44602 23264 44602 22738 44602 22742 44603 23264 44603 22740 44603 22748 44604 23265 44604 22746 44604 22750 44605 23265 44605 22748 44605 22757 44606 22753 44606 22755 44606 22766 44607 23266 44607 22764 44607 23267 44608 23266 44608 22766 44608 22768 44609 23267 44609 22766 44609 23268 44610 22771 44610 22773 44610 22775 44611 23268 44611 22773 44611 22776 44612 23268 44612 22775 44612 23269 44613 22783 44613 22785 44613 22786 44614 23269 44614 22785 44614 22788 44615 23269 44615 22786 44615 22792 44616 23270 44616 22791 44616 22794 44617 23270 44617 22792 44617 23271 44618 22808 44618 22810 44618 22813 44619 23271 44619 22810 44619 22816 44620 23272 44620 22815 44620 22818 44621 23272 44621 22816 44621 22819 44622 23273 44622 22818 44622 23274 44623 23273 44623 22819 44623 22822 44624 23274 44624 22819 44624 23275 44625 22833 44625 22835 44625 23276 44626 23275 44626 22835 44626 22837 44627 23276 44627 22835 44627 22839 44628 23276 44628 22837 44628 22848 44629 23277 44629 22847 44629 22850 44630 23277 44630 22848 44630 22859 44631 22856 44631 22857 44631 23278 44632 22866 44632 22868 44632 22870 44633 23278 44633 22868 44633 23279 44634 23278 44634 22870 44634 22871 44635 23279 44635 22870 44635 23280 44636 23279 44636 22871 44636 22873 44637 23280 44637 22871 44637 23281 44638 23280 44638 22873 44638 22875 44639 23281 44639 22873 44639 23282 44640 23281 44640 22875 44640 22876 44641 23282 44641 22875 44641 22878 44642 23282 44642 22876 44642 23283 44643 22908 44643 22910 44643 22911 44644 23283 44644 22910 44644 22913 44645 23283 44645 22911 44645 22915 44646 23284 44646 22913 44646 22917 44647 23284 44647 22915 44647 22918 44648 23285 44648 22917 44648 22920 44649 23285 44649 22918 44649 23286 44650 22933 44650 22935 44650 22937 44651 23286 44651 22935 44651 22938 44652 23286 44652 22937 44652 23287 44653 22944 44653 22945 44653 22947 44654 23287 44654 22945 44654 22949 44655 23287 44655 22947 44655 22951 44656 23288 44656 22949 44656 23289 44657 23288 44657 22951 44657 22952 44658 23289 44658 22951 44658 22965 44659 23290 44659 22963 44659 23291 44660 23290 44660 22965 44660 22967 44661 23291 44661 22965 44661 23292 44662 22973 44662 22974 44662 22976 44663 23292 44663 22974 44663 22472 44664 22983 44664 22984 44664 23294 44665 22472 44665 22984 44665 22986 44666 23294 44666 22984 44666 23293 44667 23350 44667 23351 44667 23294 44668 22986 44668 23293 44668 23294 44669 23293 44669 23351 44669 23294 44670 23351 44670 23295 44670 23296 44671 23294 44671 23295 44671 23298 44672 23296 44672 23295 44672 22472 44673 23294 44673 23296 44673 23295 44674 23351 44674 23297 44674 23298 44675 23295 44675 23297 44675 23299 44676 23296 44676 23298 44676 23299 44677 22472 44677 23296 44677 23299 44678 23298 44678 23297 44678 22471 44679 22472 44679 23299 44679 23300 44680 23299 44680 23297 44680 22471 44681 23299 44681 23300 44681 23302 44682 23300 44682 23297 44682 23302 44683 23297 44683 23301 44683 22471 44684 23300 44684 23302 44684 22470 44685 22471 44685 23302 44685 23303 44686 23302 44686 23301 44686 23305 44687 23302 44687 23303 44687 22470 44688 23302 44688 23305 44688 23303 44689 23301 44689 23304 44689 23305 44690 22469 44690 22470 44690 23306 44691 23303 44691 23304 44691 23306 44692 23305 44692 23303 44692 22469 44693 23305 44693 23306 44693 23308 44694 23306 44694 23304 44694 23309 44695 23306 44695 23308 44695 23308 44696 23304 44696 23307 44696 23309 44697 22469 44697 23306 44697 23309 44698 22467 44698 22469 44698 23307 44699 23309 44699 23308 44699 23311 44700 23309 44700 23307 44700 22467 44701 23309 44701 23311 44701 23312 44702 23307 44702 23310 44702 23311 44703 22464 44703 22467 44703 23312 44704 23311 44704 23307 44704 22464 44705 23311 44705 23313 44705 23313 44706 23311 44706 23312 44706 23314 44707 23312 44707 23310 44707 23314 44708 23313 44708 23312 44708 23315 44709 23313 44709 23314 44709 23315 44710 22464 44710 23313 44710 23316 44711 23314 44711 23310 44711 23317 44712 23315 44712 23314 44712 23316 44713 23310 44713 23318 44713 23317 44714 23314 44714 23316 44714 22461 44715 22464 44715 23315 44715 23317 44716 22461 44716 23315 44716 23319 44717 23317 44717 23316 44717 23319 44718 23316 44718 23318 44718 23319 44719 22461 44719 23317 44719 23320 44720 23319 44720 23318 44720 23321 44721 23319 44721 23320 44721 23321 44722 22461 44722 23319 44722 23323 44723 23320 44723 23318 44723 23322 44724 23321 44724 23320 44724 23324 44725 23321 44725 23322 44725 23325 44726 23322 44726 23320 44726 23325 44727 23320 44727 23323 44727 23326 44728 23322 44728 23325 44728 23327 44729 23323 44729 23318 44729 23326 44730 23324 44730 23322 44730 23328 44731 23325 44731 23323 44731 23329 44732 23326 44732 23325 44732 23328 44733 23323 44733 23327 44733 23329 44734 23325 44734 23328 44734 23330 44735 23328 44735 23327 44735 23331 44736 23329 44736 23328 44736 23331 44737 23328 44737 23330 44737 23334 44738 23329 44738 23331 44738 23332 44739 23331 44739 23330 44739 23333 44740 23330 44740 23327 44740 23332 44741 23334 44741 23331 44741 23333 44742 23332 44742 23330 44742 23333 44743 23327 44743 23335 44743 23336 44744 23332 44744 23333 44744 23336 44745 23334 44745 23332 44745 23337 44746 23336 44746 23333 44746 23335 44747 23337 44747 23333 44747 22457 44748 23334 44748 23336 44748 23338 44749 23336 44749 23337 44749 23338 44750 22457 44750 23336 44750 23340 44751 23338 44751 23337 44751 23338 44752 22459 44752 22457 44752 23341 44753 23337 44753 23335 44753 23339 44754 23341 44754 23335 44754 23341 44755 23340 44755 23337 44755 23340 44756 22459 44756 23338 44756 23342 44757 23341 44757 23339 44757 23343 44758 23340 44758 23341 44758 23343 44759 23341 44759 23342 44759 23340 44760 22463 44760 22459 44760 22463 44761 23340 44761 23343 44761 23344 44762 23343 44762 23342 44762 22462 44763 22463 44763 23343 44763 23345 44764 23342 44764 23339 44764 23344 44765 23342 44765 23345 44765 23346 44766 23345 44766 23339 44766 23344 44767 22462 44767 23343 44767 23347 44768 23344 44768 23345 44768 22466 44769 22462 44769 23344 44769 23348 44770 23345 44770 23346 44770 23347 44771 22466 44771 23344 44771 23349 44772 23345 44772 23348 44772 23349 44773 23347 44773 23345 44773 23350 44774 23348 44774 23346 44774 22466 44775 23347 44775 23349 44775 23352 44776 23349 44776 23348 44776 23350 44777 23346 44777 23351 44777 23352 44778 23348 44778 23350 44778 23353 44779 22466 44779 23349 44779 23352 44780 23353 44780 23349 44780 23352 44781 23350 44781 23293 44781 23352 44782 23293 44782 22986 44782 22986 44783 23353 44783 23352 44783 23307 44784 23335 44784 23327 44784 23307 44785 23304 44785 23301 44785 23307 44786 23346 44786 23339 44786 23307 44787 23297 44787 23351 44787 23307 44788 23339 44788 23335 44788 23307 44789 23351 44789 23346 44789 23307 44790 23301 44790 23297 44790 23310 44791 23307 44791 23327 44791 23310 44792 23327 44792 23318 44792 23355 44793 23354 44793 23356 44793 23357 44794 23436 44794 23355 44794 23357 44795 23355 44795 23356 44795 23357 44796 23356 44796 23358 44796 23359 44797 23436 44797 23357 44797 23360 44798 23357 44798 23358 44798 23360 44799 23358 44799 23361 44799 23359 44800 23357 44800 23360 44800 23362 44801 23360 44801 23361 44801 23363 44802 23359 44802 23360 44802 23364 44803 23360 44803 23362 44803 23364 44804 23363 44804 23360 44804 23365 44805 23364 44805 23362 44805 23368 44806 23365 44806 23366 44806 23369 44807 23363 44807 23364 44807 23368 44808 23364 44808 23365 44808 23368 44809 23366 44809 23367 44809 23369 44810 23364 44810 23368 44810 23370 44811 23368 44811 23367 44811 23371 44812 23370 44812 23367 44812 23369 44813 23368 44813 23370 44813 23373 44814 23369 44814 23370 44814 23373 44815 23370 44815 23371 44815 23373 44816 23371 44816 23372 44816 23375 44817 23372 44817 23374 44817 23375 44818 23373 44818 23372 44818 23376 44819 23373 44819 23375 44819 23376 44820 23369 44820 23373 44820 23377 44821 23375 44821 23374 44821 23378 44822 23376 44822 23375 44822 23380 44823 23375 44823 23377 44823 23380 44824 23378 44824 23375 44824 23380 44825 23377 44825 23379 44825 23381 44826 23378 44826 23380 44826 23382 44827 23380 44827 23379 44827 23381 44828 23380 44828 23382 44828 23386 44829 23378 44829 23381 44829 23384 44830 23382 44830 23383 44830 23381 44831 23382 44831 23384 44831 23386 44832 23381 44832 23384 44832 23384 44833 23383 44833 23385 44833 23387 44834 23386 44834 23384 44834 23388 44835 23384 44835 23385 44835 23388 44836 23385 44836 23389 44836 23388 44837 23387 44837 23384 44837 23390 44838 23388 44838 23389 44838 23391 44839 23390 44839 23389 44839 23392 44840 23387 44840 23388 44840 23392 44841 23388 44841 23390 44841 23393 44842 23390 44842 23391 44842 23396 44843 23387 44843 23392 44843 23394 44844 23390 44844 23393 44844 23394 44845 23392 44845 23390 44845 23396 44846 23392 44846 23394 44846 23394 44847 23393 44847 23395 44847 23397 44848 23394 44848 23395 44848 23396 44849 23394 44849 23397 44849 23399 44850 23396 44850 23397 44850 23397 44851 23395 44851 23398 44851 23399 44852 23397 44852 23398 44852 23401 44853 23399 44853 23398 44853 23401 44854 23398 44854 23400 44854 23402 44855 23401 44855 23400 44855 23403 44856 23399 44856 23401 44856 23403 44857 23401 44857 23404 44857 23404 44858 23401 44858 23402 44858 23405 44859 23404 44859 23402 44859 23406 44860 23404 44860 23405 44860 23407 44861 23403 44861 23404 44861 23406 44862 23407 44862 23404 44862 23408 44863 23406 44863 23405 44863 23406 44864 23408 44864 23409 44864 23410 44865 23406 44865 23409 44865 23411 44866 23406 44866 23410 44866 23411 44867 23407 44867 23406 44867 23412 44868 23410 44868 23409 44868 23411 44869 23415 44869 23407 44869 23413 44870 23410 44870 23412 44870 23413 44871 23411 44871 23410 44871 23413 44872 23412 44872 23414 44872 23415 44873 23411 44873 23413 44873 23416 44874 23413 44874 23414 44874 23417 44875 23413 44875 23416 44875 23417 44876 23415 44876 23413 44876 23419 44877 23415 44877 23417 44877 23417 44878 23416 44878 23418 44878 23420 44879 23417 44879 23418 44879 23421 44880 23417 44880 23420 44880 23419 44881 23417 44881 23421 44881 23423 44882 23420 44882 23422 44882 23421 44883 23420 44883 23423 44883 23423 44884 23422 44884 23424 44884 23425 44885 23423 44885 23424 44885 23426 44886 23419 44886 23421 44886 23421 44887 23423 44887 23425 44887 23426 44888 23421 44888 23425 44888 23427 44889 23425 44889 23424 44889 23428 44890 23425 44890 23427 44890 23430 44891 23425 44891 23428 44891 23428 44892 23427 44892 23429 44892 23430 44893 23426 44893 23425 44893 23431 44894 23428 44894 23429 44894 23432 44895 23428 44895 23431 44895 23433 44896 23430 44896 23428 44896 23433 44897 23426 44897 23430 44897 23432 44898 23433 44898 23428 44898 23434 44899 23433 44899 23432 44899 23435 44900 23432 44900 23431 44900 23434 44901 23432 44901 23435 44901 23436 44902 23433 44902 23434 44902 23436 44903 23426 44903 23433 44903 23354 44904 23434 44904 23435 44904 23355 44905 23434 44905 23354 44905 23355 44906 23436 44906 23434 44906 23356 44907 23354 44907 23437 44907 23356 44908 23437 44908 23519 44908 23358 44909 23356 44909 23519 44909 23358 44910 23519 44910 23518 44910 23361 44911 23518 44911 23438 44911 23361 44912 23358 44912 23518 44912 23362 44913 23361 44913 23438 44913 23362 44914 23438 44914 23513 44914 23365 44915 23362 44915 23513 44915 23365 44916 23513 44916 23439 44916 23366 44917 23365 44917 23439 44917 23366 44918 23439 44918 23509 44918 23367 44919 23366 44919 23509 44919 23367 44920 23509 44920 23507 44920 23371 44921 23367 44921 23507 44921 23372 44922 23371 44922 23507 44922 23372 44923 23507 44923 23440 44923 23374 44924 23372 44924 23440 44924 23374 44925 23440 44925 23441 44925 23377 44926 23374 44926 23441 44926 23377 44927 23441 44927 23442 44927 23379 44928 23377 44928 23442 44928 23379 44929 23442 44929 23443 44929 23382 44930 23379 44930 23443 44930 23382 44931 23443 44931 23499 44931 23383 44932 23382 44932 23499 44932 23383 44933 23499 44933 23444 44933 23385 44934 23383 44934 23444 44934 23385 44935 23444 44935 23495 44935 23389 44936 23385 44936 23495 44936 23389 44937 23495 44937 23445 44937 23391 44938 23445 44938 23446 44938 23391 44939 23389 44939 23445 44939 23393 44940 23391 44940 23446 44940 23393 44941 23446 44941 23490 44941 23395 44942 23393 44942 23490 44942 23395 44943 23490 44943 23447 44943 23398 44944 23395 44944 23447 44944 23398 44945 23447 44945 23485 44945 23400 44946 23398 44946 23485 44946 23400 44947 23485 44947 23448 44947 23402 44948 23400 44948 23448 44948 23402 44949 23448 44949 23483 44949 23405 44950 23483 44950 23480 44950 23405 44951 23402 44951 23483 44951 23405 44952 23480 44952 23449 44952 23408 44953 23405 44953 23449 44953 23409 44954 23408 44954 23449 44954 23409 44955 23449 44955 23450 44955 23412 44956 23409 44956 23450 44956 23412 44957 23450 44957 23451 44957 23414 44958 23412 44958 23451 44958 23414 44959 23451 44959 23452 44959 23416 44960 23414 44960 23452 44960 23416 44961 23452 44961 23453 44961 23418 44962 23416 44962 23453 44962 23418 44963 23453 44963 23454 44963 23420 44964 23418 44964 23454 44964 23422 44965 23454 44965 23455 44965 23422 44966 23420 44966 23454 44966 23424 44967 23422 44967 23455 44967 23424 44968 23455 44968 23456 44968 23427 44969 23424 44969 23456 44969 23429 44970 23456 44970 23457 44970 23429 44971 23427 44971 23456 44971 23429 44972 23457 44972 23458 44972 23431 44973 23429 44973 23458 44973 23431 44974 23458 44974 23459 44974 23435 44975 23459 44975 23460 44975 23435 44976 23431 44976 23459 44976 23354 44977 23435 44977 23460 44977 23354 44978 23460 44978 23437 44978 22485 44979 23407 44979 22993 44979 22485 44980 23403 44980 23407 44980 22994 44981 22993 44981 23407 44981 22994 44982 23407 44982 23415 44982 22485 44983 23399 44983 23403 44983 22483 44984 23399 44984 22485 44984 22994 44985 23415 44985 23419 44985 22483 44986 23396 44986 23399 44986 23226 44987 22994 44987 23419 44987 22478 44988 23396 44988 22483 44988 22478 44989 23387 44989 23396 44989 23226 44990 23419 44990 23426 44990 22481 44991 23387 44991 22478 44991 22481 44992 23386 44992 23387 44992 23227 44993 23226 44993 23426 44993 23378 44994 23386 44994 22481 44994 23378 44995 22481 44995 22477 44995 23436 44996 23227 44996 23426 44996 23376 44997 23378 44997 22477 44997 23436 44998 23225 44998 23227 44998 23369 44999 23376 44999 22477 44999 23359 45000 23225 45000 23436 45000 23369 45001 22477 45001 22474 45001 23359 45002 23228 45002 23225 45002 23363 45003 23228 45003 23359 45003 23369 45004 22474 45004 22473 45004 23363 45005 23369 45005 22473 45005 23363 45006 22473 45006 23228 45006 23460 45007 23461 45007 23437 45007 23462 45008 23461 45008 23460 45008 23464 45009 23462 45009 23460 45009 23459 45010 23464 45010 23460 45010 23464 45011 23463 45011 23462 45011 23458 45012 23464 45012 23459 45012 23465 45013 23463 45013 23464 45013 23466 45014 23464 45014 23458 45014 23465 45015 23464 45015 23466 45015 23466 45016 23458 45016 23457 45016 23467 45017 23466 45017 23457 45017 23468 45018 23465 45018 23466 45018 23467 45019 23457 45019 23456 45019 23468 45020 23466 45020 23467 45020 23469 45021 23467 45021 23456 45021 23468 45022 23467 45022 23469 45022 23469 45023 23456 45023 23455 45023 23470 45024 23468 45024 23469 45024 23471 45025 23469 45025 23455 45025 23471 45026 23470 45026 23469 45026 23471 45027 23455 45027 23454 45027 23472 45028 23471 45028 23454 45028 23473 45029 23471 45029 23472 45029 23453 45030 23472 45030 23454 45030 23473 45031 23470 45031 23471 45031 23452 45032 23472 45032 23453 45032 23452 45033 23473 45033 23472 45033 23474 45034 23473 45034 23452 45034 23475 45035 23452 45035 23451 45035 23474 45036 23452 45036 23475 45036 23450 45037 23475 45037 23451 45037 23473 45038 23474 45038 23476 45038 23477 45039 23474 45039 23475 45039 23477 45040 23475 45040 23450 45040 23476 45041 23474 45041 23477 45041 23477 45042 23450 45042 23449 45042 23478 45043 23476 45043 23477 45043 23479 45044 23477 45044 23449 45044 23478 45045 23477 45045 23479 45045 23481 45046 23476 45046 23478 45046 23480 45047 23479 45047 23449 45047 23481 45048 23478 45048 23479 45048 23481 45049 23486 45049 23476 45049 23482 45050 23479 45050 23480 45050 23482 45051 23481 45051 23479 45051 23483 45052 23482 45052 23480 45052 23486 45053 23481 45053 23482 45053 23484 45054 23486 45054 23482 45054 23484 45055 23482 45055 23483 45055 23484 45056 23483 45056 23448 45056 23484 45057 23448 45057 23485 45057 23486 45058 23484 45058 23487 45058 23487 45059 23484 45059 23485 45059 23488 45060 23485 45060 23447 45060 23488 45061 23487 45061 23485 45061 23490 45062 23488 45062 23447 45062 23489 45063 23487 45063 23488 45063 23491 45064 23488 45064 23490 45064 23491 45065 23489 45065 23488 45065 23491 45066 23490 45066 23446 45066 23493 45067 23487 45067 23489 45067 23492 45068 23491 45068 23446 45068 23493 45069 23489 45069 23491 45069 23493 45070 23491 45070 23492 45070 23445 45071 23492 45071 23446 45071 23494 45072 23493 45072 23492 45072 23494 45073 23492 45073 23445 45073 23496 45074 23493 45074 23494 45074 23495 45075 23494 45075 23445 45075 23497 45076 23494 45076 23495 45076 23497 45077 23495 45077 23444 45077 23496 45078 23494 45078 23497 45078 23498 45079 23496 45079 23497 45079 23497 45080 23444 45080 23499 45080 23500 45081 23496 45081 23498 45081 23498 45082 23497 45082 23499 45082 23500 45083 23498 45083 23499 45083 23501 45084 23499 45084 23443 45084 23501 45085 23500 45085 23499 45085 23501 45086 23443 45086 23442 45086 23502 45087 23501 45087 23442 45087 23503 45088 23500 45088 23501 45088 23441 45089 23502 45089 23442 45089 23504 45090 23501 45090 23502 45090 23503 45091 23501 45091 23504 45091 23504 45092 23502 45092 23441 45092 23504 45093 23441 45093 23440 45093 23505 45094 23503 45094 23504 45094 23506 45095 23504 45095 23440 45095 23505 45096 23504 45096 23506 45096 23507 45097 23506 45097 23440 45097 23508 45098 23506 45098 23507 45098 23505 45099 23506 45099 23508 45099 23505 45100 23511 45100 23503 45100 23508 45101 23507 45101 23509 45101 23510 45102 23508 45102 23509 45102 23511 45103 23505 45103 23508 45103 23439 45104 23510 45104 23509 45104 23512 45105 23508 45105 23510 45105 23512 45106 23510 45106 23439 45106 23512 45107 23511 45107 23508 45107 23513 45108 23512 45108 23439 45108 23514 45109 23511 45109 23512 45109 23514 45110 23512 45110 23513 45110 23516 45111 23511 45111 23514 45111 23438 45112 23514 45112 23513 45112 23515 45113 23514 45113 23438 45113 23516 45114 23514 45114 23515 45114 23517 45115 23516 45115 23515 45115 23518 45116 23515 45116 23438 45116 23517 45117 23515 45117 23518 45117 23517 45118 23518 45118 23519 45118 23520 45119 23516 45119 23517 45119 23521 45120 23517 45120 23519 45120 23521 45121 23519 45121 23437 45121 23520 45122 23517 45122 23521 45122 23462 45123 23520 45123 23521 45123 23461 45124 23521 45124 23437 45124 23461 45125 23462 45125 23521 45125 23463 45126 23520 45126 23462 45126 22444 45127 22449 45127 22451 45127 22444 45128 22446 45128 22449 45128 22442 45129 22444 45129 22452 45129 22452 45130 22444 45130 22451 45130 22439 45131 22452 45131 22453 45131 22439 45132 22442 45132 22452 45132

+
+ + + +

23523 45133 23548 45133 23522 45133 23523 45134 23522 45134 23524 45134 23523 45135 23524 45135 23525 45135 23526 45136 23523 45136 23525 45136 23526 45137 23525 45137 23527 45137 23528 45138 23526 45138 23527 45138 23528 45139 23527 45139 23529 45139 23530 45140 23528 45140 23529 45140 23530 45141 23529 45141 23531 45141 23532 45142 23530 45142 23531 45142 23532 45143 23531 45143 23533 45143 23534 45144 23532 45144 23533 45144 23534 45145 23533 45145 23535 45145 23536 45146 23534 45146 23535 45146 23536 45147 23535 45147 23537 45147 23538 45148 23536 45148 23537 45148 23538 45149 23537 45149 23539 45149 23540 45150 23538 45150 23539 45150 23540 45151 23539 45151 23541 45151 23542 45152 23540 45152 23541 45152 23542 45153 23541 45153 23543 45153 23544 45154 23542 45154 23543 45154 23544 45155 23543 45155 23545 45155 23546 45156 23544 45156 23545 45156 23546 45157 23545 45157 23547 45157 23548 45158 23547 45158 23522 45158 23548 45159 23546 45159 23547 45159 23524 10 23522 10 23547 10 23524 45160 23547 45160 23545 45160 23525 45161 23524 45161 23545 45161 23539 45162 23543 45162 23541 45162 23531 10 23537 10 23535 10 23531 10 23525 10 23545 10 23531 45163 23545 45163 23543 45163 23531 10 23535 10 23533 10 23531 45164 23543 45164 23539 45164 23531 10 23539 10 23537 10 23531 45165 23527 45165 23525 45165 23531 10 23529 10 23527 10 23546 45166 23542 45166 23544 45166 23546 45167 23538 45167 23540 45167 23546 45168 23540 45168 23542 45168 23528 272 23530 272 23532 272 23526 272 23548 272 23523 272 23526 45169 23538 45169 23546 45169 23526 45170 23536 45170 23538 45170 23526 272 23534 272 23536 272 23526 272 23532 272 23534 272 23526 272 23546 272 23548 272 23526 45171 23528 45171 23532 45171

+
+ + + +

23550 45172 23549 45172 23576 45172 23550 45173 23576 45173 23551 45173 23552 45174 23550 45174 23551 45174 23552 45175 23551 45175 23553 45175 23554 45176 23552 45176 23553 45176 23555 45177 23554 45177 23553 45177 23555 45178 23553 45178 23556 45178 23557 45179 23555 45179 23556 45179 23557 45180 23556 45180 23558 45180 23559 45181 23557 45181 23558 45181 23559 45182 23558 45182 23560 45182 23561 45183 23559 45183 23560 45183 23561 45184 23560 45184 23562 45184 23563 45185 23561 45185 23562 45185 23563 45186 23562 45186 23564 45186 23563 45187 23564 45187 23565 45187 23566 45188 23563 45188 23565 45188 23566 45189 23565 45189 23567 45189 23568 45190 23566 45190 23567 45190 23569 45191 23567 45191 23570 45191 23569 45192 23568 45192 23567 45192 23569 45193 23570 45193 23571 45193 23572 45194 23569 45194 23571 45194 23572 45195 23571 45195 23573 45195 23574 45196 23572 45196 23573 45196 23574 45197 23573 45197 23575 45197 23549 45198 23574 45198 23575 45198 23549 45199 23575 45199 23576 45199 23551 10 23576 10 23575 10 23551 45200 23575 45200 23573 45200 23567 45201 23571 45201 23570 45201 23560 45202 23565 45202 23564 45202 23560 45203 23564 45203 23562 45203 23560 10 23551 10 23573 10 23560 45204 23558 45204 23556 45204 23560 45205 23573 45205 23571 45205 23560 45206 23571 45206 23567 45206 23560 45207 23567 45207 23565 45207 23560 10 23553 10 23551 10 23560 45208 23556 45208 23553 45208 23574 45209 23569 45209 23572 45209 23574 45210 23568 45210 23569 45210 23549 45211 23568 45211 23574 45211 23555 272 23557 272 23559 272 23555 45212 23559 45212 23561 45212 23552 45213 23555 45213 23561 45213 23552 272 23549 272 23550 272 23552 45214 23566 45214 23568 45214 23552 45215 23554 45215 23555 45215 23552 45216 23563 45216 23566 45216 23552 272 23561 272 23563 272 23552 272 23568 272 23549 272

+
+ + + +

23578 45217 23605 45217 23577 45217 23578 45218 23577 45218 23579 45218 23580 45219 23578 45219 23579 45219 23580 45220 23579 45220 23581 45220 23582 45221 23580 45221 23581 45221 23582 45222 23581 45222 23583 45222 23582 45223 23583 45223 23584 45223 23585 45224 23582 45224 23584 45224 23586 45225 23585 45225 23584 45225 23586 45226 23584 45226 23587 45226 23588 45227 23586 45227 23587 45227 23588 45228 23587 45228 23589 45228 23588 45229 23589 45229 23590 45229 23591 45230 23588 45230 23590 45230 23592 45231 23591 45231 23590 45231 23592 45232 23590 45232 23593 45232 23594 45233 23592 45233 23593 45233 23595 45234 23594 45234 23593 45234 23595 45235 23593 45235 23596 45235 23597 45236 23596 45236 23598 45236 23597 45237 23595 45237 23596 45237 23599 45238 23597 45238 23598 45238 23599 45239 23598 45239 23600 45239 23599 45240 23600 45240 23601 45240 23602 45241 23599 45241 23601 45241 23603 45242 23602 45242 23601 45242 23603 45243 23601 45243 23604 45243 23605 45244 23603 45244 23604 45244 23605 45245 23604 45245 23577 45245 23577 45246 23604 45246 23601 45246 23579 10 23577 10 23601 10 23596 45247 23600 45247 23598 45247 23589 45248 23593 45248 23590 45248 23589 45249 23584 45249 23583 45249 23589 10 23579 10 23601 10 23589 10 23587 10 23584 10 23589 45250 23601 45250 23600 45250 23589 45251 23600 45251 23596 45251 23589 45252 23596 45252 23593 45252 23589 10 23581 10 23579 10 23589 10 23583 10 23581 10 23602 272 23597 272 23599 272 23588 45253 23591 45253 23592 45253 23588 45254 23592 45254 23594 45254 23603 45255 23597 45255 23602 45255 23580 45256 23588 45256 23594 45256 23580 272 23605 272 23578 272 23580 45257 23582 45257 23585 45257 23580 272 23594 272 23595 272 23580 45258 23595 45258 23597 45258 23580 272 23586 272 23588 272 23580 45259 23597 45259 23603 45259 23580 45260 23585 45260 23586 45260 23580 45261 23603 45261 23605 45261

+
+ + + +

23606 45262 23607 45262 23608 45262 23609 45263 23606 45263 23608 45263 23610 45264 23609 45264 23608 45264 23610 45265 23608 45265 23611 45265 23612 45266 23611 45266 23613 45266 23612 45267 23610 45267 23611 45267 23614 45268 23612 45268 23613 45268 23614 45269 23613 45269 23615 45269 23616 45270 23614 45270 23615 45270 23616 45271 23615 45271 23617 45271 23616 45272 23617 45272 23618 45272 23619 45273 23616 45273 23618 45273 23619 45274 23618 45274 23620 45274 23621 45275 23619 45275 23620 45275 23622 45276 23621 45276 23620 45276 23622 45277 23620 45277 23623 45277 23624 45278 23622 45278 23623 45278 23624 45279 23623 45279 23625 45279 23626 45280 23624 45280 23625 45280 23626 45281 23625 45281 23627 45281 23628 45282 23626 45282 23627 45282 23628 45283 23627 45283 23629 45283 23630 45284 23628 45284 23629 45284 23630 45285 23629 45285 23631 45285 23632 45286 23630 45286 23631 45286 23632 45287 23631 45287 23633 45287 23634 45288 23632 45288 23633 45288 23634 45289 23633 45289 23607 45289 23606 45290 23634 45290 23607 45290 23625 10 23629 10 23627 10 23625 45291 23631 45291 23629 45291 23613 10 23608 10 23607 10 23613 10 23611 10 23608 10 23623 45292 23631 45292 23625 45292 23618 45293 23607 45293 23633 45293 23618 45294 23633 45294 23631 45294 23618 10 23631 10 23623 10 23618 10 23623 10 23620 10 23618 45295 23617 45295 23615 45295 23618 45296 23615 45296 23613 45296 23618 10 23613 10 23607 10 23632 45297 23628 45297 23630 45297 23616 45298 23619 45298 23621 45298 23606 45299 23632 45299 23634 45299 23612 45300 23614 45300 23616 45300 23609 45301 23628 45301 23632 45301 23609 45302 23624 45302 23626 45302 23609 45303 23626 45303 23628 45303 23609 45304 23632 45304 23606 45304 23610 272 23624 272 23609 272 23610 45305 23612 45305 23616 45305 23610 272 23616 272 23621 272 23610 45306 23622 45306 23624 45306 23610 272 23621 272 23622 272

+
+ + + +

23637 45307 23635 45307 23636 45307 23637 45308 23636 45308 23638 45308 23639 45309 23637 45309 23638 45309 23639 45310 23638 45310 23640 45310 23639 45311 23640 45311 23641 45311 23642 45312 23639 45312 23641 45312 23642 45313 23641 45313 23643 45313 23644 45314 23642 45314 23643 45314 23644 45315 23643 45315 23645 45315 23646 45316 23644 45316 23645 45316 23646 45317 23645 45317 23647 45317 23648 45318 23646 45318 23647 45318 23649 45319 23648 45319 23647 45319 23649 45320 23647 45320 23650 45320 23649 45321 23650 45321 23651 45321 23652 45322 23649 45322 23651 45322 23652 45323 23651 45323 23653 45323 23654 45324 23652 45324 23653 45324 23654 45325 23653 45325 23655 45325 23656 45326 23654 45326 23655 45326 23656 45327 23655 45327 23657 45327 23658 45328 23656 45328 23657 45328 23658 45329 23657 45329 23659 45329 23660 45330 23658 45330 23659 45330 23661 45331 23659 45331 23662 45331 23661 45332 23660 45332 23659 45332 23663 45333 23661 45333 23662 45333 23663 45334 23662 45334 23664 45334 23665 45335 23663 45335 23664 45335 23665 45336 23664 45336 23666 45336 23665 45337 23666 45337 23667 45337 23668 45338 23665 45338 23667 45338 23669 45339 23668 45339 23667 45339 23669 45340 23667 45340 23670 45340 23671 45341 23670 45341 23672 45341 23671 45342 23669 45342 23670 45342 23673 45343 23672 45343 23674 45343 23673 45344 23671 45344 23672 45344 23635 45345 23673 45345 23674 45345 23635 45346 23674 45346 23636 45346 23658 45347 23660 45347 23661 45347 23669 45348 23665 45348 23668 45348 23649 10 23658 10 23661 10 23649 45349 23661 45349 23663 45349 23649 45350 23656 45350 23658 45350 23649 45351 23654 45351 23656 45351 23649 45352 23652 45352 23654 45352 23648 45353 23665 45353 23669 45353 23648 45354 23669 45354 23671 45354 23648 10 23649 10 23663 10 23648 45355 23663 45355 23665 45355 23635 45356 23671 45356 23673 45356 23635 10 23648 10 23671 10 23639 10 23635 10 23637 10 23639 10 23648 10 23635 10 23639 10 23642 10 23644 10 23639 45357 23646 45357 23648 45357 23639 45358 23644 45358 23646 45358 23677 45359 23675 45359 23676 45359 23677 45360 23676 45360 23678 45360 23677 45361 23678 45361 23679 45361 23680 45362 23677 45362 23679 45362 23680 45363 23679 45363 23681 45363 23682 45364 23680 45364 23681 45364 23682 45365 23681 45365 23683 45365 23684 45366 23682 45366 23683 45366 23684 45367 23683 45367 23685 45367 23686 45368 23684 45368 23685 45368 23686 45369 23685 45369 23687 45369 23688 45370 23686 45370 23687 45370 23688 45371 23687 45371 23689 45371 23690 45372 23688 45372 23689 45372 23690 45373 23689 45373 23691 45373 23690 45374 23691 45374 23692 45374 23693 45375 23690 45375 23692 45375 23694 45376 23692 45376 23695 45376 23694 45377 23693 45377 23692 45377 23694 45378 23695 45378 23696 45378 23697 45379 23694 45379 23696 45379 23697 45380 23696 45380 23698 45380 23697 45381 23698 45381 23699 45381 23700 45382 23697 45382 23699 45382 23700 45383 23699 45383 23701 45383 23702 45384 23700 45384 23701 45384 23702 45385 23701 45385 23703 45385 23704 45386 23703 45386 23705 45386 23704 45387 23702 45387 23703 45387 23706 45388 23705 45388 23707 45388 23706 45389 23704 45389 23705 45389 23706 45390 23707 45390 23708 45390 23709 45391 23706 45391 23708 45391 23709 45392 23708 45392 23710 45392 23711 45393 23709 45393 23710 45393 23711 45394 23710 45394 23712 45394 23713 45395 23711 45395 23712 45395 23713 45396 23712 45396 23714 45396 23715 45397 23713 45397 23714 45397 23716 45398 23715 45398 23714 45398 23716 45399 23714 45399 23717 45399 23718 45400 23717 45400 23719 45400 23718 45401 23716 45401 23717 45401 23720 45402 23719 45402 23721 45402 23720 45403 23718 45403 23719 45403 23722 45404 23721 45404 23723 45404 23722 45405 23720 45405 23721 45405 23724 45406 23723 45406 23725 45406 23724 45407 23722 45407 23723 45407 23724 45408 23725 45408 23726 45408 23727 45409 23724 45409 23726 45409 23727 45410 23726 45410 23728 45410 23729 45411 23727 45411 23728 45411 23730 45412 23729 45412 23728 45412 23730 45413 23728 45413 23731 45413 23730 45414 23731 45414 23732 45414 23733 45415 23730 45415 23732 45415 23733 45416 23732 45416 23734 45416 23735 45417 23733 45417 23734 45417 23735 45418 23734 45418 23736 45418 23737 45419 23736 45419 23738 45419 23737 45420 23735 45420 23736 45420 23737 45421 23738 45421 23739 45421 23740 45422 23739 45422 23741 45422 23740 45423 23737 45423 23739 45423 23740 45424 23741 45424 23742 45424 23743 45425 23742 45425 23744 45425 23743 45426 23740 45426 23742 45426 23743 45427 23744 45427 23745 45427 23746 45428 23743 45428 23745 45428 23747 45429 23746 45429 23745 45429 23747 45430 23745 45430 23748 45430 23675 45431 23747 45431 23748 45431 23675 45432 23748 45432 23676 45432 23716 45433 23718 45433 23720 45433 23729 45434 23722 45434 23724 45434 23729 45435 23724 45435 23727 45435 23716 272 23720 272 23722 272 23713 45436 23715 45436 23716 45436 23709 45437 23711 45437 23713 45437 23735 45438 23716 45438 23722 45438 23735 45439 23722 45439 23729 45439 23735 45440 23713 45440 23716 45440 23735 272 23730 272 23733 272 23735 272 23729 272 23730 272 23706 45441 23709 45441 23713 45441 23706 45442 23713 45442 23735 45442 23700 272 23702 272 23704 272 23743 45443 23706 45443 23735 45443 23743 45444 23704 45444 23706 45444 23743 272 23735 272 23737 272 23743 272 23737 272 23740 272 23743 45445 23700 45445 23704 45445 23747 272 23743 272 23746 272 23694 45446 23697 45446 23700 45446 23675 272 23743 272 23747 272 23677 272 23743 272 23675 272 23690 272 23693 272 23694 272 23690 45447 23743 45447 23677 45447 23690 272 23700 272 23743 272 23690 272 23694 272 23700 272 23686 272 23688 272 23690 272 23684 45448 23680 45448 23682 45448 23684 45449 23690 45449 23677 45449 23684 45450 23677 45450 23680 45450 23684 272 23686 272 23690 272 23712 45451 23749 45451 23714 45451 23749 45452 23750 45452 23714 45452 23714 45453 23750 45453 23717 45453 23750 45454 23751 45454 23717 45454 23717 45455 23751 45455 23719 45455 23719 45456 23752 45456 23721 45456 23751 45457 23752 45457 23719 45457 23752 45458 23753 45458 23721 45458 23721 45459 23753 45459 23723 45459 23753 45460 23754 45460 23723 45460 23754 45461 23755 45461 23723 45461 23723 45462 23755 45462 23725 45462 23725 45463 23755 45463 23726 45463 23755 45464 23756 45464 23726 45464 23726 45465 23756 45465 23728 45465 23756 45466 23757 45466 23728 45466 23728 45467 23758 45467 23731 45467 23757 45468 23758 45468 23728 45468 23731 45469 23759 45469 23732 45469 23758 45470 23759 45470 23731 45470 23732 45471 23759 45471 23734 45471 23759 45472 23760 45472 23734 45472 23760 45473 23761 45473 23734 45473 23734 45474 23761 45474 23736 45474 23761 45475 23762 45475 23736 45475 23736 45476 23762 45476 23738 45476 23738 45477 23762 45477 23739 45477 23762 45478 23763 45478 23739 45478 23739 45479 23763 45479 23741 45479 23763 45480 23764 45480 23741 45480 23741 45481 23764 45481 23742 45481 23742 45482 23765 45482 23744 45482 23764 45483 23765 45483 23742 45483 23765 45484 23766 45484 23744 45484 23744 45485 23766 45485 23745 45485 23766 45486 23767 45486 23745 45486 23745 45487 23767 45487 23748 45487 23767 45488 23768 45488 23748 45488 23748 45489 23769 45489 23676 45489 23768 45490 23769 45490 23748 45490 23769 45491 23770 45491 23676 45491 23770 45492 23678 45492 23676 45492 23770 45493 23771 45493 23678 45493 23771 45494 23679 45494 23678 45494 23771 45495 23772 45495 23679 45495 23772 45496 23681 45496 23679 45496 23772 45497 23773 45497 23681 45497 23773 45498 23774 45498 23681 45498 23774 45499 23683 45499 23681 45499 23774 45500 23775 45500 23683 45500 23775 45501 23685 45501 23683 45501 23775 45502 23776 45502 23685 45502 23685 45503 23776 45503 23687 45503 23776 45504 23777 45504 23687 45504 23777 45505 23689 45505 23687 45505 23777 45506 23778 45506 23689 45506 23689 45507 23778 45507 23691 45507 23778 45508 23779 45508 23691 45508 23779 45509 23692 45509 23691 45509 23779 45510 23780 45510 23692 45510 23780 45511 23781 45511 23692 45511 23692 45512 23781 45512 23695 45512 23781 45513 23782 45513 23695 45513 23782 45514 23696 45514 23695 45514 23782 45515 23783 45515 23696 45515 23696 45516 23783 45516 23698 45516 23783 45517 23784 45517 23698 45517 23698 45518 23784 45518 23699 45518 23784 45519 23701 45519 23699 45519 23784 45520 23785 45520 23701 45520 23701 45521 23785 45521 23703 45521 23785 45522 23786 45522 23703 45522 23786 45523 23705 45523 23703 45523 23786 45524 23787 45524 23705 45524 23787 45525 23707 45525 23705 45525 23787 45526 23788 45526 23707 45526 23707 45527 23788 45527 23708 45527 23788 45528 23789 45528 23708 45528 23789 45529 23710 45529 23708 45529 23789 45530 23790 45530 23710 45530 23790 45531 23712 45531 23710 45531 23790 45532 23749 45532 23712 45532 23749 45533 23790 45533 23791 45533 23790 45534 23789 45534 23791 45534 23791 45535 23789 45535 23792 45535 23789 45536 23788 45536 23792 45536 23792 45537 23788 45537 23793 45537 23788 45538 23787 45538 23793 45538 23793 45539 23787 45539 23794 45539 23787 45540 23786 45540 23794 45540 23794 45541 23786 45541 23795 45541 23786 45542 23785 45542 23795 45542 23795 45543 23785 45543 23796 45543 23785 45544 23784 45544 23796 45544 23796 45545 23784 45545 23797 45545 23784 45546 23783 45546 23797 45546 23797 45547 23783 45547 23798 45547 23798 45548 23782 45548 23799 45548 23783 45549 23782 45549 23798 45549 23782 45550 23781 45550 23799 45550 23799 45551 23781 45551 23800 45551 23781 45552 23780 45552 23800 45552 23800 45553 23780 45553 23801 45553 23780 45554 23779 45554 23801 45554 23801 45555 23779 45555 23802 45555 23779 45556 23778 45556 23802 45556 23802 45557 23778 45557 23803 45557 23778 45558 23777 45558 23803 45558 23803 45559 23777 45559 23804 45559 23777 45560 23776 45560 23804 45560 23804 45561 23776 45561 23805 45561 23805 45562 23776 45562 23806 45562 23776 45563 23775 45563 23806 45563 23806 45564 23775 45564 23807 45564 23775 45565 23774 45565 23807 45565 23774 45566 23773 45566 23807 45566 23807 45567 23773 45567 23808 45567 23773 45568 23772 45568 23808 45568 23808 45569 23772 45569 23809 45569 23772 45570 23771 45570 23809 45570 23809 45571 23771 45571 23810 45571 23771 45572 23770 45572 23810 45572 23810 45573 23770 45573 23811 45573 23770 45574 23769 45574 23811 45574 23811 45575 23769 45575 23812 45575 23769 45576 23768 45576 23812 45576 23768 45577 23767 45577 23812 45577 23812 45578 23767 45578 23813 45578 23767 45579 23766 45579 23813 45579 23813 45580 23766 45580 23814 45580 23814 45581 23766 45581 23815 45581 23766 45582 23765 45582 23815 45582 23765 45583 23764 45583 23815 45583 23815 45584 23764 45584 23816 45584 23764 45585 23763 45585 23816 45585 23816 45586 23763 45586 23817 45586 23817 45587 23762 45587 23818 45587 23763 45588 23762 45588 23817 45588 23818 45589 23761 45589 23819 45589 23762 45590 23761 45590 23818 45590 23761 45591 23760 45591 23819 45591 23819 45592 23760 45592 23820 45592 23760 45593 23759 45593 23820 45593 23820 45594 23759 45594 23821 45594 23821 45595 23758 45595 23822 45595 23759 45596 23758 45596 23821 45596 23822 45597 23757 45597 23823 45597 23758 45598 23757 45598 23822 45598 23823 45599 23756 45599 23824 45599 23757 45600 23756 45600 23823 45600 23824 45601 23755 45601 23825 45601 23756 45602 23755 45602 23824 45602 23825 45603 23755 45603 23826 45603 23755 45604 23754 45604 23826 45604 23826 45605 23754 45605 23827 45605 23754 45606 23753 45606 23827 45606 23827 45607 23753 45607 23828 45607 23753 45608 23752 45608 23828 45608 23752 45609 23751 45609 23828 45609 23828 45610 23751 45610 23829 45610 23751 45611 23750 45611 23829 45611 23829 45612 23750 45612 23830 45612 23750 45613 23749 45613 23830 45613 23830 45614 23749 45614 23831 45614 23831 45615 23749 45615 23791 45615 23659 45616 23832 45616 23662 45616 23662 45617 23832 45617 23833 45617 23659 45618 23834 45618 23832 45618 23662 45619 23833 45619 23835 45619 23657 45620 23834 45620 23659 45620 23657 45621 23836 45621 23834 45621 23664 45622 23662 45622 23835 45622 23664 45623 23835 45623 23837 45623 23657 45624 23838 45624 23836 45624 23655 45625 23838 45625 23657 45625 23655 45626 23839 45626 23838 45626 23664 45627 23837 45627 23840 45627 23666 45628 23664 45628 23840 45628 23666 45629 23840 45629 23841 45629 23653 45630 23839 45630 23655 45630 23653 45631 23842 45631 23839 45631 23667 45632 23666 45632 23841 45632 23667 45633 23841 45633 23843 45633 23653 45634 23844 45634 23842 45634 23667 45635 23843 45635 23845 45635 23651 45636 23844 45636 23653 45636 23651 45637 23846 45637 23844 45637 23670 45638 23667 45638 23845 45638 23670 45639 23845 45639 23847 45639 23650 45640 23846 45640 23651 45640 23650 45641 23848 45641 23846 45641 23847 45642 23672 45642 23670 45642 23849 45643 23672 45643 23847 45643 23850 45644 23848 45644 23650 45644 23850 45645 23650 45645 23647 45645 23851 45646 23672 45646 23849 45646 23852 45647 23850 45647 23647 45647 23851 45648 23674 45648 23672 45648 23853 45649 23647 45649 23645 45649 23853 45650 23852 45650 23647 45650 23854 45651 23674 45651 23851 45651 23854 45652 23636 45652 23674 45652 23855 45653 23853 45653 23645 45653 23856 45654 23636 45654 23854 45654 23857 45655 23855 45655 23645 45655 23857 45656 23645 45656 23643 45656 23858 45657 23857 45657 23643 45657 23859 45658 23636 45658 23856 45658 23859 45659 23638 45659 23636 45659 23860 45660 23858 45660 23643 45660 23860 45661 23643 45661 23641 45661 23861 45662 23638 45662 23859 45662 23862 45663 23860 45663 23641 45663 23863 45664 23638 45664 23861 45664 23863 45665 23640 45665 23638 45665 23864 45666 23641 45666 23640 45666 23864 45667 23862 45667 23641 45667 23864 45668 23640 45668 23863 45668 23865 45669 23866 45669 23856 45669 23865 45670 23856 45670 23854 45670 23867 45671 23865 45671 23854 45671 23867 45672 23854 45672 23851 45672 23868 45673 23867 45673 23851 45673 23869 45674 23851 45674 23849 45674 23869 45675 23868 45675 23851 45675 23870 45676 23869 45676 23849 45676 23870 45677 23849 45677 23847 45677 23871 45678 23870 45678 23847 45678 23871 45679 23847 45679 23845 45679 23872 45680 23871 45680 23845 45680 23873 45681 23872 45681 23845 45681 23873 45682 23845 45682 23843 45682 23874 45683 23873 45683 23843 45683 23874 45684 23843 45684 23841 45684 23875 45685 23874 45685 23841 45685 23875 45686 23841 45686 23840 45686 23876 45687 23875 45687 23840 45687 23876 45688 23840 45688 23837 45688 23877 45689 23876 45689 23837 45689 23878 45690 23877 45690 23837 45690 23878 45691 23837 45691 23835 45691 23879 45692 23878 45692 23835 45692 23879 45693 23835 45693 23833 45693 23880 45694 23879 45694 23833 45694 23880 45695 23833 45695 23832 45695 23881 45696 23880 45696 23832 45696 23882 45697 23881 45697 23832 45697 23882 45698 23832 45698 23834 45698 23883 45699 23882 45699 23834 45699 23883 45700 23834 45700 23836 45700 23884 45701 23883 45701 23836 45701 23884 45702 23836 45702 23838 45702 23885 45703 23884 45703 23838 45703 23885 45704 23838 45704 23839 45704 23886 45705 23885 45705 23839 45705 23886 45706 23839 45706 23842 45706 23887 45707 23886 45707 23842 45707 23888 45708 23887 45708 23842 45708 23888 45709 23842 45709 23844 45709 23889 45710 23888 45710 23844 45710 23889 45711 23844 45711 23846 45711 23890 45712 23889 45712 23846 45712 23891 45713 23846 45713 23848 45713 23891 45714 23890 45714 23846 45714 23892 45715 23848 45715 23850 45715 23892 45716 23891 45716 23848 45716 23893 45717 23892 45717 23850 45717 23893 45718 23850 45718 23852 45718 23894 45719 23893 45719 23852 45719 23895 45720 23894 45720 23852 45720 23895 45721 23852 45721 23853 45721 23896 45722 23895 45722 23853 45722 23896 45723 23853 45723 23855 45723 23896 45724 23855 45724 23857 45724 23897 45725 23896 45725 23857 45725 23897 45726 23857 45726 23858 45726 23898 45727 23897 45727 23858 45727 23898 45728 23858 45728 23860 45728 23899 45729 23898 45729 23860 45729 23900 45730 23860 45730 23862 45730 23900 45731 23899 45731 23860 45731 23901 45732 23862 45732 23864 45732 23901 45733 23900 45733 23862 45733 23902 45734 23901 45734 23864 45734 23902 45735 23864 45735 23863 45735 23903 45736 23902 45736 23863 45736 23903 45737 23863 45737 23861 45737 23904 45738 23903 45738 23861 45738 23904 45739 23861 45739 23859 45739 23905 45740 23904 45740 23859 45740 23905 45741 23859 45741 23856 45741 23866 45742 23905 45742 23856 45742 23905 45743 23866 45743 23906 45743 23905 45744 23906 45744 23907 45744 23905 45745 23907 45745 23908 45745 23904 45746 23905 45746 23908 45746 23904 45747 23908 45747 23909 45747 23903 45748 23904 45748 23909 45748 23902 45749 23903 45749 23909 45749 23902 45750 23909 45750 23910 45750 23901 45751 23902 45751 23910 45751 23901 45752 23910 45752 23911 45752 23900 45753 23901 45753 23911 45753 23900 45754 23911 45754 23912 45754 23899 45755 23900 45755 23912 45755 23899 45756 23912 45756 23913 45756 23898 45757 23899 45757 23913 45757 23898 45758 23913 45758 23914 45758 23897 45759 23898 45759 23914 45759 23897 45760 23914 45760 23915 45760 23897 45761 23915 45761 23916 45761 23896 45762 23897 45762 23916 45762 23896 45763 23916 45763 23917 45763 23895 45764 23896 45764 23917 45764 23895 45765 23917 45765 23918 45765 23894 45766 23895 45766 23918 45766 23893 45767 23894 45767 23918 45767 23893 45768 23918 45768 23919 45768 23893 45769 23919 45769 23920 45769 23892 45770 23893 45770 23920 45770 23892 45771 23920 45771 23921 45771 23891 45772 23892 45772 23921 45772 23891 45773 23921 45773 23922 45773 23890 45774 23891 45774 23922 45774 23889 45775 23890 45775 23922 45775 23889 45776 23922 45776 23923 45776 23888 45777 23889 45777 23923 45777 23888 45778 23923 45778 23924 45778 23887 45779 23924 45779 23925 45779 23887 45780 23888 45780 23924 45780 23886 45781 23887 45781 23925 45781 23886 45782 23925 45782 23926 45782 23885 45783 23886 45783 23926 45783 23885 45784 23926 45784 23927 45784 23884 45785 23885 45785 23927 45785 23884 45786 23927 45786 23928 45786 23883 45787 23884 45787 23928 45787 23883 45788 23928 45788 23929 45788 23882 45789 23883 45789 23929 45789 23882 45790 23929 45790 23930 45790 23882 45791 23930 45791 23931 45791 23881 45792 23882 45792 23931 45792 23881 45793 23931 45793 23932 45793 23880 45794 23881 45794 23932 45794 23880 45795 23932 45795 23933 45795 23879 45796 23880 45796 23933 45796 23879 45797 23933 45797 23934 45797 23878 45798 23879 45798 23934 45798 23878 45799 23934 45799 23935 45799 23877 45800 23878 45800 23935 45800 23877 45801 23935 45801 23936 45801 23876 45802 23877 45802 23936 45802 23876 45803 23936 45803 23937 45803 23875 45804 23876 45804 23937 45804 23874 45805 23937 45805 23938 45805 23874 45806 23875 45806 23937 45806 23874 45807 23938 45807 23939 45807 23873 45808 23874 45808 23939 45808 23873 45809 23939 45809 23940 45809 23872 45810 23873 45810 23940 45810 23872 45811 23940 45811 23941 45811 23871 45812 23872 45812 23941 45812 23871 45813 23941 45813 23942 45813 23870 45814 23871 45814 23942 45814 23869 45815 23942 45815 23943 45815 23869 45816 23870 45816 23942 45816 23869 45817 23943 45817 23944 45817 23868 45818 23869 45818 23944 45818 23868 45819 23944 45819 23945 45819 23867 45820 23868 45820 23945 45820 23867 45821 23945 45821 23946 45821 23865 45822 23867 45822 23946 45822 23865 45823 23946 45823 23947 45823 23866 45824 23865 45824 23947 45824 23866 45825 23947 45825 23906 45825 23796 45826 23932 45826 23931 45826 23795 45827 23796 45827 23931 45827 23794 272 23931 272 23930 272 23794 45828 23795 45828 23931 45828 23797 272 23933 272 23932 272 23797 45829 23932 45829 23796 45829 23794 45830 23930 45830 23929 45830 23793 272 23794 272 23929 272 23797 45831 23934 45831 23933 45831 23798 272 23934 272 23797 272 23792 272 23793 272 23929 272 23792 272 23929 272 23928 272 23798 272 23935 272 23934 272 23799 45832 23935 45832 23798 45832 23791 272 23792 272 23928 272 23799 45833 23936 45833 23935 45833 23791 272 23928 272 23927 272 23800 272 23936 272 23799 272 23800 272 23937 272 23936 272 23791 45834 23927 45834 23926 45834 23831 272 23791 272 23926 272 23801 45835 23937 45835 23800 45835 23938 272 23937 272 23801 272 23831 45836 23926 45836 23925 45836 23830 272 23831 272 23925 272 23802 272 23938 272 23801 272 23939 45837 23938 45837 23802 45837 23830 272 23925 272 23924 272 23803 272 23939 272 23802 272 23829 272 23830 272 23924 272 23940 272 23939 272 23803 272 23829 272 23924 272 23923 272 23804 272 23940 272 23803 272 23828 45838 23829 45838 23923 45838 23828 272 23923 272 23922 272 23941 45839 23940 45839 23804 45839 23805 272 23941 272 23804 272 23806 45840 23941 45840 23805 45840 23827 272 23922 272 23921 272 23827 45841 23828 45841 23922 45841 23942 45842 23941 45842 23806 45842 23826 45843 23827 45843 23921 45843 23920 272 23826 272 23921 272 23942 272 23806 272 23807 272 23943 45844 23942 45844 23807 45844 23825 272 23826 272 23920 272 23919 272 23825 272 23920 272 23944 45845 23943 45845 23807 45845 23944 45846 23807 45846 23808 45846 23824 45847 23825 45847 23919 45847 23918 45848 23824 45848 23919 45848 23945 45849 23944 45849 23808 45849 23823 45850 23824 45850 23918 45850 23945 45851 23808 45851 23809 45851 23917 272 23823 272 23918 272 23946 45852 23945 45852 23809 45852 23946 45853 23809 45853 23810 45853 23822 45854 23823 45854 23917 45854 23916 45855 23822 45855 23917 45855 23947 45856 23946 45856 23810 45856 23947 45857 23810 45857 23811 45857 23916 272 23821 272 23822 272 23906 272 23947 272 23811 272 23906 45858 23811 45858 23812 45858 23915 45859 23821 45859 23916 45859 23914 272 23820 272 23821 272 23914 45860 23821 45860 23915 45860 23907 45861 23906 45861 23812 45861 23907 45862 23812 45862 23813 45862 23914 272 23819 272 23820 272 23908 272 23907 272 23813 272 23913 45863 23819 45863 23914 45863 23908 45864 23813 45864 23814 45864 23913 45865 23818 45865 23819 45865 23912 272 23818 272 23913 272 23909 272 23908 272 23814 272 23909 272 23814 272 23815 272 23911 45866 23818 45866 23912 45866 23911 272 23817 272 23818 272 23910 272 23815 272 23816 272 23910 272 23909 272 23815 272 23910 45867 23816 45867 23817 45867 23910 45868 23817 45868 23911 45868

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 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 + + + + + + + +
\ No newline at end of file diff --git a/models/gimbal_small_3d/meshes/camera_enclosure.dae b/models/gimbal_small_3d/meshes/camera_enclosure.dae new file mode 100644 index 0000000..30c7598 --- /dev/null +++ b/models/gimbal_small_3d/meshes/camera_enclosure.dae @@ -0,0 +1,448 @@ + + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-05-11T22:44:55 + 2023-05-11T22:44:55 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1000 + 29.99998 + 75 + 0.15 + 0 + 1 + 2 + 0.04999995 + 30.002 + 1 + 3 + 2880 + 3 + 1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.02344995 0.03767538 0.01044994 0.02344995 0.03608769 0.007699966 0.03145337 0.03767591 0.01044994 0.03144997 0.03608769 0.007699966 0.02344995 0.03291225 0.007699966 0.03144997 0.03291225 0.007699966 0.02344995 0.03132456 0.01044994 0.03144997 0.03132456 0.01044994 0.02344995 0.03291225 0.01319998 0.03144997 0.03291225 0.01319998 0.03144997 0.03608769 0.01319998 0.02344995 0.03608769 0.01319998 0.02344995 0.03340888 0.009402751 0.02344995 0.03400576 0.009017527 0.02344995 0.03309249 0.009910345 0.02344995 0.03298884 0.01069045 0.02344995 0.03472554 0.008953571 0.02344995 0.03529608 0.009169936 0.02344995 0.03575885 0.00960654 0.02344995 0.03405547 0.01189112 0.02344995 0.03343802 0.01153874 0.02344995 0.03601515 0.01034879 0.02344995 0.03587347 0.01108306 0.02344995 0.03546273 0.01161628 0.02344995 0.03476405 0.01194775 0.01644998 0.03446239 0.008941531 0.01644998 0.03504031 0.009040236 0.01644998 0.03565794 0.009462118 0.01644998 0.03602069 0.01032346 0.01644998 0.03585129 0.01112908 0.01644998 0.03523468 0.01179909 0.01644998 0.03431165 0.01195251 0.01644998 0.03374695 0.01175421 0.01644998 0.03328472 0.0113551 0.01644998 0.03297114 0.01051372 0.01644998 0.03319638 0.009683251 0.01644998 0.03374969 0.00912559 0.02144998 0.03467506 0.007430315 0.01644998 0.03551548 0.007587671 0.02144998 0.03568887 0.007687568 0.02144998 0.03651589 0.008202075 0.01644998 0.03680568 0.008483171 0.02144998 0.03726696 0.009228169 0.01644998 0.03739559 0.009610652 0.02144998 0.03752666 0.01070159 0.01644998 0.03749513 0.010953 0.02144998 0.03709894 0.01197785 0.01644998 0.03700065 0.01212668 0.02144998 0.0362491 0.01292484 0.01644998 0.03626358 0.01290291 0.01644998 0.03509896 0.01341295 0.02144998 0.03507405 0.01340961 0.02144998 0.03375107 0.01339101 0.01644998 0.03385156 0.013399 0.01644998 0.03288608 0.0129916 0.02144998 0.03250098 0.01271516 0.01644998 0.03210771 0.01229226 0.02144998 0.03178101 0.0117594 0.01644998 0.03153443 0.01107454 0.02144998 0.03151494 0.01082402 0.02144998 0.03155285 0.009777307 0.01644998 0.03155559 0.009802281 0.01644998 0.03189468 0.008945763 0.02144998 0.03222107 0.008438825 0.01644998 0.03250312 0.008187234 0.02144998 0.03341931 0.007630527 0.01644998 0.03331106 0.007687568 0.01644998 0.03417617 0.007452607 0.02182972 0.03238552 0.005921483 0.021824 0.03636181 0.005815088 0.02178329 0.03685384 0.006061255 0.02153688 0.03635668 0.006014823 0.02145779 0.03667533 0.006383597 0.02167963 0.03585487 0.005706667 0.02188062 0.03572154 0.005601882 0.02146399 0.03543978 0.005889773 0.02181291 0.03510606 0.005495309 0.02156913 0.03485649 0.005617439 0.02181506 0.03457474 0.005456447 0.0214557 0.03449785 0.005834996 0.02185857 0.03389489 0.00548762 0.0216735 0.03376859 0.005576193 0.02152746 0.03355449 0.005752146 0.02184998 0.03314226 0.005641281 0.02166837 0.032907 0.005794405 0.02145504 0.03272408 0.006187021 0.0216645 0.03211683 0.006143987 0.02152442 0.03244727 0.006140589 0.02179938 0.03015172 0.008013248 0.02147746 0.03040605 0.008163452 0.021452 0.03017961 0.008924484 0.02185249 0.03165692 0.006340563 0.02175933 0.0312004 0.006717026 0.02169686 0.03074973 0.007224738 0.02146136 0.03116136 0.00721246 0.02183598 0.03051942 0.007426917 0.0215637 0.03104245 0.007070481 0.0215556 0.03038722 0.007909953 0.02154517 0.03167718 0.00654447 0.02179747 0.02983212 0.008683264 0.02182656 0.02992707 0.01247394 0.02159965 0.03000038 0.008595764 0.02186346 0.02969574 0.009069681 0.0215075 0.02985978 0.009398579 0.02166199 0.02967834 0.009472966 0.02185064 0.02956026 0.009704351 0.02186143 0.0294969 0.01043426 0.02171629 0.02954614 0.01045298 0.021456 0.02987402 0.01066124 0.02156209 0.02967214 0.01040488 0.02183997 0.02960431 0.01146745 0.02161717 0.02966904 0.01120239 0.02158606 0.0298711 0.01193445 0.02151197 0.02998781 0.01196855 0.02166914 0.03015482 0.01276999 0.02145504 0.0302878 0.0123524 0.02177673 0.03222125 0.01487851 0.02145463 0.03223603 0.01445782 0.02183872 0.03053003 0.01349669 0.02146142 0.03102338 0.01354956 0.02167576 0.03067237 0.01356309 0.02172029 0.03123766 0.01419591 0.02155458 0.0306046 0.01332217 0.02152687 0.03157353 0.01423549 0.02175879 0.03167277 0.01454544 0.02155661 0.03246933 0.01482862 0.02187508 0.0328381 0.01516854 0.02168667 0.03303951 0.01516366 0.02147692 0.0330398 0.01490491 0.02185845 0.03365129 0.01537638 0.02155107 0.03367167 0.01519697 0.02170461 0.03387862 0.01536059 0.02184921 0.03435945 0.01544547 0.02145135 0.03455507 0.0150339 0.02187877 0.03500121 0.01543092 0.02151012 0.03432714 0.01520651 0.02166718 0.03501206 0.01534759 0.02151024 0.0351969 0.01515853 0.02177232 0.03583455 0.01525187 0.02148127 0.03586989 0.01494753 0.02182358 0.03644651 0.01504695 0.02157253 0.03643465 0.01489305 0.02183377 0.03696763 0.01479047 0.0214585 0.03679263 0.01446813 0.02175837 0.03776413 0.01421934 0.02180922 0.03856182 0.01336085 0.02182418 0.03908133 0.01245319 0.02145212 0.03873836 0.01223009 0.02145743 0.0376541 0.0138427 0.02154839 0.03749233 0.01421946 0.02149957 0.03839504 0.0131427 0.02164852 0.03889453 0.01265096 0.02151304 0.03882998 0.01242035 0.0216456 0.03700774 0.01466929 0.02158159 0.03816926 0.01363885 0.02168595 0.03928083 0.01167768 0.02181446 0.03938949 0.01146686 0.02150595 0.03913688 0.01152908 0.02185285 0.03950488 0.0105589 0.02166211 0.03942286 0.01053887 0.02151972 0.03927242 0.01044845 0.02145326 0.03908455 0.009907424 0.02178901 0.03941887 0.009634673 0.02155619 0.03921353 0.009407043 0.0218352 0.03930449 0.009083449 0.02166974 0.03906905 0.008613109 0.02188605 0.03902745 0.008315861 0.02150231 0.03893792 0.008803844 0.02177399 0.0386523 0.007684171 0.02146118 0.03853911 0.00817871 0.02174299 0.03822207 0.007144868 0.02145832 0.03789448 0.007296323 0.02181905 0.03750985 0.006462395 0.02156698 0.03805118 0.007138848 0.02155309 0.03716617 0.006420969 0.02158826 0.0387873 0.008165478 0.026452 0.03166282 0.0164681 0.0240482 0.02949732 0.010526 0.02601361 0.03197222 0.01613467 0.02644962 0.03066408 0.01645749 0.0259211 0.03063827 0.01592618 0.0251038 0.03153795 0.01553887 0.0253697 0.03237092 0.01577532 0.02644985 0.02971613 0.0160706 0.02496546 0.03081929 0.01513451 0.0240767 0.03156262 0.01506459 0.02572053 0.02955442 0.01477921 0.02645039 0.02897083 0.01537489 0.02501571 0.03023636 0.01472675 0.02645015 0.02855777 0.01451826 0.02574503 0.02912086 0.01397782 0.02397614 0.03034126 0.01402086 0.02597486 0.02881038 0.01305824 0.02645176 0.02844834 0.013471 0.02435123 0.02983808 0.01343512 0.0253477 0.02919238 0.01247328 0.02452892 0.02953284 0.01268959 0.02447277 0.02947902 0.01168334 0.02474611 0.03280913 0.01553851 0.02435201 0.03401446 0.01545453 0.02337425 0.0326898 0.01521956 0.02301996 0.0317735 0.01479482 0.02297055 0.03102409 0.01425498 0.0229994 0.03025984 0.01337707 0.02335458 0.02973985 0.0122798 0.02316951 0.02960389 0.01155811 0.02582234 0.02898383 0.00830084 0.02643442 0.02847164 0.007534086 0.02381062 0.02954387 0.009646832 0.02451419 0.03440684 0.005430817 0.02645039 0.0284723 0.006781637 0.02511674 0.02928113 0.00849241 0.02592211 0.02913355 0.006387829 0.02645045 0.02872741 0.00593549 0.02428966 0.02949643 0.009208917 0.02510607 0.0294103 0.007484138 0.02404767 0.02967286 0.008268952 0.02644985 0.02924376 0.0052163 0.02505117 0.02987182 0.006561815 0.02571839 0.03016853 0.005509018 0.02436435 0.02992862 0.007221102 0.02645152 0.03009045 0.004617154 0.02502053 0.03039467 0.006024718 0.0259397 0.03069239 0.004974663 0.02284938 0.02996116 0.008228957 0.02644681 0.0311492 0.004394948 0.02306056 0.0304532 0.007235944 0.02371609 0.03095757 0.006421566 0.02576822 0.03205263 0.004907071 0.02507883 0.03134024 0.005435407 0.02382463 0.03171342 0.005904912 0.02646255 0.03195369 0.004510641 0.02450871 0.0322647 0.005490422 0.02304881 0.03182047 0.006042242 0.02487605 0.03290319 0.005327463 0.02370846 0.0332331 0.005527734 0.02397006 0.03484177 0.005452454 0.02440321 0.03951132 0.01032388 0.02369147 0.03944176 0.01136934 0.02341073 0.03559958 0.0153594 0.02442848 0.03463071 0.0154612 0.02642327 0.03330689 0.01601576 0.0264247 0.03548443 0.0159794 0.02524524 0.0344944 0.01556551 0.02603691 0.04020386 0.01298034 0.02645468 0.04055804 0.01347136 0.02531963 0.03980427 0.0125547 0.02646917 0.04047763 0.01436078 0.02510589 0.03958874 0.01341694 0.02459901 0.0395652 0.01215672 0.02587002 0.03947645 0.01505666 0.02644985 0.04012054 0.01523387 0.02502584 0.03918677 0.0141983 0.02344745 0.0393067 0.01215732 0.02645081 0.03937232 0.01602232 0.02380019 0.03888553 0.01354551 0.02501821 0.03859275 0.01487398 0.02594536 0.03813791 0.01600396 0.02644914 0.03830564 0.01646322 0.0233187 0.03898435 0.01301175 0.02505159 0.03786081 0.01536411 0.0237149 0.03821527 0.01432496 0.02280092 0.03796124 0.01425671 0.02646726 0.03731238 0.01645523 0.02517688 0.03707796 0.01565909 0.0237832 0.037575 0.01482325 0.02539759 0.036412 0.01576471 0.02358579 0.0367372 0.01511341 0.02453047 0.03606534 0.01549309 0.02645385 0.04011636 0.00904721 0.02645426 0.04018348 0.01212197 0.02590256 0.03981482 0.009738504 0.02547216 0.03965574 0.01058101 0.02592653 0.03984701 0.01146298 0.02644532 0.0399906 0.01076835 0.02645236 0.02896398 0.009443879 0.0255925 0.02928543 0.01116859 0.02644872 0.0289551 0.01135826 0.02558761 0.02928936 0.00981903 0.02647143 0.03732329 0.004442095 0.02548283 0.03637981 0.005114078 0.02645021 0.03840047 0.004451215 0.02594006 0.03787845 0.004854381 0.02512753 0.03724467 0.005287885 0.02415382 0.03588372 0.005496859 0.02412837 0.03687012 0.00564301 0.02570867 0.03858035 0.005359113 0.02645045 0.03945219 0.004940927 0.02501547 0.03788954 0.005576133 0.02569943 0.03929805 0.005976915 0.0264489 0.04008883 0.005626022 0.02645039 0.04045575 0.006415903 0.02470129 0.03866481 0.006333172 0.02377498 0.03806465 0.006396293 0.02594691 0.04013645 0.007065057 0.02284902 0.03672116 0.005911052 0.02507221 0.03943115 0.007098853 0.02301836 0.03771466 0.006413936 0.02645093 0.04054534 0.00748676 0.025191 0.03971481 0.007874369 0.02585005 0.04003882 0.008251607 0.0233848 0.03866899 0.007326841 0.02405416 0.03928333 0.008051931 0.02487713 0.0396226 0.008854389 0.02317732 0.0391007 0.008222639 0.02371025 0.03942239 0.00918442 0.02644485 0.03275781 0.004751384 0.02645295 0.03590142 0.004834234 0.02646237 0.03405416 0.004957497 0.02556365 0.03464478 0.005275249 0.02982938 0.03254872 0.00471735 0.02967834 0.03169322 0.00444734 0.03025454 0.03161412 0.004586815 0.03038239 0.03272068 0.004973411 0.02975541 0.03342503 0.004892051 0.03070169 0.03177958 0.004904568 0.03086602 0.03270161 0.005326986 0.02975755 0.03414106 0.004959046 0.03113299 0.03150027 0.005328476 0.03029632 0.03391116 0.005118966 0.03119152 0.03249335 0.005719304 0.03076839 0.03389036 0.005418837 0.03140395 0.03154456 0.00602442 0.03126138 0.03101891 0.005508124 0.03007245 0.03466826 0.005039215 0.02986371 0.03527504 0.004941701 0.03144407 0.03064441 0.006309151 0.03111791 0.03424155 0.005848705 0.03137302 0.0336827 0.00635153 0.02976357 0.03610759 0.004800736 0.03084921 0.03506231 0.005503356 0.03049188 0.03542971 0.00518912 0.03033578 0.03619581 0.004964232 0.03118431 0.03604418 0.005814671 0.03026092 0.03713405 0.004658401 0.03136736 0.03580421 0.00629878 0.03083741 0.03634673 0.005291461 0.03144401 0.03556072 0.006743431 0.03084242 0.03733468 0.005000352 0.03124761 0.03771406 0.005477368 0.03062498 0.03798884 0.004762649 0.03059005 0.03866612 0.004894435 0.03144448 0.03876501 0.006917715 0.02984201 0.03905165 0.004729986 0.02980291 0.0377193 0.004408895 0.02957987 0.03727835 0.004446744 0.0301755 0.04038655 0.007591962 0.02988177 0.04052817 0.007257342 0.029554 0.04050368 0.006616473 0.02975821 0.04013258 0.00570774 0.02963703 0.04028153 0.008405566 0.03028589 0.03974038 0.005470693 0.02970463 0.03952896 0.005025625 0.02981829 0.03849929 0.00451225 0.03132379 0.03926557 0.007276296 0.0310682 0.0397337 0.007446765 0.03125077 0.03931242 0.006503224 0.03053879 0.04023778 0.007413923 0.0309025 0.03989237 0.006701886 0.03143876 0.03806382 0.006136775 0.0313028 0.03858983 0.005824804 0.03078567 0.03968459 0.00591576 0.03036439 0.04018682 0.006250083 0.03102672 0.03913718 0.005674898 0.03106641 0.03851091 0.005349457 0.03051644 0.03929638 0.005204558 0.03024089 0.03995639 0.009042143 0.02976924 0.04010838 0.009060978 0.03065985 0.03975987 0.008822977 0.02964502 0.04001116 0.009914278 0.03105676 0.03937596 0.008705079 0.030312 0.0398041 0.01058447 0.0312637 0.03894919 0.009018719 0.02977657 0.03998595 0.01079028 0.03076285 0.03952574 0.01009517 0.03140145 0.03845649 0.009563803 0.03114777 0.03905826 0.01028877 0.02986472 0.040039 0.01148778 0.03087812 0.03943604 0.01114696 0.03044855 0.03989446 0.01204615 0.02980715 0.04022359 0.0123552 0.03143894 0.03820341 0.01092022 0.03085929 0.03960651 0.01217031 0.03117161 0.03915214 0.01202315 0.03043848 0.04023188 0.01315969 0.03136837 0.03872078 0.01205724 0.03099656 0.0397951 0.01337099 0.03057587 0.04006022 0.01461577 0.03062158 0.04018276 0.01376551 0.02984845 0.04052156 0.01362431 0.0298919 0.0404734 0.01428997 0.02967911 0.04045122 0.01306474 0.03031742 0.03736734 0.01627814 0.02970963 0.03730636 0.01645112 0.02976989 0.03810703 0.01646459 0.02979272 0.03873807 0.01632016 0.02983319 0.03995901 0.01542335 0.02969628 0.03944635 0.01594513 0.0297743 0.04032987 0.01477807 0.0314387 0.03747713 0.01472783 0.03121125 0.03766763 0.01548683 0.03138667 0.03866446 0.01475471 0.03078329 0.03754323 0.01600021 0.03109675 0.03842598 0.01555263 0.03044414 0.03820592 0.01621288 0.03096497 0.0393427 0.01513826 0.03144323 0.03882825 0.01379704 0.03074568 0.03888994 0.01578271 0.03046369 0.03916174 0.01582813 0.0312764 0.03943645 0.01389884 0.03105604 0.0396918 0.01432347 0.03034663 0.03981238 0.01531958 0.02981775 0.03623712 0.01612669 0.03068131 0.03617227 0.01571822 0.02975463 0.03522425 0.01596575 0.0302661 0.0353958 0.01582413 0.03067582 0.03541636 0.01559311 0.03120517 0.03673839 0.01522886 0.02981394 0.03429394 0.01592493 0.03110575 0.03532308 0.01510876 0.03131866 0.03533327 0.01469302 0.03061687 0.03453141 0.01558327 0.02981036 0.03325134 0.01602542 0.0303567 0.03376197 0.01576966 0.03142243 0.03488171 0.01426911 0.03082317 0.03403431 0.0154227 0.03124469 0.03352302 0.01490712 0.03144538 0.03331959 0.01414388 0.03026103 0.03270506 0.0159986 0.03069889 0.03283458 0.01568078 0.03102034 0.03277069 0.01537024 0.03035116 0.03175133 0.01622891 0.03132867 0.03240591 0.01491868 0.03125435 0.03143429 0.01536673 0.03144401 0.03134328 0.01474165 0.0308957 0.03150445 0.01588815 0.03053843 0.03102308 0.01619631 0.02992653 0.03041684 0.01635044 0.03144115 0.03024613 0.01383113 0.03052425 0.02995938 0.01587247 0.02972739 0.03106808 0.01648354 0.02971696 0.03170704 0.0164445 0.03005957 0.02852952 0.01376569 0.02971619 0.0285021 0.01324766 0.02972453 0.02848875 0.01412284 0.02980303 0.02863216 0.01469224 0.02977681 0.02906095 0.01546114 0.02966314 0.02979916 0.01611602 0.03130388 0.029688 0.01356673 0.03108525 0.02928656 0.01357048 0.0307638 0.02892351 0.01355004 0.03129464 0.02981728 0.01445078 0.0314179 0.03053289 0.01467496 0.03040087 0.02881973 0.01295608 0.03104346 0.02937489 0.01451396 0.03047209 0.02880877 0.01439613 0.03069865 0.0291925 0.01491254 0.03124934 0.03040599 0.01521676 0.03082501 0.02967524 0.01536488 0.03036308 0.02915167 0.0152558 0.03105717 0.03066712 0.0156368 0.02972835 0.02890622 0.01179236 0.03031605 0.02909964 0.01164776 0.0309292 0.02947908 0.01210653 0.03125786 0.02998167 0.01213723 0.02973431 0.02901655 0.01004946 0.03023195 0.02914005 0.01065903 0.03078687 0.02949762 0.01101374 0.03139013 0.03042262 0.01189309 0.03018808 0.02909642 0.00959593 0.03056645 0.02931183 0.009899735 0.03109925 0.02985751 0.01034539 0.02965307 0.02879965 0.008679091 0.03010278 0.02888423 0.008631348 0.03142702 0.03060221 0.00966078 0.03063184 0.02921664 0.008802473 0.03132635 0.03012365 0.00872457 0.03103709 0.02959614 0.008720695 0.03058987 0.02886074 0.007679045 0.03144925 0.03035217 0.006905198 0.03056484 0.02887803 0.006423652 0.03127598 0.02961647 0.007364332 0.03047299 0.02871781 0.007104098 0.03052473 0.02913594 0.005823969 0.02976989 0.02848535 0.00684297 0.0297833 0.02849984 0.007619619 0.02975785 0.03094524 0.004424393 0.03028601 0.03081107 0.004611194 0.02978891 0.03019374 0.004605114 0.0297963 0.02947932 0.005024611 0.03047132 0.03007978 0.004941642 0.02971285 0.02894419 0.005600512 0.02973186 0.02862817 0.006204009 0.03078699 0.03087604 0.004912853 0.03126621 0.03006815 0.005999863 0.03100669 0.03013479 0.005430102 0.03139269 0.02991527 0.006881356 0.03055614 0.02959853 0.00531423 0.03103542 0.02948176 0.006165564 0.03103756 0.02919626 0.007248997 0.01295 0.03463846 0.01195597 0.01295 0.03541135 0.01167386 0.01644998 0.03565239 0.01145029 0.01295 0.03591966 0.01097977 0.01644998 0.03600013 0.01066374 0.01295 0.03600013 0.0102362 0.01644998 0.03585982 0.009738683 0.01295 0.03573501 0.009577095 0.01295 0.03529608 0.009169936 0.01644998 0.03527581 0.009157598 0.01295 0.03466349 0.008940219 0.01644998 0.03448736 0.008915424 0.01295 0.03395962 0.009040236 0.01644998 0.03360551 0.009226858 0.01295 0.03328788 0.00951606 0.01644998 0.03316837 0.009738504 0.01295 0.03297793 0.01043754 0.01644998 0.03299099 0.01034909 0.01644998 0.03316223 0.01119279 0.01295 0.03318423 0.0111956 0.01295 0.03379076 0.01180583 0.01644998 0.03385227 0.01182347 0.01644998 0.03477799 0.01195466 0.03022456 -0.00388354 0.01249808 0.03223025 -0.003881812 0.0124402 0.03019839 -0.003567218 0.01164096 0.03223025 -0.003499805 0.01154386 0.03022533 -0.00275892 0.01081895 0.03223025 -0.002812147 0.01086336 0.03223025 -0.002095341 0.0105701 0.03029984 -0.001494824 0.01047027 0.03223025 -0.001206219 0.01048868 0.0303924 -2.21461e-4 0.01083678 0.03223025 -1.93685e-4 0.01087522 0.03223025 4.65403e-4 0.01150172 0.03046858 5.66738e-4 0.01165622 0.03223025 8.70332e-4 0.01243638 0.03053653 8.75354e-4 0.0125094 0.02962321 8.973e-4 0.03461617 0.03223025 8.90782e-4 0.03463119 0.03066432 8.96975e-4 0.02606725 0.03085827 8.95145e-4 0.01916933 0.03223025 -0.002493202 0.03484749 0.03494995 -0.002462387 0.03500968 0.03223025 -0.002295196 0.03528022 0.03494995 -0.001964092 0.03556418 0.03223025 -0.001874387 0.03559166 0.03223025 -0.001278221 0.03564268 0.03494995 -0.001320898 0.03564548 0.03494995 -8.69917e-4 0.03543317 0.03223025 -8.20629e-4 0.03538739 0.03494995 -5.36853e-4 0.0349707 0.03223025 -5.36133e-4 0.03496003 0.03223025 -5.13712e-4 0.01247686 0.03494995 -5.25409e-4 0.01239758 0.03223025 6.93238e-4 0.03540271 0.02942806 5.8793e-4 0.03561609 0.03223025 1.35552e-4 0.03617215 0.02928459 -8.91073e-5 0.03635537 0.03223025 -5.17672e-4 0.03659456 0.02918475 -0.00100404 0.03676843 0.03223025 -0.001267313 0.03680318 0.02913963 -0.002166032 0.03673356 0.03223025 -0.002331972 0.0366795 0.02917313 -0.003096044 0.0362156 0.03223025 -0.003242194 0.03607904 0.02925485 -0.003645002 0.03551423 0.03223025 -0.003858983 0.03503084 0.0293678 -0.003889143 0.03474563 0.03009498 -0.003908574 0.02972596 0.03043937 -0.003907144 0.02566069 0.03050023 -0.0039047 0.01700198 0.03223025 -7.34495e-4 0.0119813 0.03494995 -7.81177e-4 0.01194411 0.03494995 -0.001360237 0.01163393 0.03223025 -0.001344501 0.01164257 0.03223025 -0.001912117 0.01172769 0.03494995 -0.00207895 0.01180791 0.03223025 -0.002295196 0.01201969 0.03494995 -0.002476215 0.01234591 0.03223025 -0.002491593 0.01244688 0.03021711 0.00462985 0.01238858 0.03223025 0.004609167 0.01254528 0.03223025 0.004983425 0.01153784 0.03009527 0.004966855 0.01160448 0.02994775 0.005496799 0.01100486 0.03223025 0.0056867 0.01088058 0.02966892 0.006623268 0.01048886 0.03223025 0.006403803 0.01055783 0.03223025 0.007536172 0.01053178 0.02938997 0.007800519 0.01062601 0.03223025 0.008499085 0.0110141 0.02920246 0.008632361 0.01111787 0.03223025 0.009015202 0.0115891 0.02908724 0.00932908 0.01219558 0.03223025 0.00936836 0.01241922 0.0287081 0.009395003 0.03138208 0.03223025 0.009354054 0.03502279 0.02809852 0.009348154 0.0349906 0.02931344 0.009395241 0.02566957 0.02946943 0.00939548 0.01903039 0.03223025 0.006006777 0.03484749 0.03494995 0.006017029 0.03491044 0.03223025 0.006204724 0.03528022 0.03494995 0.006401002 0.03549093 0.03223025 0.006625533 0.03559166 0.03494995 0.007129907 0.03565835 0.03223025 0.007221698 0.03564268 0.03494995 0.00763005 0.03543317 0.03223025 0.007755339 0.03532087 0.03494995 0.00796312 0.0349707 0.03223025 0.007980823 0.03486096 0.03223025 0.007982492 0.01244455 0.03494995 0.007981896 0.01244688 0.02805525 0.008875012 0.03591102 0.03223025 0.00876522 0.03603821 0.02811926 0.008246183 0.03646188 0.03223025 0.008099079 0.03654426 0.02830082 0.007277727 0.03680908 0.03223025 0.007228076 0.03680521 0.03223025 0.00610727 0.03666001 0.02864003 0.005971431 0.03660923 0.03223025 0.005188524 0.0360046 0.02897191 0.005078136 0.03586918 0.03223025 0.004629373 0.03496861 0.02922272 0.004628717 0.03491866 0.03010684 0.004595398 0.02898788 0.03059673 0.00459522 0.01957607 0.03494995 0.00769931 0.0119034 0.03223025 0.007765352 0.01199299 0.03223025 0.007190167 0.01164239 0.03494995 0.006995141 0.01162892 0.03223025 0.00658065 0.0117315 0.03494995 0.006404578 0.0118286 0.03223025 0.006204724 0.01201969 0.03494995 0.006028831 0.01232111 0.03223025 0.006008327 0.01244688 0.025123 -0.00561726 0.04695039 0.02367782 -0.01090162 0.04694437 0.0122841 0.02407538 0.02051341 0.009669959 0.0245127 0.01956498 0.02569782 0.01385235 0.004013597 0.02629315 0.01402759 0.007639169 0.02444988 0.01605546 0.006276965 0.02691239 0.01130533 0.002949953 -0.01095128 0.024266 0.03798568 -0.009235918 0.02462428 0.03843039 -0.00908482 0.02416396 0.04105901 -0.0121355 0.02374482 0.03895211 -0.01221495 0.0225532 0.04317224 -0.01505011 0.02242177 0.03964537 -0.009866476 0.02482581 0.03571736 0.02703255 0.009623229 1.61064e-4 -0.006807148 0.0252304 0.03696602 0.02444946 0.01419657 -1.85029e-4 0.02812868 0.006377696 5.50516e-4 -0.006675481 0.02530896 0.0363633 -0.002441227 0.02584385 0.03003418 -0.001115143 0.0257222 0.02512127 6.55073e-4 0.02579134 0.03140169 -0.005955517 0.02564203 0.02928495 -0.003731608 0.02564233 0.02455562 0.02585661 0.01048099 -0.00260812 0.02630293 0.007689595 -0.004388809 -0.01505005 0.02330434 0.03489261 -0.01167321 0.02431976 0.03617906 0.02569544 0.01228731 -1.48809e-4 -0.008670032 0.0252701 0.03205651 -0.008064866 0.02536249 0.03222805 -0.01111471 0.02477735 0.0319131 -0.01252126 0.02436953 0.03258949 0.02445006 0.01266211 -0.003264784 -0.009113252 0.02520328 0.03165429 -0.009333848 0.02517735 0.03092002 -0.01253986 0.02446711 0.0288698 -0.01091814 0.02486622 0.02905434 -0.00911498 0.02522408 0.03025966 -0.01504993 0.02363198 0.02951478 -0.008023738 0.02531564 0.02619016 -0.006394565 0.02534836 0.02323931 -0.007987082 0.02540522 0.02968609 -0.00860691 0.02531123 0.02979379 0.01231133 0.0224055 0.006884336 0.01545017 0.0224837 0.01289433 0.01029181 0.02322143 0.009593307 0.01095277 0.02343219 0.01177239 -0.01067906 0.02478981 0.02454733 0.01545006 0.02085834 0.00311166 -0.01504987 0.02358323 0.02440279 0.00876224 0.02299946 0.006956756 -0.008706271 0.02487409 0.02109682 0.009873926 0.02167892 0.001182913 0.01300424 0.02086609 7.50171e-5 -0.0118907 0.0243448 0.02188563 -0.009996056 0.02446699 0.0191341 -0.01505005 0.02295279 0.01656085 -0.01086103 0.02406418 0.01697039 0.0154491 0.01952236 -0.002444267 0.01142799 0.0201773 -0.003517925 0.006457328 0.02281183 0.004803001 0.004816651 0.0227217 0.003857553 0.01544898 0.01849979 -0.005461931 0.009392261 0.01945191 -0.006247401 0.006022274 0.02138602 -0.001465916 0.01264506 0.01853942 -0.007153391 0.01058799 0.0170564 -0.01104676 0.003329217 0.02189821 1.20052e-4 0.002919077 0.02262151 0.003112256 5.49828e-5 0.0225436 0.002724587 -0.001551151 0.0217145 -5.95701e-4 0.005523681 0.01968848 -0.006396055 0.006794691 0.01740986 -0.01105105 -0.002298593 0.02254164 0.002961039 -0.004561543 0.02259629 0.003670692 -0.01144438 0.02223336 0.005810916 -0.009341597 0.02291572 0.007650911 -0.007243871 0.02272552 0.005300462 -0.01504999 0.02163404 0.007324874 -0.01061117 0.0231418 0.01012527 -0.009410798 0.02202653 0.003144085 -0.007724404 0.02152884 9.11954e-5 -0.01127636 0.02169734 0.002956926 -0.01505023 0.01993691 -7.67334e-4 -0.008027851 0.02037537 -0.003878057 -0.003460586 0.02006524 -0.005495071 -0.01079273 0.02052825 -0.002196788 -0.003721117 0.01892548 -0.00802958 -0.006266534 0.01734685 -0.01105004 -0.01505011 0.01824432 -0.005980432 -0.00830096 0.01922774 -0.006715953 -0.01229703 0.01844084 -0.007154762 -0.01163309 0.0166549 -0.01104551 0.02992159 -8.96241e-4 0.006929457 0.0294106 -0.002966642 0.004602432 0.02991187 0.001760721 0.007005691 0.02694422 0.01485031 0.02106237 0.02612447 0.01592171 0.01828122 0.0277388 0.01335722 0.01797991 0.02859801 0.01161992 0.02345508 0.02882748 0.01111954 0.01907902 0.0289328 -5.34146e-4 0.001040458 0.02852296 -0.004891753 0.001255512 0.02868539 0.007965803 0.005525529 0.0283662 0.0104162 0.009090125 0.02951735 0.004878878 0.006664574 0.02637058 0.01519298 0.01406389 0.02445 0.01783895 0.01831066 0.02445119 0.01698064 0.01075357 0.02236735 -0.01049983 -0.01101875 0.02371758 -0.00654143 -0.01104921 -0.0150485 0.01935815 0.04694008 -0.01244443 0.02077347 0.04695022 0.01117891 0.02372598 0.01435893 0.0107069 0.02411985 0.01715844 -0.01124298 0.02369934 0.01466834 -0.01118361 0.02341908 0.01259279 -0.01504719 0.01559746 -0.01105177 0.02660989 -0.005908429 0.04359972 0.02609401 -0.01087051 0.04171669 0.02790218 -0.005793452 0.03997337 0.02744829 -0.01085388 0.03673648 0.02733892 -9.0883e-4 0.04311579 0.02553123 -0.001535713 0.04694998 0.02873897 -0.005715191 0.03666925 0.02536171 0.002323269 0.04694992 0.02830255 -0.002108037 0.04003471 0.02658468 0.00435394 0.04395866 0.02922403 -0.006372332 0.03314852 0.02829688 -0.01083481 0.03112387 0.02833515 9.23862e-4 0.04003733 0.02452254 0.006465554 0.04695028 0.0277062 0.004574477 0.04092693 0.02928888 -0.007951974 0.02926492 0.02873146 -0.01082414 0.02414143 0.02922135 0.00122869 0.03651887 0.02508121 0.009089887 0.04433727 0.02719795 0.007366836 0.04068231 0.02965223 -0.007911205 0.02389425 0.02496975 0.01100152 0.04291152 0.02306741 0.0102958 0.04695004 0.02659642 0.009803533 0.04003822 0.0236746 0.01345163 0.04278504 0.02120292 0.01350665 0.04694992 0.02133202 0.01591616 0.04364299 0.02735608 0.0104711 0.0365194 0.01854544 0.0165733 0.04695004 0.02567988 0.01356816 0.03735661 0.02537256 0.01251083 0.04003506 0.02190434 0.0171926 0.04017984 0.0238105 0.01500153 0.0400297 0.02815544 0.01097828 0.03145051 0.01961469 0.01820647 0.04245978 0.02444416 0.01631283 0.03495377 0.03025835 -0.005566358 0.01935166 0.01791524 0.01976537 0.04175162 0.01514792 0.0192272 0.04694986 0.02659922 0.01423573 0.031309 0.02445089 0.01669174 0.03347873 0.02267044 0.01825249 0.03495103 0.0146557 0.02093601 0.04346674 0.02068591 0.01915365 0.03767198 0.01964253 0.0205776 0.03495085 0.02969062 -0.006580471 0.01262664 0.02771794 -0.01083129 0.007973849 0.0285387 -0.01082593 0.01609462 0.01165103 0.02198368 0.04428458 0.01594376 0.02137398 0.04028189 0.02445387 0.01751905 0.02934426 0.02977818 -0.005261719 0.01041609 0.01736062 0.02185612 0.03495138 0.01544636 0.02271652 0.03494846 0.02736908 0.0138902 0.02552878 0.01099479 0.02321654 0.04062294 0.02581471 0.0163415 0.02463477 0.02444994 0.01795405 0.02345216 0.02862066 -0.007005631 0.004844963 0.0260995 -0.01085603 -0.001492381 0.01158124 0.02406859 0.03441351 0.005422532 0.02438521 0.04120928 0.005413174 0.02492237 0.03776007 0.004878938 0.02494776 0.03814691 0.01544952 0.02332109 0.02735102 0.0301491 0.003735125 0.0104168 0.008205711 0.02500897 0.03117483 0.005579292 0.0250622 0.03634393 0.02738445 -0.007185161 -0.001343786 0.001456618 0.02504831 0.03996598 0.00361067 0.0251345 0.03788763 0.004133641 0.02503919 0.03817528 0.01276916 0.02412462 0.02827036 0.008120238 0.02505081 0.03042775 0.02639901 -0.006352424 -0.005343317 0.02465605 -0.01086914 -0.006039679 0.006213247 0.02523183 0.03294998 0.006567239 0.02522248 0.03215801 0.007286846 0.02511388 0.0321958 0.004304826 0.02528291 0.03568357 0.006110906 0.02529644 0.03190416 8.35913e-4 0.02550399 0.03647899 0.003207385 0.02524757 0.03726369 0.003648936 0.02532792 0.03597646 0.003285408 0.02532035 0.03646093 0.02761244 0.01239973 0.01041609 0.02772259 -0.004298925 -0.002614676 0.02490615 -0.006538331 -0.00862652 0.01544994 0.02321016 0.02105134 -0.005540788 0.02524203 0.03820866 -0.0061149 0.02518445 0.03807991 -0.004973411 0.02529835 0.03808003 0.006623327 0.02529561 0.0297169 0.007481992 0.02516996 0.02977001 0.005984246 0.02536821 0.03010761 0.005735099 0.02536582 0.03134804 0.02656978 -0.003143668 -0.006281852 0.007590472 0.02514171 0.02497476 0.003316879 0.02554762 0.02465867 0.005465924 0.02532935 0.02371615 0.02676868 -5.22378e-4 -0.006165862 0.02838587 6.67523e-4 -0.001349687 0.02771741 0.003931939 -0.002762198 0.02430635 -0.002281308 -0.01104938 0.005704343 0.02538836 0.03070974 0.02658337 0.002198755 -0.006284475 -0.007361292 0.02548027 0.03202414 -0.006036698 0.02543586 0.03576362 -0.006910562 0.02553486 0.03152334 0.001071691 0.02568238 0.02510899 0.02623951 0.004793524 -0.006245374 0.02414768 0.002214431 -0.01104968 -0.007453322 0.02547919 0.0298227 -0.006918966 0.02554559 0.03034758 0.0244522 0.01058161 -0.006009221 0.02441579 0.00905317 -0.007368803 0.0247358 0.007026791 -0.008049964 0.02307486 0.006900966 -0.01105082 0.02178668 0.009885013 -0.01105099 0.02310979 0.01160341 -0.007405817 0.01989728 0.01274281 -0.01105058 0.02188646 0.01330512 -0.007426142 0.02079582 0.01445555 -0.007470667 0.01923 0.01569396 -0.007515907 0.01725894 0.01489871 -0.01104909 0.01723408 0.01682686 -0.007556378 0.01407217 0.0163123 -0.01104682 0.01545065 0.01755923 -0.007544755 0.02955484 -0.007810771 0.01627868 0.02592921 0.01524662 0.03133183 0.01176065 0.02102261 0.04694962 0.008836805 0.02212709 0.04694741 0.007304608 0.02336347 0.04407989 0.005298316 0.02301532 0.04695069 0.001936554 0.02408295 0.04458016 0.008907854 0.02420246 0.03836542 0.00569415 0.0249499 0.03719681 4.18094e-4 0.02347224 0.04694986 0.02845376 0.01154911 0.01468598 -0.001071751 0.02465456 0.0428192 -0.004457175 0.02391004 0.04488998 0.008946955 0.02463322 0.03476643 0.007932722 0.02502977 0.03175669 0.005008339 0.02518612 0.03581982 0.02862036 0.003677904 5.85448e-4 -0.003642737 0.02326935 0.04694968 -0.0080899 0.02237629 0.0469501 -0.00221467 0.0253238 0.03895658 -0.004487991 0.02538836 0.03762948 -0.004271984 0.02547734 0.03690922 -0.00878632 0.02352887 0.04348313 -0.003237664 0.02578556 0.03314352 -0.004534661 0.02552449 0.03620231 -0.01075685 0.02236896 0.04504352 0.007773041 0.02497357 0.02203357 -0.005105018 0.02552038 0.03575485 -0.01310217 0.02175319 0.04425412 -0.01504987 0.02126973 0.04312521 -0.006783485 0.02555692 0.0309652 -0.006649076 0.02518022 0.03759002 0.03494882 -0.005053043 0.03904789 0.03494942 -0.007011055 0.03716278 0.0349484 -0.003097236 0.0403214 0.03495001 -0.008611083 0.03468638 0.03494995 -0.009625315 0.03177976 0.03494685 -7.39661e-4 0.04124212 0.03494995 8.39848e-4 0.04161643 0.03494995 0.003353655 0.04174876 0.03494995 0.006537437 0.0412181 0.03494995 0.01000368 0.0395171 0.03494995 0.01233023 0.03739035 0.03494995 0.01410359 0.03478205 0.03494995 0.01512897 0.03180211 0.03494793 -0.009126782 0.01460921 0.03494805 -0.008471608 0.01330012 0.03494977 -0.007525503 0.01134884 0.03494995 0.01539868 0.02965283 0.03494995 -0.006337642 0.009517729 0.03494989 -0.00448352 0.007792294 0.03495001 -0.003011941 0.00683248 0.03494995 -3.63407e-4 0.00579518 0.03494995 0.002188205 0.005532562 0.03494995 0.01536411 0.01780295 0.03494989 0.004588365 0.005792796 0.03494995 0.0148735 0.01545506 0.03495013 0.007532775 0.006912767 0.03494954 0.01382559 0.0129289 0.03494912 0.009025871 0.007803916 0.03494989 0.01229137 0.01074278 0.03494995 0.010495 0.008941709 -0.01628214 0.03479069 0.01242393 -0.01754212 0.03453856 0.01117295 -0.01754719 0.03380566 0.01041913 -0.01736915 0.03391224 0.01156109 -0.0172736 0.03452432 0.01184171 -0.01750373 0.03375023 0.01102453 -0.01707875 0.03405332 0.012003 -0.01687157 0.03464239 0.01220768 -0.01631778 0.03351348 0.012187 -0.01624578 0.03409212 0.01240926 -0.01739507 0.03332132 0.01063829 -0.01734435 0.03325724 0.01006686 -0.01620417 0.03309285 0.01186782 -0.01638352 0.03281337 0.01149398 -0.01750564 0.03429323 0.009527504 -0.01754683 0.03486937 0.009864211 -0.01739501 0.03362464 0.009640812 -0.0162087 0.03249275 0.01044213 -0.01624768 0.03262352 0.009745061 -0.01645195 0.0330109 0.009153425 -0.01735275 0.03492099 0.009242415 -0.01620483 0.03336405 0.008795559 -0.01740986 0.03523224 0.009560346 -0.01624166 0.03403049 0.00850588 -0.01754122 0.03516817 0.01080429 -0.01637858 0.03538489 0.008674144 -0.01744288 0.03555589 0.01019138 -0.01619797 0.03574103 0.008881628 -0.01636779 0.03610652 0.009281098 -0.01625829 0.03638225 0.00976932 -0.01663047 0.03439068 0.01234865 -0.01716977 0.03323835 0.01130968 -0.01686531 0.03364908 0.01202237 -0.01670289 0.03316479 0.01174944 -0.01682156 0.03285938 0.01119256 -0.01709336 0.03291147 0.01062977 -0.01682746 0.03271007 0.01023274 -0.01641827 0.03258055 0.01096165 -0.0170716 0.03327864 0.009380817 -0.01675158 0.03287214 0.009579479 -0.01717084 0.03375887 0.009114503 -0.01721125 0.0344547 0.008978009 -0.01667016 0.03357923 0.008808732 -0.01685315 0.03423845 0.008684813 -0.01676976 0.03464734 0.008610665 -0.01684933 0.03535282 0.008883833 -0.01625609 0.0347442 0.008459806 -0.01729518 0.03572118 0.009842336 -0.01710593 0.03562176 0.009311497 -0.01670289 0.03583514 0.009150505 -0.01684427 0.0362088 0.009878158 -0.01734429 0.03581166 0.01052355 -0.0167458 0.03633964 0.01058191 -0.01626276 0.03648447 0.01024901 -0.0162186 0.03647541 0.01076048 -0.01653951 0.0363239 0.01106947 -0.01721704 0.03565281 0.01135563 -0.01720851 0.03503102 0.01182621 -0.01616996 0.036264 0.01140761 -0.01660823 0.03508716 0.01225769 -0.01620703 0.03527039 0.01230037 -0.01695984 0.03610819 0.0110324 -0.01746785 0.0350095 0.01135307 -0.01683002 0.03590977 0.01157045 -0.01671093 0.03548437 0.01204389 -0.01614254 0.03579193 0.01198601 -0.016492 0.03606617 0.01160502 -0.01504999 0.03393703 0.01239037 -0.01504999 0.03303909 0.0118519 -0.01504999 0.03257173 0.01102787 -0.01504999 0.03249865 0.01023352 -0.01504999 0.03276181 0.009427726 -0.01504999 0.03337752 0.008774757 -0.01504999 0.03416627 0.008464872 -0.01504999 0.03486377 0.008476018 -0.01504999 0.03556525 0.008737862 -0.01504999 0.03613114 0.009277284 -0.01504999 0.03647702 0.0100336 -0.01504999 0.03645461 0.01093113 -0.01504999 0.03613263 0.01162379 -0.01504999 0.03549599 0.0122078 -0.01504999 0.03473418 0.01244342 0.03116166 -0.01146852 0.03039193 0.03133314 -0.01128816 0.03056454 0.03097379 -0.01151257 0.03109884 0.03091061 -0.01149564 0.03206443 0.03092604 -0.01136904 0.03329926 0.03067034 -0.01146221 0.03415012 0.03042775 -0.01150208 0.03503191 0.03045934 -0.01139175 0.03593909 0.02992373 -0.01152616 0.03679454 0.02996373 -0.01146501 0.03778755 0.02988284 -0.01141119 0.03843963 0.02948051 -0.01144284 0.03979599 0.02958345 -0.01149684 0.03905093 0.02917921 -0.01153242 0.04007285 0.02900063 -0.01141369 0.04145103 0.02846801 -0.01152312 0.0424357 0.02825558 -0.01143836 0.04337441 0.02812737 -0.01133346 0.04389625 0.02793514 -0.01154166 0.04370182 0.02802968 -0.01156467 0.04322153 0.027368 -0.01156878 0.04485565 0.02659457 -0.01137346 0.04694879 0.02639716 -0.01154822 0.04694914 0.02618974 -0.01168286 -0.008292078 0.0301823 -0.01162266 0.005587816 0.03014194 -0.01168984 0.006418883 0.0304948 -0.01160693 0.007617175 0.03020679 -0.01169133 0.007970988 0.03062468 -0.01163733 0.009132146 0.03117221 -0.01149964 0.01258021 0.03101831 -0.0116387 0.01333051 0.03132593 -0.01155298 0.01542544 0.03125572 -0.01161003 0.01642888 0.03123021 -0.0116133 0.01868754 0.03154391 -0.0115205 0.02044534 0.0314787 -0.01155287 0.02180725 0.03169184 -0.01138371 0.02012169 0.03108125 -0.01153695 0.02929478 0.02624166 -0.01169157 -0.007845401 0.02656328 -0.01148283 -0.008275449 0.02669662 -0.011702 -0.006963014 0.02777796 -0.01164335 -0.004987537 0.02812939 -0.01150774 -0.004421412 0.02711141 -0.01170438 -0.00589019 0.02814048 -0.01171487 -0.002802968 0.02965575 -0.01171147 0.004232525 0.02939951 -0.0117166 0.002495288 0.0304284 -0.01146262 0.00618714 0.03070062 -0.01166641 0.01191425 0.03108155 -0.01163524 0.01607 0.03156501 -0.0112791 0.02791392 0.03164356 -0.01139503 0.02478349 0.03117042 -0.0115472 0.02746373 0.03067898 -0.01152682 0.03227186 0.03081321 -0.01130652 0.0343942 0.03032624 -0.01129311 0.03700774 0.02882778 -0.01154619 0.04082489 0.02602213 -0.01161849 0.04694932 0.02706426 -0.01149696 -0.007194459 0.02860057 -0.01148015 -0.00294888 0.02881455 -0.01152348 -0.002070724 0.02956241 -0.01168006 0.002471089 0.03106522 -0.01142376 0.01092213 0.03152787 -0.01138371 0.0161221 0.03113692 -0.01138204 0.03161895 0.02944934 -0.011312 0.04033124 0.02727657 -0.01162248 -0.006358742 0.02708035 -0.01168394 -0.006491601 0.02767431 -0.01148051 -0.005742609 0.02771908 -0.0117166 -0.004362106 0.02834838 -0.01161116 -0.003387749 0.02823448 -0.01170229 -0.003153204 0.02852493 -0.0116862 -0.002317845 0.02854186 -0.0117188 -0.0013327 0.02888935 -0.0116809 -9.07598e-4 0.02941888 -0.01152473 5.70047e-4 0.02895182 -0.01172244 2.23179e-4 0.02984166 -0.01146185 0.002609133 0.0295729 -0.01160418 0.001801371 0.02984327 -0.01160287 0.003283202 0.03098016 -0.01155447 0.01116341 0.03071117 -0.01166528 0.01067304 0.0313217 -0.01150417 0.01443141 0.03106182 -0.01164221 0.01463919 0.03146988 -0.0115053 0.01691979 0.03144168 -0.0115664 0.01882922 0.0317133 -0.0113489 0.02384394 0.03129392 -0.01158505 0.02196216 0.03135073 -0.01156276 0.02428472 0.03127717 -0.01156443 0.02507412 0.03151774 -0.01150166 0.02468514 0.03147131 -0.0115031 0.02556049 0.03152334 -0.01140469 0.02709919 0.03140133 -0.01151114 0.02664005 0.0301184 -0.01150113 0.03670132 0.02990448 -0.01129603 0.03876113 0.02952527 -0.01153486 0.03858047 0.02871203 -0.01136356 0.04240983 0.02828234 -0.01156115 0.04237002 0.02762663 -0.01134127 0.04499065 0.02731949 -0.01157897 0.04447668 0.02716708 -0.01151472 0.04557341 0.02681291 -0.01159501 0.04583531 0.0263192 -0.01161652 0.04661571 0.02661502 -0.01162827 -0.007795572 0.02806484 -0.01167261 -0.003950119 0.02909165 -0.01160246 -5.91447e-4 0.02930402 -0.01169049 0.001138269 0.02980601 -0.01169466 0.004212439 0.03013312 -0.01156246 0.00479573 0.03079736 -0.01155185 0.009524405 0.03044664 -0.01168596 0.009174823 0.03092783 -0.01163887 0.01220542 0.03110522 -0.01162308 0.01408219 0.03151845 -0.01150089 0.01795327 0.03138512 -0.01158791 0.0201556 0.03164529 -0.01145046 0.02181857 0.03147292 -0.01154279 0.02352017 0.03132396 -0.011491 0.02817636 0.03140181 -0.01139688 0.0288515 0.03052008 -0.01152563 0.03388774 0.02883303 -0.01152253 0.04137605 0.02762937 -0.01149004 0.04465073 0.03038382 -0.01167899 0.008110046 0.02623808 -0.01142394 -0.008851706 0.02557241 -0.01162809 -0.008905827 0.02467077 -0.01145565 -0.009765684 0.02585667 -0.01135104 -0.00935322 0.02487349 -0.01144349 -0.009870707 0.02535003 -0.01128435 -0.009828686 0.02464854 -0.01108676 -0.0103656 0.02456635 -0.01127117 -0.01025176 0.02386134 -0.0112161 -0.01040303 0.02335494 -0.01100516 -0.01071143 0.02275919 -0.01074326 -0.01090711 0.02613633 -0.0116043 -0.008683502 0.02555233 -0.01154673 -0.009365141 0.02350473 -0.01115679 -0.01040816 0.02388185 -0.01091873 -0.01071709 0.02304953 -0.01064503 -0.01096826 0.02243155 -0.01082867 -0.01065975 -0.01504999 0.02276301 0.04694998 -0.01257336 0.02396982 0.04695022 -0.008441269 0.02539169 0.04694992 0.02789765 -0.006983995 0.04695022 -0.003417372 0.02633297 0.04695034 0.02844345 -0.003281414 0.04694998 0.001752197 0.02643084 0.0469498 0.02853178 1.54369e-4 0.04694998 0.02815878 0.003919243 0.04694998 0.006086051 0.02590143 0.04695004 0.02727484 0.007748425 0.04694998 0.01020985 0.02480685 0.0469501 0.014072 0.02325421 0.0469501 0.0259515 0.01120024 0.04694992 0.02459239 0.01378601 0.04694998 0.01728469 0.02139878 0.04694974 0.02306622 0.01604306 0.04694914 0.0206179 0.01876145 0.04694831 -0.01505059 0.02448815 0.04356336 -0.009049236 0.02793258 0.03702241 -0.01020258 0.02796447 0.03403836 -0.0133 0.02717334 0.03395724 -0.01329994 0.02736467 0.02954012 -0.01078897 0.02796453 0.02823978 -0.0133 0.02721017 0.02412694 -0.008548319 0.02796316 0.0212872 -0.009895682 0.0275433 0.01932281 -0.0133 0.02676212 0.01855868 -0.01072108 0.02718687 0.01740425 -0.01117658 0.02684968 0.015365 -0.0132997 0.0254845 0.00893265 -0.01124578 0.02654999 0.01327288 -0.01090526 0.02629166 0.01111662 0.008327126 0.02796685 0.03241258 0.008971929 0.02793389 0.03090333 -0.01015633 0.02607417 0.00908488 -0.008598268 0.0258516 0.006635487 0.01545017 0.02592599 0.03495031 0.01543289 0.02580171 0.03580069 0.01295006 0.02712661 0.02953535 0.00925076 0.02796471 0.02797836 0.008800089 0.02778267 0.02084082 0.008056461 0.02796477 0.02169799 -0.01505029 0.02168172 -0.005184769 0.01294976 0.02720183 0.02438455 0.009926855 0.02747642 0.01907539 -0.0128892 0.02081406 -0.008288919 0.02973532 0.0048514 0.04359114 0.01294994 0.02663403 0.01600277 0.01078557 0.02713102 0.01688277 0.0111503 0.02680897 0.01454967 0.02990525 0.002800822 0.04384011 0.03019583 8.10266e-4 0.04358083 0.01106572 0.02655613 0.01245129 0.0303418 -0.001807689 0.04318547 0.01295 0.02534085 0.006953001 0.01049071 0.0263074 0.01007932 0.009252429 0.02608376 0.007666528 0.03129982 -0.009361922 0.03491687 0.01544922 0.02164381 -0.005372166 0.01544994 0.02172273 -0.005045294 0.03133833 -0.01003921 0.03346526 0.01307296 0.02087265 -0.008494436 0.01705998 0.019656 -0.008539855 0.01702553 0.02126526 -0.005050122 0.02094292 0.01771742 -0.008269608 0.01956534 0.02015578 -0.005039036 0.01869916 0.01891976 -0.008519053 0.02233737 0.01845586 -0.005050539 0.02328062 0.01557886 -0.008319079 0.03218621 -0.008814573 0.01345086 0.03215658 -0.009309649 0.01535183 0.03195315 -0.01026672 0.01689392 0.03207987 -0.008644938 0.01110953 -0.0118395 0.02575898 0.04347133 -0.01318091 0.02631813 0.03999376 -0.009050011 0.02700722 0.04194492 -0.01505011 0.02591967 0.03872787 -0.006051599 0.02756011 0.04195016 -0.003285169 0.02778196 0.0419178 -0.01504665 0.02650272 0.03529918 8.04046e-4 0.02720057 0.04444903 0.001556456 0.0277208 0.04193019 -0.001130759 0.02782112 0.04190695 0.005116403 0.02733159 0.04195249 0.008207142 0.0262143 0.04410552 0.007947921 0.02687174 0.04188698 0.007096529 0.02696424 0.04194992 0.01157915 0.02535265 0.04370987 0.01514619 0.02462446 0.0417208 0.01107144 0.02643519 0.03997719 0.007950127 0.0275585 0.03768867 0.0181716 0.02239334 0.04347497 0.01102459 0.0273112 0.03442776 0.01295018 0.02684694 0.03379839 0.007965445 0.02798575 0.03268259 0.02187031 0.02018398 0.04251497 0.01804333 0.02369421 0.03999817 0.008764445 0.02792739 0.03182494 0.0220254 0.02148973 0.03905838 0.01834368 0.02472275 0.03495156 0.02656203 0.01465386 0.04257965 0.02161628 0.02287673 0.03495132 0.02445167 0.02066874 0.03495109 0.02753669 0.01191079 0.04351025 0.0291571 0.01037788 0.04142194 0.02652478 0.01635509 0.04003119 0.02864789 0.01453071 0.03722715 0.0288248 0.01286053 0.03938734 -0.01330024 0.02230328 -0.004680752 -0.009884595 0.02118724 -0.008572876 -0.009313464 0.02321743 -0.004036903 0.02944779 0.007592976 0.04285031 0.02619302 0.01804155 0.03751885 0.02855676 0.01605284 0.03393054 0.02444988 0.02150088 0.03034257 0.02722841 0.01834172 0.03217071 0.02861356 0.01674872 0.03100067 -0.007033944 0.0214408 -0.008642256 0.02445286 0.02191191 0.0261352 -0.004218459 0.0235933 -0.004055619 -0.001859903 0.02157527 -0.008750975 0.03039455 -0.004625916 0.04235225 0.03055721 -0.00554496 0.04152357 0.005295693 0.02315139 -0.005273938 0.002970576 0.02164036 -0.008684039 0.005817472 0.02404719 -0.002641677 0.02630621 0.02024614 0.01889199 0.0290538 0.01712012 0.0179556 0.02903735 -0.008796811 0.04350286 0.01051115 0.0238319 -0.001868247 0.01295 0.02387446 -1.10475e-4 0.01295036 0.02254563 -0.004627287 0.03056401 -0.008195698 0.03956967 0.008331418 0.0214979 -0.008578121 0.01022887 0.02271413 -0.005325615 0.02445441 0.02015626 0.006024479 0.02445036 0.02135294 0.01352775 0.02929228 0.01585292 0.01162815 0.01530575 0.0202555 -0.008556306 0.02445006 0.01839822 -7.81617e-4 0.02445167 0.01652812 -0.005050837 0.02500844 0.01307743 -0.00856626 0.02657455 0.0134741 -0.005340516 0.02674192 0.009534299 -0.00860691 0.02806359 0.01049536 -0.005343616 0.03000563 0.008433163 -0.002053439 0.02846819 0.01139229 -0.00347042 0.02913105 0.007309496 -0.005345463 0.03072714 0.004334032 -0.002611279 0.03162074 0.005329847 0.001573383 0.02759164 0.00650078 -0.008775472 0.02980363 0.003997206 -0.005346119 0.03103512 8.90256e-4 -0.002610981 0.03203386 -5.40406e-4 0.001523792 0.03191888 0.002096056 0.00122559 0.02846574 0.002955198 -0.008411765 0.03009891 6.36821e-4 -0.005345821 0.03113716 -0.003702223 -0.001578807 0.02847981 -2.77682e-4 -0.008767247 0.03001952 -0.002701163 -0.005344688 0.02842116 -0.002817332 -0.00874406 0.02983248 -0.005963623 -0.004660844 0.02797967 -0.005842745 -0.00881952 0.02904427 -0.00914067 -0.004384398 0.02761369 -0.008081197 -0.008528947 -0.008175015 0.02645677 0.04444158 -0.001909136 0.0272141 0.04443323 0.02446126 0.01755464 0.04258185 0.02410161 0.01925671 0.04002302 -0.01045012 0.02453488 0.001381218 -0.01329976 0.02371627 6.49649e-5 -0.006205499 0.02567732 0.004562079 -0.005748987 0.02474617 1.70503e-4 0.026165 0.01890194 0.0349617 -0.004086792 0.02558958 0.003484785 0.02632647 0.0194866 0.03168737 -0.001265168 0.02553629 0.002764642 0.02639865 0.01986938 0.02880531 0.02874588 0.01699417 0.02867341 0.02715671 0.01919126 0.02758169 0.02885615 0.01727294 0.0260424 0.002790927 0.02491366 1.34495e-4 0.001649618 0.02557802 0.002862691 0.003711521 0.02566015 0.003382802 0.02670538 0.01997321 0.02252894 0.0244497 0.02188676 0.0199061 0.006458759 0.02491843 7.36839e-4 0.006075859 0.02579295 0.004529237 0.02890133 0.01741486 0.02185994 0.009377181 0.02494704 0.001999616 0.007899224 0.02593713 0.00604695 0.02672731 0.01940488 0.01387071 0.02897244 0.01679271 0.01436001 0.02752906 0.01749682 0.008018314 0.02982652 0.0143066 0.008785605 0.02813076 0.0163623 0.006643116 0.02634584 0.0175606 0.002851009 0.03050184 0.01233464 0.006538569 0.02780449 0.01560527 0.002446174 0.02847671 0.01523876 0.004484415 0.02587646 0.01666998 -0.001467466 0.02690243 0.01443368 -0.003294825 0.0292533 0.01242774 8.01851e-4 0.03065377 0.01050847 0.003701984 0.03001523 0.01031965 3.47681e-4 0.03118914 0.008103013 0.002516806 0.03090852 -0.007504761 8.29482e-4 0.03179043 -0.006050407 0.003859221 0.03198873 -0.003411173 0.002332866 0.0307824 -0.00816679 0.03888589 0.03118103 -0.008202135 0.03767949 0.03140497 -0.008298218 0.03685635 0.03184694 -0.008442819 0.03559249 0.0314213 -0.008826494 0.03557068 0.03103399 -0.008681774 0.03719526 0.03233557 -0.008611202 0.03469443 0.03183859 -0.008884668 0.03457123 0.03152424 -0.009162306 0.03462171 0.03249561 -0.009092688 0.03354763 0.03249651 -0.009655654 0.03159469 0.03144639 -0.01049864 0.03172677 0.03209918 -0.009083807 0.03382873 0.0324276 -0.009444713 0.03251647 0.03193914 -0.009606361 0.0326963 0.03153651 -0.009662091 0.0335226 0.03166288 -0.01015341 0.03172457 0.03184121 -0.01001942 0.03140044 0.03258836 -0.009670436 0.03055357 0.03218209 -0.009846627 0.03041362 0.03251498 -0.009847939 0.02580547 0.03314936 -0.009646773 0.02272576 0.03290969 -0.009667277 0.02662914 0.03277766 -0.009750008 0.02234184 0.03224295 -0.01011705 0.02358818 0.03204959 -0.01041877 0.02209889 0.03248524 -0.009870469 0.01839947 0.03264403 -0.009768366 0.01782554 0.03287148 -0.009659588 0.01593846 0.0331096 -0.00965023 0.0201745 0.03244066 -0.009834766 0.01626819 0.0327689 -0.009669363 0.02855736 0.03168618 -0.01033395 0.03043746 0.03246086 -0.009822189 0.02752864 0.03213834 -0.009946405 0.02926558 0.031861 -0.01038902 0.02796733 0.03212976 -0.01005059 0.02795821 0.03223323 -0.01006931 0.02578324 0.03201162 -0.01038295 0.02525836 0.03230559 -0.01006841 0.02188557 0.03277337 -0.009752154 0.02097582 0.03209167 -0.01030796 0.02016067 0.03217214 -0.01012063 0.01792001 0.03195756 -0.01034528 0.01699686 0.03279542 -0.009731233 0.01925605 0.03244328 -0.009929716 0.01982861 0.03361159 -0.00826019 0.03530853 0.0328173 -0.007966935 0.03600537 0.0340234 -0.006971359 0.03721845 0.03280472 -0.007154643 0.03747016 0.03256446 -0.006022393 0.03885167 0.03331285 -0.006753087 0.03769683 0.03389787 -0.00592494 0.03834199 0.03197956 -0.007733225 0.03731876 0.031147 -0.007702112 0.03876036 0.03171002 -0.007128894 0.0385462 0.03428447 -0.001900136 0.04087483 0.03385502 0.001751244 0.04172223 0.03352451 0.004273653 0.04167318 0.03241306 0.006710112 0.04117679 0.0330609 0.007940828 0.04065275 0.03236931 0.009852766 0.03959357 0.03209328 0.01129561 0.03845816 0.03151702 0.01474767 0.03317826 0.03162688 0.0154069 0.02963477 0.03494822 -0.009633541 0.01546865 0.03296422 -0.00894916 0.0143339 0.03286433 -0.008592486 0.01279997 0.03359687 -0.008021533 0.01142847 0.03406393 -0.00858134 0.01340574 -0.01504921 0.01630294 -0.01100361 0.02605676 -0.008876621 -0.009960889 0.02698761 -0.00772798 -0.00947386 0.02623188 -0.00699079 -0.01025074 0.02757763 -0.004053115 -0.009636163 0.02329415 0.01476228 -0.009141147 0.02263826 0.0142064 -0.009994804 0.02195262 0.01595437 -0.009343087 0.01944041 0.0172311 -0.009884238 0.02058571 0.01737809 -0.009043395 0.02365761 -0.008916318 -0.01097637 0.02536153 -0.01027834 -0.01010847 0.0249533 -0.006606459 -0.01085805 0.02498841 -0.008513927 -0.01064252 0.02485805 -0.003834724 -0.01099592 0.02614504 -0.004670679 -0.01056826 0.02554726 -0.003128111 -0.01085716 0.02554219 -5.55315e-4 -0.01089006 0.02783429 5.66473e-4 -0.009543359 0.02551013 0.002626836 -0.01083618 0.02451843 0.004379391 -0.011002 0.02439254 0.007336795 -0.01087534 0.02780592 0.003849625 -0.009207546 0.02260071 0.01001673 -0.01100528 0.02352643 0.01030886 -0.01076781 0.02048939 0.01316034 -0.01099717 0.02098506 0.01373124 -0.01081466 0.02582865 0.01062238 -0.009202361 0.02065771 0.01523721 -0.01046395 0.0190683 0.01518511 -0.01087009 0.01605868 0.01716756 -0.01077723 0.01566803 0.01654237 -0.01097416 0.01865047 0.0165897 -0.01050239 0.01252293 0.01801455 -0.01083427 0.01402777 0.01848083 -0.0105046 0.01078259 0.01784408 -0.0109561 0.008038043 0.01798975 -0.0109843 0.01250833 0.02047306 -0.009234845 0.007338881 0.01875752 -0.01082181 0.007936298 0.02106535 -0.009217798 0.006269097 0.02061522 -0.009797334 0.004850983 0.0211215 -0.009331941 0.001390337 0.02118653 -0.009295642 -0.005892872 0.02090007 -0.009454011 -0.004798412 0.01909351 -0.01071119 -0.009083926 0.01851111 -0.01079559 -0.009096741 0.02078086 -0.009307205 -0.01223039 0.0178548 -0.01084715 -0.01227754 0.02048069 -0.009043097 -0.01504725 0.01712113 -0.0108276 -0.01504969 0.01990926 -0.008848071 0.02679097 -0.00292468 -0.01032781 0.02483791 0.001594603 -0.01100826 0.02629524 -4.57504e-4 -0.01063162 0.02710139 4.66384e-4 -0.0101599 0.02635425 0.003258764 -0.01046508 0.0273118 0.002582728 -0.00987339 0.02568519 0.00544846 -0.01058471 0.02656471 0.005791246 -0.01003205 0.02523368 0.008054792 -0.01045739 0.02683019 0.007281541 -0.009442806 0.0258134 0.008860588 -0.009895026 0.02438282 0.01090908 -0.01024907 0.02428466 0.01247167 -0.009737133 0.01792997 0.01512444 -0.01101237 0.02258861 0.0129494 -0.01052772 0.01728498 0.01794344 -0.01015377 0.01669025 0.01755207 -0.01051318 0.01848614 0.01845347 -0.009257614 0.01503419 0.01874035 -0.01019716 0.01616817 0.01923847 -0.009505569 0.01390665 0.01973748 -0.009671211 0.0125159 0.01942843 -0.01016288 0.009855985 0.02023255 -0.009881198 0.01042562 0.01929396 -0.01046103 0.006121218 0.02012014 -0.01018416 0.00585556 0.01950687 -0.01054835 0.004485607 0.01818257 -0.01098132 7.84885e-4 0.02080297 -0.009708046 -0.002611875 0.01852494 -0.01092052 3.55122e-4 0.01888447 -0.01082187 1.52451e-4 0.01947438 -0.01059228 3.08676e-4 0.02012574 -0.01023662 -0.003133356 0.02053415 -0.009900391 -0.003617823 0.0197333 -0.01043242 -0.005892157 0.01814085 -0.01096451 -0.008806288 0.01777744 -0.01098674 -0.00587517 0.01972633 -0.01039344 -0.007960855 0.02002453 -0.01009094 -0.009518861 0.01942974 -0.01036876 -0.01220679 0.01874542 -0.0104891 -0.01214444 0.01965975 -0.009916603 -0.0150482 0.01837134 -0.0102809 -0.01504975 0.0190894 -0.009746968 -0.01504999 0.03824228 0.01189279 -0.01504999 0.03850817 0.01073741 -0.01504999 0.03838312 0.009422659 -0.01504999 0.03766286 0.007932066 0.01295 0.0329411 0.01314997 0.01295 0.03138226 0.01044994 0.01295 0.03605884 0.01314997 0.01295 0.0329411 0.007749974 0.01295 0.03761768 0.01044994 0.01295 0.03605884 0.007749974 0.009949982 0.03138226 0.01044994 0.009949982 0.0329411 0.01314997 0.009949982 0.0329411 0.007749974 0.009949982 0.03605884 0.007749974 0.009949982 0.03761768 0.01044994 0.009949982 0.03605884 0.01314997 0.01029062 0.03440278 0.0144394 0.01037788 0.03519064 0.01439267 0.01013588 0.03489845 0.01433032 0.01029813 0.0357241 0.0142495 0.01003491 0.0354501 0.01412707 0.00995332 0.03555679 0.01388132 0.01015859 0.03613042 0.01401567 0.01035016 0.03651952 0.01390278 0.01000869 0.03639197 0.01369857 0.01017922 0.03680628 0.01363193 0.01036882 0.03714835 0.01345044 0.009957969 0.03691846 0.0131756 0.0101481 0.03722643 0.01326096 0.0103299 0.03769195 0.01285535 0.01004719 0.03761959 0.01264911 0.009953498 0.0375753 0.01232588 0.01036214 0.03811669 0.01216161 0.01013308 0.03798937 0.01220589 0.0103144 0.03834021 0.01153898 0.01011812 0.03826671 0.01139223 0.009996294 0.03808164 0.01149713 0.01031398 0.03848391 0.0107817 0.009955108 0.03813087 0.01018822 0.01001787 0.03824502 0.01086902 0.01014155 0.03840637 0.01027619 0.01034367 0.03845602 0.009865999 0.01003479 0.03825604 0.009852766 0.01029711 0.03828316 0.009173631 0.009952962 0.03752636 0.00849694 0.01010167 0.03809279 0.009004533 0.01033592 0.03785789 0.00827372 0.01016896 0.0378561 0.008416533 0.01000124 0.03779447 0.008658289 0.01033341 0.03733491 0.007635354 0.01013988 0.03731638 0.007740736 0.01000624 0.03732025 0.007981896 0.01030409 0.03691428 0.007273793 0.009961724 0.03681987 0.007622659 0.01005434 0.03649997 0.007187962 0.01030015 0.03626996 0.006870925 0.01009893 0.03599447 0.006886065 0.009960174 0.03557336 0.006964087 0.01029545 0.03570187 0.006648659 0.01030248 0.03522372 0.006525754 0.0100919 0.03526681 0.00666362 0.01034659 0.03468972 0.006457805 0.009962141 0.03451496 0.006798267 0.01011842 0.03468328 0.006569266 0.01032376 0.03403186 0.006481409 0.01008808 0.03401595 0.006619453 0.01027733 0.03335094 0.00663346 0.01005637 0.03315025 0.006870806 0.00995773 0.03332906 0.007008135 0.01025694 0.03276968 0.006865501 0.01036262 0.0321533 0.007208824 0.01017689 0.03221058 0.007255375 0.009994745 0.03240084 0.007362425 0.01034647 0.03157722 0.007719874 0.0101298 0.03172147 0.007723033 0.009989917 0.03174322 0.007959306 0.01030337 0.03119444 0.008214116 0.01004862 0.03133088 0.008321702 0.00995177 0.03158086 0.008323192 0.01016676 0.031084 0.008528172 0.01036781 0.03085792 0.008798182 0.01012277 0.03084766 0.009090185 0.01034945 0.03062057 0.009475708 0.009957134 0.03102642 0.009399175 0.0101701 0.03059786 0.009976983 0.010019 0.03081059 0.009692132 0.01037126 0.03049504 0.0103513 0.01005083 0.03068709 0.01048254 0.01020872 0.03056883 0.01077413 0.009959757 0.03087472 0.01079481 0.01028889 0.03057557 0.011155 0.01003885 0.03080302 0.01134228 0.01030194 0.03074139 0.01179009 0.0101183 0.03085023 0.01177603 0.01030045 0.03102916 0.0124244 0.009952783 0.03125923 0.01201528 0.01010823 0.0311324 0.01236879 0.01000547 0.03135579 0.01251143 0.01036131 0.03129327 0.01284337 0.01007986 0.03151232 0.0128746 0.01026272 0.03162783 0.01320481 0.01028442 0.03205627 0.01359653 0.009960711 0.03203564 0.01313173 0.01005399 0.0321756 0.01347875 0.01034355 0.03241825 0.013861 0.01017481 0.03266543 0.01392596 0.01037538 0.0330376 0.01417607 0.009958326 0.03285771 0.01368665 0.01003432 0.0331341 0.01400035 0.01016479 0.03321462 0.01415377 0.010365 0.03386306 0.01440423 0.01014292 0.03375965 0.01428455 0.009954154 0.03401583 0.01402205 0.01000374 0.03451758 0.01420551 0.01545083 0.03187221 0.008423566 0.01545095 0.03273683 0.007647871 0.01545059 0.03136825 0.009389698 0.01546525 0.03320449 0.007390677 0.01545065 0.03425377 0.007149875 0.01545023 0.03130739 0.01131558 0.01545011 0.03160047 0.01204097 0.01545 0.03759002 0.007854282 0.01545059 0.03653466 0.007834315 0.01545 0.03548347 0.007278442 0.01546233 0.03208553 0.01272118 0.01545703 0.03723108 0.008570432 0.01545 0.03263741 0.0131849 0.01545035 0.03349214 0.01360893 0.015459 0.03755384 0.009162008 0.01545 0.03837591 0.009364008 0.01545929 0.03780013 0.01010167 0.01545906 0.03780692 0.01073527 0.01544988 0.03473502 0.01375323 0.01545 0.03849673 0.01092725 0.01545059 0.03759735 0.01161277 0.01545 0.03817176 0.01205265 0.01544994 0.03717631 0.01240146 0.01545351 0.03543782 0.01362246 0.03413426 -0.0067932 0.009430706 0.03345471 -0.007125675 0.00913316 0.03274554 -0.007200062 0.008150458 0.03171968 -0.008524119 0.007859826 0.03174757 -0.008068799 0.006768882 0.0322346 -0.00815171 0.008965015 0.03266644 -0.008251249 0.01065587 0.03036564 0.01559132 0.03072053 0.03053075 0.0157234 0.0284878 0.0306496 -0.006749153 0.0405631 0.03109049 -0.006068706 0.04029577 0.0317229 -0.005617737 0.03984665 0.03359615 -0.004984855 0.03921395 0.0315743 -0.003833711 0.04106909 0.03106623 -0.003877639 0.04158598 0.0325846 -0.004260301 0.04010152 0.03348934 -0.003578782 0.04015457 0.03248482 -0.00284177 0.04088014 0.03337454 -0.002312481 0.04078412 0.03317141 -0.001039326 0.04127472 0.03230834 -8.49093e-4 0.04162579 0.03316223 4.74802e-5 0.04154658 0.03213387 5.09956e-4 0.04194569 0.03301262 0.001551747 0.04178369 0.03202998 0.002060413 0.04208976 0.0318399 0.003563225 0.04208296 0.03261399 0.004244029 0.04176819 0.03022748 0.00587368 0.04265952 0.03103154 0.004891097 0.04225552 0.03086239 0.006417453 0.04190802 0.03164952 0.005446732 0.04181432 0.03010249 0.008376002 0.04159176 0.03080356 0.008280456 0.04109448 0.03145235 0.007321476 0.04123979 0.02978283 0.009612441 0.04112595 0.03203409 0.008556842 0.04043233 0.0305742 0.01006233 0.04008203 0.02962613 0.01171046 0.03948336 0.03123843 0.00917989 0.04034131 0.03013575 0.01101201 0.03962755 0.03173768 0.01033502 0.03933751 0.03100383 0.01088786 0.03916263 0.03068816 0.01211088 0.03807789 0.03166228 0.01195883 0.03785037 0.03153818 0.01289147 0.03673589 0.03056508 0.01303392 0.03697603 0.03044444 0.01390886 0.03565382 0.03140014 0.01377797 0.03537511 0.03034549 0.01467746 0.03410804 0.03134191 0.01428294 0.03439861 0.03124761 0.0149905 0.03246128 0.03034406 0.01522731 0.03246539 0.03135126 0.01533466 0.03074753 0.02935445 0.01593297 0.03176558 0.0295192 0.01343876 0.03738278 0.02933722 0.01480609 0.0351994 0.03110814 -0.001511633 0.0422734 0.03094553 8.47689e-4 0.04276078 0.03063595 0.003196418 0.04288679 0.02946138 0.01638919 0.02813965 0.02998101 0.01615107 0.02712231 0.03056854 0.01581001 0.02716761 0.03179234 0.01540619 0.02843147 0.03177005 0.01540249 0.02677345 0.03299909 0.01540571 0.02428495 0.03148084 0.01570004 0.0248388 0.0299623 0.01641684 0.02500808 0.03000563 0.01649451 0.02129256 0.02897083 0.01729649 0.02021211 0.03079879 0.0160281 0.01992833 0.03183662 0.01564025 0.02071887 0.03286713 0.01541668 0.01868009 0.0325039 0.006680905 0.004478096 0.03188717 0.006589293 0.003368854 0.03322321 0.006666719 0.005332887 0.03236645 0.008510053 0.005568981 0.03397411 0.008243143 0.006828129 0.03333324 0.009132325 0.007017254 0.03347516 0.01056152 0.00838375 0.03154706 0.008510947 0.004157006 0.03204315 0.009940087 0.006430327 0.0312156 0.01008599 0.005102336 0.03242641 0.01047444 0.007434844 0.03121411 0.01145356 0.00689882 0.03084427 0.01277792 0.008273124 0.03209489 0.0121231 0.009156763 0.03327256 -0.005698502 0.007221817 0.03427559 -0.004953026 0.007635951 0.03398394 -0.003381907 0.006266891 0.03363603 -0.002029538 0.00520575 0.03404974 -6.80356e-4 0.005189657 0.03319895 -0.001304805 0.004412174 0.0343753 8.78204e-4 0.005177676 0.03318953 3.67714e-4 0.004047632 0.03348588 0.001754581 0.004338383 0.03333157 0.00373435 0.004381537 0.03428399 0.003164947 0.005143165 0.03296548 -0.003896594 0.005270957 0.03252726 -0.005845129 0.006036877 0.03383392 0.01312577 0.01172333 0.03419238 0.004930496 0.005446791 0.03417354 0.006578922 0.006035745 0.03401428 0.01162338 0.009788453 0.0328862 0.01294624 0.01102733 0.03168386 0.01326978 0.01052218 0.0321716 -0.005913138 0.005224585 0.03271746 -0.003403306 0.004543423 0.03232026 -0.003909051 0.003946721 0.03268069 -0.00110042 0.003454923 0.03241014 -0.001184821 0.002881586 0.03259998 0.002167284 0.003083586 0.03229188 0.002143979 0.002442121 0.03215348 0.004597008 0.002876818 0.03287184 0.004854798 0.004147112 0.03050523 0.01415181 0.01039016 0.03292191 0.01510703 0.01620888 0.03400439 0.01429706 0.01387232 0.0327574 0.01408451 0.01304578 0.03162091 0.01426756 0.01243913 0.03247791 0.01475834 0.01465976 0.0307793 0.01495105 0.01303857 0.02962869 0.01575464 0.01264518 0.03111493 0.01567029 0.0167557 0.03258436 0.01534414 0.01748567 0.03010058 0.0155434 0.01338195 0.03110462 0.01522988 0.01463222 0.02972793 0.01640856 0.0164178 -0.0133 0.03762882 0.007909774 0.01295 0.03660899 0.007023036 -0.009186267 0.02796435 0.03263133 -0.00905013 0.02896434 0.0326842 -0.009502172 0.02896434 0.03234392 -0.009968459 0.02796435 0.03161203 -0.01000803 0.02896434 0.0314837 -0.01004636 0.02796435 0.03076529 -0.009990334 0.02896434 0.03038704 -0.009873747 0.02796435 0.03008973 -0.009558439 0.02896434 0.02961874 -0.009155452 0.02796435 0.02924966 -0.009051024 0.02896434 0.02921211 -0.009049952 0.02895367 0.04084634 -0.009049952 0.02837836 0.04166191 -0.009049952 0.02772521 0.04193764 -0.006740629 0.02796435 0.02295213 -0.009049952 0.02796435 0.02494996 -0.004954099 0.02796435 0.02403724 -0.009049952 0.02796435 0.02894997 -0.002499282 0.02796435 0.02491283 -0.009049952 0.02896434 0.02894997 0.00795257 0.02796435 0.02920931 0.007910251 0.02896434 0.02913749 0.008474409 0.02896434 0.02962416 0.008642911 0.02796435 0.02983117 0.008888244 0.02896434 0.03040903 0.008930206 0.02896434 0.03139466 0.008523046 0.02896434 0.0321967 0.007955908 0.02896434 0.03269761 0.007949948 0.02758097 0.04194808 0.007949948 0.02797299 0.04186791 0.007949948 0.0285291 0.04153192 0.007949948 0.02895855 0.04076284 0.00635308 0.02796435 0.02316981 0.007949948 0.02796435 0.02494996 0.004300951 0.02796435 0.02428793 0.007949948 0.02796435 0.02894997 0.002203464 0.02796435 0.02493816 -0.00666505 0.02896434 0.03756159 -0.006039738 0.02896434 0.03812742 -0.006808459 0.02896434 0.03690057 -0.00519818 0.02896434 0.03817212 -0.006667792 0.02896434 0.0363664 -0.006120324 0.02896434 0.03580111 -0.008971214 0.02896434 0.03185075 -0.008245229 0.02896434 0.03221035 -0.009318232 0.02896434 0.03109997 -0.007621407 0.02896434 0.03214585 -0.009201288 0.02896434 0.03040111 -0.007174611 0.02896434 0.03186684 -0.005281984 0.02896434 0.03571295 -0.008639752 0.02896434 0.02980315 -0.006875216 0.02896434 0.03143364 -0.006782531 0.02896434 0.03090417 -0.007704615 0.02896434 0.02970874 0.003779232 0.02896434 0.03804427 -0.004468917 0.02896434 0.03764021 0.003285408 0.02896434 0.03743225 0.003194689 0.02896434 0.03674942 -0.004291296 0.02896434 0.03681683 -0.004600763 0.02896434 0.03609836 0.003591537 0.02896434 0.03600734 0.005544185 0.02896434 0.03759151 0.005104243 0.02896434 0.03802412 0.004579842 0.02896434 0.03820616 0.005707681 0.02896434 0.0369873 0.006015598 0.02896434 0.03180664 0.004456102 0.02896434 0.03566765 0.006535053 0.02896434 0.03216022 0.005704402 0.02896434 0.03124487 0.005188226 0.02896434 0.03592842 0.005729913 0.02896434 0.03060567 -0.006977736 0.02896434 0.03024208 0.007162034 0.02896434 0.03219974 0.00559175 0.02896434 0.03640437 0.007733404 0.02896434 0.03196018 0.006010711 0.02896434 0.03008699 0.008165597 0.02896434 0.03134578 0.00818336 0.02896434 0.03062498 0.007374048 0.02896434 0.02974987 0.007873654 0.02896434 0.03007781 0.006655752 0.02896434 0.02970272 -0.001860916 0.02696436 0.02501577 0.002063453 0.02696436 0.02494996 7.0355e-4 0.02696436 0.02514261 -0.002163469 0.02746438 0.02494996 0.002063453 0.02746438 0.02494996 -0.009049952 0.02746438 0.02894997 0.007949948 0.02746438 0.02894997 -0.009049952 0.02746438 0.02494996 0.007949948 0.02746438 0.02494996 0.01570683 0.03430461 0.01371967 0.01570737 0.03373354 0.0136395 0.01598221 0.0341084 0.01358634 0.01621884 0.03413945 0.0133841 0.01641148 0.03411483 0.01302599 0.01575148 0.03306245 0.01337808 0.01607388 0.03345179 0.0133624 0.0156514 0.03265172 0.01317274 0.01626169 0.03341114 0.01313894 0.01603943 0.03287667 0.01311653 0.01636672 0.03309822 0.01279306 0.01585435 0.03220874 0.01272654 0.01644808 0.03365164 0.01272451 0.01619076 0.03255891 0.01272559 0.01572149 0.03180897 0.01231205 0.01607906 0.03202694 0.01229685 0.01644325 0.03263533 0.01209276 0.01569718 0.03152394 0.0118305 0.01634424 0.03222543 0.01203501 0.01595366 0.03153622 0.01160913 0.01619887 0.03182929 0.01176643 0.01571172 0.03127729 0.01103383 0.01619166 0.03153878 0.01089918 0.01639568 0.03193855 0.01115828 0.01545786 0.03117901 0.01033633 0.0159161 0.0313031 0.01056462 0.01573169 0.03131771 0.009673535 0.01634341 0.03173142 0.01032108 0.01607352 0.03144627 0.009916722 0.01565665 0.03153252 0.009037494 0.01599997 0.0316531 0.00909239 0.01644694 0.03205192 0.01049339 0.01625931 0.03176474 0.009475588 0.01640456 0.03198438 0.009724497 0.01584559 0.03193503 0.00848788 0.01629918 0.03200405 0.009076118 0.01573044 0.0323159 0.008010208 0.01622515 0.03221964 0.00857532 0.0164467 0.0324034 0.009186625 0.01608771 0.03243905 0.008155405 0.0158956 0.03289449 0.00767076 0.01642131 0.03269964 0.008615136 0.0162841 0.03297907 0.008006751 0.01575738 0.03365367 0.007294178 0.01605463 0.03334504 0.00756675 0.01644033 0.03338253 0.008218765 0.0163173 0.03347527 0.007832288 0.01570594 0.03432297 0.007173895 0.01612693 0.03392529 0.007451057 0.01606631 0.03453934 0.007339954 0.01636904 0.03421914 0.007741987 0.01565909 0.03492522 0.00719124 0.01644384 0.0343225 0.008000373 0.01570856 0.03566354 0.007381796 0.01595634 0.03519207 0.007351279 0.01625639 0.03506636 0.007594823 0.01571112 0.03619796 0.007645726 0.01603937 0.03592473 0.007670402 0.01622158 0.03569734 0.007752358 0.01639539 0.03526967 0.007907807 0.01567381 0.03686046 0.008163094 0.01594203 0.03659194 0.008055865 0.01622563 0.0365166 0.00828725 0.01644057 0.03594213 0.008350729 0.0159434 0.03703063 0.008521199 0.01642525 0.03629457 0.008619904 0.01580983 0.03741675 0.009032249 0.01623332 0.03695845 0.008849382 0.01604443 0.03730648 0.009091079 0.0157113 0.03767025 0.009626805 0.01637703 0.03687494 0.009179234 0.01608407 0.03752243 0.009795963 0.01628512 0.03721719 0.009534299 0.01644682 0.03678542 0.009581208 0.0159437 0.03768491 0.01039278 0.01626145 0.03740024 0.01034379 0.01641064 0.03709065 0.01021546 0.01571911 0.03761941 0.01145875 0.01586616 0.03765422 0.01108765 0.01613175 0.03748089 0.01105809 0.01635259 0.03722029 0.01089876 0.01600939 0.0374037 0.01164567 0.01570367 0.03732705 0.01210767 0.01644355 0.03691047 0.01098936 0.01624655 0.03719687 0.01155483 0.01564848 0.03695499 0.01264208 0.01606976 0.03706842 0.01218587 0.01639366 0.03684258 0.01169526 0.01635283 0.03680038 0.01198738 0.01602751 0.0368334 0.01254463 0.01545131 0.03637456 0.01318705 0.01579844 0.03644078 0.01305371 0.01606523 0.03634339 0.01294606 0.01630038 0.03635305 0.01260459 0.01564449 0.03592669 0.01341259 0.01644504 0.03624761 0.01216053 0.01605081 0.03578174 0.01329237 0.01565104 0.0353015 0.01364308 0.01598197 0.03544574 0.01346468 0.01635134 0.03583562 0.01286447 0.01643908 0.03516316 0.01288163 0.01578468 0.0348854 0.01367813 0.01628595 0.03495204 0.01329225 0.01604801 0.03475284 0.01355063 0.01295 0.03499937 0.0144568 0.01295 0.03664898 0.0138542 0.01295 0.03777629 0.01278597 0.01295 0.03515052 0.006476938 0.01295 0.03355818 0.006535768 0.01295 0.03211337 0.007207751 0.01295 0.03104245 0.008387625 0.01295 0.03051316 0.009890496 0.01295 0.03060835 0.0114811 0.01295 0.03131324 0.01291018 0.01295 0.03251731 0.0139538 0.01295 0.03363734 0.01436203 -0.0133 0.03837299 0.009357035 -0.0133 0.03850603 0.01057398 -0.0133 0.03832775 0.01167094 0.02213937 0.01843488 -0.005050063 0.02445 0.01165354 -0.006677746 0.02445054 0.01627629 -0.005051553 0.01294219 0.0330249 0.01295971 0.01287913 0.03297889 0.01305872 0.01277899 0.03302067 0.01313716 0.01274126 0.03291696 0.01308971 0.01281702 0.03141194 0.01046395 0.01294779 0.03148883 0.01026421 0.01046276 0.03156894 0.0104404 0.01060974 0.03144079 0.01037263 0.01053351 0.03147989 0.01048672 0.01063817 0.03142881 0.01051068 0.01293718 0.03596854 0.01298648 0.01286077 0.03601425 0.0130819 0.0127539 0.03608942 0.01308006 0.01274245 0.03596293 0.01314526 0.01064652 0.0330156 0.01314115 0.01053762 0.03304952 0.01309114 0.01060247 0.03292185 0.01307868 0.01046347 0.0330159 0.01298135 0.01280325 0.03609132 0.007839381 0.01277488 0.03599107 0.007762849 0.01293492 0.03595894 0.007897496 0.01277875 0.03300642 0.007757782 0.01294094 0.03285288 0.007894992 0.01046484 0.03300869 0.007919847 0.01052719 0.033055 0.007813692 0.01064836 0.03301483 0.007758855 0.01061576 0.03290742 0.007832944 0.01294684 0.03738391 0.01045256 0.01289719 0.03749787 0.01046121 0.01278173 0.03756946 0.0103935 0.01276469 0.03756469 0.0105248 0.01061099 0.03607994 0.01308184 0.01062345 0.03596335 0.01314008 0.01046884 0.03596144 0.01301324 0.01045244 0.03594368 0.007957577 0.01049911 0.0359981 0.007859468 0.01061791 0.03607904 0.007816135 0.01062428 0.03596866 0.007759571 0.0106461 0.03757619 0.01040244 0.01052409 0.03750103 0.01037305 0.01065903 0.03756415 0.01053404 0.01053673 0.03751844 0.01050919 0.01045525 0.03739643 0.01046061 0.01044976 0.033508 0.01147103 0.01048088 0.03411316 0.01194709 0.01045018 0.03318196 0.01078331 0.01045775 0.03318899 0.01014542 0.01046234 0.03479498 0.01195508 0.01045042 0.03537416 0.01173681 0.01046758 0.03339213 0.009705722 0.01045048 0.03441435 0.009002327 0.01045107 0.03591603 0.009794175 0.01046395 0.03604716 0.01047086 0.01045066 0.03595119 0.01103174 0.01045006 0.03528255 0.009187221 0.01294344 0.03443038 0.0119971 0.01292639 0.03508836 0.0118891 0.0129497 0.03545385 0.01167505 0.01288318 0.03575241 0.01138025 0.01294243 0.03596282 0.01098859 0.01285296 0.03603535 0.01064884 0.0129373 0.03600853 0.01018273 0.01283282 0.0360006 0.01007872 0.01292777 0.03582465 0.009676396 0.01280772 0.03568357 0.009445369 0.01287531 0.03553545 0.009305238 0.01277792 0.0350458 0.008998155 0.01284623 0.03478831 0.00891298 0.01274967 0.03423315 0.008922874 0.01281076 0.03387421 0.009032607 0.012717 0.03344047 0.009308218 0.01277881 0.03314989 0.009657561 0.01267987 0.03296542 0.01017552 0.01274591 0.03296047 0.01047909 0.01269406 0.03304189 0.01099824 0.01263177 0.03332751 0.01145726 0.01269626 0.03354299 0.01167875 0.01261091 0.03378051 0.01181727 0.01262968 0.03429383 0.0119965 0.01263695 0.03505903 0.01191657 0.01256138 0.03507232 0.01189911 0.01253366 0.03573811 0.0113902 0.01260596 0.03579407 0.01131474 0.01249897 0.03605943 0.01056426 0.0125789 0.03603166 0.01064783 0.01255255 0.03595709 0.009877502 0.01247239 0.03589922 0.009799599 0.01248598 0.03553879 0.009286999 0.01243245 0.03513252 0.009044885 0.01249814 0.03485262 0.008937239 0.01240128 0.03432607 0.008895635 0.01247096 0.03412544 0.008955657 0.01245051 0.03360253 0.009195029 0.01236683 0.03341746 0.009332478 0.0124216 0.03310406 0.009763062 0.01233333 0.03298586 0.01010751 0.01238942 0.0329625 0.01071017 0.01230412 0.03302592 0.01092195 0.01235949 0.03329145 0.011406 0.01227581 0.0334357 0.01158273 0.01233416 0.03389984 0.01189583 0.01223951 0.03429752 0.01200246 0.01230198 0.03470456 0.01198023 0.01221227 0.03509974 0.0118758 0.01227682 0.03540188 0.01172751 0.01218998 0.03559911 0.01153647 0.01220381 0.03592085 0.01109701 0.01222342 0.0360617 0.01041209 0.01214307 0.03605031 0.01032978 0.01215249 0.03584718 0.009667515 0.01216757 0.03533482 0.009131073 0.01209688 0.03546833 0.00925064 0.01206701 0.0347715 0.008913755 0.01213765 0.03459811 0.008913338 0.01208478 0.03401637 0.008971095 0.01201277 0.03338748 0.009363412 0.01209568 0.03351467 0.009267866 0.01207053 0.03308004 0.009824991 0.01198911 0.03303372 0.009981334 0.01200759 0.03294742 0.01051062 0.01202547 0.03307616 0.01103723 0.01194375 0.03312373 0.01116478 0.0119726 0.03343486 0.01159024 0.01193809 0.03399038 0.0119245 0.01192253 0.03454935 0.01200765 0.01193493 0.03518807 0.01184499 0.01185822 0.03519773 0.0118364 0.01183456 0.03569453 0.01143431 0.01190459 0.03579729 0.01130515 0.01180565 0.03604501 0.01070058 0.01188176 0.03602355 0.01071274 0.01185786 0.03600311 0.01007956 0.01177328 0.03592121 0.009825825 0.01183104 0.03562074 0.009363174 0.01173609 0.03529679 0.009099721 0.01179558 0.03481251 0.008929848 0.01170557 0.03435122 0.008906126 0.01177018 0.03408539 0.008962035 0.01167434 0.03362548 0.009173452 0.0117464 0.03353321 0.009252667 0.01169443 0.03315752 0.009663224 0.01162177 0.03293853 0.01038879 0.01169329 0.03294014 0.01049792 0.01158702 0.03324258 0.01137661 0.01166421 0.03322553 0.01133406 0.0116378 0.03375107 0.01180034 0.01155608 0.03389447 0.01187455 0.01160913 0.03457146 0.0120185 0.01153117 0.03458869 0.01199817 0.01150667 0.03521972 0.01182073 0.01156944 0.03554379 0.01161414 0.01148653 0.03567403 0.01145696 0.01150006 0.03598517 0.01093065 0.01148033 0.03605639 0.01034528 0.01150053 0.03592759 0.009854853 0.01141881 0.03585445 0.009702503 0.01147526 0.03555458 0.009315788 0.01139515 0.03545343 0.009233474 0.01144665 0.03476071 0.00890839 0.01137632 0.03496366 0.008980572 0.011348 0.03422361 0.008919417 0.01141428 0.03396362 0.009007513 0.01135998 0.03352075 0.009241819 0.01133906 0.03315967 0.009664177 0.01128244 0.03298866 0.01013851 0.01135188 0.03296113 0.01031309 0.01126062 0.03298747 0.01076197 0.0113309 0.033028 0.01091402 0.01122683 0.03338176 0.01154661 0.01130306 0.03339546 0.01154297 0.01124143 0.03403317 0.0119366 0.01125806 0.03453886 0.01199257 0.01117223 0.03477859 0.01198256 0.01123577 0.03516149 0.01185309 0.01114612 0.03549784 0.01163804 0.01120156 0.03583174 0.01128029 0.01111036 0.0360015 0.01090139 0.01117324 0.03604739 0.01047104 0.01111912 0.03599679 0.01001191 0.01109671 0.0357483 0.009514451 0.01104235 0.03537148 0.009175598 0.01110821 0.03511279 0.009018659 0.0110203 0.03481334 0.008940517 0.01107686 0.03428632 0.008918523 0.01099812 0.03420174 0.008931338 0.01105099 0.03360491 0.009186089 0.01096773 0.03346192 0.009295225 0.01098459 0.03309088 0.009783744 0.01096272 0.03294301 0.01037931 0.01097774 0.03303408 0.01095432 0.01089555 0.03310155 0.01111596 0.0109477 0.03357505 0.01171272 0.01087373 0.03350424 0.01162981 0.01084315 0.03419619 0.01197957 0.01091545 0.0343272 0.01198303 0.01085954 0.03489977 0.01195716 0.01086401 0.03560435 0.01156508 0.0107879 0.03561902 0.01154792 0.01076143 0.03599268 0.01084768 0.01083099 0.03605645 0.01061826 0.01073247 0.03601992 0.0100997 0.01079869 0.0359131 0.009829699 0.0107091 0.03570896 0.009495019 0.01077455 0.03549915 0.009254872 0.01068848 0.03528118 0.009118139 0.0107122 0.03482443 0.008930444 0.01069068 0.03426259 0.008911132 0.0106213 0.03356778 0.009205222 0.01070421 0.03370696 0.009131133 0.01068019 0.03321444 0.009587347 0.01059037 0.03300982 0.009987175 0.01065725 0.03298318 0.01017737 0.0106337 0.03299885 0.0108143 0.01055747 0.03299713 0.01081317 0.01053172 0.0333566 0.01150465 0.01061075 0.03329128 0.01141786 0.01058715 0.03376388 0.01180434 0.01056712 0.03429931 0.01198256 0.01054584 0.03490012 0.01194763 0.01052182 0.03546392 0.01165658 0.01049947 0.03588169 0.01116383 0.01292771 0.03347927 0.009589254 0.01292645 0.03327536 0.009913206 0.0129252 0.03315418 0.01034969 0.01287341 0.03318816 0.01074707 0.01294982 0.03319412 0.01113891 0.01284921 0.03343033 0.01126146 0.01295167 0.0337677 0.01180511 0.01282268 0.03384584 0.0116226 0.01279914 0.03450745 0.01179552 0.01276433 0.03525096 0.01156502 0.01274514 0.03559392 0.01121962 0.01271933 0.03583735 0.010634 0.01269376 0.03581273 0.01014643 0.01267397 0.03558033 0.009661972 0.01265364 0.03526508 0.009352564 0.01263755 0.03485393 0.009160995 0.01261687 0.03438347 0.009122431 0.01259595 0.0337609 0.009328782 0.0125662 0.03337723 0.00973612 0.01254522 0.03319644 0.01017099 0.01253074 0.03317445 0.01059114 0.01250994 0.03328913 0.01100218 0.01248997 0.03356927 0.01141035 0.01246786 0.0340619 0.01172101 0.01245683 0.03479588 0.01176905 0.012416 0.03519374 0.01160001 0.0123955 0.0355637 0.01126068 0.01237499 0.03577113 0.01087081 0.01235496 0.03583902 0.01035839 0.01232701 0.03563576 0.009726107 0.01230138 0.03517687 0.009298086 0.01227253 0.0346086 0.009113788 0.01228505 0.03429782 0.009123027 0.01224815 0.03393661 0.009239137 0.01222753 0.03355294 0.009513497 0.01220631 0.03325611 0.009951949 0.01218587 0.03316414 0.01042181 0.01215755 0.03333222 0.01110756 0.01215898 0.03361147 0.01145654 0.01212096 0.03385585 0.01162928 0.01209706 0.03446787 0.01179039 0.01208192 0.03490656 0.01172125 0.01206403 0.03525173 0.01155459 0.01204127 0.03561335 0.01119905 0.01201641 0.03583627 0.01060885 0.01198941 0.0357564 0.009991466 0.01196688 0.03546553 0.009518325 0.01193195 0.03488492 0.009162962 0.01194709 0.03458911 0.009106159 0.01190763 0.03418219 0.009151875 0.01188617 0.03366565 0.009404659 0.01186341 0.03334796 0.009761095 0.01183813 0.03316622 0.01033073 0.01181024 0.03325837 0.01095789 0.01182085 0.03342008 0.01124483 0.01178377 0.0336771 0.01150321 0.01175701 0.03431522 0.01178193 0.01173168 0.03486168 0.01173567 0.01170992 0.03531074 0.01151734 0.01169312 0.03564381 0.01114749 0.0116707 0.03580123 0.01075232 0.01165151 0.03582394 0.01022499 0.01162731 0.03563958 0.009737372 0.01160281 0.03520023 0.009309947 0.01158136 0.03470033 0.009129464 0.01156014 0.03422284 0.009148001 0.01153957 0.03380793 0.009310841 0.01152455 0.03347355 0.009600698 0.01150268 0.03320515 0.01010376 0.01147538 0.03316134 0.01060867 0.0114519 0.03338956 0.01118606 0.01143157 0.03371703 0.01153349 0.01141512 0.03408932 0.01171928 0.0113973 0.03449314 0.01178443 0.01137518 0.03504657 0.01167899 0.01135432 0.0354377 0.01140999 0.01132547 0.03579837 0.01079541 0.0113002 0.03582167 0.0102337 0.01127052 0.03560012 0.00967586 0.01128458 0.03539878 0.009447753 0.01124626 0.0350517 0.009232044 0.01122558 0.03459292 0.009120225 0.01120483 0.03419798 0.009152352 0.01119297 0.03376019 0.009338617 0.01117122 0.03344291 0.00963664 0.01114422 0.03317075 0.01027399 0.01111871 0.03322124 0.0108214 0.01109838 0.03343129 0.01125144 0.01107591 0.03385484 0.01162642 0.01104432 0.0344578 0.01179075 0.01102769 0.03495693 0.01171892 0.01100581 0.03540486 0.01143974 0.01098304 0.03572463 0.01101487 0.01096826 0.03583329 0.01058083 0.01096409 0.03578954 0.01004791 0.01093953 0.03548538 0.009533107 0.01090139 0.03523826 0.009328484 0.01087689 0.03466051 0.009117901 0.010854 0.03408503 0.009180963 0.01083219 0.03364276 0.009433031 0.01080858 0.03330367 0.009848654 0.0107913 0.03316831 0.01033616 0.01075816 0.03325027 0.01092582 0.01077121 0.033405 0.01123797 0.01072978 0.03365206 0.01149648 0.01070755 0.03422284 0.01175856 0.01069033 0.03467464 0.01177716 0.01066863 0.03523552 0.01157677 0.01064544 0.03557604 0.01126474 0.01062291 0.03578627 0.01085138 0.01059883 0.03581422 0.01018702 0.01057791 0.0356462 0.009757399 0.0105552 0.03529244 0.009376406 0.01053291 0.03478294 0.009141087 0.01051235 0.03426724 0.009139537 0.01047599 0.0337606 0.009340107 0.01294887 0.03482806 0.00910145 0.01294076 0.0340169 0.009190142 0.01275897 0.03488409 0.01173609 0.01257753 0.0339713 0.009216845 0.01242291 0.03454667 0.01179927 0.01214843 0.03320497 0.01078724 0.01174664 0.03398895 0.01169103 0.01131671 0.03566205 0.01112282 0.01113408 0.03325921 0.009947061 0.0109142 0.03573286 0.009891867 0.0321303 0.007371842 0.02024132 0.03183025 0.007403492 0.02021598 0.03183025 0.007876157 0.01986432 0.0321303 0.007921338 0.01980471 0.03183025 0.008129537 0.01930159 0.0321303 0.008141756 0.01919776 0.03183025 0.008012831 0.01863867 0.0321303 0.007960021 0.0185495 0.03183025 0.00761938 0.01820033 0.0321303 0.007601797 0.0181939 0.0321303 0.006985664 0.01799905 0.03183025 0.006975948 0.01800251 0.03183025 0.006195783 0.01831686 0.0321303 0.006324291 0.01823264 0.0321303 0.005881309 0.01883661 0.03183025 0.005836904 0.01916933 0.0321303 0.00596255 0.01963686 0.03183025 0.006118655 0.01987344 0.0321303 0.006495237 0.02018803 0.03183025 0.006675243 0.0202521 0.0321303 0.007171452 0.01679718 0.03183025 0.007407069 0.01681363 0.0321303 0.008095204 0.01704627 0.03183025 0.008509457 0.01731514 0.0321303 0.008853018 0.01769214 0.03183025 0.009167194 0.01821386 0.0321303 0.009336233 0.0186966 0.03183025 0.009368896 0.01930844 0.0321303 0.009287834 0.01969134 0.03183025 0.009023129 0.02036714 0.0321303 0.00900346 0.02039933 0.03183025 0.008283972 0.02114552 0.0321303 0.008464992 0.02099317 0.0321303 0.007748842 0.02139329 0.03183025 0.007346928 0.02148413 0.0321303 0.006918132 0.02150714 0.03183025 0.00631237 0.021429 0.0321303 0.006113469 0.02134472 0.03183025 0.005224227 0.02073866 0.0321303 0.005198597 0.02070957 0.03183025 0.004707753 0.01975184 0.0321303 0.004686534 0.01967686 0.03183025 0.004653573 0.01881611 0.0321303 0.004660367 0.01881653 0.0321303 0.004916787 0.01801818 0.03183025 0.005022883 0.01782858 0.0321303 0.005535185 0.0172891 0.03183025 0.005796194 0.01711112 0.0321303 0.006354808 0.01687437 0.03183025 0.006528139 0.01684015 0.03183025 -0.001151621 0.02023017 0.0321303 -7.62043e-4 0.02002066 0.03183025 -5.75895e-4 0.01982951 0.0321303 -3.78171e-4 0.01936811 0.03183025 -3.71204e-4 0.01918739 0.0321303 -5.37015e-4 0.0185135 0.03183025 -4.87169e-4 0.01863867 0.03183025 -8.80572e-4 0.01820033 0.0321303 -0.001099586 0.01809269 0.03183025 -0.001524031 0.01800251 0.0321303 -0.001627385 0.01801764 0.03183025 -0.002304136 0.01831686 0.0321303 -0.002317786 0.01833015 0.03183025 -0.002663016 0.01916933 0.0321303 -0.002662539 0.0191884 0.03183025 -0.002381324 0.01987344 0.0321303 -0.002299368 0.01997804 0.03183025 -0.001824736 0.0202521 0.0321303 -0.00152409 0.02030438 0.0321303 -0.001328527 0.01679718 0.03183025 -6.60168e-4 0.01694798 0.0321303 -2.9572e-4 0.01709461 0.03183025 9.26921e-5 0.0174002 0.0321303 5.8915e-4 0.01803153 0.03183025 7.68031e-4 0.0184285 0.0321303 8.51447e-4 0.01899206 0.03183025 8.24016e-4 0.01954174 0.0321303 7.3978e-4 0.01990413 0.03183025 5.23158e-4 0.02036714 0.0321303 1.66457e-4 0.02083593 0.03183025 -2.15985e-4 0.02114552 0.0321303 -7.51139e-4 0.02139329 0.03183025 -0.001152992 0.02148413 0.0321303 -0.001581788 0.02150714 0.03183025 -0.00218755 0.021429 0.0321303 -0.00238651 0.02134472 0.03183025 -0.003275752 0.02073866 0.0321303 -0.003301382 0.02070957 0.03183025 -0.003779232 0.01978987 0.0321303 -0.003813385 0.01967686 0.03183025 -0.003854393 0.01885557 0.0321303 -0.003839552 0.01881653 0.0321303 -0.003583192 0.01801818 0.03183025 -0.003477036 0.01782858 0.0321303 -0.002964735 0.0172891 0.03183025 -0.002703726 0.01711112 0.0321303 -0.002145111 0.01687437 0.03183025 -0.001642763 0.01677489 0.03758096 -0.002164602 0.01987636 0.03758049 -0.002277016 0.01952165 0.03756868 -0.001905202 0.01988351 0.03758132 -0.001729726 0.02011287 0.03756594 -0.001619577 0.01997786 0.03758764 -0.00249046 0.0191974 0.03758037 -0.002366304 0.01890283 0.03757971 -0.001182138 0.01992976 0.0375806 -7.51443e-4 0.01978468 0.03757113 -0.002279281 0.01854687 0.03756701 -7.9751e-4 0.01962506 0.03759044 -0.001988708 0.01829195 0.0375778 -0.001696288 0.01818686 0.03758841 -5.76659e-4 0.01945233 0.03758078 -5.24556e-4 0.01915985 0.037584 -6.17527e-4 0.01872229 0.0318365 -6.53988e-4 0.01865714 0.03187859 -5.18412e-4 0.01910185 0.03183418 -0.001470088 0.01998561 0.03189134 -6.01561e-4 0.01955682 0.03182882 -6.06235e-4 0.01942086 0.03191888 -9.50267e-4 0.01997405 0.03183054 -0.001045048 0.019872 0.03193551 -0.001374244 0.02012777 0.03194576 -0.001708269 0.0201109 0.03184711 -0.001890003 0.01989692 0.03196758 -0.002125978 0.01992845 0.03188365 -0.00224018 0.01955211 0.03198659 -0.002415716 0.01952594 0.03190588 -0.002347707 0.01908868 0.03200501 -0.002494156 0.01905101 0.03190439 -0.002169787 0.0186581 0.0320248 -0.002340614 0.01863265 0.03203558 -0.002055525 0.01832669 0.03191936 -0.001909792 0.01842987 0.03193831 -0.001557528 0.01832044 0.03205883 -0.001756668 0.01819318 0.03207856 -0.001211285 0.0181998 0.03198599 -0.001089513 0.01840722 0.03209614 -8.30052e-4 0.01843142 0.03209257 -6.29217e-4 0.01870381 0.03201615 -6.95982e-4 0.01889371 0.03211891 -5.3314e-4 0.01892453 0.03204202 -7.12843e-4 0.0194332 0.03214055 -5.58771e-4 0.01944565 0.03215801 -8.49234e-4 0.01989769 0.03203886 -0.001008033 0.01981675 0.0321781 -0.001392066 0.02013087 0.03206533 -0.001437902 0.01997995 0.03220963 -0.001876115 0.02007108 0.032072 -0.001753389 0.01994234 0.03222256 -0.002299845 0.01974314 0.03212743 -0.002176344 0.01965916 0.03214895 -0.00233823 0.0192418 0.03224527 -0.002483189 0.01929146 0.03226631 -0.002457618 0.01888507 0.03213298 -0.002316176 0.01897799 0.03215724 -0.002117931 0.01858794 0.03228962 -0.002152144 0.01838934 0.03219139 -0.001624524 0.01831996 0.03229004 -0.001727998 0.01819455 0.03231668 -0.001486659 0.01815485 0.03220576 -0.001164853 0.01839292 0.03233838 -0.00104922 0.01827538 0.0322507 -8.56005e-4 0.01861137 0.03234779 -6.92124e-4 0.0185827 0.03224974 -6.70733e-4 0.01912641 0.03237241 -5.20538e-4 0.01902502 0.03227025 -7.37059e-4 0.01947736 0.03238904 -5.59651e-4 0.01943236 0.03240567 -7.62219e-4 0.01981014 0.03228545 -9.7447e-4 0.01978838 0.03232896 -0.001258552 0.01995897 0.03242707 -0.00109142 0.0200482 0.03244054 -0.001535236 0.02013683 0.03233087 -0.001754999 0.01994019 0.03246104 -0.001923799 0.02004271 0.03246891 -0.00220406 0.01984673 0.03234761 -0.002130746 0.01969993 0.03249084 -0.002440989 0.01947671 0.03236883 -0.002321124 0.01929485 0.03250145 -0.00248897 0.01910549 0.03241842 -0.002299249 0.01883286 0.03251922 -0.002393126 0.0187174 0.03253906 -0.002043902 0.01831185 0.03245103 -0.001821458 0.01836079 0.03256618 -0.001576006 0.018166 0.03247547 -0.001300334 0.01833701 0.03257513 -0.001188814 0.01821559 0.03246182 -0.001013219 0.0184797 0.0325908 -8.6587e-4 0.01840204 0.03261148 -6.06218e-4 0.01872187 0.03251349 -7.23044e-4 0.01884263 0.03262877 -5.21717e-4 0.01924562 0.032534 -6.75528e-4 0.01927059 0.03264492 -6.18561e-4 0.01958787 0.03255599 -8.52687e-4 0.01968526 0.03266775 -8.14018e-4 0.01985687 0.0326724 -0.001131951 0.02006417 0.03258091 -0.001302182 0.01997041 0.03268557 -0.001487851 0.02013629 0.03256934 -0.001594662 0.01998108 0.03270918 -0.001891851 0.02005666 0.03260046 -0.002113044 0.01972383 0.03271734 -0.002221286 0.01983129 0.03264296 -0.002318084 0.01936662 0.03274637 -0.002434849 0.01947808 0.03274828 -0.002493262 0.01915645 0.03266555 -0.002306938 0.01889622 0.03277242 -0.00240153 0.01873433 0.03277683 -0.002160131 0.01840949 0.032691 -0.00199455 0.01845777 0.03281015 -0.001784861 0.01819789 0.03269058 -0.001526474 0.01831662 0.03281986 -0.001299977 0.0181837 0.03271412 -0.001088976 0.01842427 0.03284221 -9.00295e-4 0.01836854 0.03276437 -7.10083e-4 0.01886147 0.03286308 -5.87725e-4 0.01876801 0.03288543 -5.29611e-4 0.01936119 0.03276634 -7.15767e-4 0.01942074 0.03290235 -7.81277e-4 0.01981866 0.03282058 -0.001091182 0.01989626 0.03292298 -0.001049816 0.02002543 0.03294467 -0.001550436 0.02014499 0.03284847 -0.001673996 0.01997488 0.03296345 -0.002099573 0.01994895 0.03287482 -0.002142548 0.01970815 0.03298467 -0.00242412 0.01951146 0.03287488 -0.002338886 0.01914787 0.03300178 -0.002489924 0.01915252 0.03289651 -0.002271771 0.01883393 0.0330156 -0.002420783 0.01877611 0.03293997 -0.00202465 0.01847618 0.03303712 -0.00207287 0.0183385 0.03306251 -0.001544117 0.01815533 0.03294074 -0.001499474 0.01832067 0.03308296 -0.001037597 0.01827961 0.03295397 -0.001132428 0.01841145 0.03297626 -8.85481e-4 0.01860064 0.03309971 -6.96779e-4 0.01858001 0.03298974 -7.06956e-4 0.01892989 0.03311902 -5.60532e-4 0.01885133 0.0331307 -5.29148e-4 0.0192908 0.03301388 -6.94479e-4 0.01933217 0.03314548 -6.36554e-4 0.01961636 0.03306239 -9.54837e-4 0.01979339 0.03315877 -8.12036e-4 0.01985669 0.0331729 -0.001058697 0.02002787 0.03309267 -0.001528918 0.02000105 0.03318744 -0.001468777 0.02014029 0.03321444 -0.001924633 0.02004575 0.03309255 -0.001960635 0.0198487 0.03322356 -0.002273976 0.01977503 0.0330947 -0.00216633 0.01965647 0.03324687 -0.002488255 0.01930445 0.0331543 -0.002350807 0.01911664 0.03326624 -0.002430856 0.01880347 0.0331462 -0.002228796 0.01873689 0.03327649 -0.002232372 0.01847803 0.03316718 -0.001939713 0.01843839 0.03330188 -0.001848757 0.01822465 0.03319019 -0.001503348 0.01831823 0.03331518 -0.001456141 0.0181654 0.03333246 -0.001073122 0.01826125 0.03320431 -0.001168549 0.01839113 0.0332542 -8.08814e-4 0.01867669 0.03334939 -7.27051e-4 0.01853936 0.033369 -5.63769e-4 0.01885288 0.03328198 -6.55765e-4 0.01924175 0.03338724 -5.31554e-4 0.01933616 0.03340423 -7.07066e-4 0.01974129 0.03330969 -9.07713e-4 0.01973885 0.03340148 -9.7489e-4 0.01998138 0.03329926 -0.001321256 0.01996237 0.03342968 -0.001242458 0.02011066 0.03334307 -0.001550793 0.01998794 0.03345096 -0.001744985 0.02011144 0.0333293 -0.00181514 0.01992052 0.03347176 -0.0021438 0.01990109 0.03338086 -0.002217531 0.01960307 0.03348028 -0.002358198 0.01964348 0.03349363 -0.002475082 0.01930671 0.03340309 -0.002342104 0.01915353 0.03350794 -0.002474129 0.01897162 0.03339558 -0.002243041 0.01877242 0.03352588 -0.00232619 0.01859414 0.03344666 -0.001900851 0.01839756 0.03355193 -0.001909613 0.01824003 0.03356856 -0.001378238 0.01816976 0.03344517 -0.001414 0.01832497 0.0334959 -9.25799e-4 0.01852929 0.03358811 -9.78485e-4 0.01831722 0.0336008 -7.26923e-4 0.01854425 0.03361946 -5.20854e-4 0.01900249 0.03352081 -6.81727e-4 0.01898843 0.03352153 -7.43023e-4 0.01949733 0.03364169 -5.7129e-4 0.01946383 0.03365081 -7.53365e-4 0.01978623 0.03356474 -9.85238e-4 0.01982283 0.03366994 -0.001005828 0.02000427 0.03359466 -0.001604497 0.01999521 0.03368407 -0.001366257 0.02012455 0.03370302 -0.00172472 0.02011066 0.03371274 -0.002063095 0.01996439 0.03360188 -0.002144217 0.01968824 0.03373473 -0.002397596 0.01958906 0.03364562 -0.002339482 0.01931643 0.0337578 -0.002488732 0.01898056 0.0336427 -0.002241134 0.01875615 0.03377938 -0.002247869 0.01850241 0.03366708 -0.002004921 0.01847988 0.03379577 -0.001962721 0.01827692 0.03368896 -0.001542687 0.01831853 0.03381437 -0.00158298 0.01816684 0.03383135 -0.001130998 0.01823061 0.03373795 -0.001058936 0.01842981 0.03384804 -7.7524e-4 0.01847535 0.03373789 -7.11916e-4 0.01889407 0.0338605 -5.68337e-4 0.01883274 0.03378522 -6.69705e-4 0.01931524 0.03388214 -5.26076e-4 0.01930493 0.03390121 -6.9937e-4 0.01971566 0.03378713 -9.73049e-4 0.01979273 0.03391391 -9.41249e-4 0.01995921 0.03393268 -0.001289904 0.02011328 0.03380459 -0.001334786 0.01996183 0.03385293 -0.001751959 0.01995337 0.03394687 -0.001667439 0.02012026 0.03396666 -0.002030313 0.01998919 0.03387415 -0.002129316 0.01971089 0.03397411 -0.002273559 0.01977133 0.03398889 -0.002463936 0.0194078 0.03387659 -0.002334177 0.01924717 0.03401648 -0.00245428 0.01887029 0.03392648 -0.002222597 0.01868021 0.03402823 -0.002255082 0.01850211 0.03404545 -0.001900374 0.01824814 0.0339232 -0.001830697 0.01839089 0.03393942 -0.001431047 0.01832073 0.03406226 -0.001556456 0.01816713 0.03407979 -0.001214563 0.01820617 0.03396534 -0.00107038 0.01843976 0.03409349 -7.85702e-4 0.01846474 0.03398132 -7.70131e-4 0.01876598 0.03411626 -5.46779e-4 0.01890611 0.03402894 -6.65715e-4 0.01916778 0.03413468 -5.26364e-4 0.01923769 0.03414565 -6.26751e-4 0.01960343 0.03405427 -8.28635e-4 0.01966261 0.03416621 -9.46674e-4 0.01996958 0.03408354 -0.001347362 0.01998436 0.03418391 -0.001377105 0.02012717 0.03419685 -0.001728832 0.02010959 0.03408223 -0.001849234 0.0199055 0.03421533 -0.00213015 0.01991933 0.0341317 -0.002233743 0.01958483 0.03423351 -0.002357363 0.01964366 0.03424715 -0.002478837 0.01930409 0.0341593 -0.002339243 0.01902294 0.03425931 -0.002464056 0.01893192 0.03427726 -0.00233823 0.01861941 0.03415304 -0.002157568 0.01863408 0.03429412 -0.001964509 0.01826971 0.03417468 -0.001814842 0.01838213 0.03431367 -0.001480162 0.0181626 0.03419011 -0.001496732 0.01832467 0.03420519 -0.001178324 0.01838904 0.03433912 -0.00106585 0.01826369 0.03434818 -7.28567e-4 0.01853531 0.03422147 -9.12385e-4 0.01857632 0.0342704 -6.64316e-4 0.01900142 0.03436481 -5.38418e-4 0.01895445 0.03438347 -5.2881e-4 0.01932126 0.03429824 -7.67554e-4 0.0195508 0.03440809 -8.31429e-4 0.01988345 0.0342909 -0.00104922 0.01984101 0.03442412 -0.001241803 0.02010172 0.03433716 -0.001424789 0.01998502 0.03444582 -0.001599192 0.02012854 0.03436022 -0.001900136 0.01989626 0.0344581 -0.001953125 0.02002799 0.0344718 -0.002269327 0.01977604 0.03436094 -0.002267897 0.01948589 0.03448885 -0.002435505 0.01946908 0.03437674 -0.002334177 0.01914632 0.03450709 -0.002494573 0.01910835 0.03441625 -0.002298533 0.01887851 0.03452432 -0.002359032 0.01865422 0.03443795 -0.002045869 0.0185064 0.03453785 -0.002093017 0.01836025 0.03455895 -0.001743078 0.01819026 0.0344274 -0.00171709 0.01834821 0.03455197 -0.001430571 0.01817297 0.03447842 -0.001242518 0.01834332 0.03457933 -0.001169919 0.01821666 0.03447598 -8.18601e-4 0.01867824 0.03459668 -7.76657e-4 0.01847922 0.0345202 -6.79111e-4 0.01898872 0.03461289 -5.8918e-4 0.01878142 0.03462648 -5.16589e-4 0.01916307 0.03454595 -7.44383e-4 0.01952689 0.03464311 -5.86226e-4 0.01951617 0.03466421 -8.54071e-4 0.01989865 0.03457409 -0.001158833 0.01991981 0.03468006 -0.001223742 0.0200923 0.03469252 -0.00159198 0.0201326 0.03459382 -0.001568317 0.01998138 0.03461456 -0.001982212 0.01985138 0.03471297 -0.001979053 0.0200172 0.03471964 -0.002209603 0.01984047 0.03461283 -0.002278923 0.01944535 0.03473621 -0.002409934 0.01953804 0.03474646 -0.002494633 0.01919794 0.03463363 -0.002329647 0.01902759 0.034774 -0.002387344 0.01870334 0.03468388 -0.002109885 0.01856482 0.03479063 -0.00209254 0.0183528 0.03468203 -0.001690447 0.01834005 0.0348097 -0.001646041 0.01816761 0.03482222 -0.001244723 0.01818984 0.03470069 -0.001213073 0.01836889 0.03474974 -8.60148e-4 0.01860052 0.03484767 -7.6578e-4 0.01848828 0.03486317 -5.38307e-4 0.01893806 0.03477895 -6.56113e-4 0.01916968 0.03488522 -5.31238e-4 0.0193383 0.03477817 -8.52577e-4 0.01966851 0.03490072 -6.88929e-4 0.01970845 0.03491729 -9.01057e-4 0.01993107 0.03479939 -0.001174271 0.01990735 0.03493326 -0.001369237 0.02013397 0.03481507 -0.00153315 0.01997965 0.03495931 -0.001918911 0.02005147 0.03486782 -0.002044439 0.0198028 0.03497362 -0.002327859 0.01970273 0.03486931 -0.002322256 0.01931375 0.03500008 -0.002498269 0.01921159 0.0349099 -0.00233525 0.01900213 0.03501898 -0.002397239 0.01872229 0.03493684 -0.002065539 0.01851433 0.03503561 -0.002163946 0.01840877 0.03505778 -0.001628041 0.01816636 0.03496426 -0.001540362 0.01830571 0.03507834 -0.001158654 0.01822012 0.03495991 -0.00104171 0.01846033 0.03509378 -7.71789e-4 0.01848834 0.03500282 -8.30088e-4 0.01864683 0.03512024 -5.29772e-4 0.01894503 0.03498274 -7.19468e-4 0.01886498 0.03503972 -6.95979e-4 0.01939451 0.03514224 -5.77673e-4 0.01949489 0.0351637 -8.86469e-4 0.01992869 0.03503704 -0.001002073 0.01981186 0.03505837 -0.00127983 0.01994782 0.03518128 -0.001383721 0.02013272 0.03507357 -0.001684904 0.01996153 0.03520172 -0.001832842 0.02008146 0.03512483 -0.002149641 0.01970493 0.03521841 -0.002180814 0.01987814 0.03524541 -0.002405405 0.01957499 0.03512561 -0.002336919 0.01913779 0.03525316 -0.002492725 0.0190823 0.03517013 -0.00227493 0.01881194 0.0352689 -0.002390146 0.01871865 0.03529238 -0.002060532 0.01832157 0.03519278 -0.00195825 0.01843976 0.03531372 -0.001511931 0.01815831 0.03518253 -0.001655101 0.01833409 0.03519654 -0.001308977 0.01834118 0.03533035 -0.001072227 0.01826483 0.03524655 -9.20025e-4 0.01854783 0.03535568 -6.97318e-4 0.01856744 0.03527271 -6.62886e-4 0.01902556 0.03536796 -5.2166e-4 0.01905393 0.03539705 -5.81952e-4 0.01951622 0.03529936 -7.78456e-4 0.01957368 0.03541094 -8.56096e-4 0.01989102 0.03532397 -0.00116235 0.01992416 0.03542524 -0.001124501 0.02006042 0.03542184 -0.00145322 0.02013111 0.03534746 -0.001644372 0.01997548 0.03544747 -0.001674294 0.02013015 0.03537166 -0.002098143 0.01975876 0.03546613 -0.002071082 0.01995968 0.03548753 -0.002374053 0.01962 0.03540009 -0.002349436 0.0192126 0.0354976 -0.002502083 0.01916134 0.03543001 -0.002168893 0.01861542 0.03552281 -0.00238049 0.0187059 0.03553444 -0.002181291 0.01843076 0.0355488 -0.001900255 0.01824933 0.03545981 -0.001620948 0.01831126 0.0355677 -0.001476407 0.01815855 0.03557789 -0.001054883 0.01826339 0.03545564 -0.001204133 0.01836943 0.03548765 -7.59056e-4 0.01877188 0.03560781 -6.55918e-4 0.01864069 0.03562426 -5.10176e-4 0.01916712 0.03550654 -6.75815e-4 0.01920449 0.03552341 -7.76984e-4 0.01954084 0.03564912 -6.62119e-4 0.01967114 0.03553837 -0.001015663 0.01981931 0.03566759 -9.85212e-4 0.01999139 0.03558623 -0.001407742 0.01999002 0.03569042 -0.00142771 0.02013808 0.03570371 -0.001832187 0.02007853 0.0355851 -0.001881539 0.01988786 0.03571772 -0.002166867 0.01988261 0.03559821 -0.002180278 0.01963037 0.03573727 -0.002401828 0.01955801 0.03562092 -0.002307116 0.01936465 0.03574424 -0.002489507 0.01921743 0.03563821 -0.002306044 0.01893305 0.03576862 -0.002435505 0.01882082 0.03568863 -0.002037942 0.018494 0.03578239 -0.002199292 0.01844584 0.03580427 -0.00171566 0.01817589 0.03568494 -0.00155127 0.01832038 0.03571218 -0.001111268 0.01841455 0.03582835 -0.001162946 0.01821959 0.03585237 -7.72542e-4 0.01848149 0.03576052 -7.46782e-4 0.01878511 0.03586828 -5.60667e-4 0.01886647 0.03587508 -5.19771e-4 0.01916283 0.03578168 -6.7014e-4 0.01922732 0.03589093 -6.20118e-4 0.01959776 0.03580713 -8.6565e-4 0.01971065 0.03591221 -8.83239e-4 0.01991969 0.03580701 -0.001330673 0.01995962 0.03592962 -0.001183986 0.02008712 0.03594678 -0.00167936 0.02012461 0.03585612 -0.00182414 0.01993191 0.03597152 -0.002180457 0.01988101 0.03587853 -0.002186596 0.01963812 0.03599053 -0.002430737 0.01948505 0.03587096 -0.002328157 0.01927709 0.03600114 -0.002491831 0.01913857 0.03589773 -0.002250969 0.01877701 0.03601253 -0.002421021 0.01878547 0.03603249 -0.002221643 0.01847261 0.035914 -0.001983642 0.01846754 0.03605693 -0.00184971 0.01822119 0.03606456 -0.001464903 0.01815885 0.03593766 -0.001539289 0.0183165 0.03608816 -8.95536e-4 0.01835858 0.03595954 -0.001109421 0.01842242 0.03597813 -8.35219e-4 0.01866042 0.03611314 -5.62295e-4 0.01884722 0.03598964 -7.02988e-4 0.01894563 0.03604185 -7.03881e-4 0.01942455 0.03613078 -5.25462e-4 0.01927381 0.03614878 -6.4668e-4 0.01964479 0.036067 -0.001036882 0.01985102 0.03616696 -9.69194e-4 0.01998239 0.03606462 -0.001531183 0.01998156 0.03618687 -0.001437008 0.02014046 0.03610605 -0.001819729 0.01992827 0.03621155 -0.001908957 0.02005207 0.03621882 -0.00222367 0.01982486 0.03612595 -0.002150714 0.01968437 0.03623938 -0.00242573 0.01949763 0.03611373 -0.002297401 0.01937633 0.03625988 -0.002492487 0.01904749 0.03615814 -0.002338469 0.01904934 0.03625255 -0.002402126 0.01876497 0.03618216 -0.002137482 0.01858878 0.03628301 -0.002226114 0.01846826 0.03616565 -0.00188452 0.01840472 0.0363062 -0.001738786 0.01818341 0.03619778 -0.001387298 0.01832681 0.0363233 -0.001276671 0.01819282 0.03634268 -9.48727e-4 0.01833289 0.03624701 -9.14027e-4 0.01854777 0.03635674 -6.1046e-4 0.01871496 0.0362702 -6.79108e-4 0.01898682 0.03638529 -5.2418e-4 0.01932525 0.03625595 -6.87502e-4 0.01929575 0.03628039 -8.62851e-4 0.01967525 0.03640872 -7.71363e-4 0.01981252 0.03641825 -0.00103265 0.02001827 0.03629589 -0.001156806 0.01990282 0.03644043 -0.001483678 0.02013838 0.03631836 -0.001597404 0.01997834 0.03645044 -0.001835107 0.02008217 0.03634148 -0.002012014 0.01980572 0.03647166 -0.002277612 0.01977646 0.03638613 -0.00226897 0.01949876 0.03649628 -0.002468883 0.01935929 0.03640919 -0.002338826 0.0190162 0.03651475 -0.002462506 0.01889592 0.03653144 -0.002231538 0.01847755 0.03640556 -0.002140522 0.01862382 0.03642302 -0.001840174 0.01838809 0.03655332 -0.001810252 0.01820749 0.03644245 -0.001453042 0.01832401 0.0365687 -0.001406252 0.01816773 0.03657788 -0.001086235 0.01825684 0.03649115 -9.91792e-4 0.01847648 0.03660279 -7.45242e-4 0.01851981 0.0364843 -7.50957e-4 0.01881003 0.0366137 -5.73507e-4 0.0188263 0.03650236 -6.77051e-4 0.0191282 0.03663206 -5.20815e-4 0.0192539 0.03651839 -7.63036e-4 0.01952868 0.03664976 -6.63214e-4 0.01966804 0.03665816 -8.85923e-4 0.01991599 0.03656947 -0.00106877 0.01987189 0.03668725 -0.001365005 0.02013891 0.03659158 -0.001526892 0.01998972 0.03670865 -0.001911044 0.02005177 0.03659296 -0.001945972 0.01985347 0.03671801 -0.002200305 0.01985228 0.03663557 -0.002271473 0.01951813 0.03673911 -0.002451062 0.01945167 0.03666508 -0.002315402 0.01889806 0.03676164 -0.002471923 0.01895695 0.0367735 -0.002355813 0.0186482 0.03668934 -0.002027034 0.01849615 0.03679418 -0.002043426 0.01831644 0.03678399 -0.001857459 0.01823019 0.03670889 -0.001643896 0.01831984 0.03681319 -0.001545608 0.01816374 0.03669428 -0.001342356 0.01833349 0.03683239 -0.001205265 0.01820838 0.03672003 -9.51871e-4 0.01853239 0.03684377 -7.56462e-4 0.01849424 0.03673636 -7.34461e-4 0.01883399 0.03687244 -5.17582e-4 0.0190187 0.03679031 -6.92458e-4 0.01939815 0.03689074 -5.85697e-4 0.01951235 0.03690975 -7.5683e-4 0.01979255 0.0367856 -9.62063e-4 0.01977968 0.03691947 -0.001063823 0.02003037 0.03683924 -0.001484453 0.01999908 0.03693819 -0.001505136 0.02014422 0.03683751 -0.001984 0.01982814 0.03695803 -0.001973748 0.0200203 0.03697955 -0.002313971 0.01973253 0.03686791 -0.002274155 0.01947087 0.03699725 -0.002483844 0.01926386 0.03687167 -0.002339899 0.01914513 0.0370121 -0.002453744 0.01886045 0.03690135 -0.002202153 0.01869899 0.03703469 -0.002294719 0.01855039 0.03694844 -0.001857221 0.01838195 0.03704386 -0.001942753 0.01826626 0.03706526 -0.001597881 0.01817029 0.03694081 -0.001313626 0.01833784 0.03707414 -0.001167118 0.01821446 0.03698593 -0.001096844 0.0184099 0.03710252 -7.52701e-4 0.01851075 0.03698885 -7.27017e-4 0.01884377 0.03711426 -5.73708e-4 0.01883149 0.03700393 -6.75284e-4 0.01919722 0.03712654 -5.15357e-4 0.01914829 0.03702247 -7.6291e-4 0.01953226 0.03713947 -5.82599e-4 0.01948863 0.03715282 -8.06537e-4 0.0198546 0.03706347 -9.75096e-4 0.01980036 0.03716582 -0.001294314 0.02011144 0.03708511 -0.001392602 0.01998519 0.03719484 -0.001632571 0.02013373 0.03710877 -0.001872062 0.01990693 0.03721481 -0.00206393 0.01997154 0.0370987 -0.002180039 0.01963669 0.03723251 -0.002372384 0.01962041 0.03712195 -0.002326786 0.01928323 0.03725385 -0.002485752 0.01925939 0.03726083 -0.002459526 0.018902 0.03714275 -0.00229454 0.01890486 0.03728348 -0.002221405 0.01846021 0.03718715 -0.002059638 0.01851028 0.0372976 -0.001852929 0.01822966 0.03718113 -0.001699626 0.01834416 0.03731507 -0.001503884 0.018166 0.03723055 -0.001200854 0.01836156 0.03732615 -0.001164317 0.01822406 0.03734552 -8.46315e-4 0.01841664 0.0372259 -8.39299e-4 0.01865416 0.03736728 -5.55041e-4 0.0188471 0.03727692 -6.60202e-4 0.01912122 0.03738808 -5.46204e-4 0.01938849 0.03727382 -8.0369e-4 0.01958996 0.03740251 -7.09414e-4 0.01973688 0.03741133 -9.50565e-4 0.01996713 0.03729468 -0.001101195 0.01987707 0.03743517 -0.001336455 0.02012044 0.03730982 -0.00145775 0.01997476 0.03744804 -0.001679658 0.02012026 0.03735202 -0.001735568 0.01995563 0.03745639 -0.002010583 0.01999545 0.03737723 -0.002176344 0.01967215 0.03747862 -0.002301156 0.01973301 0.03748881 -0.002464294 0.01938164 0.03737992 -0.002335846 0.01912587 0.03750783 -0.0024814 0.01898032 0.037427 -0.002203464 0.01867836 0.03753727 -0.002273678 0.01852285 0.03754353 -0.001968741 0.01827836 0.03742277 -0.00182718 0.01838731 0.03754609 -0.001564621 0.01816254 0.03744322 -0.001465916 0.01831793 0.03746157 -0.001017808 0.01847547 0.03750896 -7.73565e-4 0.0187478 0.03752809 -6.6379e-4 0.019131 0.03183031 -0.002066135 0.01977264 0.03183436 -0.00231558 0.01938378 0.03183919 -0.002355694 0.01908737 0.03193008 -0.001163423 0.0183891 0.03195393 -7.78299e-4 0.01870107 0.03198653 -6.82112e-4 0.0193752 0.03206688 -0.002048373 0.0197882 0.03208696 -0.002294421 0.01943898 0.03214794 -0.001824796 0.01837158 0.03220599 -7.63923e-4 0.01874077 0.03228437 -0.001411974 0.0199868 0.03236734 -0.002276599 0.01881164 0.03238904 -0.001994073 0.01846945 0.03241217 -0.001533269 0.01830333 0.03246515 -6.82386e-4 0.01892375 0.03249216 -7.3272e-4 0.01947897 0.0325154 -0.001042842 0.01985782 0.03255635 -0.001871705 0.0199092 0.03260248 -0.0023548 0.01914048 0.03263241 -0.002100706 0.01854103 0.03269577 -8.95408e-4 0.01857292 0.03271704 -6.86567e-4 0.01895767 0.0327627 -9.97132e-4 0.01982241 0.03278815 -0.001501023 0.01999622 0.03281122 -0.001959621 0.01985287 0.03283172 -0.002246558 0.01954722 0.03289175 -0.001942098 0.01842612 0.03300851 -9.16335e-4 0.01976859 0.03303611 -0.001450479 0.01998865 0.03309512 -0.002340972 0.0192697 0.03320372 -7.92409e-4 0.01869243 0.03322786 -6.65366e-4 0.01919001 0.03325414 -8.57448e-4 0.01970052 0.0333206 -0.002109527 0.01973438 0.03334575 -0.0023458 0.01925796 0.03339314 -0.001918017 0.01841336 0.03343474 -0.001076519 0.01843315 0.03345352 -7.94762e-4 0.01870143 0.0334782 -6.59652e-4 0.01918029 0.03351998 -0.001124083 0.0198999 0.03354054 -0.001545608 0.01998746 0.03356063 -0.001950681 0.01986128 0.03359746 -0.002339661 0.01921987 0.0336911 -9.58531e-4 0.01849311 0.03373724 -6.98294e-4 0.01938468 0.0338062 -0.001865208 0.01991909 0.03383189 -0.002251565 0.01953643 0.03387516 -0.002205252 0.01867467 0.03398084 -6.62801e-4 0.01924937 0.03400623 -8.96352e-4 0.01973044 0.03403121 -0.001341819 0.01997983 0.03407764 -0.002202272 0.01961743 0.03410112 -0.002350449 0.01914453 0.03421342 -7.00968e-4 0.01889014 0.03424203 -7.17968e-4 0.01946908 0.0342881 -0.001504421 0.01999872 0.03431552 -0.002029955 0.01980936 0.03437703 -0.002180933 0.01863473 0.03442716 -0.001219451 0.01835519 0.0344823 -6.60043e-4 0.01928102 0.03451013 -9.57487e-4 0.01978832 0.03453683 -0.00146532 0.01999896 0.03456473 -0.002018034 0.01982021 0.03463095 -0.002123475 0.01857197 0.0347045 -7.80322e-4 0.01871615 0.03472864 -6.6525e-4 0.01920729 0.03480684 -0.001877188 0.01990157 0.03482848 -0.002216935 0.01960057 0.03486943 -0.00225991 0.0187714 0.03489333 -0.001918494 0.01841872 0.03491693 -0.001435577 0.01830869 0.03498953 -7.01554e-4 0.01942181 0.03507679 -0.002204656 0.01964497 0.03512942 -0.002143025 0.01858818 0.03519952 -8.38381e-4 0.01862472 0.03522896 -6.58225e-4 0.01920229 0.03525561 -8.80681e-4 0.01971673 0.03528261 -0.001389205 0.01999294 0.03531396 -0.001999557 0.01984024 0.03533756 -0.002295553 0.01942688 0.03535604 -0.002334356 0.01903814 0.0353741 -0.002205133 0.01868927 0.03539884 -0.00181204 0.01835882 0.0354436 -9.29143e-4 0.01853251 0.03553783 -0.001476764 0.01999336 0.03563576 -0.002051651 0.01849836 0.03570091 -8.2496e-4 0.01865786 0.03572851 -6.51949e-4 0.01919865 0.03575861 -9.24354e-4 0.01976555 0.0357967 -0.00167638 0.01997238 0.03581905 -0.002090811 0.01975548 0.03599262 -7.17615e-4 0.01948791 0.03602087 -0.001147389 0.0199114 0.03606772 -0.002077162 0.01977849 0.03611379 -0.002315104 0.01887595 0.0361849 -0.001071214 0.01843017 0.03620886 -7.40637e-4 0.01879137 0.03634029 -0.002322733 0.01937812 0.03636389 -0.002298593 0.01888358 0.03643691 -0.001034855 0.01844811 0.03652459 -0.001205027 0.0199486 0.03655099 -0.001765549 0.0199486 0.03658676 -0.002301931 0.01944082 0.03661876 -0.002282142 0.01879721 0.03664678 -0.001853048 0.0183832 0.03673458 -6.78229e-4 0.01932346 0.03678596 -0.001459538 0.0200017 0.03689944 -0.001796066 0.01835387 0.03694683 -8.77086e-4 0.01858711 0.03702157 -0.001160264 0.01991891 0.03704881 -0.001709759 0.01997339 0.03713226 -0.002100348 0.01855826 0.03717541 -0.001272201 0.01833397 0.03722542 -6.53999e-4 0.0191468 0.03730767 -0.001900017 0.01989674 0.03733253 -0.002255558 0.01952999 0.03737819 -0.002160251 0.01861166 0.03746473 -6.85195e-4 0.01892167 0.03749501 -7.49192e-4 0.01953393 0.03752017 -0.001127481 0.01990091 0.03183412 -0.001161098 0.01821786 0.03183072 -0.002207875 0.01853287 0.0318315 -0.001770913 0.01823669 0.0318672 -7.25124e-4 0.01853197 0.0321877 -0.001075744 0.02003729 0.03304427 -0.002273261 0.01853805 0.03441232 -6.31905e-4 0.01960629 0.03506332 -0.00190854 0.01825219 0.03718703 -0.001058459 0.02003067 0.03779673 -0.001461386 0.02001214 0.03782379 -7.90128e-4 0.01956212 0.03768038 -0.001435518 0.02010726 0.03779357 -0.001065075 0.01989936 0.03769433 -0.001181483 0.02004593 0.03758084 -0.001194059 0.02008408 0.0376752 -9.47793e-4 0.01993477 0.03771203 -7.75835e-4 0.0197522 0.03781521 -7.23098e-4 0.01940184 0.03771018 -6.1075e-4 0.01945924 0.03782886 -7.33143e-4 0.01903963 0.03778195 -6.22623e-4 0.01911586 0.03767299 -5.50509e-4 0.01926589 0.0376895 -5.58881e-4 0.01899337 0.03781479 -8.10859e-4 0.01869213 0.03775113 -6.44168e-4 0.01883971 0.03764921 -6.59522e-4 0.01867264 0.03782886 -0.001275479 0.01838839 0.03770095 -8.08348e-4 0.01849752 0.03775697 -0.001007318 0.01838725 0.03780573 -0.001292288 0.01832795 0.03757596 -0.001020967 0.01829075 0.03766489 -0.001286327 0.0182051 0.03775292 -0.001409471 0.01824092 0.03768241 -0.001621842 0.01819515 0.03782552 -0.001713633 0.01837199 0.03773182 -0.001813173 0.01827394 0.03778612 -0.002004981 0.0184195 0.03781986 -0.002196848 0.01871979 0.03767943 -0.00221765 0.0185061 0.03770947 -0.00234729 0.01871347 0.03782433 -0.002302169 0.01905858 0.0377497 -0.002415895 0.01902782 0.03782403 -0.002236843 0.01950466 0.03758788 -0.002459287 0.01891642 0.03773182 -0.002397716 0.01944035 0.037826 -0.00191456 0.01983636 0.03759896 -0.002337455 0.01968145 0.03773987 -0.002145886 0.01982039 0.03774201 -0.00181514 0.02002948 0.03768301 -0.001898467 0.02003002 0.0378291 -0.001456439 0.0199452 0.03066164 -0.002216398 0.01956081 0.03066122 -0.00148189 0.01998674 0.03065961 -0.002219021 0.0187391 0.03066039 -0.001506149 0.01832658 0.03066068 -7.92434e-4 0.01873737 0.03065782 -7.89338e-4 0.01958686 0.02994191 -0.002268552 0.01959049 0.02994149 -0.00227046 0.01870983 0.02994185 -7.39454e-4 0.01958793 0.02994143 -0.001506328 0.02003228 0.02994173 -7.41008e-4 0.01870709 0.02994149 -0.001506447 0.01826685 0.02993029 -0.002650916 0.01766228 0.02993029 -0.003186047 0.01834034 0.02993029 -0.00338006 0.01914995 0.02993029 -0.001888632 0.01732575 0.02993029 -5.45411e-4 0.01755172 0.02993029 -0.001195311 0.01730877 0.02993029 -0.003162205 0.02001661 0.02993029 -0.002691805 0.02058738 0.02993029 3.48444e-5 0.01808184 0.02993029 -0.002012073 0.02095264 0.02993029 3.87366e-4 0.01913446 0.02993029 -0.001226842 0.02099418 0.02993029 -4.75463e-4 0.02071583 0.02993029 9.59843e-5 0.02011072 0.03183025 -9.82701e-4 0.01735025 0.03183025 -4.53495e-5 0.01794558 0.03183025 3.61206e-4 0.01897847 0.03183025 2.00559e-4 0.01993626 0.03183025 -5.21704e-4 0.02075886 0.03183025 -0.001489758 0.02102017 0.03183025 -0.002215325 0.02087342 0.03183025 -0.002902686 0.02040398 0.03183025 -0.003315091 0.01961094 0.03183025 -0.003334343 0.01873242 0.03183025 -0.002944588 0.01796132 0.03183025 -0.002436041 0.01753705 0.03183025 -0.001814365 0.01730877 0.03758656 0.006325125 0.01986938 0.03757494 0.006426155 0.01977038 0.03758019 0.00613898 0.01962876 0.03758037 0.006668746 0.02007436 0.03758144 0.006094992 0.01909989 0.03756076 0.006815075 0.01996529 0.0375806 0.006015539 0.01919847 0.03757828 0.007250964 0.01996403 0.03758025 0.007086455 0.02012592 0.03758025 0.006116211 0.01869183 0.03758025 0.007510781 0.01998502 0.03757661 0.006454527 0.01833635 0.03758126 0.007834494 0.01967018 0.03756701 0.007680535 0.01964628 0.03759127 0.007955074 0.01931172 0.03756874 0.006979703 0.0181632 0.03758484 0.007962346 0.01899653 0.03758192 0.007839679 0.0186522 0.03184545 0.007891535 0.01873326 0.03187835 0.007982075 0.01915425 0.03183418 0.007029831 0.01998561 0.03189116 0.007924556 0.01948016 0.03183025 0.007886469 0.0193547 0.03189873 0.00776261 0.01976853 0.03191941 0.007484376 0.02000463 0.03183007 0.00756514 0.01981639 0.03193438 0.007193624 0.02011716 0.03194886 0.006790637 0.02011305 0.03184711 0.006609976 0.01989692 0.03196847 0.006360054 0.0199148 0.03184419 0.006401956 0.01974439 0.03198665 0.006083846 0.01952511 0.03189963 0.006153702 0.01922786 0.03200078 0.006010413 0.0191695 0.03201496 0.006072521 0.01879388 0.03192627 0.006288051 0.01868438 0.03204095 0.006413042 0.01833927 0.03192454 0.006680488 0.01837813 0.03206437 0.007011055 0.01815611 0.03195381 0.007144749 0.01833242 0.03208541 0.007502555 0.01830208 0.0319603 0.007451891 0.0184558 0.03210383 0.007767021 0.01854121 0.03201466 0.007787883 0.01885998 0.03211736 0.007982075 0.01899194 0.0320115 0.007810592 0.01930308 0.0321452 0.007882952 0.01959156 0.03206264 0.007553279 0.01979225 0.03216683 0.00757575 0.01994866 0.03218364 0.007165849 0.02012413 0.03208732 0.007064402 0.01998496 0.03219902 0.00675863 0.02010577 0.03211057 0.006601154 0.01989781 0.03221786 0.006410062 0.01994794 0.03222817 0.006156921 0.0196703 0.03213512 0.006238758 0.01952028 0.0322439 0.00603193 0.01935726 0.03212982 0.006167113 0.01912176 0.03225594 0.006018042 0.01900076 0.03214639 0.006267786 0.01874864 0.03227674 0.006186902 0.01858443 0.03216564 0.006509363 0.01848274 0.03228944 0.006458997 0.01832258 0.03218048 0.006813049 0.0183385 0.03231275 0.006784558 0.01818913 0.03231984 0.007143676 0.01816922 0.03219813 0.007263302 0.01836341 0.03233778 0.00750786 0.01830774 0.03224551 0.00756812 0.01853203 0.03234785 0.007774055 0.01854145 0.03227311 0.007841587 0.01905232 0.03236371 0.007937371 0.0188657 0.03238141 0.007977664 0.01927649 0.03227829 0.007680058 0.01962822 0.03239881 0.007811129 0.01970541 0.03241664 0.007548093 0.01997071 0.03229314 0.007387518 0.01988637 0.03243124 0.007188022 0.02011585 0.03231012 0.007034063 0.01997482 0.03245109 0.006812989 0.02012532 0.03232997 0.006688237 0.01992237 0.0324676 0.006412446 0.01994186 0.03238314 0.006254136 0.01956856 0.03247958 0.006163239 0.01968783 0.03248935 0.006026864 0.01934593 0.03240966 0.006165444 0.01900851 0.03251135 0.006046772 0.01886701 0.03243643 0.006428241 0.01851689 0.03253108 0.006266117 0.01847481 0.03253823 0.006739854 0.01820009 0.03243583 0.006947576 0.01832139 0.03256684 0.007001757 0.01815724 0.03248262 0.007338702 0.01838243 0.03258442 0.007376253 0.01824325 0.03259384 0.007685244 0.01844626 0.03250414 0.007685065 0.01867067 0.03261077 0.007919311 0.01879608 0.03252381 0.00782603 0.01905423 0.03263366 0.007979393 0.01926827 0.03251284 0.007762014 0.0194664 0.03265368 0.007822036 0.01968652 0.03255605 0.007642149 0.01968127 0.03266042 0.007561385 0.01995658 0.03257459 0.007324576 0.0199207 0.03268086 0.007208824 0.02011489 0.03259736 0.006843924 0.01998311 0.03269785 0.006739735 0.02010929 0.03262311 0.00638473 0.01972937 0.03271573 0.00640583 0.01995003 0.03273302 0.006148934 0.01965546 0.03264802 0.006156384 0.01926016 0.03275048 0.006006777 0.01922148 0.03277176 0.006095886 0.01873809 0.03267651 0.006295502 0.01866531 0.03278493 0.006318032 0.01843726 0.03279632 0.0066123 0.0182349 0.0327059 0.006784915 0.01833194 0.0328198 0.007072329 0.01816725 0.0327304 0.007304191 0.01836651 0.03283518 0.007556915 0.01832479 0.03272038 0.007575333 0.01854699 0.03286141 0.007905244 0.0187658 0.03277546 0.007841885 0.01909303 0.03287625 0.007980585 0.01916921 0.03289741 0.007913291 0.01950716 0.0327695 0.00774753 0.01950782 0.03290295 0.007745444 0.01978725 0.03278809 0.007470548 0.01983129 0.03291958 0.007365882 0.02007424 0.03281664 0.007054924 0.01997941 0.03294241 0.006958842 0.02013576 0.03286093 0.006586492 0.01988571 0.03296238 0.006518602 0.02002096 0.03285712 0.006307482 0.01962 0.03298377 0.006151854 0.01966518 0.03297764 0.006031572 0.01935803 0.03290784 0.006149947 0.01904088 0.03299891 0.006055474 0.018857 0.03290992 0.006481587 0.01849097 0.03302991 0.006217718 0.01853615 0.033046 0.006516695 0.01828813 0.03295832 0.006853938 0.01831078 0.03306633 0.006918132 0.01816493 0.03307861 0.007329165 0.01821559 0.03295791 0.007329702 0.0183925 0.03309524 0.007717192 0.01846933 0.03297579 0.007622241 0.01859933 0.03311288 0.00794506 0.01888275 0.03298819 0.007790744 0.01890426 0.0331335 0.007970452 0.0193181 0.03304207 0.007788181 0.01943582 0.03315669 0.007739484 0.01981252 0.03306937 0.007426857 0.01988244 0.03317928 0.007228434 0.02011513 0.03307539 0.006849884 0.01997005 0.03320425 0.006648063 0.02008444 0.03312677 0.006326556 0.01967829 0.03323173 0.006183147 0.01972168 0.03324455 0.006021618 0.01930749 0.03315377 0.006154179 0.01913487 0.03325873 0.006031394 0.01896417 0.03317505 0.006279647 0.01871216 0.03327727 0.006151497 0.01863586 0.03328448 0.006375074 0.01838332 0.03319501 0.006570041 0.01842743 0.0333051 0.00680083 0.01817846 0.03318935 0.006976127 0.01831674 0.0333243 0.007228732 0.01819181 0.03324389 0.007546901 0.01850402 0.03334128 0.007602393 0.01837027 0.03335762 0.007863402 0.018682 0.03326851 0.007808983 0.01894885 0.03337347 0.007972478 0.0190286 0.03329354 0.007784247 0.01946276 0.03339356 0.007924973 0.01949661 0.0334084 0.007599174 0.01993983 0.03332048 0.007407188 0.01988613 0.03344345 0.00708276 0.02013981 0.03332167 0.006909251 0.01997596 0.03345483 0.006600499 0.02005988 0.03333908 0.00650835 0.01982444 0.03347396 0.006242871 0.01978921 0.03335726 0.006272435 0.01955014 0.03349113 0.006053209 0.01944774 0.03337156 0.006170928 0.01924145 0.03350216 0.006013095 0.0190401 0.03341734 0.006207883 0.01886343 0.03352504 0.00618869 0.01857137 0.03343844 0.006466209 0.01849359 0.03354865 0.006543397 0.0182715 0.0334652 0.006983935 0.0183025 0.03356164 0.006896555 0.01817065 0.03357565 0.00738424 0.01823252 0.03349047 0.007490694 0.01846975 0.03360331 0.007795989 0.01856148 0.03347647 0.007700622 0.01870477 0.03362828 0.007978856 0.01904046 0.03350228 0.007827639 0.01918607 0.03363692 0.007935345 0.01945614 0.0335536 0.00766927 0.01966553 0.03366047 0.007618129 0.01992946 0.03358089 0.007203876 0.01996618 0.03368389 0.007103085 0.02013301 0.03360718 0.006650984 0.01992559 0.0337001 0.006762802 0.02010923 0.03371345 0.006439924 0.01996493 0.03363674 0.00621587 0.01948869 0.03373128 0.006203114 0.01973575 0.03374665 0.006021916 0.01933199 0.03374177 0.006017804 0.01902413 0.03364193 0.006204605 0.01888453 0.03376978 0.006084382 0.01875799 0.03366214 0.006466925 0.01850765 0.03378742 0.00635302 0.01839458 0.03380459 0.006742656 0.01819556 0.03368163 0.006793141 0.0183506 0.03372436 0.007182538 0.01832842 0.03382122 0.007192909 0.01817816 0.03383916 0.007533907 0.01832193 0.03374677 0.007578194 0.01854729 0.0338574 0.00787568 0.01868712 0.03377264 0.007839918 0.01903027 0.03388273 0.007981896 0.01914846 0.03389757 0.007878422 0.01960301 0.0338031 0.007680237 0.01964992 0.0339114 0.007631838 0.01991367 0.03380262 0.007262706 0.01993411 0.03392463 0.007309257 0.02008295 0.03393888 0.00690782 0.02013403 0.03381633 0.006934463 0.01997256 0.0338338 0.006608724 0.01988404 0.0339598 0.00656408 0.02003657 0.03397655 0.006176769 0.01971632 0.03388381 0.006246685 0.01955372 0.03399819 0.006019651 0.01928651 0.03387248 0.006164848 0.01919251 0.03400903 0.00604403 0.01888608 0.03392606 0.00628817 0.01868736 0.03403604 0.006328463 0.01841419 0.03391879 0.006638467 0.01839852 0.0340476 0.006627142 0.01823472 0.03394061 0.006963372 0.0183196 0.0340631 0.007039785 0.01816159 0.03396171 0.007424831 0.01843535 0.03408855 0.007464826 0.01828235 0.03409487 0.007762551 0.01852905 0.03398162 0.007713794 0.01874023 0.03411626 0.007932841 0.01884788 0.03400325 0.007829487 0.01915675 0.03413134 0.007977187 0.01925826 0.03402006 0.007705211 0.0195738 0.03415465 0.007784664 0.01975655 0.03406667 0.007480204 0.01983565 0.03417414 0.007359206 0.02006733 0.03409063 0.006994783 0.01999688 0.03419041 0.006888687 0.02013593 0.03409051 0.006494283 0.01981186 0.03421187 0.006465017 0.01998627 0.0341311 0.006282091 0.01959413 0.03423041 0.006167411 0.01969462 0.03424477 0.006027638 0.01933008 0.03415727 0.006148219 0.01905632 0.03425914 0.006024599 0.01895934 0.0342763 0.00619024 0.01857149 0.03418987 0.006486892 0.01846349 0.03429549 0.006688952 0.01820456 0.03421735 0.007024943 0.0183115 0.03431946 0.007137894 0.01817613 0.03424131 0.007500231 0.01847082 0.03433907 0.007466197 0.01828557 0.03434938 0.007750451 0.01851254 0.03426742 0.007810831 0.01893073 0.03436064 0.007928848 0.01883792 0.03438103 0.007978737 0.01923102 0.03425377 0.00782001 0.01928335 0.03439527 0.007846951 0.01965361 0.03428655 0.007591903 0.01973015 0.03441488 0.007616341 0.01991683 0.03429484 0.007310271 0.01991915 0.0344296 0.007175385 0.02012795 0.03432357 0.006888449 0.01997268 0.03445291 0.006611108 0.02005857 0.0343337 0.00653398 0.019845 0.03447204 0.006253242 0.01980674 0.03436082 0.006232023 0.01948612 0.03449487 0.006017148 0.01931905 0.03440654 0.006154477 0.019082 0.03451979 0.006090819 0.01873213 0.03438156 0.006195783 0.01889061 0.03444361 0.006549239 0.01843422 0.03453826 0.006467878 0.01831167 0.03443932 0.006926476 0.01832073 0.03456509 0.00703895 0.01815855 0.03444927 0.007280647 0.01836711 0.03458231 0.007463157 0.01827931 0.03460127 0.007789492 0.01856303 0.03447657 0.007652282 0.01864236 0.03461688 0.007955074 0.01893192 0.0345264 0.007840991 0.01910656 0.03464049 0.007966637 0.01934522 0.03455662 0.007638633 0.01971256 0.03465169 0.00779128 0.01974242 0.03466773 0.007499814 0.0199998 0.03458333 0.007148385 0.01997363 0.03468757 0.007064521 0.02014076 0.03460586 0.006690263 0.0199368 0.03470659 0.00659722 0.02005976 0.03471916 0.006331384 0.01988339 0.03462696 0.006335794 0.01966458 0.03473269 0.006095588 0.01956826 0.03464823 0.006156563 0.01925295 0.03475224 0.006008923 0.01915532 0.03476125 0.006078243 0.01879036 0.03466993 0.006231486 0.01881104 0.03478688 0.006283283 0.01846164 0.03468966 0.006479322 0.0184834 0.034801 0.006670832 0.01821732 0.03471279 0.00693202 0.01831209 0.03481668 0.007061958 0.01816803 0.03471261 0.007376194 0.01841145 0.03482967 0.007391154 0.01824665 0.03475493 0.007705211 0.01868641 0.03485202 0.007791817 0.01855343 0.03487789 0.007990121 0.01913285 0.03477686 0.007828831 0.0191164 0.03479731 0.007745504 0.01953762 0.03489762 0.007861554 0.01962041 0.03491777 0.007558882 0.01996821 0.03482002 0.007416129 0.01987504 0.03493201 0.007091403 0.02013504 0.03480994 0.007061839 0.0199719 0.03482908 0.006706893 0.01992928 0.03495651 0.006572484 0.02004855 0.03487765 0.00631982 0.01966059 0.03498566 0.006151199 0.01967322 0.03499758 0.0060063 0.01924896 0.03487479 0.006160795 0.01912665 0.03492164 0.006236612 0.01876878 0.03501421 0.006063818 0.01882874 0.03503096 0.006231129 0.01852267 0.03504103 0.006484448 0.01831012 0.03495097 0.006685912 0.01836013 0.03505343 0.00685662 0.01816964 0.03497689 0.007224678 0.01834058 0.03507775 0.007190763 0.01818323 0.03509587 0.007645308 0.01839894 0.03499633 0.007577061 0.01854974 0.03510683 0.00788176 0.0187084 0.03501749 0.007813692 0.01893323 0.03512227 0.007975161 0.01908916 0.03501641 0.007768392 0.01944917 0.03514164 0.007922768 0.0195049 0.03503376 0.007554054 0.01975947 0.03516054 0.007680714 0.01985359 0.03507834 0.007255375 0.01995205 0.03517985 0.007280826 0.02010476 0.03520077 0.006760001 0.02011227 0.03507518 0.00670278 0.01993274 0.03521335 0.006422221 0.01996088 0.03511863 0.006452739 0.01979571 0.03521001 0.006223261 0.01976251 0.03514188 0.006187081 0.01938319 0.03524112 0.006041228 0.0194329 0.03516769 0.006199479 0.01885962 0.03526371 0.006025016 0.01894414 0.0352841 0.006234109 0.01852309 0.03516018 0.006428897 0.01854336 0.03529304 0.006500899 0.01829332 0.03521078 0.006896495 0.01831018 0.03530675 0.006815254 0.01817792 0.03532028 0.007160663 0.01818209 0.0352084 0.007383584 0.01841598 0.0353406 0.007557988 0.01833039 0.03535836 0.007864356 0.01867485 0.03526264 0.007784843 0.01883065 0.03536522 0.007968068 0.01897931 0.03527265 0.007771432 0.01946187 0.03539067 0.007946789 0.01941955 0.03540456 0.007761716 0.01976704 0.03528678 0.007483422 0.01982349 0.03542059 0.007424175 0.020051 0.03531074 0.007160305 0.01996707 0.0354461 0.006825029 0.02012783 0.03535962 0.006605923 0.01990669 0.03546458 0.006352961 0.01990413 0.03538835 0.006212294 0.01946628 0.03549003 0.006066143 0.01949375 0.03550964 0.006014943 0.019028 0.03541034 0.006170094 0.01900023 0.0355184 0.006114661 0.01871633 0.03540354 0.006399214 0.01856482 0.03553789 0.00633645 0.01841074 0.03543061 0.00670892 0.01836466 0.03555262 0.006686687 0.01821136 0.03557133 0.00716716 0.01817065 0.03547805 0.007250249 0.01834565 0.03558748 0.007544279 0.0183289 0.03547441 0.007630705 0.01861935 0.0356 0.007793426 0.01857727 0.0354942 0.007801532 0.01895129 0.03561538 0.007968187 0.01895511 0.03554546 0.007763385 0.01951283 0.03563958 0.00796169 0.01934516 0.03564912 0.007810235 0.01970213 0.03566604 0.007510781 0.01999658 0.03557074 0.007402718 0.01988244 0.03556662 0.006964921 0.01997894 0.0356912 0.007053911 0.0201379 0.03570818 0.006619691 0.02006316 0.0355814 0.006609261 0.01988166 0.03572118 0.006277978 0.01983529 0.03562599 0.006343722 0.01968079 0.03574401 0.006028354 0.01939594 0.03564494 0.006177425 0.01932597 0.03574883 0.006009399 0.01905101 0.03563255 0.006174445 0.01903319 0.03565156 0.006323814 0.01866036 0.0357725 0.006160378 0.01862287 0.03579145 0.006459295 0.01831299 0.03567069 0.006614208 0.01841431 0.03568536 0.006931066 0.01832669 0.03581017 0.006832599 0.01817309 0.03570371 0.00727564 0.01836764 0.03582578 0.007315635 0.01821261 0.03584527 0.00762248 0.01838511 0.03572165 0.007632017 0.01861757 0.03586286 0.00793159 0.01881641 0.03577071 0.007822811 0.01899003 0.03588891 0.00796312 0.01936566 0.03579348 0.007774293 0.01946431 0.03590339 0.007727205 0.01981616 0.03581482 0.007506489 0.01981616 0.035923 0.007382333 0.02005547 0.03579497 0.007271885 0.01993429 0.0359475 0.006959617 0.02014309 0.03582435 0.006843984 0.0199657 0.03595846 0.006497859 0.02000403 0.03587406 0.006368815 0.01972305 0.03597372 0.006195187 0.01972728 0.03599119 0.006038606 0.01939016 0.03590059 0.006153345 0.01920044 0.03600811 0.006012439 0.01907074 0.03590583 0.006311774 0.018669 0.03602874 0.006160676 0.0186091 0.03604906 0.006623923 0.01822429 0.03595286 0.006732761 0.01835018 0.03607016 0.007122933 0.01817172 0.03593915 0.007018983 0.01832175 0.03609144 0.007600903 0.01835799 0.0359584 0.007415771 0.01843142 0.03600859 0.007736504 0.01874876 0.03610414 0.00785768 0.01867413 0.03612661 0.007979214 0.01907289 0.03600317 0.007819175 0.01925116 0.03613471 0.007958948 0.01936477 0.03602564 0.007706642 0.01958137 0.03615176 0.007793664 0.01973152 0.03604209 0.007391214 0.01988345 0.03617048 0.007369518 0.02007442 0.03608381 0.007143914 0.01997262 0.03619635 0.00690025 0.02012902 0.03610318 0.006730079 0.0199477 0.03620737 0.006516098 0.02001458 0.03609687 0.006407737 0.0197376 0.0362302 0.006168603 0.01969665 0.03611344 0.006193876 0.01937907 0.03625476 0.006005406 0.01919776 0.0361396 0.006195127 0.01892119 0.03624653 0.006042063 0.0189113 0.0362752 0.006142318 0.01864856 0.03619021 0.006486535 0.01846766 0.03628933 0.006398618 0.01836633 0.03631067 0.006807982 0.01817268 0.03621649 0.007009387 0.01831054 0.03633332 0.00739789 0.0182408 0.03623902 0.007458448 0.01844561 0.03634798 0.007720828 0.01848155 0.03621673 0.007632076 0.01860487 0.03635501 0.007936835 0.01883739 0.03627628 0.007836937 0.01910537 0.03638398 0.007980227 0.01922225 0.03627282 0.007670938 0.01964116 0.03640377 0.007797539 0.01974207 0.03631657 0.007478654 0.01984035 0.03642761 0.007322669 0.02008599 0.03634023 0.006999254 0.01999199 0.0364421 0.006894648 0.02012991 0.03645801 0.006487071 0.02000176 0.03636765 0.006453931 0.01980775 0.03648263 0.006149649 0.01966041 0.03639435 0.006176531 0.01933801 0.03649657 0.0060184 0.01928502 0.03641575 0.0061962 0.01889157 0.03651332 0.006054878 0.01884239 0.03644007 0.006491363 0.01846826 0.03653723 0.006362915 0.01837861 0.03655898 0.006904065 0.01816189 0.03643834 0.00705254 0.01831871 0.036484 0.007364869 0.01839417 0.03657841 0.0073269 0.01821553 0.03659343 0.007629752 0.01839119 0.03650587 0.007706701 0.01870352 0.03661113 0.007868587 0.0186907 0.03649461 0.007819831 0.01905214 0.03662592 0.007982194 0.01910156 0.03651839 0.007770836 0.01945286 0.03664684 0.007888317 0.01957643 0.03665608 0.007595658 0.01993966 0.03653937 0.007490694 0.01982015 0.03656256 0.007029116 0.01998192 0.03668612 0.007217764 0.02011305 0.03670239 0.006720602 0.02010369 0.03657984 0.006656825 0.01990485 0.03671979 0.006318032 0.01986753 0.03663206 0.006257355 0.01958292 0.03673142 0.006105244 0.01958143 0.03675371 0.006007909 0.01912432 0.03663098 0.006166219 0.0190677 0.03676986 0.006112217 0.01870703 0.03668248 0.006365358 0.01859372 0.0367909 0.006365478 0.0183928 0.0366699 0.006656706 0.01839601 0.03679674 0.006668269 0.01821857 0.03669154 0.007089257 0.01831972 0.03681641 0.007013499 0.01816606 0.03683418 0.007384717 0.01824414 0.03674054 0.007494032 0.01846128 0.03684532 0.00770241 0.01845794 0.03686088 0.007895708 0.01875412 0.03676325 0.00776875 0.0188381 0.03687554 0.007981181 0.01910746 0.036785 0.007832348 0.01928097 0.03688883 0.007942318 0.01942503 0.03690314 0.007795631 0.01972877 0.03680819 0.007607936 0.01972115 0.03691607 0.00752896 0.01998102 0.03679752 0.007364034 0.01989626 0.03693592 0.00713098 0.0201379 0.0368449 0.006905853 0.01998305 0.03694438 0.006794452 0.02012002 0.03686696 0.006480753 0.0198183 0.03696376 0.006420016 0.01995003 0.03698223 0.00617659 0.01970064 0.03685033 0.006287097 0.01959252 0.0369907 0.006043314 0.01941543 0.03690779 0.00614804 0.01906126 0.03700304 0.006010293 0.01904565 0.0370298 0.006168842 0.01860964 0.03693938 0.006464898 0.0184822 0.03703361 0.006373763 0.01837903 0.03705579 0.006731271 0.01820075 0.03693491 0.006878137 0.0183264 0.03707331 0.007190108 0.01817494 0.03698509 0.007387459 0.01840347 0.03708589 0.007564246 0.01833939 0.0369811 0.007669389 0.01866316 0.03710705 0.007873654 0.01869946 0.03702795 0.007840096 0.01914674 0.03713142 0.007984578 0.01914304 0.03714042 0.007930815 0.01946038 0.03702384 0.00768423 0.01960879 0.03715282 0.007777988 0.01975166 0.03704392 0.007441341 0.01985508 0.03716903 0.007487118 0.02001303 0.03719007 0.006986141 0.02014201 0.0370965 0.00686872 0.01999074 0.03719133 0.006578981 0.02004557 0.03712218 0.006406188 0.01974666 0.03721821 0.006362199 0.01991981 0.03711158 0.006182909 0.01933521 0.03723716 0.006083548 0.01953464 0.03715723 0.006157517 0.01906824 0.03725272 0.006010055 0.01917302 0.03727328 0.006100952 0.01871955 0.03715723 0.00633943 0.01864272 0.03728455 0.006402194 0.0183596 0.03717547 0.006690561 0.01837396 0.03730732 0.006799995 0.01818144 0.03719216 0.007091701 0.01833039 0.03732299 0.007224678 0.01818966 0.03724008 0.007475197 0.01845401 0.0373404 0.007599115 0.01836681 0.03726267 0.007771015 0.01883119 0.0373581 0.007854461 0.01866596 0.03737294 0.00797522 0.01902943 0.03726375 0.007812201 0.01932197 0.03738766 0.00792092 0.01950466 0.03731012 0.007581651 0.01976555 0.03740489 0.007773876 0.01976668 0.03742492 0.007406651 0.02005302 0.03731191 0.007046878 0.01998144 0.03744173 0.006961226 0.02013486 0.03746211 0.006555259 0.02003628 0.03733438 0.006617426 0.01988971 0.03747141 0.006204605 0.01974511 0.03735184 0.006296336 0.01960116 0.03748965 0.006035268 0.0193786 0.03737962 0.006162106 0.01914978 0.0375083 0.006017088 0.01899778 0.03743404 0.006391465 0.01854133 0.03753221 0.006236553 0.01850533 0.03756433 0.006660282 0.01822686 0.03742116 0.006745398 0.01835548 0.03747642 0.007212758 0.01834046 0.03747022 0.007565498 0.01854944 0.03758478 0.00763607 0.01840245 0.03751373 0.007779359 0.01884454 0.03753823 0.007816672 0.0193395 0.03183406 0.006184399 0.01938408 0.03186643 0.00622189 0.01878958 0.03195828 0.007757246 0.0187807 0.03200036 0.007682979 0.01963478 0.03202742 0.007227957 0.01996833 0.03205239 0.006709873 0.01993727 0.03207647 0.00629884 0.01963716 0.03220283 0.007697582 0.01867741 0.03222686 0.00783509 0.01916795 0.03232747 0.006293535 0.01962363 0.03235745 0.006153404 0.01902037 0.03238797 0.006484925 0.01847016 0.03243893 0.007494509 0.01846057 0.03246819 0.007828712 0.01899147 0.0325163 0.007442951 0.01986902 0.03254091 0.006942451 0.01998829 0.03256177 0.006534457 0.0198515 0.03258419 0.006225407 0.01949423 0.03260862 0.006167232 0.01899486 0.03263509 0.006440758 0.01850652 0.03266465 0.00701934 0.0183016 0.03271365 0.007805824 0.01888388 0.03280133 0.006733119 0.0199508 0.03283959 0.006190836 0.0193842 0.03286397 0.006190955 0.01887875 0.03291052 0.006932318 0.01831477 0.03297877 0.007834494 0.01921039 0.03300148 0.007671415 0.01964962 0.0330246 0.007289528 0.0199393 0.03306114 0.006544828 0.01986289 0.03308701 0.006199717 0.01944154 0.03311067 0.006181418 0.01894736 0.03313529 0.006441116 0.01850819 0.03318226 0.007377326 0.01839452 0.03320652 0.007738232 0.01875847 0.03322708 0.007833898 0.01917248 0.03325015 0.00769037 0.01962739 0.03327333 0.007306218 0.01993131 0.03337299 0.006268918 0.01870435 0.03340023 0.006716668 0.01835644 0.03342539 0.007248282 0.01834082 0.03349941 0.007689952 0.01961731 0.03352183 0.007344782 0.01991903 0.03354525 0.006852447 0.01997822 0.03356826 0.006420314 0.01976579 0.03359407 0.006163775 0.01930546 0.03367716 0.007262647 0.01833993 0.0337035 0.007700443 0.01869362 0.03372746 0.007840573 0.01918578 0.03375405 0.007638156 0.01969736 0.03382766 0.006297886 0.01961249 0.03387033 0.006248414 0.01875531 0.0340203 0.007380545 0.01990234 0.03404647 0.006821572 0.01997846 0.03408896 0.006187379 0.01939755 0.03411495 0.006201982 0.01885968 0.03414249 0.00655651 0.0184257 0.03416931 0.007124304 0.0183131 0.03420132 0.007683575 0.01864022 0.03438365 0.006419599 0.0185315 0.03447782 0.007848799 0.01917451 0.03450417 0.00763148 0.0196973 0.0345304 0.007156133 0.01998758 0.03456336 0.006506502 0.01984786 0.03459072 0.006179988 0.01936382 0.03461909 0.006227254 0.0187816 0.03464508 0.006620764 0.01839798 0.03466844 0.007092952 0.01831179 0.03470522 0.007723927 0.01873391 0.03473067 0.007838845 0.0192576 0.03476333 0.007507205 0.01983392 0.03482764 0.006291568 0.01961708 0.03487437 0.006301343 0.01868373 0.0348941 0.006595313 0.01840943 0.03491771 0.00708127 0.01831191 0.03494417 0.007583379 0.01853847 0.03497034 0.007829546 0.01903194 0.03503209 0.007128655 0.01998466 0.03508305 0.006219029 0.01950961 0.0351113 0.006183207 0.01893687 0.03515565 0.006820559 0.01831328 0.03520351 0.007703661 0.0186938 0.03522717 0.007837593 0.01917719 0.0353021 0.006711304 0.01993662 0.03532463 0.006330549 0.01967352 0.03535413 0.006144881 0.0190891 0.03542661 0.007258832 0.01834386 0.03548693 0.007808387 0.01938366 0.03551679 0.007437407 0.01987922 0.03558146 0.006249904 0.01955145 0.03572237 0.00783658 0.01907551 0.03574967 0.007699668 0.01962023 0.03581506 0.006477832 0.01981759 0.03583568 0.006218969 0.01946139 0.03585374 0.006157934 0.01908922 0.03589171 0.006556928 0.01842999 0.03596013 0.007774531 0.01882416 0.03604465 0.006863296 0.01998353 0.03613108 0.006389677 0.01857632 0.0361514 0.006745815 0.01834285 0.0361737 0.007210493 0.0183404 0.03622698 0.007849514 0.01917457 0.0362761 0.007253527 0.01995086 0.03630244 0.006712079 0.01995003 0.03632968 0.006268382 0.0195803 0.03635323 0.006156325 0.01910197 0.03637427 0.006293952 0.01868879 0.03639572 0.00663191 0.01839089 0.03644418 0.007588863 0.01854264 0.03657782 0.006289064 0.0196141 0.03662544 0.006303429 0.01866668 0.03669339 0.007565915 0.0185346 0.03671771 0.007825791 0.01897913 0.03674513 0.007745087 0.01953697 0.03678381 0.007091283 0.01998716 0.03680509 0.006653785 0.01991522 0.03685986 0.006158232 0.0189833 0.03688472 0.006442487 0.01852017 0.03692567 0.007251262 0.01834714 0.0369659 0.007808566 0.0189327 0.03698652 0.007803499 0.0193687 0.03703862 0.006991505 0.01999014 0.0370655 0.006459593 0.01981288 0.03711426 0.006201446 0.01887661 0.03718852 0.007488727 0.01846492 0.03721642 0.007818162 0.01893907 0.03726172 0.007518887 0.01981264 0.03737455 0.006284892 0.01868396 0.03742623 0.007271945 0.01834547 0.03746807 0.007825911 0.01898711 0.0374931 0.007760047 0.01949703 0.03752064 0.007383167 0.01990818 0.03183454 0.007294952 0.01820737 0.03183043 0.00611031 0.0189535 0.0318315 0.006566762 0.01828473 0.03184074 0.007676362 0.01843672 0.03255778 0.006472468 0.01831614 0.03302037 0.006005287 0.01910281 0.03404003 0.006165266 0.01862233 0.03430551 0.006420493 0.01835113 0.03445893 0.006909728 0.02012789 0.03457033 0.006743073 0.01819753 0.0378127 0.007187247 0.01996511 0.03768801 0.00708723 0.02010196 0.03767108 0.007380723 0.02004057 0.03778141 0.007383167 0.01994132 0.03771775 0.007659256 0.01982015 0.03782415 0.007628917 0.01965034 0.03772813 0.007818341 0.01959335 0.03782665 0.00778079 0.01901853 0.03779941 0.007827997 0.01935744 0.03767669 0.007927477 0.01938486 0.03774654 0.007914304 0.01910912 0.03782773 0.007573902 0.0185979 0.03765833 0.00795412 0.01898628 0.03776484 0.007822215 0.01878714 0.03770685 0.007780909 0.01861345 0.03782278 0.007321417 0.01840263 0.03774446 0.007452368 0.01834595 0.03758722 0.007422208 0.0182603 0.03782159 0.006850659 0.01834493 0.03775292 0.007099568 0.0182417 0.0376324 0.007153332 0.0181896 0.03768092 0.00681895 0.01820105 0.03782904 0.006470799 0.01855206 0.03774142 0.006500184 0.01836448 0.03780406 0.006219625 0.01877927 0.03767603 0.006241142 0.01854318 0.0377295 0.006117761 0.01882857 0.03782379 0.006201922 0.01931238 0.03772377 0.006055772 0.01907873 0.037687 0.006071627 0.01942306 0.03773844 0.006258189 0.01972419 0.03781944 0.006428301 0.01975125 0.037826 0.006841778 0.01993745 0.0376811 0.006525099 0.01998603 0.03776198 0.006787896 0.02003651 0.03767108 0.006792068 0.02009344 0.03066164 0.006283521 0.01956081 0.03066122 0.007018029 0.01998674 0.03065961 0.006280899 0.0187391 0.03066039 0.00699377 0.01832658 0.03066068 0.007707536 0.01873737 0.03065782 0.007710635 0.01958686 0.02994191 0.006231367 0.01959049 0.02994149 0.00622946 0.01870983 0.02994185 0.007760524 0.01958793 0.02994143 0.006993591 0.02003228 0.02994173 0.007758975 0.01870709 0.02994149 0.006993472 0.01826685 0.02993029 0.005744159 0.0177325 0.02993029 0.005198895 0.01862895 0.02993029 0.005141913 0.01933538 0.02993029 0.007927775 0.01750349 0.02993029 0.006792902 0.01728296 0.02993029 0.005337715 0.02001661 0.02993029 0.005808115 0.02058738 0.02993029 0.008708178 0.01837706 0.02993029 0.006487905 0.02095264 0.02993029 0.008858501 0.01933646 0.02993029 0.007273077 0.02099418 0.02993029 0.008024513 0.02071583 0.02993029 0.008595943 0.02011072 0.03183025 0.00845462 0.01794558 0.03183025 0.008861184 0.01897847 0.03183025 0.008700549 0.01993626 0.03183025 0.00797826 0.02075886 0.03183025 0.007010161 0.02102017 0.03183025 0.006284594 0.02087342 0.03183025 0.005496144 0.02030491 0.03183025 0.00512892 0.01928985 0.03183025 0.005228877 0.01855653 0.03183025 0.005555391 0.01796132 0.03183025 0.006223857 0.01744067 0.03183025 0.007339 0.01728922 0.03757995 -0.00197649 0.02851986 0.03757399 -0.002079844 0.02826434 0.03759026 -0.002382814 0.02809828 0.03758025 -0.001861691 0.02841258 0.0375806 -0.002462625 0.02786904 0.03758144 -0.002404928 0.02759987 0.0375629 -0.001543164 0.02848988 0.03758078 -0.002472877 0.02748233 0.03758072 -0.001196563 0.02858418 0.03757476 -0.001077532 0.02837121 0.03757387 -0.002101719 0.02687048 0.03756701 -8.19576e-4 0.0281465 0.03756815 -0.001724064 0.0266869 0.03758889 -5.2218e-4 0.02763658 0.03758323 -6.42995e-4 0.02718532 0.03757572 -9.17869e-4 0.02686256 0.03184342 -5.98648e-4 0.0272684 0.03188031 -5.16062e-4 0.0276637 0.03183692 -0.001605391 0.02849179 0.03189617 -6.24053e-4 0.02811139 0.03183025 -6.13513e-4 0.02785468 0.03191089 -9.65165e-4 0.02847647 0.03183007 -9.34837e-4 0.02831637 0.03193336 -0.001330375 0.02862352 0.03194969 -0.001773715 0.02860021 0.03184854 -0.002072632 0.02826315 0.0319671 -0.002127826 0.0284186 0.03198671 -0.002394676 0.02808344 0.03190088 -0.002358555 0.02771145 0.03200572 -0.002492547 0.02760869 0.03202414 -0.00233674 0.02710175 0.03193128 -0.002144634 0.02709507 0.03205072 -0.001823246 0.02670377 0.03191924 -0.001833796 0.02688533 0.03194844 -0.001420855 0.0268262 0.03207486 -0.001316905 0.0266841 0.03199589 -9.13278e-4 0.02703249 0.03209239 -9.19167e-4 0.02684873 0.03210276 -6.52856e-4 0.02715212 0.03198462 -7.1635e-4 0.02739179 0.03212332 -5.2222e-4 0.02755504 0.0320115 -6.8937e-4 0.027803 0.03213596 -5.68412e-4 0.02796 0.03202635 -8.25643e-4 0.02812463 0.03215295 -7.24661e-4 0.02825307 0.03204452 -0.001125991 0.0283932 0.03216689 -9.54842e-4 0.02847278 0.03218704 -0.001374959 0.0286327 0.03206443 -0.001556158 0.02847546 0.03211468 -0.001997113 0.02835232 0.03220582 -0.001853585 0.02857393 0.03222185 -0.00225389 0.02830213 0.03214758 -0.002344191 0.02777665 0.03224313 -0.002481043 0.02781695 0.03226041 -0.002465426 0.02742522 0.03217518 -0.002221941 0.02720117 0.03228831 -0.002293705 0.02704322 0.03227752 -0.002017259 0.02680766 0.03217893 -0.00181955 0.02687954 0.03221881 -0.001445055 0.02680289 0.03230667 -0.001703381 0.02667599 0.03232258 -0.001303255 0.0266804 0.03222078 -9.48415e-4 0.02703374 0.0323373 -9.9496e-4 0.0268014 0.03235363 -6.82437e-4 0.02709883 0.03226315 -7.22385e-4 0.02733534 0.03236913 -5.45515e-4 0.02742207 0.03226578 -7.00195e-4 0.02786803 0.03238481 -5.2867e-4 0.02779537 0.03239899 -6.58445e-4 0.02815139 0.03228479 -9.55968e-4 0.02827411 0.03241235 -9.18463e-4 0.02844834 0.03230738 -0.001312315 0.02845597 0.03244495 -0.001452386 0.02864581 0.03245151 -0.00183016 0.02858835 0.03235542 -0.001815736 0.028436 0.03247183 -0.002248764 0.02830266 0.03234231 -0.002108037 0.02822744 0.03248965 -0.002436876 0.02796721 0.03239798 -0.00233829 0.02776402 0.03250509 -0.002489805 0.02759546 0.0323984 -0.002235591 0.02724963 0.03251945 -0.002367734 0.0271604 0.0324186 -0.001871407 0.02690094 0.03254508 -0.001980602 0.02677911 0.03246223 -0.001579344 0.02681308 0.0325641 -0.001456141 0.02665984 0.03248727 -0.001058936 0.02692723 0.03258502 -9.95521e-4 0.02679699 0.0326181 -6.3537e-4 0.0271613 0.03251665 -6.9308e-4 0.02740859 0.03262096 -5.20985e-4 0.02755975 0.03251707 -7.27738e-4 0.02794075 0.03263968 -5.80665e-4 0.0280084 0.03266233 -9.05448e-4 0.02844089 0.03253608 -9.53636e-4 0.02826893 0.03255367 -0.001301586 0.02845299 0.0326842 -0.00139153 0.02863448 0.03260236 -0.001745343 0.02845585 0.03270101 -0.001762092 0.02859944 0.03272026 -0.002188503 0.02837759 0.03262984 -0.002223134 0.0281127 0.03275042 -0.002485871 0.02781611 0.03262919 -0.002334058 0.02759557 0.03276622 -0.002444922 0.02733153 0.03265249 -0.002208888 0.02720689 0.03277617 -0.002283275 0.02704101 0.03279352 -0.001911759 0.0267471 0.03270363 -0.001766324 0.0268402 0.03281331 -0.001516461 0.02666449 0.0327304 -0.001195788 0.02686649 0.03283149 -0.001213848 0.02670919 0.03284102 -8.88105e-4 0.02687948 0.03272193 -9.21519e-4 0.02706152 0.03286176 -5.94032e-4 0.02725642 0.03273421 -7.44626e-4 0.02731448 0.03288084 -5.20713e-4 0.02775335 0.03275334 -6.76288e-4 0.02772045 0.03289431 -6.44403e-4 0.02812445 0.03277808 -8.2313e-4 0.02812057 0.03291237 -8.75222e-4 0.02841228 0.03279083 -0.001120984 0.02838778 0.03292882 -0.001297712 0.02861928 0.03283852 -0.001455545 0.02848953 0.03295433 -0.001877546 0.02856844 0.03286093 -0.001913428 0.02838569 0.03296738 -0.002159535 0.02839201 0.03286004 -0.002272546 0.02797961 0.03298813 -0.002423465 0.02801579 0.03299719 -0.002494573 0.02769249 0.03290593 -0.002353489 0.0275954 0.03301918 -0.00240153 0.02723878 0.03290557 -0.002119064 0.02709048 0.03304266 -0.002066433 0.02682596 0.03292584 -0.001780271 0.02686941 0.0330609 -0.001622617 0.02667313 0.03297263 -0.001369833 0.02681368 0.03307539 -0.001195788 0.02670288 0.03299486 -9.48408e-4 0.0270254 0.0331003 -7.25704e-4 0.02703666 0.03301471 -7.09278e-4 0.0273754 0.03311902 -5.44979e-4 0.02742683 0.03313285 -5.32047e-4 0.02784782 0.03300702 -6.75306e-4 0.02771586 0.03306013 -9.12302e-4 0.02826368 0.03315377 -7.23545e-4 0.02824807 0.03317105 -9.79676e-4 0.02848601 0.03317832 -0.001284062 0.02861034 0.03309077 -0.001494348 0.02849686 0.03319555 -0.001655995 0.02862471 0.03308916 -0.001993179 0.02832239 0.03320854 -0.00198704 0.02850866 0.03323006 -0.002317607 0.02821433 0.03310894 -0.002245485 0.02802705 0.03324681 -0.002482771 0.02780038 0.03313571 -0.002334058 0.02755182 0.03326594 -0.002444148 0.0273413 0.03327733 -0.002286434 0.0270403 0.03314846 -0.002192914 0.02717953 0.03329133 -0.00196743 0.02678114 0.033167 -0.001913607 0.02692943 0.03319132 -0.001515448 0.02681946 0.03331434 -0.001492083 0.02665364 0.033243 -9.65726e-4 0.02699065 0.03333395 -0.001019239 0.02679175 0.0333513 -7.53667e-4 0.02700841 0.03324425 -6.87423e-4 0.02750015 0.03337049 -5.28947e-4 0.02746164 0.03326267 -6.94505e-4 0.02784216 0.03339153 -5.63774e-4 0.02794027 0.03340709 -7.65883e-4 0.02831476 0.03328061 -8.56534e-4 0.02816283 0.03329831 -0.001185357 0.02842015 0.03342717 -0.001187264 0.02858561 0.03343981 -0.001519501 0.02863913 0.03334772 -0.001659274 0.02848094 0.03346186 -0.00201404 0.02850395 0.0333451 -0.00210464 0.02822244 0.03347855 -0.002370238 0.02814626 0.03338778 -0.002277851 0.02797067 0.0335071 -0.002492189 0.02752834 0.03340959 -0.002338886 0.02752423 0.03352671 -0.00231713 0.02709203 0.03340995 -0.002078771 0.02703821 0.03353768 -0.002022087 0.02680969 0.03344953 -0.001836299 0.0268709 0.03355878 -0.001677513 0.02667593 0.03343099 -0.001556038 0.0268166 0.03358262 -0.001196205 0.02670836 0.0334593 -0.001115024 0.02691799 0.03359669 -7.69274e-4 0.02698111 0.0334745 -8.63844e-4 0.02712863 0.03361302 -5.40729e-4 0.02743887 0.03352493 -6.5933e-4 0.0275771 0.033634 -5.2603e-4 0.02779585 0.03352731 -8.02747e-4 0.02809214 0.03365296 -6.60334e-4 0.02815657 0.03366816 -0.001019477 0.02852153 0.03357583 -0.001191854 0.02844619 0.03369158 -0.001603007 0.02863657 0.03357613 -0.00174725 0.02844494 0.03371924 -0.002097964 0.02844518 0.03359699 -0.002088844 0.02823668 0.03373199 -0.002389729 0.02808707 0.03364574 -0.002335846 0.02781003 0.03375345 -0.002497494 0.02758288 0.03366732 -0.00229001 0.02736473 0.03377503 -0.002316951 0.02708709 0.03366017 -0.00205338 0.02702367 0.03379172 -0.002014279 0.02680307 0.03367942 -0.00169599 0.02684605 0.03381025 -0.001704514 0.02668291 0.03369939 -0.001327276 0.02683889 0.03383016 -0.001158833 0.02671521 0.03375005 -8.67197e-4 0.02709507 0.03384959 -7.83859e-4 0.02698135 0.03386348 -5.71971e-4 0.02731055 0.03375017 -6.75532e-4 0.02759647 0.0338692 -5.1256e-4 0.02769917 0.0338 -7.76335e-4 0.0280916 0.03389918 -6.24874e-4 0.02809721 0.03390961 -8.6801e-4 0.02840197 0.03379625 -0.001124322 0.02838826 0.03392988 -0.001160919 0.02857434 0.0338118 -0.001442611 0.0284745 0.03393918 -0.001576244 0.02863413 0.03383004 -0.001796424 0.02843016 0.03395944 -0.001924693 0.02854162 0.03397852 -0.002291619 0.02825385 0.03388381 -0.002253234 0.02805376 0.03399002 -0.002459228 0.0278989 0.03390836 -0.002335548 0.02754092 0.03400647 -0.00248152 0.02751016 0.03390604 -0.002132713 0.02710133 0.0340228 -0.002350986 0.02714747 0.03403908 -0.002128243 0.02688491 0.03392571 -0.001759588 0.02685898 0.03405314 -0.001805007 0.02671456 0.03406739 -0.001446425 0.02666336 0.03394365 -0.00138247 0.02683264 0.03408628 -0.001033782 0.02677989 0.03396439 -0.001048266 0.02695494 0.03409397 -6.89571e-4 0.02708399 0.03398126 -7.62511e-4 0.0272811 0.03400516 -6.73031e-4 0.02767652 0.03412419 -5.36583e-4 0.02745389 0.03413224 -5.4084e-4 0.02783817 0.03405612 -8.53789e-4 0.02819484 0.03415668 -7.13739e-4 0.02825814 0.03417694 -0.001135826 0.02856415 0.03405547 -0.001308381 0.02845442 0.0341835 -0.001396656 0.02863246 0.03420305 -0.001802265 0.02859538 0.03410667 -0.001857042 0.02842718 0.03421711 -0.002141356 0.02840375 0.03423351 -0.002380669 0.0281192 0.03413891 -0.00230354 0.02793991 0.03423053 -0.002474725 0.0277974 0.03413867 -0.002289533 0.0273723 0.03425902 -0.002484679 0.02749609 0.03428536 -0.002267479 0.02700847 0.03419017 -0.002010464 0.02696734 0.03430193 -0.00173527 0.026681 0.03418821 -0.001546204 0.02681761 0.03432399 -0.001294672 0.02669012 0.03424131 -9.99763e-4 0.0269708 0.03434067 -9.48178e-4 0.02683418 0.03435367 -6.79773e-4 0.02711009 0.03427028 -6.68484e-4 0.02748805 0.03437411 -5.15282e-4 0.02756661 0.03427368 -7.85233e-4 0.02806591 0.03439718 -6.05603e-4 0.02806162 0.0344063 -8.12917e-4 0.02835297 0.03432255 -0.001123726 0.02841055 0.03442955 -0.001242637 0.02861005 0.03432327 -0.001664876 0.02846401 0.034451 -0.001822173 0.02859085 0.03436988 -0.002067923 0.0282799 0.0344755 -0.002240419 0.02831006 0.03449094 -0.002467036 0.0278902 0.0343908 -0.002296864 0.02791255 0.03441119 -0.002334058 0.02747923 0.03451007 -0.002469003 0.0274415 0.03453296 -0.002286851 0.02704447 0.0344398 -0.00202316 0.02697837 0.03453344 -0.002017378 0.02679491 0.03446209 -0.00158596 0.02681863 0.03456324 -0.001541256 0.02666318 0.03445255 -0.001209378 0.02687019 0.03457909 -0.001137554 0.02672946 0.03460663 -7.81653e-4 0.02697211 0.03450703 -7.77627e-4 0.02721518 0.03460949 -5.39408e-4 0.0274046 0.03453177 -6.67346e-4 0.02772718 0.03463846 -5.48453e-4 0.02789151 0.03452497 -8.20989e-4 0.02811664 0.03466302 -8.05398e-4 0.02836096 0.03455084 -0.001133561 0.02839565 0.03467684 -0.001208961 0.02859312 0.03455847 -0.001450538 0.02848035 0.03469252 -0.001684486 0.02862435 0.03458136 -0.001856625 0.02839869 0.03471553 -0.00204432 0.02847284 0.03460097 -0.002179741 0.02813816 0.03472942 -0.002328276 0.02819532 0.03462344 -0.002332925 0.0277366 0.03474515 -0.002476036 0.02782255 0.03475826 -0.002465307 0.02742153 0.03464192 -0.002273201 0.02734225 0.03468525 -0.002087652 0.02703815 0.03477847 -0.002243638 0.02698349 0.03480166 -0.001642644 0.02666425 0.03471255 -0.001581549 0.02680736 0.03482818 -0.001135051 0.02673399 0.03471499 -0.00109452 0.02692896 0.03484618 -8.21262e-4 0.02693557 0.03472512 -7.79029e-4 0.0272417 0.03486347 -5.93576e-4 0.02727228 0.03476876 -6.88007e-4 0.0274555 0.03488212 -5.16609e-4 0.02770066 0.03475886 -6.7822e-4 0.02775067 0.03489536 -6.33748e-4 0.02811276 0.03480947 -9.03514e-4 0.02824556 0.03491383 -9.10491e-4 0.02844232 0.03483533 -0.00138992 0.02848511 0.03492993 -0.001382172 0.02863168 0.03482347 -0.001713097 0.02845561 0.03495264 -0.00177288 0.02860426 0.03487503 -0.002143025 0.02819752 0.03496658 -0.002112984 0.02842122 0.03497892 -0.00234133 0.02817434 0.03486645 -0.002324879 0.02780795 0.03500044 -0.002496898 0.02772581 0.03491461 -0.00231719 0.02741318 0.03502321 -0.002347886 0.027116 0.03493887 -0.002032518 0.02699643 0.03504514 -0.001952409 0.02676826 0.03496438 -0.001540243 0.02680182 0.03506594 -0.001482248 0.02665227 0.03498941 -0.001028954 0.02695775 0.0350874 -9.81287e-4 0.02680546 0.0350154 -6.9224e-4 0.02739626 0.03510475 -6.69087e-4 0.02712255 0.03512024 -5.52962e-4 0.02739715 0.03513002 -5.27467e-4 0.02776253 0.0350455 -7.32835e-4 0.02799457 0.03514856 -6.1677e-4 0.02807974 0.03516232 -8.80375e-4 0.02841603 0.03503406 -9.59976e-4 0.02827614 0.03505587 -0.001374065 0.0284723 0.03518688 -0.001352012 0.02863281 0.03519719 -0.001719951 0.02861571 0.03507584 -0.001776576 0.02843481 0.03521162 -0.002145349 0.02840828 0.03511947 -0.002061128 0.02828609 0.03514826 -0.002350926 0.02775478 0.03523457 -0.002376973 0.02810329 0.0352534 -0.002491891 0.02771723 0.03526741 -0.002424061 0.0272786 0.03514993 -0.002214372 0.02721971 0.035286 -0.002093911 0.02684926 0.03516566 -0.001979887 0.02697652 0.03517979 -0.001671075 0.02683687 0.0353102 -0.001631617 0.02667123 0.03520017 -0.001306593 0.02684628 0.03532832 -0.001152276 0.02672386 0.03524529 -9.30264e-4 0.02703106 0.03534966 -7.37817e-4 0.02702301 0.03524672 -6.90525e-4 0.02748739 0.03537237 -5.23739e-4 0.02750486 0.0352627 -7.07953e-4 0.02789103 0.03539741 -6.06833e-4 0.02808064 0.03528404 -9.3636e-4 0.02825164 0.03541356 -9.61234e-4 0.02847695 0.03530734 -0.001295506 0.02845436 0.0354374 -0.001470088 0.02864348 0.03531861 -0.001669168 0.02846318 0.03546684 -0.00206393 0.02847635 0.0353434 -0.002030432 0.02829289 0.03548419 -0.002397716 0.0280683 0.03536343 -0.002299606 0.027902 0.03550499 -0.00249803 0.0275951 0.03541553 -0.002309978 0.02737444 0.03551995 -0.00232613 0.02710169 0.03544145 -0.001985967 0.02696317 0.03554838 -0.001996099 0.02678143 0.03546506 -0.001510798 0.02680265 0.03556764 -0.001490712 0.02666568 0.03558593 -0.001057803 0.02676063 0.03546035 -0.00108546 0.02693766 0.0355972 -7.55102e-4 0.02700459 0.03547972 -8.07235e-4 0.02720034 0.03561586 -5.54771e-4 0.02737337 0.0355305 -6.59734e-4 0.02770841 0.03562748 -5.2382e-4 0.02776122 0.03565317 -6.75264e-4 0.02818608 0.03553146 -8.82303e-4 0.0282039 0.03566133 -9.75798e-4 0.02848553 0.03554987 -0.001174211 0.02840816 0.03568518 -0.001411974 0.02863842 0.03559386 -0.001567363 0.02848672 0.035703 -0.001812934 0.02858996 0.03559136 -0.002031862 0.02829718 0.03571486 -0.002084553 0.02844548 0.0356335 -0.002243399 0.0280503 0.03572797 -0.002296388 0.02823895 0.03574126 -0.002454817 0.02791357 0.03565812 -0.00234574 0.02753448 0.03576254 -0.002484261 0.02752411 0.03577184 -0.002343595 0.02712345 0.03564661 -0.002199053 0.02719295 0.03579211 -0.001986622 0.02678608 0.03566879 -0.00191617 0.02692782 0.03571856 -0.001446962 0.02681034 0.03580993 -0.001580715 0.02666616 0.03582793 -0.001257419 0.02669388 0.03574746 -8.9036e-4 0.02705216 0.0358408 -8.23662e-4 0.02692997 0.03586024 -6.1833e-4 0.02720957 0.0357781 -6.60116e-4 0.02765476 0.03588259 -5.10258e-4 0.02770477 0.03577172 -7.77177e-4 0.02805161 0.03589916 -6.62365e-4 0.02816033 0.03590983 -9.2879e-4 0.02845209 0.03578633 -9.87656e-4 0.02829605 0.0358054 -0.001332342 0.02846235 0.03593069 -0.001245379 0.02860873 0.03594756 -0.001701414 0.02861714 0.03582364 -0.001707673 0.02845317 0.03584456 -0.002077937 0.02825218 0.03596216 -0.002012372 0.02849251 0.03597939 -0.002286612 0.02825444 0.03589236 -0.002309143 0.02787959 0.03598737 -0.002467572 0.02786582 0.03591448 -0.002318263 0.02741867 0.0360077 -0.002487123 0.02754062 0.03602957 -0.002348899 0.02713286 0.03594404 -0.001943528 0.02691668 0.03604477 -0.001961529 0.02676653 0.03606832 -0.001493155 0.02666187 0.03594624 -0.001410245 0.02682185 0.03606998 -0.001207768 0.02670854 0.03599733 -8.98334e-4 0.02705919 0.03609406 -8.76864e-4 0.02689123 0.03610575 -6.28129e-4 0.02719402 0.03602385 -6.68286e-4 0.02754914 0.03613066 -5.16236e-4 0.02763473 0.03604954 -7.81721e-4 0.02809453 0.03614109 -6.27666e-4 0.02811527 0.03616708 -9.41057e-4 0.02846348 0.03607708 -0.001217782 0.02844268 0.03619068 -0.001367151 0.0286287 0.03609842 -0.001663804 0.02847146 0.03619539 -0.00174874 0.02860987 0.03609526 -0.002063512 0.02826738 0.03621929 -0.00218141 0.0283724 0.03624236 -0.00244224 0.02796232 0.0361492 -0.002353489 0.02773654 0.03624969 -0.00249052 0.02757823 0.03615415 -0.002181828 0.02716696 0.03627341 -0.002364873 0.02716404 0.03619813 -0.001862764 0.026883 0.03628867 -0.002114355 0.02687728 0.03630459 -0.001746118 0.02668815 0.03622335 -0.001345336 0.02682447 0.03632175 -0.001315712 0.02668476 0.0363391 -0.001008391 0.02679705 0.0362482 -8.85458e-4 0.02707165 0.0363509 -7.44916e-4 0.02702647 0.03636693 -5.26596e-4 0.02744674 0.0362755 -6.62264e-4 0.02758806 0.03639447 -5.93807e-4 0.02803742 0.03630429 -8.29924e-4 0.02817106 0.03640621 -8.39687e-4 0.02837866 0.03630429 -0.001228094 0.02843201 0.03642469 -0.001130759 0.02856004 0.03643697 -0.001524031 0.02863836 0.03635156 -0.001727521 0.0284658 0.03645282 -0.001803576 0.02859538 0.03637546 -0.002146661 0.02819114 0.03647202 -0.002161622 0.02839046 0.03649139 -0.002471745 0.02789694 0.03639978 -0.002350032 0.02771657 0.03651601 -0.002457618 0.0274077 0.03640055 -0.002216219 0.02722692 0.03652817 -0.002251207 0.02698695 0.03641802 -0.001915812 0.0269258 0.03654932 -0.001775979 0.02670055 0.03646755 -0.001474916 0.0267989 0.03656828 -0.001473546 0.02665919 0.03658384 -0.00100547 0.02679574 0.03645515 -0.001124083 0.02691417 0.03647714 -8.28714e-4 0.02717053 0.03660297 -6.96204e-4 0.02707463 0.0364952 -6.93513e-4 0.02749305 0.03662282 -5.18801e-4 0.02753692 0.03651314 -7.04042e-4 0.02787089 0.03664046 -5.64218e-4 0.027947 0.0366559 -7.92058e-4 0.02834552 0.03653913 -9.19524e-4 0.02824252 0.03656095 -0.001348435 0.0284658 0.03667861 -0.001307427 0.02861744 0.03669953 -0.001753568 0.02860867 0.03657823 -0.001766562 0.02843785 0.03662729 -0.002181708 0.02816581 0.03672122 -0.002190649 0.02836239 0.03674083 -0.002430796 0.02799999 0.03674441 -0.0024966 0.02762275 0.03662443 -0.002332687 0.02774572 0.03667443 -0.002232313 0.02722352 0.03677088 -0.002384662 0.02720004 0.03678733 -0.002182722 0.02693593 0.03666603 -0.001981675 0.02697378 0.03679966 -0.001793146 0.02670168 0.0366823 -0.001642942 0.02682971 0.03682827 -0.001346945 0.02667284 0.03673142 -0.001185894 0.02687662 0.03684079 -8.93136e-4 0.02686828 0.03675419 -8.04271e-4 0.02717167 0.03685557 -5.89247e-4 0.02726101 0.03675806 -6.76618e-4 0.02772808 0.03688305 -5.30156e-4 0.02785187 0.03677433 -8.02113e-4 0.02808636 0.03690165 -6.81634e-4 0.02819555 0.03682172 -0.001116693 0.02839821 0.03691822 -9.52191e-4 0.02847039 0.03693449 -0.001396 0.02863323 0.03684633 -0.001630723 0.02848517 0.03695368 -0.001902759 0.0285601 0.0368424 -0.002158045 0.02817809 0.03697508 -0.002226531 0.02832913 0.03688687 -0.002271056 0.02799379 0.03699368 -0.002443671 0.02794611 0.0369122 -0.002332925 0.02745562 0.03700101 -0.002490341 0.02759647 0.03702276 -0.002389907 0.02721548 0.03694307 -0.001963376 0.02693319 0.03703635 -0.002069413 0.02683103 0.03706204 -0.001547217 0.02665883 0.03696763 -0.001469254 0.02681434 0.03698825 -0.001054465 0.02693718 0.03708809 -0.001018762 0.02677786 0.03710317 -6.58525e-4 0.02714759 0.03697258 -8.36345e-4 0.02714908 0.03700226 -6.7357e-4 0.02761811 0.03712505 -5.27449e-4 0.02749544 0.0371403 -5.60353e-4 0.02793747 0.0370472 -7.60851e-4 0.02802664 0.03715491 -7.89588e-4 0.02833551 0.03706657 -0.001025915 0.02834618 0.03717905 -0.001222193 0.02859926 0.03708821 -0.001449346 0.02848333 0.03719466 -0.001685917 0.02861934 0.03710997 -0.001895248 0.02840179 0.03721737 -0.002033889 0.02848285 0.03720992 -0.002276182 0.02825623 0.03713667 -0.00227636 0.02799266 0.03723645 -0.002404272 0.02807122 0.03725475 -0.002491474 0.02764755 0.03712618 -0.00233376 0.0276336 0.0372681 -0.002398967 0.02723366 0.03715044 -0.002207338 0.0272026 0.03729242 -0.002132296 0.02688413 0.0371983 -0.001859366 0.02689206 0.03730398 -0.001781582 0.02670347 0.03722536 -0.001312613 0.02681541 0.03731626 -0.00139147 0.02666425 0.03733414 -9.75032e-4 0.02681946 0.03721964 -9.18596e-4 0.02706974 0.03735363 -7.2556e-4 0.02705037 0.03723609 -7.2873e-4 0.02735787 0.03737187 -5.39898e-4 0.02742123 0.03725838 -6.83882e-4 0.02778553 0.03738027 -5.26434e-4 0.02778595 0.03739482 -6.49539e-4 0.02813577 0.03730821 -8.78781e-4 0.02822917 0.03741717 -9.17494e-4 0.02845036 0.03733813 -0.001446545 0.02849519 0.03743469 -0.001358985 0.02862489 0.03744566 -0.001663208 0.02862411 0.03733354 -0.001874625 0.02838909 0.03745645 -0.002056479 0.02847069 0.03738003 -0.002213299 0.02811402 0.03748452 -0.002421617 0.02802324 0.03740555 -0.002344608 0.02760404 0.03750646 -0.002488315 0.02754968 0.03740531 -0.002128601 0.02709186 0.03751987 -0.002349734 0.02714025 0.03753751 -0.002140522 0.02689754 0.03745126 -0.001809477 0.026856 0.03747749 -0.00124669 0.02684921 0.03744894 -0.00105524 0.02694702 0.03751367 -7.20624e-4 0.02734458 0.03753817 -6.83329e-4 0.02783954 0.03183406 -0.00231558 0.02788406 0.03186643 -0.002278029 0.02728962 0.03193891 -0.001004874 0.02696645 0.0320639 -0.001998364 0.02833467 0.03208875 -0.002309739 0.0279054 0.03211343 -0.002306282 0.02738964 0.03213721 -0.002018988 0.02698326 0.03217506 -0.001269996 0.02683675 0.03221851 -6.73064e-4 0.02749562 0.03229647 -0.001675546 0.02847135 0.03234833 -0.002356469 0.02769595 0.03242039 -0.001357376 0.02682173 0.0324468 -8.83378e-4 0.02707225 0.03247171 -6.68769e-4 0.02756017 0.03255194 -0.001791715 0.02845007 0.0325793 -0.00222671 0.02808511 0.0326448 -0.001908779 0.02689862 0.03267186 -0.001328229 0.02682656 0.03279238 -0.001588284 0.02848607 0.03281712 -0.002059519 0.02828842 0.03285992 -0.002323627 0.02746188 0.03292477 -0.001284301 0.02683335 0.03295165 -8.10095e-4 0.02716493 0.03299605 -7.65701e-4 0.02805876 0.03302037 -0.001135885 0.02840638 0.03304332 -0.001596868 0.02848523 0.0331788 -0.001185595 0.02686947 0.03320258 -8.07429e-4 0.02717995 0.03330034 -0.001750767 0.0284602 0.0333442 -0.002337157 0.02779197 0.03337067 -0.002251088 0.02725249 0.0334649 -6.9753e-4 0.02741169 0.03348469 -6.89679e-4 0.02783459 0.03352445 -0.00120449 0.0284422 0.03358387 -0.002262413 0.02800667 0.03360778 -0.002341985 0.0275017 0.03369134 -9.65849e-4 0.02700257 0.03370964 -7.40041e-4 0.02731716 0.0337463 -7.72237e-4 0.02806073 0.0338211 -0.002121925 0.02823168 0.0338515 -0.002359807 0.02762514 0.03400593 -8.70828e-4 0.02822196 0.03405261 -0.00180912 0.02844452 0.03408598 -0.002300858 0.0279684 0.03413754 -0.002015352 0.02698355 0.0341795 -0.001181125 0.02687239 0.03420054 -8.3198e-4 0.02715164 0.03422451 -6.57492e-4 0.0276094 0.03427344 -0.001191318 0.02843636 0.03432303 -0.002150475 0.02820312 0.03435009 -0.002346396 0.0276739 0.03437203 -0.002229988 0.02722597 0.03439885 -0.001822054 0.02685946 0.03445065 -8.34109e-4 0.02714496 0.03447592 -6.55772e-4 0.02763766 0.03464269 -0.001931726 0.02691179 0.03466993 -0.00137192 0.02682018 0.03474271 -7.41005e-4 0.02799421 0.03476917 -0.001107811 0.0284065 0.0348168 -0.00205034 0.02829337 0.03487312 -0.002230703 0.02721071 0.03489696 -0.001843631 0.02688312 0.03491854 -0.001401662 0.02681535 0.03494316 -9.31631e-4 0.02702713 0.03496569 -6.95483e-4 0.02743476 0.03498661 -6.91156e-4 0.02786642 0.03507375 -0.002156496 0.02817803 0.03509914 -0.002350986 0.02770775 0.03519731 -8.76764e-4 0.02708369 0.03536343 -0.002305328 0.02739024 0.03539055 -0.001970291 0.02693659 0.03541576 -0.001454651 0.0268135 0.03547757 -6.54752e-4 0.02768337 0.03554362 -0.001586616 0.02849835 0.03559637 -0.002352178 0.02774769 0.03566706 -0.00143069 0.02680385 0.03569531 -9.04122e-4 0.02705627 0.03572076 -6.66916e-4 0.02754187 0.03584188 -0.002332329 0.02783733 0.03586751 -0.002274274 0.02731359 0.03589081 -0.001959919 0.02693814 0.03593915 -0.001003146 0.02696818 0.03596597 -6.88138e-4 0.02743297 0.03599286 -7.31711e-4 0.02799504 0.03601658 -0.001067757 0.02836638 0.03604191 -0.001585185 0.0284965 0.03608995 -0.002316534 0.02788871 0.03611308 -0.002304732 0.02739799 0.03615134 -0.001754522 0.02684295 0.03617763 -0.001217186 0.02685594 0.03620451 -7.81624e-4 0.02720928 0.03622949 -6.67055e-4 0.02772605 0.03625166 -8.34215e-4 0.02815729 0.03629237 -0.001571536 0.02849113 0.03632164 -0.002145111 0.02821958 0.03635412 -0.002351045 0.02758443 0.03641414 -0.001483619 0.02681523 0.03651875 -0.001097679 0.02838528 0.03657239 -0.002137839 0.02819865 0.03661584 -0.002298474 0.02735728 0.03667879 -0.001189172 0.02686071 0.03670865 -7.29832e-4 0.02729898 0.03677195 -0.001146435 0.02842158 0.03679996 -0.001746833 0.02846014 0.03684943 -0.002342641 0.0276857 0.03687477 -0.002208411 0.02717226 0.03690016 -0.001778185 0.02685672 0.03692311 -0.001301348 0.02683001 0.03699451 -7.43972e-4 0.02802956 0.03702074 -0.001143813 0.02840936 0.03704458 -0.001634478 0.02848458 0.03707474 -0.002173125 0.02818161 0.03714638 -0.001849889 0.02686983 0.03717583 -0.001258373 0.02684396 0.03725999 -9.51649e-4 0.02829301 0.03728669 -0.001461029 0.02849078 0.03733313 -0.002266287 0.02803581 0.03736197 -0.00231719 0.02741897 0.03741085 -0.001573801 0.02680385 0.03746068 -7.10559e-4 0.02733916 0.03748947 -7.08684e-4 0.02792459 0.0375173 -0.00106734 0.02838051 0.03183484 -0.001198172 0.02670884 0.03183043 -0.002389609 0.02745354 0.0318315 -0.001933157 0.02678471 0.03184407 -8.00499e-4 0.02696007 0.03295773 -0.001567125 0.02863049 0.03480839 -0.00203514 0.02681565 0.03668355 -9.89921e-4 0.02848881 0.03749305 -0.002281844 0.02824902 0.03782922 -0.001058816 0.02828252 0.03779458 -0.001283049 0.0284928 0.03768575 -0.001441001 0.02860665 0.03772103 -0.001055598 0.02847969 0.03776586 -8.74185e-4 0.0283004 0.03782415 -8.11473e-4 0.02804934 0.03758275 -8.47986e-4 0.02838128 0.03774315 -6.56138e-4 0.02801066 0.03782635 -7.21925e-4 0.02762335 0.03758847 -6.29043e-4 0.02811002 0.03778809 -6.34507e-4 0.02774971 0.0376926 -5.63927e-4 0.02782148 0.0378282 -8.51505e-4 0.02720952 0.03778821 -6.58104e-4 0.02744728 0.0376724 -5.4857e-4 0.02754116 0.03778356 -7.95836e-4 0.02711975 0.037687 -6.15652e-4 0.0272898 0.03768151 -7.94832e-4 0.02700442 0.03782176 -0.001114726 0.02693599 0.03769499 -0.001000463 0.02683621 0.03757506 -0.00113672 0.02673214 0.03782588 -0.001730918 0.02687978 0.03777724 -0.001340568 0.02677422 0.03767526 -0.001455187 0.02668285 0.03778767 -0.001603543 0.02678477 0.03768801 -0.001817286 0.02674341 0.03774797 -0.002001047 0.02687489 0.0378226 -0.002135396 0.02713924 0.03767704 -0.002162635 0.02695113 0.03774154 -0.002284765 0.02715206 0.03782737 -0.002294182 0.02761811 0.03758621 -0.002317488 0.02709662 0.03778958 -0.002375781 0.02753657 0.03767216 -0.00242418 0.02734863 0.03767925 -0.002465188 0.02772617 0.0377534 -0.002348363 0.02800214 0.03782421 -0.002232074 0.02800154 0.03767627 -0.002204596 0.02831333 0.03782606 -0.001702189 0.02842128 0.03778493 -0.002036631 0.02836042 0.03769433 -0.001877665 0.02853262 0.03777146 -0.001593291 0.02853709 0.03758972 -0.001645028 0.02862435 0.03066164 -0.002216398 0.02806079 0.03066122 -0.00148189 0.02848672 0.03065961 -0.002219021 0.02723908 0.03066039 -0.001506149 0.02682656 0.03066068 -7.92434e-4 0.02723735 0.03065782 -7.89338e-4 0.0280869 0.02994191 -0.002268552 0.02809047 0.02994149 -0.00227046 0.02720981 0.02994185 -7.39454e-4 0.02808797 0.02994143 -0.001506328 0.02853226 0.02994173 -7.41008e-4 0.02720707 0.02994149 -0.001506447 0.02676683 0.02993029 -0.002650916 0.02616226 0.02993029 -0.003186047 0.02684032 0.02993029 -0.00338006 0.02764999 0.02993029 -0.001567542 0.02575874 0.02993029 -0.003162205 0.02851659 0.02993029 -0.002561926 0.02920049 0.02993029 -4.1855e-4 0.02611273 0.02993029 1.70756e-4 0.0268265 0.02993029 -0.00175178 0.0295006 0.02993029 3.75855e-4 0.02772843 0.02993029 -9.67968e-4 0.02944153 0.02993029 9.59866e-5 0.02861076 0.02993029 -3.43646e-4 0.02910608 0.03183025 -0.001167356 0.02581918 0.03183025 -3.93591e-4 0.02613067 0.03183025 2.488e-4 0.02697813 0.03183025 3.46906e-4 0.02792906 0.03183025 -6.17184e-5 0.02886092 0.03183025 -7.81095e-4 0.02936697 0.03183025 -0.001489758 0.02952021 0.03183025 -0.002215385 0.0293734 0.03183025 -0.002902686 0.02890402 0.03183025 -0.003315091 0.02811092 0.03183025 -0.003308415 0.02707737 0.03183025 -0.002729058 0.02624034 0.03183025 -0.001953423 0.02582639 0.03183025 -9.16121e-4 0.02863144 0.0321303 -9.00121e-4 0.02862167 0.03183025 -4.29708e-4 0.02805131 0.0321303 -4.49321e-4 0.02808481 0.0321303 -3.77693e-4 0.02758496 0.03183025 -3.9703e-4 0.02740651 0.0321303 -5.06791e-4 0.02709579 0.03183025 -6.2837e-4 0.02692651 0.0321303 -0.001033246 0.02660489 0.03183025 -0.001114964 0.02657896 0.0321303 -0.001702308 0.02653002 0.03183025 -0.001673758 0.02652907 0.03183025 -0.002209305 0.02675163 0.0321303 -0.002327978 0.02684712 0.03183025 -0.002557337 0.0272271 0.0321303 -0.002629399 0.02748048 0.03183025 -0.002631485 0.02786815 0.0321303 -0.002553105 0.02810198 0.03183025 -0.002317309 0.02844244 0.0321303 -0.002093553 0.02863144 0.03183025 -0.00170511 0.02878576 0.0321303 -0.001495718 0.02878421 0.03183025 -9.93212e-4 0.02532088 0.0321303 -9.04087e-4 0.02536606 0.0321303 3.91782e-5 0.02584004 0.03183025 -4.86895e-5 0.0257948 0.03183025 4.68783e-4 0.02635312 0.0321303 6.27866e-4 0.02664315 0.03183025 8.09666e-4 0.02716284 0.0321303 8.50429e-4 0.02743327 0.03183025 7.79508e-4 0.02833425 0.0321303 7.67422e-4 0.02828925 0.0321303 2.44659e-4 0.02927327 0.03183025 1.20666e-4 0.02937382 0.03183025 -6.2626e-4 0.02983862 0.0321303 -7.69465e-4 0.02989798 0.03183025 -0.001426994 0.03001391 0.0321303 -0.001641094 0.03000766 0.03183025 -0.002519547 0.02980178 0.0321303 -0.002477109 0.02980476 0.0321303 -0.003324687 0.02917695 0.03183025 -0.003378748 0.02909314 0.03183025 -0.003810465 0.02819579 0.0321303 -0.003795683 0.02823328 0.0321303 -0.003839671 0.0272383 0.03183025 -0.003833711 0.02725821 0.03183025 -0.003532826 0.02643281 0.0321303 -0.003427445 0.0262677 0.03183025 -0.002945601 0.02577877 0.0321303 -0.002832353 0.02570289 0.03183025 -0.002163589 0.02537834 0.0321303 -0.001957237 0.02531433 0.03183025 0.007583856 0.02863144 0.0321303 0.00759983 0.02862161 0.03183025 0.008029401 0.02812683 0.0321303 0.008101165 0.02798116 0.03183025 0.008121788 0.02743178 0.0321303 0.008059859 0.02725261 0.03183025 0.007831275 0.02688646 0.0321303 0.00777924 0.02683311 0.03183025 0.007384955 0.02657896 0.0321303 0.007356822 0.02657341 0.0321303 0.006797611 0.02653002 0.03183025 0.006826162 0.02652907 0.03183025 0.006290674 0.02675163 0.0321303 0.006172001 0.02684712 0.03183025 0.005942642 0.0272271 0.0321303 0.00587058 0.02748048 0.03183025 0.005868434 0.02786815 0.0321303 0.005975246 0.02818346 0.03183025 0.00618261 0.02844244 0.0321303 0.006484866 0.02866548 0.03183025 0.006794869 0.02878576 0.0321303 0.007004261 0.02878421 0.0321303 0.007072985 0.02528601 0.03183025 0.007506787 0.02532088 0.0321303 0.007873713 0.02546131 0.03183025 0.008451282 0.0257948 0.0321303 0.008620619 0.02592617 0.03183025 0.009103298 0.02654743 0.0321303 0.009181857 0.02674865 0.03183025 0.009364128 0.02768999 0.0321303 0.0093652 0.02794694 0.03183025 0.009155333 0.02860426 0.0321303 0.008744657 0.02927327 0.03183025 0.008620619 0.02937382 0.03183025 0.007873713 0.02983862 0.0321303 0.007730484 0.02989798 0.03183025 0.007072985 0.03001391 0.0321303 0.006858825 0.03000766 0.03183025 0.005980372 0.02980178 0.0321303 0.00602287 0.02980476 0.0321303 0.005175292 0.02917695 0.03183025 0.005121171 0.02909314 0.03183025 0.004689455 0.02819573 0.0321303 0.004704236 0.02823328 0.0321303 0.004660308 0.0272383 0.03183025 0.004673123 0.02719986 0.03183025 0.004946231 0.02648741 0.0321303 0.005072474 0.0262677 0.03183025 0.00545752 0.02584725 0.0321303 0.005962133 0.02550488 0.03183025 0.006336331 0.02537834 0.03758019 0.006228923 0.02826398 0.03757548 0.006412029 0.0282545 0.03756135 0.006828248 0.0284723 0.03758144 0.006094992 0.02759993 0.03758031 0.007001817 0.02862811 0.03758579 0.006024599 0.02747327 0.0375666 0.007113933 0.02847766 0.03758674 0.007382631 0.02855539 0.03757244 0.007475554 0.02834236 0.03758233 0.007720232 0.02832531 0.03757512 0.006423532 0.02685821 0.03756982 0.007700443 0.02813631 0.03758102 0.007947921 0.02788048 0.03758805 0.007967948 0.02754259 0.03758388 0.007856369 0.02717614 0.03184676 0.007914483 0.0272932 0.03187412 0.007979333 0.02763366 0.03183382 0.0070436 0.02848422 0.03189122 0.007901847 0.02804976 0.03183025 0.007886469 0.02785468 0.03191441 0.007581114 0.02844971 0.03183007 0.00756514 0.02831637 0.03193259 0.007249176 0.02860742 0.03194844 0.006840467 0.02862465 0.03184419 0.006666839 0.02841854 0.03196257 0.006469607 0.02848285 0.03184527 0.006428003 0.02826398 0.0319755 0.006202578 0.02823799 0.03189748 0.006158888 0.0277813 0.03199762 0.006035387 0.02787023 0.03200542 0.00601238 0.02755439 0.03192651 0.006301403 0.02714884 0.0320248 0.006150364 0.0271297 0.03204351 0.006496608 0.02679377 0.03195577 0.006783187 0.02683824 0.03205251 0.006876647 0.02667087 0.03196471 0.007245957 0.02684593 0.03207516 0.007255375 0.02669632 0.03210103 0.007638216 0.02689576 0.03200322 0.00767076 0.02715367 0.03210419 0.007879376 0.02721339 0.03200596 0.00783199 0.02764022 0.0321297 0.007981419 0.02761161 0.03213572 0.007932126 0.02796113 0.03204721 0.007740616 0.0280323 0.03215551 0.007714748 0.02832382 0.0320701 0.007411479 0.02838706 0.0321784 0.007337391 0.02858471 0.03204882 0.007180213 0.02846443 0.03219562 0.006829798 0.02862167 0.03210675 0.006665885 0.02842503 0.03221786 0.006453514 0.02847677 0.03221076 0.006208837 0.0282393 0.03209626 0.006387829 0.02821129 0.03211677 0.006185531 0.02784568 0.03223878 0.006061792 0.02800029 0.03226184 0.006014168 0.02754408 0.03213876 0.006219625 0.02733987 0.03227353 0.006139695 0.02716141 0.03218674 0.006429553 0.02701419 0.03228414 0.006332397 0.02691793 0.032301 0.006780028 0.02667844 0.03221565 0.006983995 0.02680534 0.03232628 0.007250308 0.02669519 0.03222525 0.007522463 0.02699548 0.03233981 0.007585406 0.02686142 0.032265 0.007796883 0.02736461 0.03235906 0.007849574 0.0271511 0.03237903 0.007988333 0.02765822 0.03229773 0.007752299 0.0280528 0.03239965 0.007843375 0.02815902 0.03241181 0.007573902 0.02845156 0.03229653 0.007357954 0.02839463 0.03243476 0.007147192 0.02862495 0.03234541 0.006891667 0.02849048 0.03244876 0.00681734 0.02861797 0.03245913 0.00644654 0.02847635 0.03234291 0.006470143 0.0282917 0.03248107 0.006101369 0.0280795 0.03239446 0.006160974 0.02782189 0.0325095 0.006020784 0.02743345 0.0324251 0.006270051 0.0272113 0.03252798 0.006233572 0.02701199 0.03245252 0.006718456 0.02685075 0.03254443 0.006609559 0.02674472 0.03256201 0.006932199 0.02666491 0.03248071 0.007324218 0.02686524 0.03258037 0.007394075 0.02673977 0.03259915 0.007771968 0.02703678 0.03248798 0.00773108 0.02726316 0.03261631 0.007938563 0.02734601 0.03252816 0.007830739 0.02764666 0.03263318 0.007969379 0.02783101 0.03254842 0.007736921 0.02805089 0.03266435 0.007780551 0.02825963 0.03266972 0.007420063 0.02854841 0.03254854 0.007317483 0.02842098 0.03257131 0.006942033 0.02848458 0.03269064 0.007005393 0.02863711 0.03270643 0.006568372 0.02854943 0.03261947 0.00643891 0.02829402 0.03272169 0.006239414 0.02828592 0.032615 0.0061993 0.02789443 0.03273969 0.006037533 0.02789133 0.03275901 0.006021261 0.02748751 0.03266555 0.006192982 0.0273962 0.03277862 0.006191849 0.02706998 0.0326606 0.006491124 0.02698808 0.03279322 0.006532251 0.0267803 0.03270506 0.006768465 0.02683806 0.03281033 0.006884217 0.02666819 0.03272873 0.007270634 0.02685439 0.03283077 0.007361352 0.02672851 0.03275018 0.007627189 0.02710002 0.03284686 0.007757902 0.02702105 0.0327723 0.007830023 0.02752417 0.03287023 0.007951438 0.02738434 0.03289419 0.007945358 0.02793651 0.03279834 0.007730305 0.02806979 0.03288429 0.007819831 0.02818405 0.0329141 0.007597923 0.02843707 0.03279405 0.007428467 0.0283643 0.03292948 0.007268786 0.02859687 0.03282463 0.006858408 0.0284729 0.03294456 0.006878912 0.02863222 0.03296101 0.006505012 0.02850586 0.03284138 0.006433069 0.02826207 0.03297507 0.006202816 0.02823954 0.03288537 0.006238937 0.02801525 0.03299391 0.006042003 0.02790921 0.03287994 0.006173431 0.02749967 0.03300708 0.006024658 0.0274555 0.03292149 0.006242573 0.02728158 0.03302574 0.006170272 0.02709782 0.03294503 0.006578385 0.02691113 0.03304201 0.006450057 0.0268256 0.03305894 0.006876766 0.02666389 0.03297251 0.00712949 0.02681732 0.03308516 0.007327139 0.02671462 0.03296738 0.007473886 0.02696567 0.03309655 0.007751405 0.0270099 0.03301388 0.007783532 0.02736002 0.03312647 0.007987856 0.02755123 0.03300255 0.007822453 0.02772378 0.0331465 0.007877409 0.02809894 0.03302448 0.007721841 0.0280466 0.03315848 0.007630348 0.02841007 0.03303956 0.00747621 0.02832365 0.03318428 0.007105708 0.02863997 0.03305733 0.007150888 0.02846151 0.03307044 0.006830155 0.02845889 0.03320902 0.006569802 0.02854269 0.0330916 0.006518244 0.02832728 0.03322654 0.006191909 0.02822822 0.03310441 0.006253421 0.02802342 0.03324359 0.006015777 0.02778708 0.03315567 0.006147027 0.02757966 0.03325974 0.006033718 0.02743142 0.03327405 0.006133913 0.02716296 0.03318518 0.006406903 0.02704381 0.03329551 0.006444215 0.0268265 0.03318268 0.006887078 0.02682667 0.03330743 0.006926 0.02666229 0.03323239 0.00736159 0.02687931 0.03332912 0.007377564 0.02673655 0.03334391 0.007645964 0.02690333 0.03326189 0.007766664 0.02731102 0.03336012 0.007882595 0.02721571 0.03337424 0.007984817 0.0276398 0.03325718 0.007818937 0.02776408 0.03339105 0.007941722 0.0279476 0.03331029 0.00758624 0.02825748 0.03340661 0.007738709 0.02829658 0.03342145 0.007399737 0.02855318 0.03333383 0.007138967 0.02847641 0.03344023 0.007031619 0.02863639 0.03335314 0.006736338 0.02844685 0.0334528 0.006612896 0.02856081 0.0333777 0.006318271 0.02816218 0.03347307 0.006295204 0.02835327 0.03348952 0.006054639 0.02794903 0.0333774 0.006165921 0.02764034 0.03350883 0.006020605 0.02744859 0.03339642 0.006256222 0.02727127 0.03352844 0.006205022 0.0270605 0.03341245 0.006469249 0.02701348 0.03354924 0.006519138 0.0267812 0.03342616 0.006757676 0.02685523 0.03356319 0.006914377 0.02666699 0.03345024 0.00714749 0.02683126 0.03357177 0.007261395 0.02670055 0.03349643 0.007580101 0.02704715 0.03359299 0.007676899 0.02692943 0.03351891 0.007813632 0.02745318 0.03361165 0.007918477 0.02730381 0.03362846 0.007978677 0.0275985 0.03354609 0.007759749 0.02802485 0.03364807 0.007902383 0.02805596 0.03366041 0.007636129 0.02839779 0.03357875 0.007242321 0.0284686 0.03367578 0.007280111 0.02860051 0.03369724 0.006857931 0.02862215 0.033607 0.006654202 0.02841907 0.03371322 0.006488323 0.0285021 0.0337252 0.006204426 0.02824795 0.03363198 0.006270945 0.02808588 0.03373908 0.006021916 0.02781683 0.03365981 0.006157696 0.02750247 0.03376185 0.00603491 0.02740114 0.03365468 0.00641185 0.02706247 0.03378278 0.006250262 0.02699255 0.0336762 0.006699383 0.02687352 0.03380036 0.006612539 0.02674251 0.03382015 0.00707519 0.02665996 0.03372043 0.007093846 0.02681565 0.03383737 0.007501482 0.02680289 0.03373885 0.007448971 0.02694809 0.03385478 0.00782299 0.02710086 0.03373211 0.007705569 0.02721524 0.03387099 0.007974743 0.02749246 0.03375542 0.007831215 0.02764147 0.03386622 0.007972776 0.02775996 0.03380239 0.007684171 0.02812892 0.03389483 0.007899582 0.02805036 0.03390842 0.007692456 0.02834707 0.0337904 0.007434904 0.02835524 0.03392183 0.007423996 0.02854079 0.0338217 0.006973206 0.02848434 0.03394281 0.007027089 0.0286383 0.03395706 0.006608605 0.02855813 0.03386729 0.006474971 0.02831327 0.03396683 0.00627321 0.02832382 0.03388905 0.006208598 0.02794152 0.03398704 0.006074488 0.02800601 0.03400415 0.006003797 0.0276072 0.03388345 0.006173312 0.02751779 0.03402179 0.006136 0.02715599 0.03393381 0.00637865 0.02706354 0.03403633 0.00634545 0.02690321 0.03392511 0.006723105 0.02686619 0.03405314 0.006718814 0.02669346 0.03394806 0.007141232 0.02682942 0.03408187 0.00741893 0.02675014 0.03400009 0.007636785 0.02709895 0.0340985 0.007784545 0.02705651 0.03411823 0.007945537 0.0273922 0.03402757 0.007843852 0.0276491 0.03413552 0.007969975 0.02782952 0.03415077 0.007748544 0.02830034 0.03402543 0.007704019 0.02807921 0.03407347 0.007356286 0.02841222 0.03417921 0.007350206 0.02856814 0.03418898 0.007009744 0.02863705 0.03409546 0.006892383 0.02848315 0.03420811 0.006589531 0.02855354 0.03408718 0.006579995 0.02837067 0.03422039 0.006236672 0.02828818 0.03413444 0.006248652 0.02803426 0.03424519 0.006011545 0.02778887 0.03416079 0.006158471 0.02748578 0.03427785 0.006102323 0.0272088 0.03426653 0.006274461 0.02697652 0.03418648 0.006426393 0.02703595 0.03430396 0.006756365 0.0266872 0.03417187 0.006689071 0.02688288 0.03419655 0.007080435 0.02682256 0.0343011 0.007040798 0.02666825 0.03432941 0.007297635 0.02670949 0.03424358 0.007537066 0.02700626 0.03435337 0.007723391 0.02697306 0.03426945 0.007825374 0.02747017 0.03435963 0.007932424 0.02734166 0.0343796 0.007976293 0.02773952 0.03427046 0.007768392 0.02796244 0.0344032 0.007847368 0.02816385 0.03432077 0.007404685 0.02839064 0.03442126 0.0073812 0.02856892 0.03434228 0.006967008 0.02848482 0.03444832 0.006880342 0.02862817 0.0344544 0.006543517 0.02852743 0.03436487 0.006509721 0.02834635 0.0344758 0.006190121 0.02822822 0.03438913 0.006213068 0.02794778 0.03449594 0.006029665 0.02784568 0.03441119 0.006165862 0.02747923 0.03450977 0.006022214 0.02749335 0.03452724 0.006149768 0.02714312 0.03443801 0.006452143 0.02700352 0.03453558 0.006356835 0.02689743 0.03454387 0.006683409 0.02671074 0.03446543 0.007004857 0.02679908 0.0345686 0.007023513 0.02666383 0.03458839 0.007464647 0.0267781 0.0344699 0.007552564 0.02703237 0.03460025 0.007796764 0.02706915 0.03451961 0.007826626 0.02747082 0.03461915 0.007960736 0.02745974 0.03463333 0.007970571 0.02779573 0.03452259 0.007750272 0.02799254 0.03464484 0.007831811 0.02816945 0.03453248 0.00754112 0.02827423 0.03466331 0.007592797 0.02844262 0.03455787 0.0071581 0.02846491 0.03468507 0.007065057 0.02863562 0.03468734 0.006663203 0.0285803 0.03457289 0.006793141 0.02844953 0.03459268 0.006490528 0.02830755 0.03470838 0.006246864 0.02828663 0.03460633 0.006239175 0.02799528 0.03473848 0.006071925 0.02801519 0.03463101 0.006164491 0.02759593 0.03475701 0.006013095 0.02752643 0.03465127 0.006306409 0.02718544 0.03477996 0.006178498 0.02709025 0.03479248 0.006461679 0.0268228 0.03466868 0.006647229 0.02689445 0.03481048 0.006865084 0.02666723 0.0347175 0.007025957 0.02679938 0.034823 0.007327675 0.02671676 0.03474783 0.007618427 0.02707022 0.0348469 0.007743656 0.02700096 0.03487879 0.007967352 0.02742576 0.03477507 0.007832288 0.0275796 0.03488731 0.007949173 0.02791607 0.03475892 0.007798254 0.02788054 0.0349 0.007749974 0.02829295 0.03478813 0.007556796 0.02825868 0.03492498 0.007370233 0.02856171 0.03479903 0.007251679 0.02843862 0.03482365 0.006825506 0.02846652 0.03494322 0.006839096 0.02863585 0.03484392 0.006393849 0.02822613 0.03496521 0.006447553 0.02846765 0.03498291 0.006162881 0.02818375 0.03489142 0.006188988 0.02790015 0.0349968 0.0060153 0.0277822 0.03491932 0.006213426 0.02731382 0.03501003 0.006062924 0.02732312 0.03503328 0.006240308 0.02701276 0.03491342 0.006488204 0.02698963 0.03504967 0.00666505 0.02671271 0.03492921 0.00684911 0.02683156 0.03507775 0.007173001 0.02667748 0.03498411 0.007380545 0.02689605 0.03508806 0.007565498 0.02683979 0.03510403 0.007830858 0.02712464 0.0350095 0.00774306 0.02726602 0.03511744 0.007980108 0.02754348 0.0350365 0.007829785 0.0278179 0.03514432 0.007908403 0.02804189 0.03504157 0.007496416 0.02831554 0.03516203 0.007604777 0.02842676 0.03508305 0.007157683 0.02847421 0.03518605 0.007232487 0.02861344 0.03520059 0.006763517 0.02860993 0.03511095 0.006573617 0.02839624 0.03521043 0.006326556 0.02839154 0.03511679 0.006201028 0.02789908 0.0352419 0.006043076 0.02792769 0.0351625 0.006179988 0.02745795 0.03527021 0.006045877 0.02734065 0.03518515 0.006412446 0.02703529 0.0352894 0.006386458 0.02686721 0.03530627 0.006755948 0.02668452 0.03518617 0.00697112 0.0268141 0.03531652 0.007102012 0.02666449 0.03522855 0.007260382 0.02685099 0.03534388 0.007637381 0.02688443 0.03525292 0.007669389 0.02714252 0.03536021 0.00791049 0.02728569 0.03527462 0.007830798 0.02758127 0.03538274 0.007983505 0.02778202 0.03529673 0.007749378 0.0280261 0.03540158 0.007781505 0.02824282 0.03529834 0.007338583 0.02841132 0.03542119 0.007483363 0.02850878 0.03543156 0.007135391 0.0286253 0.03534281 0.006946086 0.02848976 0.03544878 0.006689906 0.02859097 0.03533715 0.006489574 0.02830934 0.03547096 0.006286561 0.02834779 0.03538393 0.006246149 0.02805149 0.03548836 0.006058096 0.02797806 0.03538012 0.006165385 0.02759027 0.03550469 0.00600636 0.02768212 0.03552204 0.006091177 0.02725398 0.03543555 0.006401181 0.02703756 0.03553444 0.00631839 0.02693158 0.03555536 0.006715357 0.0266959 0.03546017 0.006880342 0.02682143 0.0355705 0.007277786 0.02669245 0.03548341 0.007348418 0.0268799 0.03559702 0.007754087 0.02701574 0.03551024 0.007758498 0.02728474 0.03561955 0.007941305 0.02736157 0.03550881 0.007818996 0.02773016 0.0356329 0.007974267 0.02773851 0.03564757 0.007861495 0.02813297 0.03555721 0.007629752 0.02821695 0.03566843 0.007546126 0.02847474 0.03566139 0.007306814 0.02858167 0.03558158 0.007193207 0.02846181 0.03569382 0.006989479 0.02863967 0.03560298 0.006742238 0.02845782 0.03570765 0.006602823 0.02855265 0.03572392 0.006273508 0.02832514 0.03560453 0.006292521 0.02809935 0.03573346 0.006062448 0.027987 0.03562301 0.00617057 0.02770328 0.03575903 0.006021261 0.02747297 0.03564018 0.006231904 0.02731096 0.03577578 0.006190598 0.02707922 0.03566294 0.006457507 0.02701103 0.03579336 0.006493806 0.02679586 0.03570806 0.006827592 0.02681571 0.03581106 0.006918549 0.02666413 0.03570479 0.007391393 0.02691823 0.03583109 0.007315814 0.02671384 0.03574639 0.007583737 0.02705198 0.03584343 0.007728695 0.02698636 0.03576487 0.007783293 0.02737057 0.03586268 0.007898032 0.02724468 0.03588515 0.007983803 0.02777248 0.03575968 0.007813096 0.02778458 0.03577595 0.007652938 0.02815502 0.03590559 0.007741272 0.0283041 0.03582024 0.007410109 0.02837979 0.03592288 0.007384359 0.02855229 0.03584378 0.00692451 0.02849292 0.03593993 0.007048606 0.02863633 0.03594988 0.006682157 0.02858394 0.03587335 0.006378769 0.0282368 0.0359739 0.006234288 0.02829718 0.03587496 0.006164133 0.02768772 0.03599637 0.006000697 0.0276941 0.03589648 0.006249129 0.02727901 0.03602522 0.006112754 0.02719223 0.0359137 0.006530523 0.02696341 0.03604167 0.006447732 0.02683085 0.03593593 0.006856083 0.02682816 0.03606456 0.006937325 0.02665293 0.0359553 0.007313191 0.02688139 0.0360856 0.007465064 0.02678209 0.03609591 0.007694363 0.02695262 0.03597128 0.007636964 0.02712494 0.03611022 0.00789839 0.0272507 0.03602087 0.00782454 0.02749419 0.03612726 0.007984876 0.02771168 0.03601837 0.00775206 0.02798974 0.03614521 0.007832169 0.02817398 0.03606319 0.007534265 0.02829915 0.03616577 0.00757873 0.0284506 0.03606426 0.007068216 0.02847707 0.03618109 0.007242739 0.02860301 0.03619527 0.00687468 0.02862852 0.03611189 0.006569445 0.02838444 0.03621 0.006504118 0.02850484 0.03622823 0.006235659 0.02827703 0.03613978 0.006197094 0.02793055 0.03623461 0.0060485 0.02793103 0.0361607 0.006173908 0.02749741 0.03626585 0.006015837 0.02748501 0.0361796 0.006332039 0.02713441 0.03627246 0.006214737 0.02704334 0.03615957 0.00651288 0.02696871 0.03630536 0.006587624 0.02674567 0.03630924 0.006950438 0.02666389 0.03618836 0.006940484 0.02681869 0.03632694 0.007352352 0.02673095 0.03623646 0.007411241 0.02692168 0.03634631 0.007728993 0.02698177 0.03622996 0.007695436 0.02721059 0.03627353 0.007838368 0.02755266 0.03636622 0.00793612 0.02735048 0.03638195 0.007978498 0.02769041 0.03639632 0.007886707 0.02807372 0.03627634 0.007684588 0.02811717 0.03640753 0.007622897 0.02841544 0.03629559 0.007417201 0.02836418 0.03642863 0.007223546 0.02861076 0.03631269 0.007050871 0.02847695 0.0364542 0.006824612 0.02862805 0.03636312 0.006523311 0.02836167 0.03646451 0.006443977 0.02846765 0.03647685 0.006165623 0.02819311 0.03638947 0.006207227 0.02793419 0.03649324 0.006023406 0.02781456 0.03641057 0.006166338 0.02749729 0.03651165 0.006037414 0.02741354 0.03653109 0.006285786 0.02695 0.03643214 0.006368041 0.02709305 0.03645229 0.006709694 0.02686178 0.036556 0.006728887 0.02669823 0.03644692 0.007083535 0.02682197 0.03657293 0.007130146 0.02667427 0.03658354 0.007432639 0.02676659 0.03645479 0.007366538 0.0269044 0.03659641 0.007808327 0.0270766 0.03650975 0.007752418 0.02727502 0.03662151 0.007971167 0.02750092 0.03653693 0.007820844 0.02784043 0.03663891 0.007942557 0.02795296 0.03651881 0.00769174 0.02811706 0.03666031 0.007688224 0.02835577 0.03654891 0.007308363 0.0284186 0.03668069 0.00731939 0.02858096 0.03668969 0.006973922 0.02863621 0.03659862 0.006832182 0.02847617 0.03671056 0.006575882 0.02854496 0.03662657 0.006326913 0.02818042 0.0367183 0.006299614 0.02835637 0.03673666 0.006092727 0.02804833 0.03674387 0.006008386 0.02768391 0.03662407 0.006164014 0.02771192 0.03664052 0.006234049 0.02732723 0.03676539 0.006065428 0.02731871 0.03678607 0.006234049 0.02702045 0.03669142 0.006516516 0.02695387 0.03679537 0.006542205 0.02677553 0.03680914 0.006863653 0.02667146 0.03668802 0.007002234 0.02681946 0.03682672 0.007302403 0.0267077 0.03673392 0.007365524 0.0268945 0.03684347 0.007674098 0.02693575 0.03675901 0.007749795 0.02726459 0.03686326 0.007912039 0.02727758 0.03687852 0.007978796 0.0277006 0.03678554 0.007824361 0.02779674 0.03689497 0.007884204 0.02808487 0.03681182 0.007550776 0.02829498 0.03691065 0.007564961 0.02845782 0.03693222 0.007220268 0.02861464 0.03684115 0.006978631 0.02849477 0.03695249 0.006712317 0.02860087 0.03686863 0.006452262 0.02829998 0.03697848 0.006211817 0.02826738 0.03689259 0.006186664 0.02787303 0.03699553 0.006023049 0.02780592 0.03700762 0.006031334 0.02743011 0.03691345 0.006180822 0.02743977 0.03702914 0.006242156 0.02700632 0.03694069 0.006493151 0.02696049 0.03704684 0.006528496 0.02678239 0.0370652 0.006902933 0.02666521 0.03694224 0.007092058 0.02682238 0.03707629 0.007387101 0.02673923 0.03698593 0.007403016 0.02690988 0.03709751 0.007742881 0.02700728 0.03701323 0.007783174 0.02733671 0.03712075 0.007927656 0.02732414 0.03712987 0.007982313 0.02769857 0.03703916 0.007805764 0.02787542 0.03713959 0.007922887 0.02797901 0.03715437 0.007739603 0.02829784 0.03706175 0.007551193 0.02828168 0.03717529 0.007320702 0.02859193 0.03708308 0.007159292 0.02847158 0.03719729 0.006767868 0.02861207 0.0371077 0.006650149 0.02842628 0.03721982 0.006342291 0.02839624 0.03713768 0.006210923 0.02797889 0.03723788 0.006078839 0.02801263 0.03725749 0.006007373 0.0276317 0.03714013 0.006201028 0.02740341 0.03726452 0.006064534 0.02731895 0.03718262 0.006373465 0.02708476 0.03728425 0.006320118 0.02691781 0.03717994 0.006757736 0.02685344 0.03730022 0.006690263 0.02671623 0.03721958 0.007066726 0.02680766 0.03732031 0.0071069 0.02666485 0.03734016 0.007549643 0.02683055 0.03721439 0.007585108 0.02705556 0.03735101 0.007830798 0.02712142 0.0372588 0.007739365 0.02725398 0.0373699 0.007965385 0.02748292 0.0372827 0.007831931 0.02774965 0.03739023 0.007956385 0.02786964 0.03739827 0.007824003 0.02819025 0.0372827 0.007611155 0.02821028 0.03741729 0.007492601 0.02850651 0.03732895 0.00724256 0.02844709 0.037436 0.007052659 0.02863425 0.03732532 0.006853938 0.02846843 0.03745675 0.006612598 0.02856469 0.03734046 0.006484627 0.02830195 0.03747397 0.006194591 0.0282337 0.03736054 0.006240069 0.02799522 0.03749775 0.006026446 0.02784425 0.03738629 0.006169438 0.02753734 0.03750932 0.006036102 0.02743339 0.03752934 0.006231188 0.02700728 0.03743553 0.006413102 0.02703636 0.03756469 0.006680309 0.02672004 0.03743541 0.006896436 0.02682608 0.03756946 0.006964564 0.02666592 0.03745269 0.007238745 0.02686148 0.03756403 0.007350325 0.02673953 0.03746372 0.007532656 0.02701866 0.03748595 0.007733464 0.02726876 0.03750401 0.007823348 0.02772146 0.03183406 0.006184399 0.02788412 0.03186643 0.00622189 0.02728956 0.03189599 0.006651878 0.02687972 0.03193527 0.007435023 0.02693468 0.03196001 0.007771909 0.02731341 0.03200423 0.007640242 0.02819514 0.03204929 0.006776332 0.02846491 0.03214555 0.006624519 0.02688413 0.03217774 0.007283926 0.02684682 0.03221851 0.007823288 0.02749621 0.03224563 0.007747769 0.02804177 0.0322923 0.006912112 0.02848899 0.03233486 0.006220102 0.02797871 0.03236186 0.006175041 0.02743119 0.03238666 0.006465494 0.02699846 0.03241336 0.006985366 0.02679616 0.03244215 0.007546722 0.02701294 0.0324825 0.007832229 0.02777093 0.03250735 0.007589519 0.02824789 0.03256577 0.006461977 0.02829617 0.03261399 0.006190717 0.02737563 0.03266137 0.006951868 0.02680951 0.0326879 0.007474243 0.02694934 0.03271126 0.00777322 0.02734076 0.032736 0.007819592 0.02786713 0.03278106 0.007150352 0.02847713 0.03284043 0.006184518 0.02786719 0.03288048 0.006380498 0.02708286 0.03290623 0.006842255 0.02680873 0.03295338 0.007709681 0.02719515 0.03310233 0.006158292 0.02761852 0.03312289 0.006276667 0.02721285 0.03314244 0.006570339 0.02692878 0.03318053 0.00734359 0.02688556 0.03320538 0.00772655 0.02722305 0.03325086 0.007674872 0.02813667 0.03327256 0.00732553 0.02842962 0.03330248 0.006699562 0.02844983 0.03333204 0.006240904 0.02803397 0.0334466 0.007617831 0.02706879 0.03347325 0.007833123 0.02758735 0.03349691 0.007723808 0.02807766 0.03352075 0.007359445 0.02840626 0.03354507 0.00685203 0.02848553 0.03356826 0.006424963 0.02826201 0.03358709 0.006208658 0.02794367 0.03361022 0.006174087 0.02745163 0.03367644 0.007254183 0.02684277 0.03374063 0.007786154 0.02795076 0.03380292 0.006705701 0.02843976 0.03382956 0.006266653 0.02808982 0.03387951 0.006367266 0.0270968 0.0339415 0.007546782 0.02699744 0.03397226 0.007840812 0.02757799 0.03401118 0.007532954 0.02829658 0.03403383 0.00709176 0.02848702 0.03407561 0.00631684 0.02815026 0.03409862 0.006155669 0.02769958 0.0341255 0.006294131 0.02716994 0.03418505 0.007431149 0.02692854 0.03421252 0.007797062 0.02736794 0.03425395 0.007636189 0.02819263 0.03427487 0.007273077 0.02844214 0.03429996 0.006759822 0.02846425 0.0343284 0.006281673 0.02810835 0.03435373 0.006156206 0.02758926 0.03437882 0.006343781 0.02711063 0.03440046 0.006731927 0.02685606 0.03442221 0.007173359 0.02682393 0.03446942 0.007829666 0.02750879 0.03466647 0.007055282 0.02681761 0.03468614 0.00745207 0.02694123 0.0347104 0.007774651 0.02732962 0.03484511 0.006162464 0.02777248 0.03486496 0.006210982 0.02735924 0.03492867 0.00731045 0.02686816 0.03495407 0.007716774 0.02720946 0.03497534 0.007830977 0.02763646 0.03499716 0.00772804 0.02806758 0.03503984 0.006969928 0.02849429 0.03506535 0.006466984 0.02830898 0.03511399 0.006187379 0.02738595 0.03514254 0.006568074 0.02691912 0.03519105 0.007536649 0.0269984 0.03522062 0.007832467 0.02751684 0.03524982 0.007695019 0.02813625 0.03529727 0.006816089 0.02847015 0.03533321 0.006242513 0.02801084 0.0353707 0.006257116 0.02725106 0.03539443 0.006608545 0.02689725 0.03542345 0.007186472 0.02682399 0.03545427 0.007719039 0.02719753 0.03549623 0.007726907 0.02806115 0.0355218 0.007350027 0.0284202 0.03555268 0.006704211 0.0284537 0.03566259 0.006977021 0.02680736 0.03571099 0.007789075 0.02733987 0.03577446 0.007284045 0.0284397 0.03580123 0.006727337 0.0284574 0.03582906 0.006274342 0.0280891 0.03597277 0.007835686 0.02757477 0.03601688 0.007435083 0.02836859 0.03605681 0.006624341 0.02840286 0.03608071 0.00625962 0.02806764 0.0361095 0.006163418 0.02746182 0.03618454 0.007414937 0.02690708 0.03622919 0.007844567 0.02772563 0.036309 0.006575107 0.02838283 0.03633719 0.006201326 0.0279501 0.03636288 0.006190598 0.02740144 0.03638994 0.006519436 0.02694559 0.03645187 0.00768876 0.02717161 0.03647446 0.007834553 0.02761721 0.03654807 0.006782293 0.02847594 0.03657406 0.00633949 0.02817153 0.03663867 0.006496489 0.0269615 0.03669226 0.00754565 0.02700138 0.03672212 0.007839083 0.02756041 0.03674995 0.007689535 0.02813458 0.03678101 0.007165074 0.02848726 0.03680843 0.006588637 0.02838605 0.03683042 0.00626856 0.02807086 0.03684967 0.006157815 0.02767413 0.03687477 0.006291091 0.02717292 0.03690093 0.006737291 0.0268498 0.03694516 0.007597386 0.02705597 0.03696858 0.007820308 0.02749747 0.03699368 0.007762074 0.02801257 0.03702294 0.007313251 0.0284388 0.03705292 0.006710648 0.02844673 0.03707396 0.006342828 0.02817422 0.03709465 0.006164848 0.02778667 0.0371387 0.006505012 0.02696287 0.03717386 0.007215559 0.02684116 0.03722572 0.007852852 0.02766102 0.03727757 0.007239699 0.0284627 0.03736948 0.006249189 0.02727133 0.037391 0.006538569 0.02694028 0.03750532 0.007618248 0.02822065 0.03183388 0.007294654 0.02670544 0.03183043 0.00611031 0.02745354 0.0318315 0.006566822 0.02678471 0.03184413 0.007700145 0.02696079 0.03251397 0.006012558 0.02775722 0.03408235 0.007051467 0.02666598 0.03430932 0.006504118 0.02679866 0.03469157 0.007336378 0.02857351 0.03472733 0.006490647 0.02850502 0.03782558 0.007387995 0.02835303 0.03778874 0.007172048 0.02850288 0.03770005 0.007080495 0.02860414 0.03772807 0.007515013 0.0284276 0.03782588 0.007680416 0.0280627 0.03776383 0.007767319 0.02812439 0.03768134 0.007734596 0.02826017 0.03767359 0.007890939 0.0279982 0.0377897 0.007853627 0.02780318 0.03782367 0.007777929 0.02748394 0.0377025 0.007945179 0.0277124 0.03782469 0.007677614 0.02720975 0.03777337 0.007858037 0.02742379 0.03767359 0.007930815 0.02742666 0.03768771 0.007844805 0.02720981 0.03782552 0.007118999 0.02685236 0.03770732 0.007699131 0.02701967 0.03777432 0.007447123 0.0268712 0.03758066 0.007657647 0.02692538 0.03767603 0.007445812 0.02679598 0.03767251 0.007156729 0.02669781 0.03769963 0.006871819 0.02670228 0.03781878 0.006743967 0.02685952 0.03782355 0.006388902 0.02711981 0.03775048 0.006468117 0.02689933 0.03766143 0.006568074 0.02678436 0.03767102 0.00627011 0.02701056 0.03778767 0.006233096 0.0272234 0.0375806 0.006171762 0.02711957 0.03782641 0.006193161 0.02770656 0.03768026 0.006123542 0.02724903 0.03776574 0.006089329 0.02758634 0.0378279 0.00635457 0.02810561 0.03767269 0.006034433 0.02774119 0.03775376 0.006157338 0.02801263 0.03758698 0.006081342 0.02802133 0.03777742 0.006357669 0.02827578 0.03766798 0.006293654 0.02831745 0.0378229 0.006787836 0.02843916 0.03767478 0.006527662 0.02849072 0.03775233 0.00670433 0.02851784 0.03758734 0.006671488 0.02858394 0.03066164 0.006283521 0.02806079 0.03066122 0.007018029 0.02848672 0.03065961 0.006280899 0.02723908 0.03066039 0.00699377 0.02682656 0.03066068 0.007707536 0.02723735 0.03065782 0.007710635 0.0280869 0.02994191 0.006231367 0.02809047 0.02994149 0.00622946 0.02720981 0.02994185 0.007760524 0.02808797 0.02994143 0.006993591 0.02853226 0.02994173 0.007758975 0.02720707 0.02994149 0.006993472 0.02676683 0.02993029 0.005593657 0.02641314 0.02993029 0.005198895 0.02712893 0.02993029 0.005141913 0.02783542 0.02993029 0.006424129 0.0258513 0.02993029 0.007625997 0.02587145 0.02993029 0.005337715 0.02851659 0.02993029 0.005937993 0.02920049 0.02993029 0.008447945 0.02647215 0.02993029 0.008774816 0.02710103 0.02993029 0.006748139 0.0295006 0.02993029 0.008858501 0.02783644 0.02993029 0.007532 0.02944153 0.02993029 0.008595943 0.02861076 0.02993029 0.008156299 0.02910608 0.03183025 0.007655024 0.025882 0.03183025 0.008528769 0.0265662 0.03183025 0.008861184 0.02747851 0.03183025 0.008700549 0.02843624 0.03183025 0.00797826 0.02925884 0.03183025 0.007010161 0.02952021 0.03183025 0.005981564 0.02924793 0.03183025 0.005267143 0.02837836 0.03183025 0.005131423 0.02755695 0.03183025 0.005312025 0.02683943 0.03183025 0.005770921 0.02624034 0.03183025 0.006546497 0.02582639 0.04834997 0.001194059 0.01882058 0.05434995 0.001161515 0.01887494 0.04834997 9.64615e-4 0.01949292 0.05434995 9.7158e-4 0.01946985 0.05434995 0.001025378 0.02014094 0.04834997 0.001050174 0.02019864 0.05434995 0.001497209 0.02081501 0.04834997 0.001516163 0.02083057 0.05434995 0.002100169 0.02111464 0.04834997 0.002233266 0.02115058 0.05434995 0.002810418 0.02112895 0.04834997 0.002977073 0.0210734 0.05434995 0.003441691 0.02080214 0.04834997 0.003673136 0.02058815 0.05434995 0.003867983 0.02023375 0.04834997 0.003977656 0.01975661 0.05434995 0.003971099 0.01959365 0.04834997 0.003782868 0.01886773 0.05434995 0.003790915 0.01889264 0.05434995 0.003226876 0.01834595 0.04834997 0.003072917 0.01825916 0.05434995 0.002447068 0.01812136 0.04834997 0.002384126 0.01814246 0.04834997 0.001758992 0.01831203 0.05434995 0.001662373 0.01837098 0.04834997 0.009114921 0.02787828 0.04834997 0.01141095 0.03020286 0.04834997 0.008221983 0.03224676 0.04834997 0.009705722 0.0277816 0.04834997 0.008512079 0.02771872 0.04834997 0.01021718 0.02747154 0.04834997 0.007960855 0.02726989 0.04834997 0.004939615 0.03324782 0.04834997 0.01064002 0.02680987 0.04834997 0.0135281 0.02793556 0.04834997 0.007669806 0.02648752 0.04834997 0.002293884 0.03346645 0.04834997 -0.002807796 0.026784 0.04834997 -0.003995835 0.03187674 0.04834997 -0.003667056 0.02674531 0.04834997 -0.007001876 0.02975767 0.04834997 -7.81139e-4 0.03310215 0.04834997 -0.00420165 0.02642399 0.04834997 -0.0021317 0.02638286 0.04834997 0.01065653 0.0260244 0.04834997 -0.004574596 0.02592402 0.04834997 -0.001764535 0.02581888 0.04834997 0.01479512 0.02587407 0.04834997 -0.008993208 0.02735877 0.04834997 -0.004695773 0.02533721 0.04834997 -0.001709461 0.02492296 0.04834997 -0.01016223 0.02526623 0.04834997 0.010333 0.0253784 0.04834997 -0.004544794 0.02459114 0.04834997 0.01590341 0.02300387 0.04834997 -0.01118415 0.02199029 0.04834997 0.009638547 0.02491492 0.04834997 0.007824778 0.0256921 0.04834997 -0.002255797 0.02410405 0.04834997 0.008286654 0.02515208 0.04834997 0.0162869 0.01957529 0.04834997 0.008865654 0.02488988 0.04834997 -0.002984106 0.02380955 0.04834997 -0.01129186 0.01820403 0.04834997 0.008318722 0.01550257 0.04834997 0.007517397 0.01538109 0.04834997 0.00897783 0.01523464 0.04834997 0.01599806 0.01683825 0.04834997 0.006978034 0.01497846 0.04834997 0.009419381 0.0147776 0.04834997 0.01504725 0.01389759 0.04834997 0.00661087 0.01422762 0.04834997 -0.004520475 0.01442068 0.04834997 -0.003789424 0.02390319 0.04834997 -0.003736913 0.01436501 0.04834997 -0.005276143 0.0140649 0.04834997 -0.01070564 0.01549708 0.04834997 -0.003159701 0.01397097 0.04834997 -0.009798467 0.01327836 0.04834997 -0.002794921 0.01337486 0.04834997 -0.005673468 0.01343005 0.04834997 -0.00277841 0.01258945 0.04834997 0.006729185 0.01341295 0.04834997 0.009652793 0.01387196 0.04834997 -0.005761444 0.0128504 0.04834997 0.01323878 0.01097106 0.04834997 -0.007874429 0.01043689 0.04834997 -0.005508482 0.01206743 0.04834997 0.009272336 0.013004 0.04834997 -0.004856526 0.01154541 0.04834997 0.01095026 0.008734762 0.04834997 0.008577883 0.01254057 0.04834997 -0.004896402 0.007932543 0.04834997 -0.004182636 0.01142168 0.04834997 0.00861603 0.007276535 0.04834997 0.007804989 0.01251548 0.04834997 -0.003545105 0.01159614 0.04834997 -0.001774549 0.006486833 0.04834997 -0.003058671 0.01200544 0.04834997 0.006044209 0.006296336 0.04834997 0.007141828 0.01283407 0.04834997 9.195e-4 0.005923092 0.04834997 0.003326833 0.005859255 0.04635 0.01059144 0.02582228 0.04635 0.01069378 0.02644956 0.04635 0.01049262 0.02713084 0.04635 0.0099985 0.02764153 0.04635 0.009177148 0.02789759 0.04635 0.008152902 0.02750653 0.04635 0.00771439 0.02672213 0.04635 0.007729887 0.02589917 0.04635 0.008224785 0.02519541 0.04635 0.00908792 0.02483427 0.04635 0.01012182 0.02516049 0.04635 -0.001875102 0.0245549 0.04635 -0.001665294 0.02542769 0.04635 -0.002053737 0.0263189 0.04635 -0.002785682 0.02677041 0.04635 -0.003459215 0.02679014 0.04635 -0.00409311 0.02652955 0.04635 -0.00452888 0.02600067 0.04635 -0.004698276 0.0254265 0.04635 -0.004589557 0.02472436 0.04635 -0.004112839 0.0241003 0.04635 -0.00323534 0.0237773 0.04635 -0.002385079 0.0240246 0.04635 0.009363412 0.01312458 0.04635 0.009601831 0.0137012 0.04635 0.009586393 0.01441168 0.04635 0.009122848 0.015136 0.04635 0.008524537 0.01544606 0.04635 0.007777035 0.01547938 0.04635 0.006996154 0.0150128 0.04635 0.006653726 0.01434779 0.04635 0.006669223 0.01352477 0.04635 0.00711894 0.01286566 0.04635 0.007766067 0.01251471 0.04635 0.008698642 0.01257842 0.04635 -0.003083825 0.0119614 0.04635 -0.002788841 0.01256722 0.04635 -0.002774178 0.01331532 0.04635 -0.003208279 0.01402884 0.04635 -0.004003942 0.01444548 0.04635 -0.004926204 0.01429033 0.04635 -0.005591988 0.01366996 0.04635 -0.005759954 0.01282608 0.04635 -0.005494117 0.01204699 0.04635 -0.004811108 0.01152431 0.04635 -0.003891587 0.01144218 0.03635072 0.01189178 0.009541809 0.03635072 0.01370775 0.01160985 0.03635072 0.015078 0.01399677 0.03635072 0.01594811 0.01660794 0.03635072 0.01628357 0.01933968 0.03635072 0.01607108 0.02208358 0.03635072 0.01553666 0.02408909 0.03635072 0.01474934 0.02598559 0.03635072 0.01325047 0.02829384 0.03635072 0.01182198 0.02979952 0.03635072 0.01022344 0.03108859 0.03635114 0.008362174 0.03213328 0.03634947 0.006449878 0.03288096 0.03635072 0.003808259 0.0334056 0.03635114 0.001674056 0.0334329 0.03634947 -3.62967e-4 0.03317493 0.03635072 -0.002933859 0.03237229 0.03634893 -0.005751371 0.03078436 0.03635072 -0.008099257 0.02856004 0.03635072 -0.009655237 0.02628988 0.03635066 -0.01048958 0.02441364 0.03635072 -0.01107388 0.02242201 0.03635072 -0.01135468 0.01968413 0.03634947 -0.0110957 0.01700341 0.03635174 -0.01031732 0.01438629 0.03635156 -0.009225845 0.01230335 0.03634893 -0.007560014 0.01011168 0.03634947 -0.005108594 0.008093535 0.03635174 -0.002691686 0.00682336 0.03635227 2.34684e-4 0.006001889 0.03634971 0.002982616 0.005845963 0.03635227 0.005711257 0.00620681 0.03634971 0.008303999 0.007130503 0.03635156 0.01010191 0.008144736 0.03534996 0.001733541 0.02581977 0.04234999 0.001629054 0.02563124 0.03534996 0.001569688 0.02535545 0.04234999 0.001584708 0.02517002 0.03534996 0.001751542 0.02474188 0.04234999 0.001818835 0.02467012 0.03534996 0.002328217 0.02441745 0.04234999 0.002402722 0.02440905 0.03534996 0.002830088 0.02449059 0.04234999 0.003056645 0.02460908 0.03534996 0.003234207 0.02483296 0.04234999 0.003352344 0.02517718 0.03534996 0.003359556 0.02536988 0.04234999 0.003250479 0.0257641 0.03534996 0.003120899 0.02594012 0.04234999 0.002728462 0.02617037 0.03534996 0.002602934 0.02618825 0.04234999 0.002047121 0.02611565 0.03534996 0.00212717 0.02613973 0.04234999 0.001565217 0.01414805 0.03534996 0.001594126 0.01417344 0.03534996 0.00160712 0.01373219 0.04234999 0.00172466 0.01348292 0.03534996 0.00188744 0.01330953 0.04234999 0.002245843 0.0131123 0.03534996 0.002394855 0.01309347 0.04234999 0.002901136 0.01320236 0.03534996 0.002949893 0.01323688 0.04234999 0.003289639 0.01363378 0.03534996 0.003258049 0.01358264 0.03534996 0.003362953 0.01403403 0.04234999 0.003351986 0.01409292 0.04234999 0.003181219 0.01453959 0.03534996 0.003195583 0.01451277 0.03534996 0.002824008 0.01481342 0.04234999 0.002781808 0.01482796 0.03534996 0.002388358 0.01488226 0.04234999 0.00227648 0.01487457 0.03534996 0.001849353 0.01466351 0.04234999 0.001857578 0.01464313 0.04234999 -0.004002869 0.02005368 0.03534996 -0.004056036 0.01989746 0.04234999 -0.004058361 0.01940184 0.03534996 -0.00402379 0.01930296 0.04234999 -0.00377798 0.01897859 0.03534996 -0.003661036 0.01888775 0.04234999 -0.003299415 0.01875138 0.03534996 -0.003035724 0.01874911 0.04234999 -0.002821266 0.01884126 0.04234999 -0.00247091 0.0191096 0.03534996 -0.002389729 0.01920944 0.04234999 -0.002286851 0.01969891 0.03534996 -0.002319753 0.01986771 0.04234999 -0.00250709 0.02022868 0.03534996 -0.00254935 0.02026993 0.04234999 -0.00287497 0.0204848 0.03534996 -0.002964854 0.02052122 0.04234999 -0.003455519 0.02052158 0.03534996 -0.003644406 0.02044355 0.03534996 0.007276237 0.01996225 0.04234999 0.007231891 0.01969051 0.03534996 0.007279038 0.01932287 0.04234999 0.007334411 0.01921617 0.03534996 0.00765264 0.01888775 0.04234999 0.007717847 0.01885122 0.03534996 0.008277893 0.01874911 0.04234999 0.008306682 0.0187608 0.04234999 0.008842706 0.0191096 0.03534996 0.008851468 0.01912146 0.04234999 0.009020507 0.01963144 0.03534996 0.009012162 0.01957941 0.03534996 0.008883714 0.02015483 0.04234999 0.008894979 0.02010023 0.04234999 0.008452177 0.02049934 0.03534996 0.008232414 0.0205543 0.04234999 0.007855832 0.02050286 0.03534996 0.007627308 0.02039676 0.04234999 0.007399141 0.02019339 0.0353499 0.009517788 0.01137763 0.0353499 0.01206457 0.01457703 0.03534996 0.01317059 0.01794791 0.03534996 0.01317423 0.0214008 0.0353499 0.0118373 0.02515804 0.03534996 0.009365916 0.02800905 0.03534996 0.006306171 0.02980476 0.03534996 0.003140389 0.03045344 0.0353499 -2.97952e-4 0.03016275 0.03534996 -0.003521919 0.02867263 0.0353499 -0.005931913 0.02652019 0.03534978 -0.008058249 0.02252465 0.03534996 -0.008277356 0.01821529 0.03534984 -0.007034599 0.0143215 0.03534978 -0.003522694 0.01053082 0.03534996 4.97746e-4 0.008991301 0.03534972 0.005030512 0.009026885 + + + + + + + + + + 5.46108e-5 -0.8660243 0.5000021 0 -0.8659569 0.5001189 0 0 1 0 0.8660251 0.5000008 0 0.866023 0.5000042 0 0.866023 -0.5000042 0 0.8660251 -0.5000008 0 -0.8659581 -0.5001166 5.34208e-5 -0.8660242 -0.5000022 0 0 -1 1 3.01246e-6 0 1 1.36253e-6 0 1 0 0 1 -1.78633e-6 0 1 1.77314e-6 0 1 3.56364e-6 0 1 3.76943e-7 0 1 1.47479e-6 0 1 -1.85074e-6 0 1 -1.84193e-6 0 1 -2.76953e-6 0 0.004632234 -0.1683912 0.9857094 -0.004367887 -0.3545926 0.9350107 0.00530827 -0.5639757 0.8257743 -0.005119323 -0.6862311 0.7273656 0.005274474 -0.9216064 0.3880901 -0.001930236 -0.9452329 0.3263911 0.001745104 -0.978596 -0.205784 -9.13024e-5 -0.9818807 -0.1895003 0.006290972 -0.7357907 -0.6771799 -0.001502752 -0.7922329 -0.610217 -0.009623825 -0.428616 -0.9034356 0.009929478 -0.1639845 -0.986413 -0.005827724 0.07971096 -0.996801 0.003849685 0.3313511 -0.9434998 -0.004858314 0.4956451 -0.8685116 0.005542695 0.6534997 -0.7569066 -0.007081389 0.883725 -0.4679532 0.006448805 0.9370302 -0.3491888 -0.005828797 0.9912746 0.1316843 0.005834102 0.9651241 0.261728 -0.004563927 0.848641 0.5289496 0.006678342 0.7098335 0.7043378 -0.006860375 0.5422264 0.8402044 0.005800902 0.2501099 0.9682002 -0.005043506 0.08850717 0.9960628 -0.01444453 0.1003134 -0.9948511 0.01084226 0.2459605 -0.9692193 -0.001345217 0.5281968 -0.849121 -0.01314103 0.5701469 -0.8214378 0.01355892 0.8068686 -0.5905754 -0.01266616 0.8859822 -0.4635463 0.01205694 0.9847499 -0.1735581 -0.01000124 0.9972107 -0.07396525 0.01000159 0.9481233 0.3177453 -0.006558001 0.9215286 0.3882552 0.005248248 0.7442528 0.6678776 -9.26792e-4 0.7251559 0.6885842 -0.002863645 0.4011673 0.9160004 0.002517163 0.3813441 0.9244298 5.98041e-4 -0.01405841 0.999901 0.001370072 -0.0111941 0.9999364 -0.006345987 -0.3887187 0.9213346 0.01200711 -0.4755455 0.8796092 -0.01034671 -0.668299 0.7438208 0.01193356 -0.7986809 0.6016367 -0.01372176 -0.9046745 0.4258823 0.009958326 -0.9617964 0.2735849 -6.25468e-4 -0.9998616 -0.01662439 -0.005708932 -0.9993277 -0.03621685 -0.002345263 -0.929793 -0.3680756 0.01312595 -0.8946177 -0.4466397 -0.01250958 -0.7799797 -0.62568 0.01017147 -0.5592068 -0.8289659 0.001676917 -0.5259463 -0.8505161 -0.005340516 -0.2621288 -0.9650182 0.01130616 -0.1574323 -0.9874652 -1 0 0 -1 1.26663e-6 0 -1 -2.63422e-6 0 -1 1.35035e-6 0 -1 -1.16278e-6 0 -1 7.94024e-7 0 -1 -3.31425e-6 0 -1 -5.00768e-7 0 -1 2.00913e-6 0 -1 -3.09607e-7 0 -1 -4.9368e-7 0 -1 1.31318e-6 0 -1 -1.12821e-6 0 -0.541141 0.3400056 -0.7691311 -0.9060065 0.2041928 -0.3707526 -0.5447589 0.320794 -0.774809 -0.2921352 0.278803 -0.9148366 -0.9456699 0.1165457 -0.3035219 -0.3474574 0.1969645 -0.9167762 -0.7870369 0.1443568 -0.5997785 -0.5505606 0.134602 -0.8238722 -0.7841593 0.1408374 -0.6043667 -0.4965792 0.06133836 -0.8658214 -0.9071484 0.03240042 -0.4195616 -0.3930362 -0.0671997 -0.9170643 -0.5659311 -0.02302855 -0.824131 -0.7406443 -0.04562139 -0.6703467 -0.870436 -0.02299129 -0.4917444 -0.3178696 -0.1862191 -0.9296674 -0.4496476 -0.2167943 -0.8664972 -0.6321811 -0.1867049 -0.7519896 -0.964928 -0.05075031 -0.2575624 -0.3338812 -0.3194164 -0.8868464 -0.7743558 -0.2075788 -0.5977325 -0.5009617 -0.3480917 -0.7923822 -0.8883811 -0.1498129 -0.4339758 -0.6782464 -0.2945218 -0.6732301 -0.470207 -0.5023939 -0.7256072 -0.528815 -0.4886558 -0.6939527 -0.9540603 -0.1670787 -0.2487041 -0.7081507 -0.5532327 -0.4386983 -0.9353944 -0.1837251 -0.3021302 -0.6442502 -0.4990896 -0.5795267 -0.8750933 -0.3237124 -0.3597529 -0.5839651 -0.5701069 -0.5778954 -0.9058317 -0.3390552 -0.2539894 -0.9929189 -0.1006252 -0.06314134 -0.3197004 -0.4799309 -0.816981 -0.2220708 -0.7154662 -0.6624143 -0.8711563 -0.3829148 -0.3073484 -0.4933063 -0.7227492 -0.4840274 -0.493174 -0.7227959 -0.4840925 -0.7489557 -0.3235213 -0.5782728 -0.499133 -0.7815712 -0.3741829 -0.5532706 -0.7402369 -0.3820223 -0.8420138 -0.4912059 -0.2230013 -0.8725519 -0.4542666 -0.1797085 -0.5607412 -0.7893702 -0.2499283 -0.9196513 -0.366958 -0.1399408 -0.7039106 -0.6815079 -0.2001423 -0.407149 -0.8808815 -0.2414074 -0.3277143 -0.9225929 -0.2035334 -0.3294416 -0.9410416 -0.07687109 -0.9738648 -0.2240618 -0.03719729 -0.4408395 -0.8924431 -0.09594708 -0.617585 -0.7832534 -0.071437 -0.7414068 -0.6657864 -0.08393228 -0.9008721 -0.4329141 -0.03186076 -0.6397958 -0.7674371 0.04125261 -0.3095099 -0.9464372 0.09197974 -0.3850862 -0.9174972 0.09953659 -0.8522453 -0.5200395 0.05689519 -0.4961374 -0.8421432 0.2112878 -0.8836823 -0.4595111 0.08919239 -0.8302232 -0.5511382 0.08352363 -0.9621436 -0.2648598 0.06425714 -0.4108553 -0.8697342 0.2734234 -0.5333308 -0.7834191 0.319081 -0.77503 -0.5708935 0.2709412 -0.8018208 -0.5338602 0.2684716 -0.8498588 -0.4689821 0.2404078 -0.4512932 -0.745602 0.4903185 -0.5309484 -0.7076303 0.4662116 -0.3411614 -0.6889842 0.6394606 -0.6433102 -0.4440139 0.6237016 -0.708361 -0.5009247 0.4972919 -0.8245555 -0.4003797 0.3997554 -0.9535839 -0.1839232 0.2384325 -0.6709987 -0.3936881 0.6283078 -0.6053949 -0.3985925 0.6889275 -0.2734425 -0.8271726 0.4909327 -0.8927173 -0.2277499 0.3888263 -0.9286098 -0.3139097 0.1978499 -0.7315988 -0.4785794 0.4855152 -0.3868647 -0.3411453 0.8567121 -0.5452642 -0.3287405 0.7711139 -0.9150935 -0.1763446 0.3626385 -0.7557224 -0.1950116 0.6251833 -0.4320083 -0.2316333 0.8716163 -0.255053 -0.2157364 0.9425528 -0.773363 -0.1889638 0.6051467 -0.6019207 -0.1702025 0.7802069 -0.9952474 -0.02479702 0.09416908 -0.2430377 -0.09728616 0.965126 -0.9260377 -0.0633043 0.3720842 -0.9607393 -0.0395773 0.2746157 -0.6932583 -0.05378848 0.7186792 -0.4907377 -0.006245851 0.871285 -0.6380969 -0.0122745 0.7698582 -0.3644003 0.03786742 0.9304723 -0.938558 0.01912605 0.3445915 -0.7510684 0.03644508 0.6592178 -0.3552472 0.1527388 0.9222096 -0.6702537 0.1697553 0.7224563 -0.9658179 0.03878146 0.2563043 -0.699167 0.1863584 0.6902436 -0.700441 0.1797832 0.6906957 -0.5071883 0.3115967 0.8035345 -0.9941678 0.02940618 0.1037576 -0.4323616 0.4049367 0.8056612 -0.4981643 0.3697201 0.7843083 -0.8996812 0.1835876 0.3960675 -0.3843245 0.5136585 0.7671048 -0.6088033 0.4706815 0.638606 -0.8648303 0.350666 0.3593077 -0.5994262 0.6640378 0.4469253 -0.9421243 0.2946966 0.1598618 -0.9181171 0.2320674 0.3212568 -0.6579576 0.5086381 0.555319 -0.4287975 0.6743361 0.6011685 -0.8936018 0.3340559 0.299804 -0.7079032 0.5913609 0.3862194 -0.3484138 0.8159695 0.4613044 -0.980576 0.1612498 0.1116651 -0.7836651 0.5385282 0.3096069 -0.8148903 0.2979955 0.4971444 -0.8479388 0.2708367 0.4556833 -0.5171689 0.8021607 0.2984536 -0.717262 0.6566827 0.2330304 -0.7126781 0.6614941 0.2334854 -0.2984395 0.9101738 0.2872589 -0.927631 0.3508033 0.1282103 -0.5232176 0.8442289 0.1162799 -0.6725548 0.7324923 0.1054759 -0.4017632 0.910407 0.098719 -0.7460307 0.6618446 0.07348477 -0.9835219 0.1788826 0.02618545 -0.960933 0.2758799 0.02232128 -0.3891166 0.9193199 -0.05864584 -0.6085662 0.7885105 -0.0888729 -0.7050949 0.7061629 -0.06461542 -0.8772704 0.4765226 -0.05764734 -0.5191775 0.8271387 -0.2151659 -0.5275597 0.8192937 -0.2245854 -0.9204669 0.3799766 -0.09142547 -0.2979143 0.8914223 -0.3414873 -0.4086853 0.814711 -0.4113666 -0.7448574 0.6295204 -0.2211144 -0.4787726 0.7796973 -0.4035457 -0.9744809 0.2127408 -0.07161271 -0.7552462 0.6078879 -0.2451032 -0.8729928 0.4351837 -0.2202242 -0.9408413 0.2033564 -0.2710423 -0.6855154 0.5878793 -0.4294958 -0.6134939 0.6477348 -0.4517356 -0.496929 0.4722988 -0.7280079 -0.8960483 0.359852 -0.260008 -0.5220599 0.5603534 -0.6430068 -0.5748215 0.5208843 -0.6310784 -0.8978533 0.2857677 -0.3349574 -0.6061699 0.3663434 -0.7059395 -0.8589219 0.4244468 -0.2865275 -0.608452 -0.006944 0.7935604 -0.706166 -0.06127637 0.7053899 -0.5120725 -0.09785842 0.8533498 -0.5209578 -0.0750336 0.8502782 -0.673949 -0.2793344 0.6839336 -0.6435276 -0.2775679 0.7133221 -0.418529 -0.1218457 0.8999928 -0.4222751 -0.1150879 0.8991321 -0.7866503 -0.3741509 0.4911136 -0.7524307 -0.449718 0.4812505 -0.6095475 -0.4889823 0.6239778 -0.5719603 -0.543919 0.6140143 -0.3933982 -0.392205 0.8315125 -0.7342147 -0.6062566 0.3055843 -0.7248871 -0.6204234 0.2993553 -0.514939 -0.5206938 0.6809669 -0.5026507 -0.5373492 0.6771988 -0.644984 -0.7601616 0.07842153 -0.6612371 -0.745196 0.08630454 -0.6195596 -0.6015663 0.5042459 -0.5367206 -0.7488577 0.3887712 -0.3850566 -0.807378 0.4470708 -0.595318 -0.7945622 0.1194471 -0.5123119 -0.8306829 0.2179509 -0.3712202 -0.9269755 0.05396485 -0.3671783 -0.9275053 0.07010012 -0.2259658 -0.0059852 0.9741169 -0.04755282 -0.1403078 0.9889654 -0.1980835 -0.2536169 0.9468059 -0.07193207 -0.4149872 0.9069793 -0.2924637 -0.306783 0.9057313 -0.0800997 -0.3935625 0.9158016 -0.1271343 -0.5117943 0.8496491 -0.1413401 -0.6123201 0.7778735 -0.3078179 -0.5426731 0.7815077 -0.1141213 -0.5757105 0.8096505 -0.2457464 -0.6179779 0.7468011 -0.1534358 -0.7074257 0.6899321 -0.1079095 -0.7515932 0.6507406 -0.3427646 -0.7140989 0.6103894 -0.1463007 -0.8514031 0.5036953 -0.274785 -0.8092242 0.5192777 -0.05909603 -0.9093507 0.4118118 -0.2940551 -0.8970443 0.3299141 -0.2687386 -0.9121804 0.3093647 -0.09297031 -0.9738426 0.2073336 -0.1946009 -0.9788439 0.06320798 -0.1133413 -0.9706847 0.2119558 -0.09722596 -0.9950623 0.01995646 -0.2715357 -0.8862586 0.375252 -0.7762144 -0.6302401 -0.01699233 -0.7010832 -0.6827116 -0.2058819 -0.5718203 -0.8144718 -0.09827184 -0.5584357 -0.8016526 -0.2133136 -0.7469965 -0.5403388 -0.3873374 -0.6501634 -0.6942504 -0.3087135 -0.319997 -0.9401619 -0.1170365 -0.7770233 -0.4892555 -0.3960604 -0.4343627 -0.8155981 -0.3822684 -0.08285373 -0.9964118 0.01729005 -0.4553228 -0.823426 -0.3386015 -0.7259675 -0.3963379 -0.5620387 -0.6052404 -0.5873936 -0.5372643 -0.5961238 -0.5846312 -0.5503117 -0.75214 -0.2872445 -0.5931071 -0.6807063 -0.1533274 -0.7163307 -0.1283107 -0.8365535 -0.5326487 -0.06779158 -0.8881752 -0.4544768 -0.5214894 -0.7036147 -0.4826751 -0.6968855 -0.1229597 -0.7065632 -0.6462268 -0.3937895 -0.6536977 -0.6259933 -0.3843022 -0.6785604 -0.463492 -0.6480129 -0.6043629 -0.5314687 -0.1087476 -0.8400685 -0.1445896 -0.7218005 -0.6768294 -0.4279969 -0.4588716 -0.7786241 -0.4351313 -0.464664 -0.7711992 -0.4768182 0.1342389 -0.8686912 -0.4402526 -0.2196657 -0.8705888 -0.1093317 -0.6190248 -0.7777242 -0.0773822 -0.6560735 -0.7507195 -0.1454792 -0.4967064 -0.8556393 -0.3930569 -0.1888146 -0.8999196 -0.4189988 0.009288489 -0.9079393 -0.0671156 -0.3448669 -0.9362491 -0.04186141 -0.3245913 -0.9449276 -0.05887949 -0.04195731 -0.9973831 -0.203377 -0.1306859 -0.9703396 -0.3253698 -0.941017 -0.092853 -0.2283095 -0.9658511 -0.1225005 -0.3565609 -0.8770875 -0.3218414 -0.1919134 -0.862542 -0.4681778 -0.0558865 -0.931432 -0.3595986 -0.02618187 -0.9440529 -0.3287532 -0.07507729 -0.8999741 -0.4294301 -0.2867046 -0.6938874 -0.6605459 -0.3918879 -0.6069766 -0.6913778 -0.2181547 -0.5291738 -0.8199902 -0.2132042 -0.4041486 -0.8894987 -0.2910102 -0.2044867 -0.9346114 -0.02111631 -0.9521061 0.3050381 -0.007369339 -0.9946275 0.1032565 -0.003972649 -0.9950452 0.09934455 0.002439379 -0.9985641 -0.05351591 -0.0108844 -0.9962046 -0.08636063 -0.01432996 -0.9778099 -0.2090039 0.01764947 -0.2002217 -0.9795917 -0.01237863 -0.04660332 -0.9988368 -0.006925463 0.04110771 -0.9991308 -0.01086491 0.07293039 -0.9972779 0.001320421 0.1704546 -0.9853647 0.01854211 0.9792743 -0.2016883 -0.01099425 0.99571 -0.0918734 0.003826379 0.9976073 0.06903004 -0.02111458 0.9919106 0.1251706 -0.01107382 0.9544194 0.2982633 -0.01648348 0.318791 0.9476818 -0.03469485 0.2056793 0.9780042 0.003981351 0.1085795 0.9940798 -0.008515596 0.02302873 0.9996985 -0.005026996 -0.01016926 0.9999358 -0.01701575 -0.0972737 0.9951123 0.005690932 -0.2475274 0.9688642 -0.9999719 -0.002663671 -0.007007241 -0.9999721 -0.006491363 -0.003697037 -0.9999949 -0.001784324 -0.002645194 -0.9999992 -0.001130104 -5.6446e-4 -0.999995 -0.002615451 0.001824438 -0.9999946 -5.18145e-4 -0.003254592 -0.9999936 -3.27682e-4 -0.003554999 -0.9999934 -0.003644883 -1.32058e-4 -0.9999932 -0.003689408 3.36893e-4 -0.9999482 0.009087622 -0.004600286 -0.9999951 -0.003037631 8.63329e-4 -0.9999652 0.002052128 -0.008090913 -0.9999697 -0.002032697 -0.007524609 -0.9999862 0.00345391 -0.003989994 -0.9999885 0.002532303 -0.004070758 -0.9999948 -0.002600789 0.001958668 -0.9999656 -0.003510117 0.007518887 -0.9999844 0.005528867 -8.31934e-4 -0.9999769 0.005491137 -0.0040192 -0.9999754 -0.006826341 0.001645803 -0.9999961 -0.001342475 0.00248003 -0.999975 0.003977119 -0.005853772 -0.9999981 0.001916587 -3.37779e-4 -0.9999969 -0.001848995 0.001756906 -0.9999997 -1.43255e-5 8.57363e-4 -0.999998 0.001992166 -1.84676e-4 -0.9999911 0.003706753 0.002045631 -0.9999992 0.001238405 4.14949e-4 -0.9999864 0.001993358 0.004829645 -0.9999864 0.002192258 0.004758 -0.9999926 7.23593e-4 0.003781795 -0.99999 0.003342211 0.003000736 -0.4848371 0.2241271 0.8453993 -0.3887208 -0.2236084 0.8938095 -0.2710606 -0.07814621 0.9593849 -0.3429511 0.01591926 0.9392185 -0.2925214 0.07139039 0.9535905 -0.2973132 0.09050583 0.9504808 -0.2693549 -0.07833123 0.9598501 -0.3815744 0.1975571 0.9029797 -0.1287971 -0.0129137 0.9915869 -0.1258746 0.004917442 0.992034 -0.1361958 0.02449953 0.990379 -0.393141 0.9010243 -0.1832911 -0.6952109 0.7147852 0.07592135 -0.5491846 0.8356781 0.006216526 -0.5220122 0.8489091 0.08280485 -0.7536817 0.6139936 0.2344698 -0.1209431 0.9925263 -0.01625919 -0.6557703 0.6965355 0.2912111 -0.6351417 0.6595202 0.40203 -0.3593335 0.9285843 0.09279406 -0.3464499 0.9266724 0.1457762 -0.2179341 0.9709377 0.09891891 -0.7125666 0.5085101 0.4833908 -0.1122494 0.984605 0.1339901 -0.4081681 0.8280999 0.3842521 -0.376863 0.7885754 0.4859251 -0.6789819 0.5551915 0.4803604 -0.7967439 0.3185663 0.5135317 -0.6960978 0.2751313 0.663137 -0.5994889 0.4395956 0.6688563 -0.06747913 0.9368209 0.3432392 -0.1276283 0.8616897 0.4911231 -0.4718226 0.664847 0.5791045 -0.6106579 0.4211763 0.6706023 -0.4389886 0.7044306 0.5577334 -0.07814824 0.7859209 0.6133689 -0.6702665 -0.01820456 0.7418972 -0.6099315 0.1920639 0.768827 -0.5367982 0.1173515 0.8355097 -0.1614805 0.7277117 0.6666031 -0.4331139 0.4877671 0.7579549 -0.4551546 0.5161255 0.725568 -0.4340522 0.3844326 0.8147455 -0.5198509 -0.03689241 0.85346 -0.1365936 0.5686866 0.8111338 -0.3642549 0.276754 0.8892276 -0.1063162 0.4407138 0.8913295 -0.08474314 0.5342863 0.8410451 -0.3353004 0.05994153 0.9402025 -0.07322371 0.2215726 0.9723909 -0.315265 0.04588758 0.9478937 -0.3796751 0.785952 0.4879821 -0.2534968 0.7469762 0.6146267 -0.220696 0.5842702 0.7809749 -0.3460839 0.378799 0.858334 -0.1127455 -0.01409709 0.993524 -0.2075478 0.9251796 0.3177525 -0.2120208 0.2376449 0.9479305 -0.4284301 0.871047 0.2402599 -0.4491899 0.8609248 -0.2388241 -0.307414 0.9392972 0.1523727 -0.3205698 0.9349204 0.1521805 -0.4157062 0.9072287 0.06422334 -0.2357552 0.9697917 0.06263905 -0.2840352 0.9587122 -0.01396501 -0.4171687 0.9001214 -0.1255063 -0.1630059 0.9863769 0.02212959 -0.1408046 0.9895968 0.02953314 -0.3676249 0.9298933 -0.01226562 -0.3473302 0.9181568 -0.1906567 -0.2314953 0.9685909 -0.09078347 -0.2669762 0.9592225 -0.0928213 -0.1302767 0.9913607 -0.01522856 -0.4408971 -0.8681321 0.2279401 -0.3079349 -0.9252698 -0.2214772 -0.4149363 -0.8987087 -0.1419536 -0.5462009 -0.8318329 -0.09858369 -0.3589897 -0.933328 -0.005032122 -0.2182815 -0.9696535 -0.1101151 -0.3527185 -0.9357284 -0.001459181 -0.2927448 -0.9451416 0.1449408 -0.171387 -0.9852013 -0.002260625 -0.1908392 -0.9788426 0.07380855 -0.354377 -0.9258072 0.1315225 -0.02991396 -0.999541 -0.004804372 -0.1597672 -0.9871427 0.004886329 -0.117348 -0.9928722 -0.02084243 -0.6165834 -0.005475163 -0.7872706 -0.5300487 -0.04762375 -0.8466289 -0.2404147 -0.1008961 -0.9654122 -0.5339955 0.1113468 -0.8381234 -0.3493549 0.04456585 -0.9359301 -0.7335996 0.2204044 -0.642848 -0.7096942 0.2975293 -0.6386004 -0.5751807 0.3440389 -0.742162 -0.595667 0.2392016 -0.7667877 -0.3191832 0.1308208 -0.9386203 -0.04972296 0.05127483 -0.997446 -0.7650073 0.4144532 -0.4929427 -0.7371523 0.4941448 -0.4608984 -0.4191954 0.3087487 -0.8537855 -0.6168938 0.4075186 -0.6733281 -0.4776672 0.3631588 -0.7999686 -0.7556733 0.5905772 -0.2831545 -0.7449448 0.6055653 -0.2799075 -0.5638561 0.5346075 -0.6294929 -0.405611 0.5491604 -0.7306864 -0.5823662 0.702609 -0.4088891 -0.1233569 0.5226321 -0.8435869 -0.06756585 0.4597521 -0.8854734 -0.594332 0.8014454 -0.06674599 -0.5884442 0.6959871 -0.4115039 -0.4592846 0.6445713 -0.6112164 -0.6213493 0.7617616 -0.1834238 -0.1447168 0.6764648 -0.7221167 -0.40584 0.7367755 -0.5407919 -0.6358093 0.7717589 0.01161068 -0.1438442 0.7776393 -0.6120344 -0.1160887 0.7094889 -0.6950892 -0.378073 0.8866302 -0.2663599 -0.425451 0.8452289 -0.3233879 -0.4573773 0.8885529 0.03577542 -0.1179912 0.8628371 -0.4915184 -0.4181605 0.9070695 -0.04865008 -0.08284318 0.890116 -0.4481413 -0.07786101 0.936093 -0.3430271 -0.3583638 0.9331906 -0.02703428 -0.04414111 0.954536 -0.2948096 -0.0604974 0.9973228 -0.0410766 -0.2164374 0.9589068 -0.1834462 -0.2184039 0.137493 -0.966124 -0.2330652 0.4705246 -0.8510507 -0.2360464 0.467422 -0.8519382 -0.02132594 0.3141929 -0.9491196 -0.07109344 0.4415356 -0.8944228 -0.06837409 0.3546288 -0.9325039 -0.3447237 0.7146177 -0.6086767 -0.2666175 0.8426499 -0.4678207 -0.2353318 0.9534548 -0.1885287 -0.4538006 0.2463615 -0.8563709 -0.3157367 0.1331698 -0.9394553 -0.3682752 0.1508355 -0.9173997 -0.2831939 0.08317869 -0.9554489 -0.3696761 -0.06373101 -0.9269726 -0.3220137 -0.1024441 -0.9411761 -0.1610216 0.02905809 -0.9865231 -0.1534072 0.03097057 -0.9876777 -0.3770946 -0.2416865 -0.8940847 -0.1483844 0.008029937 -0.9888973 -0.005036711 0.04346382 -0.9990424 0.2599201 0.2485872 -0.9330842 0.3315592 0.2768286 -0.901906 0.5049651 0.2321333 -0.831339 0.5775192 0.2527175 -0.7762767 0.7435072 0.1644591 -0.64819 0.2131641 0.2083176 -0.9545496 0.8016126 0.177459 -0.570899 0.3801134 0.1392556 -0.914397 0.3175471 0.08734321 -0.9442114 0.5352967 0.1405129 -0.8328948 0.5894345 0.1102223 -0.8002613 0.9238692 0.1095764 -0.3666863 0.9261676 0.08960133 -0.3663132 0.3150361 -0.04397398 -0.9480605 0.2769303 -0.01929265 -0.9606963 0.7872849 0.07842236 -0.6115819 0.7242737 0.1120313 -0.6803504 0.9180569 0.06757771 -0.3906468 0.9123056 0.07481628 -0.4026179 0.535036 -0.02986264 -0.8443014 0.3362392 2.36073e-4 -0.9417766 0.3710081 -0.02155148 -0.9283796 0.6649482 0.008015632 -0.7468465 0.9976643 0.02423137 -0.06386709 0.7793072 -0.008542656 -0.6265839 0.2904298 -0.1257074 -0.9486033 0.3989344 -0.18256 -0.8986231 0.9536235 0.02649056 -0.299834 0.740419 -0.0399456 -0.6709576 0.2397306 -0.2463259 -0.9390702 0.8876439 -0.009096443 -0.4604406 0.5776374 -0.1277069 -0.806242 0.303003 -0.2733598 -0.9129424 0.5679503 -0.1232163 -0.8137876 0.9853057 -0.001634597 -0.1707922 0.8056017 -0.08922815 -0.5856999 0.5495738 -0.2189102 -0.8062549 0.9276387 -0.04118567 -0.3712011 0.5795385 -0.2330422 -0.780914 0.7663688 -0.1851398 -0.6151441 0.808229 -0.1458814 -0.5705126 0.9088244 -0.1154379 -0.4008896 0.9659337 -0.04874908 -0.2541571 0.9800637 -0.04484909 -0.1935554 0.7565748 0.0139867 -0.6537577 0.4011573 0.1948221 -0.8950515 0.5347183 -0.1258293 -0.8356096 0.4123005 -0.064767 -0.9087429 0.2500222 -0.2075307 -0.9457378 0.2856182 0.9408954 -0.1820385 0.211498 0.9205556 -0.3283993 0.3675663 0.7905452 -0.4898298 0.2397061 0.7176436 -0.6538568 0.332889 0.6059511 -0.7225013 0.328579 0.5638343 -0.7577116 0.3611859 0.3285276 -0.8727052 0.3604466 0.1155037 -0.9256011 0.9563007 0.2830811 -0.07317221 0.8684189 0.4930831 -0.05213212 0.8435105 0.5319495 -0.07429653 0.6895383 0.7242487 9.07928e-4 0.9624086 0.2194909 -0.15998 0.9750096 0.1617012 -0.152345 0.783912 0.5614913 -0.2649712 0.1819933 0.9526938 0.2434198 0.5514633 0.8256933 -0.1188234 0.3957513 0.9174476 0.04087632 0.6327978 0.7201726 -0.2844617 0.4225015 0.9005173 -0.1027667 0.8054907 0.4968279 -0.3230279 0.8795554 0.3577865 -0.313642 0.8353822 0.2942638 -0.4642688 0.6591708 0.5265178 -0.5369105 0.4983857 0.7296971 -0.4681386 0.7027516 0.3626559 -0.6120629 0.9492214 0.06251186 -0.3083361 0.5592103 0.620146 -0.5501844 0.6877663 0.3835815 -0.6163139 0.8796883 0.1264245 -0.4584378 0.7090252 0.1697256 -0.6844534 0.7655048 0.07139188 -0.6394573 0.403693 0.4414427 -0.8013491 0.1506064 0.9628921 0.2239568 0.4640366 0.8547276 0.2326174 0.3057035 0.9164846 0.2580727 0.51117 0.8263486 0.2363331 0.6715176 0.7173662 0.1856071 0.711244 0.6744214 0.1982114 0.1670092 0.9765884 0.1355838 0.8389726 0.5213765 0.1558578 0.308684 0.9478473 0.07937127 0.8887571 0.444643 0.1113708 0.4731332 0.8724609 0.1222991 0.9775055 0.2070737 0.04004645 0.3146995 0.9489821 -0.01993018 0.5671023 0.8218086 0.05500644 0.9247225 0.3676412 0.09863233 0.7045232 0.705925 0.07291823 0.7506827 0.6547501 0.08819359 0.8867315 0.4604276 0.04139846 0.2822188 0.9532314 -0.1081778 0.8445337 0.5301464 0.07555091 0.535699 0.8443046 0.01327985 0.3179467 0.9440076 -0.08808845 0.7779583 0.6275125 -0.03176653 0.5919874 0.7991129 -0.1047357 0.9429916 0.3277359 0.05793172 0.6208012 0.7750865 -0.1176727 0.3849577 0.9075905 -0.1675927 0.7613398 0.6467577 -0.04545873 0.2971292 0.9234893 -0.2426555 0.9049258 0.4240965 -0.03537732 0.3330584 0.9032338 -0.2706305 0.8086811 0.5824844 -0.08213901 0.9103138 0.4127067 -0.03165495 0.9903625 0.1384915 -0.001526892 0.6041506 0.7641403 -0.2260349 0.6486416 0.7370074 -0.1899584 0.7814729 0.5964795 -0.1830639 0.9993285 0.0354709 -0.009190559 0.8619555 0.4919068 -0.1227214 0.9074085 0.4050244 -0.1120936 0.960218 0.2731201 -0.05819594 0.9644796 0.2578378 -0.05743587 0.6555407 0.7416675 0.142112 0.7325551 0.6801316 0.02800428 0.4574954 0.8763178 0.1508812 0.6414843 0.7555775 -0.1326669 0.3948085 0.9178639 0.04064816 0.4084733 0.9114212 -0.04960864 0.3470395 0.02058339 0.9376247 0.2769451 -0.0369814 0.9601739 0.3166667 0.2007144 0.9270578 0.3029128 0.4778376 0.8245696 0.3389928 0.6250736 0.7031124 0.3214755 0.6183444 0.7171497 0.3643493 0.8348534 0.4126374 0.3280157 0.8316812 0.4480091 0.3610643 0.8675073 0.3421456 0.29531 0.9327897 -0.206629 0.9969206 0.04218518 0.06610453 0.9597361 0.03575104 0.2786189 0.923676 0.107587 0.3677604 0.7597457 0.05856311 0.6475777 0.5154475 -0.01115751 0.8568487 0.6856453 0.1205328 0.7178875 0.8614633 0.3067698 0.4046893 0.676393 0.1546666 0.7201186 0.7885745 0.3438189 0.5098422 0.9637315 0.2477115 0.09930115 0.8792867 0.4044399 0.2515616 0.4191759 0.3436756 0.8403444 0.8997187 0.3556646 0.253 0.6102437 0.5354842 0.5838316 0.4305864 0.3046691 0.8495717 0.5942365 0.5589318 0.578341 0.6947346 0.6297369 0.3475275 0.6224182 0.652373 0.432441 0.7734854 0.6334865 0.02038145 0.2881726 -0.251228 0.9240353 0.5577031 -0.2068396 0.8038561 0.3913483 -0.2900449 0.8733386 0.4133507 -0.1515937 0.8978645 0.4924214 -0.05010044 0.8689138 0.7765192 -0.1818451 0.6032831 0.3150454 -0.1680665 0.9340772 0.7669236 -0.1763194 0.6170412 0.7386115 -0.1083502 0.665367 0.9473747 -0.09134864 0.3068172 0.2744939 -0.0247066 0.9612715 0.731529 -0.1165002 0.6717835 0.886572 -0.1005991 0.4515199 0.4923031 -0.04247152 0.869387 0.4114753 -0.08585584 0.9073681 0.9348993 -0.05803138 0.3501367 0.3640261 0.1012337 0.9258708 0.9535732 -0.05819135 0.295486 0.7411996 -0.05680459 0.6688771 0.6658214 0.03553593 0.7452644 0.3531981 0.08858221 0.9313455 0.6003016 -0.009236156 0.7997204 0.768018 -0.01244181 0.6403074 -0.9768744 -0.03127652 0.2115147 0.2742066 0.1797897 0.9447151 0.5456229 0.1218808 0.8291205 0.889777 0.01759105 0.4560565 0.331364 0.228387 0.9154438 0.5576802 0.127184 0.8202542 0.7008313 0.07992583 0.7088353 0.2958907 0.2505471 0.9217782 0.8180829 0.1041695 0.5655875 0.96868 -0.01023012 0.2481018 0.520404 0.2465872 0.8175417 0.5850297 0.2087071 0.7836975 0.8490063 0.06924068 0.5238264 0.9099968 0.07262665 0.408205 0.7006609 0.2099525 0.6819049 0.9884346 0.002337038 0.1516301 0.8242981 0.1429326 0.5478165 0.8689101 0.1509463 0.471392 0.9576479 0.05694484 0.282255 0.971697 0.06778991 0.226295 0.4720808 -0.2625111 0.8415627 0.5620542 0.1078636 0.820037 0.3487375 -0.9192796 -0.1825028 0.3237248 -0.9252028 0.1979956 0.3276841 -0.9258972 0.187983 0.2941819 -0.8304051 0.4731643 0.3440378 -0.6121913 0.7119409 0.3190689 -0.6009687 0.7328245 0.3196303 -0.452347 0.8325976 0.3278959 -0.09189248 0.9402341 0.3362823 0.06292724 0.9396565 0.3191514 0.03972953 0.9468707 0.9644119 -0.2599939 0.04809314 0.8758108 -0.476181 0.07878595 0.8716521 -0.4829039 0.08382469 0.9985908 -0.03541684 0.03952372 0.9757772 -0.1975455 0.0939933 0.7426159 -0.6629515 0.09495824 0.45527 -0.8816608 -0.1241111 0.6825746 -0.7176661 0.1380123 0.6572719 -0.7137661 0.2419331 0.9420459 -0.2367364 0.2377091 0.500356 -0.8640503 0.05532771 0.1038225 -0.9944645 -0.01616698 0.8294757 -0.418056 0.3704041 0.7381578 -0.5539761 0.3850114 0.8365636 -0.4126481 0.3603928 0.4815768 -0.7913407 0.3766481 0.3906593 -0.8369319 0.383315 0.5925515 -0.6279088 0.5045921 0.735198 -0.3040537 0.6058345 0.9569625 -0.05428743 0.2850888 0.8899384 -0.07010436 0.4506608 0.7380936 -0.36732 0.5659452 0.9538668 -0.04791337 0.2963824 0.51241 -0.5833552 0.6301848 0.8230903 -0.01168566 0.5677903 0.6348922 -0.2327516 0.736708 0.7071364 -0.0746681 0.7031237 0.3172109 -0.9144605 -0.2512753 0.256286 -0.9416778 -0.2180835 0.5945305 -0.7709065 -0.2285538 0.6203122 -0.7578043 -0.20235 0.743035 -0.6487188 -0.1645082 0.8307528 -0.5335354 -0.1587131 0.8707643 -0.475366 -0.1256848 0.3079523 -0.9495661 -0.05907458 0.2977056 -0.9524947 -0.06422966 0.5710365 -0.8161715 -0.08821207 0.9366816 -0.3358538 -0.09914594 0.5764132 -0.8130091 -0.08224374 0.9748434 -0.2181903 -0.04553586 0.2039313 -0.978472 0.03169673 0.4849455 -0.8744012 0.01583385 0.6543515 -0.7498204 -0.09794718 0.8374115 -0.5453641 -0.03633087 0.5238333 -0.8509606 0.03827494 0.1973986 -0.9700093 0.1418303 0.7271341 -0.685862 -0.02948677 0.8968213 -0.4396809 -0.04891121 0.3367007 -0.9254205 0.1738664 -0.2389442 -0.9675812 -0.08180761 0.4279906 -0.8978497 0.1033923 0.956649 -0.2911441 -0.007607519 0.6679726 -0.7369202 0.1037375 0.6903772 -0.7179452 0.08907395 0.492251 -0.8582351 0.1453326 0.8758664 -0.4805629 0.0437892 0.9362416 -0.3433066 0.07478153 0.4545311 -0.8538917 0.2535159 0.6999066 -0.6880038 0.1917855 0.6912857 -0.6972481 0.1896559 0.8439717 -0.5175582 0.1408736 0.963703 -0.265073 0.03182506 0.8670553 -0.4764761 0.1455528 0.9606465 -0.2700338 0.06511497 0.9901013 -0.1309736 0.05045282 0.6570535 -0.7487366 -0.08760243 0.6360185 -0.7691844 0.06193524 0.3850196 -0.8965453 0.2190124 0.3951694 -0.9070661 0.1451632 0.2064388 -0.9345415 0.2898539 0.3298623 -0.01574724 -0.9438977 0.2420352 0.05547815 -0.9686802 0.2770015 -0.2138557 -0.936769 0.3234782 -0.4766548 -0.8174118 0.3737387 -0.5257903 -0.76411 0.3464471 -0.7051394 -0.6186703 0.3374812 -0.7134622 -0.6140669 0.3203063 -0.8350229 -0.447371 0.3572664 -0.8491043 -0.3890793 0.3337886 -0.9155212 -0.2245132 0.3647159 -0.9161215 -0.1664445 0.3097324 -0.9507433 0.01237839 0.9712037 -0.03144985 -0.236166 0.7196093 0.06161361 -0.6916403 0.7844181 -0.02210491 -0.6198386 0.9488329 -0.1412903 -0.2824063 0.5673345 0.04604256 -0.8221993 0.878859 -0.2156701 -0.4255505 0.7899869 -0.1757773 -0.5873867 0.5163962 -0.005777776 -0.8563304 0.989787 -0.1243926 -0.0696299 0.6615647 -0.2873091 -0.6926657 0.9634146 -0.2041494 -0.1736531 0.5235201 -0.2371175 -0.8183533 0.640748 -0.3962663 -0.6575827 0.3815052 -0.2986149 -0.8748046 0.8004248 -0.4323753 -0.4151769 0.8915772 -0.4070354 -0.198526 0.7215192 -0.5035194 -0.4752665 0.6881489 -0.5578715 -0.4639294 0.8604897 -0.4922285 -0.13141 0.6707478 -0.6640093 -0.3304378 0.7396811 -0.6503815 -0.1728461 0.8762964 -0.4747523 -0.08194458 0.001241862 -0.008039355 0.9999669 -0.001408219 -0.01668804 0.9998598 0.01291507 0.222631 0.9748173 -0.009860813 0.3819571 0.9241276 0.01030987 0.4689885 0.8831441 -0.005124986 0.7139886 0.7001386 -1.69311e-4 0.7253858 0.6883425 0.01356518 0.8674759 0.4972943 -0.006386458 0.9255962 0.3784587 0.007063031 0.9588862 0.2837032 0.003099381 0.995942 0.08994418 0.007484018 0.9973991 0.07168734 0.0164932 0.9914274 -0.1296142 -0.007144093 0.9517927 -0.3066592 0.007082223 0.9635457 -0.2674501 0.002769708 0.9781319 -0.2079674 0.01569122 0.9898629 -0.1411571 0.001899003 0.9971002 -0.07607626 0.001213312 0.9995894 0.02862918 0.01305478 0.997252 0.07292598 0.00191456 0.9935399 0.1134684 0.001262426 0.9669002 0.2551518 0.003400623 0.9642265 0.2650582 0.01919269 0.9766736 0.2138704 0.002367317 0.9992216 -0.03937816 -0.009993851 0.9964717 -0.08333313 0.01000756 0.9265201 -0.3761123 -0.001589536 0.9069005 -0.421342 -4.34782e-4 0.7489176 -0.662663 0.007119655 0.7325222 -0.6807059 0.009613931 0.5285001 -0.8488789 -0.006532609 0.4221231 -0.9065151 0.006108701 0.3665015 -0.9303975 0.01412063 0.1310459 -0.9912758 2.52661e-4 -0.08554047 -0.9963347 -0.01093387 0.008265554 -0.9999061 -0.002404391 -0.2658505 -0.9640113 0.00825411 -0.2882332 -0.9575248 0.0192247 -0.06646156 -0.9976038 4.10755e-4 -0.1669141 -0.9859713 8.71721e-4 -0.01535964 -0.9998817 -0.001990497 0.09311306 -0.9956536 0.01035159 0.1568704 -0.987565 0.002227365 0.1957243 -0.9806564 0.004384636 0.2868894 -0.9579538 0.00890696 0.2995066 -0.9540527 0.9999978 -0.001194238 -0.001720607 0.9999817 -0.001951575 0.00573194 0.9999843 -0.004196941 -0.003740906 0.9951092 -0.08554214 0.04940068 0.9999768 6.49988e-4 0.006798207 0.9999881 0 0.004889786 0.9997476 -0.0194565 -0.01123547 0.9999613 -0.00285685 0.008325755 0.9999788 0.001063942 0.006424069 0.9999682 0.002116799 -0.007694363 0.9999954 0.00194782 0.002354145 0.9999911 0 -0.0042454 0.9976827 0.05837672 -0.03495055 0.9999786 5.83835e-4 -0.006533622 0.994339 0.09035217 -0.05591517 0.9999991 -2.25205e-4 0.001358926 0.9999712 2.61732e-4 -0.007590293 0.008432924 -0.9999643 -6.57948e-4 0.003597736 -0.999821 0.01857787 0.007881402 -0.9757845 -0.2185922 -0.005332529 -0.9574081 -0.2886888 0.01119226 -0.8856799 -0.4641617 -0.005903661 -0.8123226 -0.5831785 0.01269906 -0.7334234 -0.6796535 -0.006091713 -0.5776398 -0.816269 0.01256763 -0.5062198 -0.862313 0.003736376 -0.2336989 -0.9723019 -0.00395441 -0.2053862 -0.9786731 0.01084125 0.03184819 -0.999434 -0.007938504 0.142471 -0.9897671 0.001138985 -0.9621728 0.2724376 0.009912848 -0.9683148 0.249536 -0.01316457 -0.9874981 0.1570802 0.01687026 -0.9998471 -0.004627585 -0.006504058 -0.9979786 -0.06321799 0.01638156 -0.9722859 -0.2332208 -0.002438306 -0.963536 -0.2675676 0.006386458 0.06111729 0.9981102 -0.006646931 -0.01059848 0.9999218 0.01628696 -0.195416 0.9805853 0.003433167 -0.3561621 0.9344179 -0.003323912 -0.3778838 0.9258472 -4.65013e-4 -0.6823483 0.7310271 0.006546974 -0.663044 0.7485518 0.01101714 -0.8731487 0.4873296 -0.002557516 -0.9007379 0.4343556 0.008907437 -0.9699798 0.2430227 -0.008412837 -0.9945539 0.1038841 0.01540958 -0.9997627 -0.01539945 0.003375649 0.2653322 0.9641512 0.001539349 0.2618116 0.9651179 0.02192831 0.0166909 0.9996203 -0.001267313 0.09596961 0.9953835 6.67661e-4 -0.04380536 0.99904 -0.008179008 -0.1564499 0.9876521 0.01393038 -0.2521873 0.9675782 6.60566e-4 -0.2902866 0.9569396 0.01331245 -0.3428276 -0.939304 -0.02092868 -0.4995653 -0.8660234 0.0178073 -0.8066988 -0.5906947 -0.01548045 -0.9144836 -0.4043269 0.0131424 -0.9941078 -0.1075966 -0.01831638 -0.9885216 0.1499649 0.01584935 -0.9276472 0.3731215 -0.001575648 -0.7053543 0.7088532 -0.009597599 -0.68004 0.7331123 -0.007987201 -0.293596 0.9558962 0.001349389 -0.3413119 0.9399492 0.01410573 0.1406642 0.9899569 -0.01656967 0.3329532 0.9427978 0.01498007 0.5779392 0.8159423 -0.01532429 0.7602508 0.649449 0.0120905 0.9477489 0.3187882 0.003463149 0.9602792 0.2790194 -0.008683383 0.9799838 -0.198888 0.005849599 0.9648976 -0.2625612 0.003884255 0.7092381 -0.7049584 -0.008139252 0.6746254 -0.7381154 0.002521753 0.1403085 -0.9901047 -0.007329106 0.1744104 -0.9846458 0.009178459 0.9382061 0.3459554 -0.01178193 0.919877 0.39203 0.009867727 0.7128282 0.7012693 0.002916216 0.7033668 0.7108212 -0.01046335 0.3786572 0.9254779 0.03226161 0.2639958 0.9639841 -0.02313286 0.09118205 0.9955656 0.03248739 -0.2786206 0.9598517 -0.0141524 -0.3565808 0.9341573 -0.004749596 -0.688964 0.72478 0.01920682 -0.7214869 0.6921617 -0.01791018 -0.917438 0.3974756 0.01184439 -0.9406047 0.3392972 -0.002498626 -0.9999969 -2.66302e-4 -0.00283122 -0.9999912 0.003108441 -0.01356273 -0.9999077 9.21306e-4 -0.004685461 -0.9999891 1.33569e-4 0.01451772 0.9092522 -0.4159924 -0.02076232 0.7436186 -0.6682816 0.01149213 0.5948787 -0.8037334 -0.007258713 0.08521968 -0.9963358 0.002998054 0.1254165 -0.9920998 -0.005737006 -0.4259371 -0.9047346 0.00587511 -0.4871475 -0.8733 -0.004866421 -0.8114637 -0.5843826 0.001948595 -0.8324077 -0.5541604 -2.60693e-4 -0.9999995 -9.9725e-4 -0.004315555 -0.9999907 -5.06962e-4 -9.93833e-4 -0.9687526 -0.248027 0.01360756 -0.9559821 -0.2931097 -0.01425617 -0.8095954 -0.5868154 0.01443046 -0.7387877 -0.6737838 -0.01082402 -0.5429666 -0.8396847 0.0138995 -0.4126804 -0.9107699 -0.01218515 -0.2681351 -0.9633044 0.01395332 0.02949166 -0.9994676 -0.01117449 0.1154239 -0.9932535 0.0108633 0.4868345 -0.8734267 -0.0109536 0.550609 -0.8346914 0.01017451 0.7879875 -0.6156073 -0.02041369 0.8616885 -0.507027 0.01983743 0.953731 -0.3000065 -0.01001119 0.9999359 -0.005317807 -0.01990288 0.999801 -0.001334905 -0.01271343 0.9999192 1.93977e-4 -7.25618e-4 0.9999886 0.004740655 -0.02160137 0.9997662 -0.001010239 0.007930994 -0.913418 0.4069457 -0.00824058 -0.8709654 0.4912753 0.003933191 -0.4721776 0.8814947 -4.10953e-5 -0.4854394 0.8742704 0.003990411 0.1482939 0.9889354 -0.01424288 0.2352461 0.9718316 0.01372128 0.6062254 0.7951745 -0.01769936 0.804308 0.593949 0.0103718 0.9085152 0.4177232 -0.01128715 0.9999362 -6.09764e-4 -0.005654692 0.9999841 7.10292e-5 -1 6.12559e-6 0 -1 -2.99157e-6 0 -1 7.17078e-6 0 -1 -1.08172e-5 0 -1 -2.97751e-6 0 -1 5.19339e-6 0 -1 -2.77714e-6 0 -1 -1.22464e-6 0 -1 2.6989e-6 0 -1 -1.42085e-6 0 -0.01745831 0.9372539 0.3482105 0.005144834 0.9190406 0.3941294 0.01475363 0.7510042 0.6601325 -0.01702588 0.6827292 0.7304731 0.01453244 0.4193696 0.9076994 0.01062834 0.4104193 0.911835 -0.02492433 0.02299875 0.9994248 0.02270907 -0.1103708 0.993631 0.007168233 -0.5077524 0.8614733 -0.01201033 -0.4478548 0.8940256 -0.009868502 -0.744105 0.6679898 0.02130883 -0.8385589 0.5443942 -0.01635789 -0.9200823 0.3913834 0.001525282 -0.9999179 -0.01272195 -0.01043516 -0.9999449 -0.001151084 0.01184773 -0.999889 0.009044706 -0.01132762 -0.9999357 -6.33111e-4 -0.013049 -0.9999149 -3.36268e-4 0.006200909 0.9093315 -0.4160266 -0.01743829 0.8339225 -0.5516061 0.01933914 0.5948048 -0.8036376 -0.01762008 0.2238022 -0.9744753 0.008616149 0.08521878 -0.9963251 -0.008603334 -0.410479 -0.9118295 0.01156914 -0.5163469 -0.8563014 -0.01325178 -0.8114044 -0.5843349 0.01190924 -0.8978152 -0.4402112 -0.006511688 -0.9999788 -7.41115e-5 -2.24613e-4 -0.9999997 -8.33271e-4 0.004826784 -0.8894461 -0.4570146 -0.007469177 -0.8650419 -0.5016443 0.005598723 -0.6586318 -0.7524446 -0.005696177 -0.6049373 -0.7962527 0.006831824 -0.3363096 -0.9417268 -0.004573822 -0.2869712 -0.9579284 0.008176088 0.1532917 -0.9881471 6.40595e-4 0.1284441 -0.9917166 -0.01045775 0.5807252 -0.8140325 0.01023387 0.6401702 -0.7681651 -0.01008069 0.8799687 -0.4749249 0.00687015 0.904726 -0.4259387 -1.30358e-4 0.9999842 -0.005633294 0.009952068 0.9999412 0.004297912 -0.01242512 0.9999225 -9.01247e-4 -0.01389712 0.9999033 -7.4508e-4 -5.9263e-4 -0.8872368 0.4613138 -0.007605135 -0.901184 0.4333702 0.01547664 -0.5203792 0.8537951 -0.02141773 -0.3631317 0.9314917 0.0152893 0.1446369 0.9893667 -0.01306992 0.3202967 0.9472272 0.01106148 0.6083877 0.7935629 -0.01579213 0.7949372 0.6064862 0.01247417 0.9084936 0.4177126 -0.003786385 0.9999927 5.2281e-4 -0.007528185 0.9999718 7.09985e-5 -1 6.29983e-6 0 -1 -1.82542e-6 0 -1 6.23788e-6 0 -1 9.53014e-6 0 -1 1.36146e-6 0 -1 -3.67896e-6 0 -1 0 0 -1 -2.85521e-6 0 -0.1916831 -0.9784203 0.07714563 -0.7811036 -0.6042214 0.1574606 -0.8618205 -0.4797287 0.1646993 0.2458152 -0.9522869 -0.1808993 0.3507971 -0.9029181 -0.2483554 0.3015686 -0.9190351 -0.2538323 0.2613174 -0.9463455 -0.1901143 0.1756234 -0.9778968 -0.1134651 -0.9190063 -0.3538557 0.1738207 -0.7669072 -0.6167327 0.177466 0.1671433 -0.9816824 -0.09144902 -0.9356302 -0.2922318 0.1979818 0.1576579 -0.9866466 -0.04089713 -0.02491295 -0.999527 0.01802814 0.05814522 -0.9983008 -0.003830909 0.02375823 -0.9992321 0.03115707 0.05211985 -0.9983417 0.02444523 -0.9025901 -0.3246589 0.2827151 -0.9223605 -0.2795088 0.2666949 0.3736953 -0.9119617 -0.1693453 0.233123 -0.9647797 -0.1218761 0.2373912 -0.9631131 -0.1267219 -0.8221302 -0.5327223 0.200771 -0.8556661 -0.4842575 0.1825663 -0.8827713 -0.4181516 0.2141592 0.2959571 -0.9439212 -0.1463633 0.3330129 -0.9327876 -0.1378762 0.1683318 -0.9836268 -0.06436377 0.1577476 -0.9849928 -0.07003515 -0.8776222 -0.4119714 0.2450692 0.2005494 -0.9779305 -0.05858379 0.2003093 -0.978284 -0.05326098 0.2517017 -0.9650591 -0.07285046 0.2471602 -0.9665303 -0.06878376 -0.8106802 -0.5241129 0.2609664 -0.8427777 -0.4586841 0.2816642 0.204752 -0.9784437 -0.02692079 0.3174709 -0.9441666 -0.08810055 0.2665563 -0.9634523 -0.02659612 0.2106705 -0.9774279 -0.01589745 0.19721 -0.9803532 -0.003979742 0.2404351 -0.9705694 -0.01363736 0.1838846 -0.9828063 0.01668381 0.3429307 -0.9376226 -0.05711776 0.0922054 -0.9947984 0.0432946 0.09058785 -0.9951253 0.03898131 0.1539561 -0.9877936 0.02369463 0.1204567 -0.9924245 0.02416402 0.18035 -0.9832047 0.02797019 0.3094391 -0.9505508 -0.02647107 -0.1891795 -0.9702308 0.1512061 -0.2368531 -0.9619491 0.1362151 0.1786108 -0.9835721 0.02615553 0.2357838 -0.9713733 0.0289818 -0.2778573 -0.9476322 0.1574441 0.3177593 -0.9481283 0.009043216 -0.1590906 -0.9717906 0.1741068 0.1505886 -0.9859557 0.07221192 0.1470209 -0.9873154 0.05994379 0.2645667 -0.963454 0.04196387 -0.1582322 -0.9687322 0.1911035 -0.1795135 -0.9633123 0.1995108 -0.2398756 -0.9518727 0.1907828 0.1828202 -0.9798374 0.08059537 0.2646231 -0.9634959 0.04062497 0.1833019 -0.9795704 0.08271861 0.2452475 -0.9636053 0.1063888 0.2062385 -0.9735028 0.09878247 0.2909659 -0.953657 0.07666337 -0.2815367 -0.9329462 0.2243849 -0.1584728 -0.9545278 0.2525134 -0.07880407 -0.9701732 0.229246 -0.2333248 -0.9209564 0.312088 -0.2263252 -0.9334658 0.2782419 -0.08107918 -0.970925 0.2252351 -0.1119738 -0.9567252 0.2685865 -0.1367808 -0.8995248 0.414905 -0.2176726 -0.9151053 0.3394129 -0.1571474 -0.9190518 0.3614534 -0.03889185 -0.9724766 0.2297321 -0.04755735 -0.9713304 0.2329282 -0.005278885 -0.972159 0.2342626 -0.007432997 -0.9552053 0.2958505 -0.07148498 -0.9034407 0.4227112 0.02404648 -0.9726006 0.2312354 0.001065373 -0.970329 0.2417865 0.05069041 -0.9703544 0.2363108 0.1381347 -0.9696506 0.2017338 0.1639049 -0.9712132 0.1728591 0.226352 -0.9610373 0.1586572 0.08962291 -0.9703513 0.2244682 0.1359519 -0.974371 0.179216 0.09163945 -0.9735381 0.2093466 0.05582827 -0.9692387 0.2397072 0.1457339 -0.9604922 0.2370999 0.2461658 -0.9485927 0.198933 0.1519811 -0.969737 0.1910811 0.2391332 -0.9516503 0.1928137 0.05940079 -0.9597877 0.2743706 0.04289495 -0.9518077 0.3036808 0.2107022 -0.9488818 0.2350066 0.1411789 -0.9625182 0.2315757 0.1109673 -0.956587 0.2694955 0.2295035 -0.925733 0.3005772 0.06115269 -0.9048194 0.4213814 0.1421771 -0.9223299 0.3592957 0.2050522 -0.9227594 0.3262956 0.1569687 -0.9263506 0.3423968 0.1259261 -0.8870884 0.444091 0.1157709 -0.8950809 0.4306128 0.248807 -0.8634533 0.438798 -0.9867826 0.1020047 0.1259173 -0.9928272 0.03971946 0.1127682 -0.988407 0.09161734 0.1210703 -0.9926477 -0.007093608 0.1208312 -0.8432918 -0.5357996 0.04216408 -0.8959951 -0.4437758 -0.01599866 -0.8916282 -0.4527408 0.005014955 -0.9862449 -0.008339345 0.1650803 -0.9842428 0.05346828 0.1685446 -0.9464284 -0.299368 0.1210463 -0.9620543 -0.2425182 0.125047 -0.9681128 -0.211208 0.1347177 -0.7508223 -0.6568191 0.0696758 -0.7458643 -0.6618558 0.07505697 -0.9653652 -0.1971014 0.1709417 -0.9181901 -0.360019 0.1652675 0.067496 -0.9271945 0.368449 0.05584818 -0.912738 0.4047103 -0.9912124 -0.05408519 -0.1207177 -0.9973318 -0.06741237 -0.02801835 -0.9959578 -0.07570695 0.04834014 -0.9951847 -0.08298432 0.05216354 -0.8563126 0.295347 0.4236732 -0.2482589 -0.9641427 0.09378957 -0.2355496 -0.9631294 0.1299928 0.2445684 -0.9631353 0.1120573 0.255563 -0.9570997 0.1365564 0.2556608 -0.9570596 0.1366553 0.2253394 -0.9610111 0.1602495 0.2639925 -0.8550097 0.4463929 -0.8805266 0.2454194 -0.405515 -0.8791925 0.2409116 -0.4110744 -0.9354906 0.2460908 -0.2535683 -0.9215265 0.2177941 -0.3214882 -0.90712 0.09253334 -0.4105738 -0.9064238 0.09061098 -0.4125356 -0.9437867 0.2339893 -0.2334861 -0.9012899 -0.0395959 -0.4314032 -0.9631198 0.1087386 -0.2461225 -0.968154 0.04499626 -0.246279 -0.9369103 0.1043242 -0.3336397 -0.9376013 0.1073737 -0.3307185 -0.9638002 0.1131733 -0.2414147 -0.9577099 0.1129069 -0.2646582 -0.9696981 0.1243108 -0.2103155 -0.9726318 0.1381467 -0.1868234 -0.907844 -0.06373161 -0.4144366 -0.9540196 0.2632507 -0.143338 -0.9552844 0.2376287 -0.1759666 -0.9662501 0.01060318 -0.2573878 -0.973016 0.1620092 -0.1642957 -0.9786563 0.1482214 -0.1423459 -0.9344663 -0.07623612 -0.3477944 -0.9332091 -0.07754796 -0.3508661 -0.9550263 0.2905925 -0.05899959 -0.9599675 0.2535098 -0.119144 -0.9735573 0.2054746 -0.09983259 -0.9790317 -0.03251475 -0.2010966 -0.9775338 -0.0894283 -0.190867 -0.9777001 -0.02102112 -0.2089516 -0.9645869 -0.01363104 -0.2634128 -0.969413 -0.01151406 -0.2451652 -0.8702532 -0.2419655 -0.4290829 -0.943656 -0.195182 -0.2672402 -0.9285393 -0.2666689 -0.2582683 -0.9426851 -0.2044317 -0.2637283 -0.9755044 0.2038958 -0.08256918 -0.9726985 -0.09849792 -0.2101331 -0.9621874 -0.1047865 -0.2514265 -0.9622674 -0.104561 -0.2512143 -0.9563311 -0.1450418 -0.2537593 -0.9531573 0.2960033 -0.06223618 -0.9734557 0.2196902 -0.06418925 -0.9847849 -0.09382104 -0.1462752 -0.9184833 -0.2960451 -0.2621946 -0.7714423 -0.4479645 -0.4518902 -0.7821584 -0.4364223 -0.4447067 -0.7256528 -0.5423111 -0.4234698 -0.9224497 -0.3240523 -0.2099446 -0.9188272 -0.3088402 -0.2457118 -0.916337 -0.3077137 -0.256201 -0.6741377 -0.58418 -0.4519649 -0.8802135 -0.3981986 -0.2581901 -0.8761247 -0.4023984 -0.2654832 -0.9927158 -0.1088383 -0.05166858 -0.7381829 -0.5842124 -0.337316 -0.7133162 -0.5952107 -0.3700059 -0.9338412 -0.318952 -0.1618959 -0.9154674 -0.3597044 -0.1803675 -0.8845012 -0.4293806 -0.1824555 -0.6261075 -0.6729552 -0.3938539 -0.7383267 -0.6249422 -0.253616 -0.5242457 -0.7525464 -0.3985478 -0.5696945 -0.7293565 -0.3787972 -0.8256852 -0.5331524 -0.1843709 -0.8062021 -0.5721448 -0.1506279 -0.8841643 -0.430306 -0.1819068 -0.7166173 -0.6556405 -0.2378977 -0.9407683 -0.3240587 -0.09970521 -0.4694837 -0.8171123 -0.3345333 -0.5992395 -0.7803905 -0.1786133 -0.9385314 0.3319678 0.09463804 -0.3929801 -0.8462926 -0.3596605 -0.9223809 -0.3776172 -0.08135557 -0.5077316 -0.8307504 -0.2281719 -0.3825663 -0.881748 -0.2759776 -0.9803697 0.1557029 0.1209623 -0.4785098 -0.8539534 -0.2044312 -0.8967674 -0.4324932 -0.0935834 -0.9062746 -0.4143773 -0.08341407 -0.3531637 -0.9039718 -0.2410609 -0.3539627 -0.9142512 -0.1971173 -0.4023882 -0.8959583 -0.1879963 -0.8290075 -0.553869 -0.07730227 -0.744534 -0.665809 -0.04865819 -0.808829 -0.5813691 -0.08834999 -0.9246933 0.3467504 0.1571834 -0.3065434 -0.9386916 -0.1577641 -0.1561292 -0.976036 -0.1515833 -0.9940339 -0.08225953 0.07162463 -0.9930363 -0.06061261 0.1010202 -0.9862685 -0.1349151 0.09524953 -0.9826822 -0.1490567 0.1100811 -0.9725044 -0.1657549 0.163587 -0.9895456 -0.04635614 0.1365679 -0.3199649 -0.9444327 -0.07529431 -0.2104867 -0.9755087 -0.06386142 -0.08208024 -0.9886186 -0.1260798 -0.09993231 -0.9844594 -0.144407 -0.2090484 -0.9774187 -0.0308476 -0.3078658 -0.9489834 -0.0681855 -0.1916937 -0.98142 0.008269667 -0.2216323 -0.9737569 -0.05173641 -0.9469673 -0.2923431 0.1333732 -0.9413138 -0.3203129 0.1064339 -0.9076696 0.3059803 0.2872493 -0.9076043 0.3060707 0.2873591 -0.1337034 -0.9898526 -0.04811775 -0.1463052 -0.9877766 -0.053779 -0.1231312 -0.9900952 -0.06745529 -0.108057 -0.9928458 -0.05080294 -0.0751245 -0.9924195 -0.09726285 -0.0750997 -0.9945748 -0.07197993 -0.06830757 -0.9907429 -0.117315 -0.9149462 -0.3968214 0.07352864 -0.9322687 0.2315835 0.2779282 -0.858987 0.2982041 0.416192 -0.8797131 0.2802552 0.3841378 -0.8578343 0.2955129 0.4204671 -0.2817921 -0.9593272 0.01687747 -0.08821082 -0.9951742 -0.04298013 -0.08393949 -0.9947719 -0.05816435 -0.07194054 -0.9959564 -0.05381059 -0.08769005 -0.995201 -0.04342246 -0.9290392 0.1485578 0.3388462 -0.1935742 -0.9810847 0.001400947 -0.09548729 -0.995348 0.01282918 -0.1169016 -0.9919118 0.04944729 -0.09548372 -0.9953491 0.01277869 -0.144948 -0.989436 0.002549886 -0.9504289 0.04871386 0.3071029 -0.9470149 0.05787807 0.315932 -0.9429217 -0.05067193 0.3291369 -0.8896716 0.1346674 0.4362903 -0.901309 0.165107 0.4004772 -0.8877525 0.1227095 0.4436644 -0.0800836 -0.9967806 -0.003879487 -0.08375769 -0.9959994 -0.03114378 -0.08172374 -0.996648 0.003766953 -0.05649137 -0.9941181 0.0924012 -0.9432668 -0.04992699 0.3282607 -0.2761229 -0.9573339 0.08525264 -0.2420634 -0.9649887 0.1010062 -0.8879022 -0.03130692 0.4589658 -0.8988225 0.04892748 0.4355736 0.1468508 -0.9871028 -0.06374073 0.08980292 -0.9950036 -0.04362803 -0.01812338 -0.9997059 0.0161159 -0.05720955 -0.9982709 0.01350271 -0.9239857 -0.127882 0.3604118 -0.8897384 -0.04077237 0.4546463 0.1121501 -0.9936251 0.01147067 0.1250151 -0.9909886 0.04809325 0.09653282 -0.9953257 -0.002853929 -0.8351361 -0.4386373 0.3318812 -0.8585584 -0.3291863 0.3930826 -0.918954 -0.1983731 0.3408399 -0.8837269 -0.1239153 0.4513001 -0.8562499 -0.1958918 0.4779776 -0.8660923 -0.35983 0.3469963 -0.8731158 -0.2494113 0.418883 -0.863964 -0.2776666 0.4200806 -0.8561099 -0.1872043 0.4816955 -0.8320345 -0.2903104 0.4726928 -0.7990103 -0.3448976 0.4925732 -0.7872008 -0.396263 0.4725366 -0.726925 -0.4806674 0.4904478 -0.717963 -0.5104702 0.473233 -0.6555079 -0.6038973 0.4534506 -0.5595728 -0.6851112 0.4663701 -0.5564543 -0.6864736 0.4680949 -0.1091344 -0.9733658 0.2016155 -0.4525892 -0.7820174 0.4284997 -0.3621435 -0.8171173 0.4485216 -0.3402761 -0.8355147 0.431425 -0.2492068 -0.8771856 0.4104164 -0.1880643 -0.8806624 0.4348169 -0.252579 -0.8819047 0.3980552 -0.08433002 -0.8997864 0.428104 -0.06978631 -0.9499504 0.3045064 -0.08405381 -0.939525 0.3320057 0.004365384 -0.8976897 0.4406065 -0.006934285 -0.9452795 0.3261878 -0.004252851 -0.947233 0.3205178 -0.0101915 -0.88265 0.4699203 0.002849161 -0.9121333 0.4098839 -0.9531827 0.01050126 -0.3022128 -0.8640236 -0.1749996 -0.4720576 -0.8089595 -0.3810386 -0.4476541 -0.8168045 -0.3103437 -0.4863305 -0.9146698 -0.1973944 -0.3527247 -0.8843744 -0.2491984 -0.3946923 -0.8776863 -0.3183453 -0.3582221 -0.8615502 -0.3898408 -0.3252009 -0.8765122 -0.3130426 -0.3656922 -0.8199439 -0.4516003 -0.3517803 -0.801543 -0.5033807 -0.3227024 -0.9526966 0.3030702 0.02275729 -0.9478038 0.3184367 0.01631551 -0.9601283 0.2791043 0.01595455 -0.9908974 0.1344407 -0.006926059 -0.9787134 0.2036447 -0.02547568 -0.8095669 -0.5083507 -0.2935664 -0.785701 -0.5680899 -0.2448423 -0.6506841 -0.6712838 -0.3549484 -0.5932036 -0.763139 -0.2563759 -0.972694 0.2245525 0.05867356 -0.9465495 0.314688 0.07082158 -0.9728304 0.2279283 0.04061704 -0.97859 0.1966263 0.0608263 -0.5208119 -0.8219788 -0.2304474 -0.6555296 -0.7156444 -0.2411102 -0.5971292 -0.7464826 -0.2935994 -0.8185203 -0.5379763 -0.2015091 -0.7795364 -0.6140725 -0.1234427 -0.4584648 -0.8363901 -0.300436 -0.4486396 -0.8464468 -0.286793 -0.8335953 -0.5522315 -0.01262056 -0.9748258 0.1978795 0.1027549 -0.9791283 0.1892405 0.07413452 -0.336091 -0.8903076 -0.3072386 -0.9450923 -0.3260479 -0.02221214 -0.1497994 -0.9635776 -0.2215362 -0.2342019 -0.9319828 -0.2766904 -0.2743185 -0.9276548 -0.2533893 -0.2910828 -0.9212512 -0.258006 -0.2209525 -0.9555429 -0.1952376 -0.9426149 0.3143808 0.1124363 -0.958268 0.2605953 0.1175274 -0.937192 -0.3486909 -0.009272456 -0.9701883 0.1981401 0.1395531 -0.9696433 0.1982489 0.1431407 -0.9801479 0.1552919 0.1232669 -0.2785506 -0.947611 -0.1563426 -0.1772387 -0.9747185 -0.136053 -0.221846 -0.9520449 -0.210701 -0.1896387 -0.976434 -0.1030235 -0.1742883 -0.973038 -0.1510659 -0.7709965 -0.6364631 0.02189356 -0.8377007 -0.5448448 -0.03744035 -0.8852569 -0.4648368 -0.01571726 -0.1126363 -0.9801046 -0.1634258 -0.1261961 -0.9794195 -0.157518 -0.1510261 -0.9584231 -0.2421079 -0.1024888 -0.9757391 -0.1934665 -0.08882319 -0.9492953 -0.3015773 -0.9054307 -0.4229938 0.03565555 -0.9418251 -0.3314257 0.05588001 -0.9357606 -0.349701 0.04540264 -0.9938524 -0.05066949 0.09843736 -0.752989 -0.6578685 0.01472216 -0.7828041 -0.6222039 -0.008951902 -0.9471645 0.264447 0.1815143 -0.9311942 0.318807 0.1767472 -0.02742892 -0.9636037 -0.2659242 0.03516727 -0.9573695 -0.2867177 -0.1755758 -0.9819594 -0.07020729 -0.2163621 -0.9747338 -0.05551189 -0.163193 -0.9834671 -0.07848989 -0.2232292 -0.9675677 -0.1182444 -0.1554453 -0.9857832 -0.06378233 -0.1602602 -0.9835841 -0.08293974 -0.1800459 -0.9764532 -0.1188392 -0.9188536 -0.3802937 0.1052852 -0.9500467 0.2121051 0.2289599 -0.07033091 -0.9778274 -0.197249 -0.9819249 -0.05321723 0.1816356 0.08684074 -0.9742035 -0.2082936 0.04739636 -0.948325 -0.3137407 -0.9795181 -0.1656947 0.11441 -0.9686292 -0.1741142 0.1773182 -0.985072 -0.1101737 0.132269 -0.9804854 -0.1059481 0.1656004 0.1838396 -0.9156323 -0.3575202 -0.8711721 -0.4848913 0.07706826 -0.8431813 -0.535876 0.04338735 0.06669127 -0.9796222 -0.1894538 -0.02942925 -0.9863235 -0.162173 -0.9652534 0.06441009 0.2532532 -0.9709572 0.1020041 0.2164192 -0.9745083 0.1015327 0.2000622 -0.04078346 -0.9916509 -0.1223329 0.05353659 -0.9887328 -0.1397904 0.0608592 -0.9847519 -0.1629723 0.03696012 -0.9930646 -0.1116097 -0.8711602 -0.4852401 0.07498115 -0.978816 -0.05119252 0.1982392 -0.7800624 -0.6139374 0.1207629 -0.8516727 -0.5137615 0.1034546 0.1927663 -0.9188932 -0.3442041 0.1709799 -0.9477443 -0.2693452 0.1233331 -0.9691901 -0.2132129 0.005346834 -0.9967711 -0.08011823 -0.004753649 -0.9969145 -0.07835096 -0.02341753 -0.9981749 -0.05566495 0.02333277 -0.9968963 -0.07518976 0.2531296 -0.9016667 -0.3506034 -0.2671672 -0.96338 0.02282261 0.311452 -0.8461843 -0.4324 -0.9634271 -0.0877245 0.2532048 -0.7751981 -0.6186018 0.1280618 -0.2043029 -0.9787237 0.01898777 0.2861422 -0.917682 -0.2756494 0.2861079 -0.9059346 -0.3121297 0.05549311 -0.996562 -0.06152117 0.08470183 -0.9955815 -0.04053544 -0.8824881 -0.4422857 0.1599942 -0.8821062 -0.4485301 0.1439077 0.3476275 -0.8673128 -0.3562636 0.1517639 -0.9720813 -0.1789578 0.1566321 -0.9742311 -0.162297 0.14734 -0.9627428 -0.2267538 0.4389595 -0.804793 -0.3995285 0.3552983 -0.8473831 -0.3945949 0.4339181 -0.8054223 -0.4037448 -0.180482 -0.98255 0.04496365 -0.1805853 -0.9825452 0.04465299 -0.9545095 -0.1706735 0.2445039 -0.9314417 -0.2277671 0.2837932 -0.00779128 -0.9997544 -0.02074837 0.39594 -0.8630948 -0.3135268 0.3988864 -0.8705283 -0.288219 0.08293247 -0.9959782 -0.03390824 0.07317197 -0.9972146 -0.01445406 0.07761853 -0.9967461 -0.02174323 0.1705392 -0.9777869 -0.1218573 1 -1.89873e-4 1.70092e-4 1 2.95807e-5 3.115e-4 1 -1.01551e-5 3.27726e-4 1 -4.61691e-5 3.20803e-4 1 -9.89304e-6 2.26886e-4 1 4.14731e-6 -7.60496e-6 0.9999999 4.4773e-4 5.05521e-4 0.9999976 -0.002095878 5.78556e-4 0.9999998 2.52837e-4 5.26086e-4 1 4.15638e-7 0 1 2.5834e-6 6.20114e-7 1 7.01009e-6 6.54038e-7 1 -1.59353e-6 5.86175e-7 1 -1.85592e-6 2.07487e-6 1 -1.80845e-6 -2.94892e-6 1 -2.92111e-4 -1.07425e-4 0.9999997 -5.40702e-4 -6.73214e-4 1 -3.36424e-4 -7.70852e-5 0.9999997 -1.96796e-4 8.00179e-4 1 -1.79327e-7 0 1 -1.00034e-6 -3.67015e-6 1 -5.44124e-5 7.53239e-5 1 4.54618e-6 9.24715e-7 1 1.00407e-5 -2.20701e-5 1 -4.95846e-5 1.72457e-5 1 -4.86615e-7 7.16226e-6 1 3.02531e-5 -2.54321e-6 1 7.8686e-7 0 1 3.71668e-7 0 1 4.92882e-7 -7.01481e-6 1 -3.73604e-6 -7.42119e-6 1 2.52109e-5 3.49649e-6 1 8.69832e-7 -1.44423e-5 1 -1.84051e-5 -1.10656e-5 1 0 3.49178e-6 1 -9.61646e-5 1.30999e-5 1 8.67577e-5 -1.9808e-4 1 1.25677e-5 3.77926e-5 0.9999998 6.26902e-4 1.07525e-4 1 6.93785e-5 -1.85592e-4 1 6.28727e-5 1.05126e-4 1 -3.3617e-4 -3.18029e-4 1 1.67499e-5 -8.57473e-6 1 2.24836e-5 2.31315e-5 1 0 0 1 2.00043e-6 0 -0.9278705 -0.02571725 0.3720147 -0.9959688 -0.06089085 0.06586849 -0.9579949 -0.09742385 0.2697305 -0.9585692 -0.2816002 0.04297137 -0.9464961 -0.3190842 -0.04827493 -0.9973372 -0.03346389 -0.06479811 -0.9538686 -0.2739876 -0.1227421 -0.9716078 -0.1855734 -0.1467688 -0.9505972 0.118629 -0.2868663 -0.9604337 0.2241757 -0.1652644 -0.8071393 -0.1372473 0.5741858 -0.6693598 -0.02257835 0.7425953 -0.7253537 -0.3548085 0.5898924 -0.56748 -0.08495867 0.8189925 -0.864003 -0.3791918 0.3312286 -0.7224125 -0.4189543 0.5500886 -0.4881337 -0.2173187 0.84528 -0.8687826 -0.4343332 0.2378475 -0.1781994 -0.02990996 0.9835398 -0.3570944 -0.2791225 0.891389 -0.623457 -0.5319812 0.5729725 -0.3623593 -0.5468435 0.7547569 -0.3419918 -0.2996007 0.8906633 -0.5632974 -0.6679404 0.4863659 -0.7883588 -0.5843871 0.1923076 -0.2643647 -0.627245 0.7325812 -0.4253498 -0.7522358 0.5032085 -0.2579225 -0.7103687 0.6548682 -0.6699495 -0.6957113 0.2591397 -0.8053359 -0.5927973 -0.005052924 -0.4971557 -0.8525593 0.1611795 -0.7042357 -0.7003853 -0.1162437 -0.482891 -0.8678409 0.1169133 -0.3596681 -0.8460785 0.3934337 -0.8006336 -0.4975802 -0.3337662 -0.6643139 -0.7037676 -0.2517901 -0.6777392 -0.6755104 -0.2904401 -0.7963253 -0.4107249 -0.4440398 -0.3380385 -0.9408609 0.02259808 -0.8766638 -0.2176933 -0.4290342 -0.3556783 -0.8966156 -0.2637677 -0.2776707 -0.946904 -0.1620866 -0.8530709 -0.1477142 -0.5004504 -0.4931468 -0.6632959 -0.5628897 -0.2654874 -0.8460494 -0.4622951 -0.5760555 -0.4841784 -0.6585829 -0.4896898 -0.5818831 -0.6493197 -0.9520742 0.1007038 -0.2888142 -0.8814952 2.30683e-4 -0.472193 -0.6856343 -0.17827 -0.70578 -0.2875672 -0.5750018 -0.7659492 -0.573544 -0.3022987 -0.761356 -0.2099795 -0.3994563 -0.8923807 -0.6370588 -0.00973463 -0.7707539 -0.3530672 -0.2665592 -0.896822 -0.6764394 0.1971067 -0.7096329 -0.2694619 -0.06747275 -0.9606445 -0.3126522 -0.1073108 -0.9437866 -0.6758782 0.1985785 -0.7097572 -0.8153003 0.3337643 -0.4731668 -0.7143867 0.3132581 -0.6257165 -0.9123259 0.3429719 -0.2236781 -0.4058768 0.289825 -0.8667559 -0.8319134 0.4104644 -0.3734157 -0.9838383 0.1722595 -0.04887735 -0.3156391 0.2462298 -0.9163748 -0.3743401 0.5330742 -0.75875 -0.5520852 0.6932674 -0.4632301 -0.540823 0.5267167 -0.655805 -0.8583076 0.4969351 -0.1279208 -0.6714623 0.64739 -0.3605893 -0.2921792 0.5877211 -0.7544635 -0.433489 0.7646589 -0.4768479 -0.2553971 0.6567475 -0.7095457 -0.7215369 0.6776424 -0.1420754 -0.9498564 0.3096477 0.04348874 -0.3279899 0.8521983 -0.4076527 -0.6581702 0.7513622 -0.04761165 -0.3121647 0.9285599 -0.2008224 -0.3609511 0.9246448 -0.1214343 -0.9279535 0.003815472 0.3726765 -0.1379333 0.9383595 0.3169479 -0.2253709 0.2760168 0.9343569 -0.6637175 0.7449443 0.06735903 -0.9083912 0.353329 0.2235714 -0.9828223 0.09432661 0.1586279 -0.2618204 0.9643009 0.03967249 -0.2954521 0.9426276 0.1554395 -0.6664927 0.4441059 0.5987967 -0.6471967 0.4788853 0.5931319 -0.8722931 0.1264668 0.4723463 -0.686564 0.110143 0.7186783 -0.3945446 0.1313357 0.9094424 -0.3521165 0.1322226 0.9265697 -0.90591 0.3683657 0.2088875 -0.7675119 0.597766 0.2315201 -0.4605712 0.8592533 0.2226167 -0.6502973 0.648306 0.395996 -0.4180884 0.8149159 0.4013906 -0.8357226 0.3241064 0.4433089 -0.4433256 0.7916994 0.4203267 -0.260636 0.8607043 0.4373297 -0.3667194 0.6442555 0.6711571 -0.5865824 0.2610806 0.7666538 -0.576261 0.260655 0.7745853 -0.08529597 0.7699255 0.6324076 -0.2753875 0.39952 0.874383 -0.2750612 0.6427958 0.714951 -0.1991284 0.5237995 0.8282404 -0.0168336 -0.02184766 0.9996196 0.007157146 -0.06642991 0.9977655 -0.03127568 -0.3550372 0.9343289 0.03421705 -0.5139976 0.8571089 -0.01733088 -0.6073392 0.7942536 -0.02860063 -0.7939318 0.607334 -0.02534407 -0.9153237 0.4019206 0.01484143 -0.8697436 0.4932806 -0.01413512 -0.986849 0.1610258 0.02156382 -0.9955639 0.0915839 -0.02789318 -0.9827591 -0.1827744 0.027511 -0.9502356 -0.3103152 -0.04478532 -0.8427906 -0.5363754 -0.004372656 -0.7102652 -0.7039207 0.004971802 -0.7275483 -0.6860385 -0.01183116 -0.3991255 -0.91682 0.009620606 -0.3656943 -0.9306854 -0.02694207 -0.06494361 -0.9975252 0.01186835 0.01603066 -0.9998011 -0.01835471 0.3140428 -0.9492315 -0.002539873 0.3496655 -0.9368713 -0.02866774 0.5140051 -0.857308 0.03024893 0.7437776 -0.6677424 -0.01494854 0.6899273 -0.7237243 -0.01767086 0.8723225 -0.4886114 0.01963329 0.909229 -0.4158332 -0.03103911 0.9774996 -0.2086416 0.009156346 0.9998157 0.01687687 0.01418006 0.9995878 0.02496278 -0.02868378 0.9495238 0.3123807 0.02499312 0.9065533 0.4213508 -0.03142857 0.7736148 0.6328763 0.03348481 0.6756094 0.736499 -0.03286087 0.5189044 0.8542006 0.01878881 0.2954325 0.9551789 -0.00385642 0.2500568 0.9682235 -0.9999885 0.003443479 0.003350913 -0.999983 0.002964556 0.005033016 0.6868064 -0.7231227 0.07342046 0.3448235 -0.9380789 0.03324067 0.5591757 -0.8254073 0.07762414 0.6444659 -0.7572721 0.1058437 0.4798588 -0.8727787 0.08940273 0.6575401 -0.7397966 0.1426256 0.5660091 -0.8151146 -0.1233781 0.5383133 -0.8415135 -0.04553955 -0.006948649 -0.9999681 0.003956854 -0.02543526 -0.9996314 0.009509563 0.07933914 -0.9968477 -2.25253e-4 0.8678362 -0.4952282 0.04011589 0.02708041 -0.9996256 0.003908038 0.4974198 -0.8628281 -0.09000611 0.8426169 -0.5271906 0.1098492 0.8779265 -0.4642891 0.1169645 0.1819717 -0.9707886 0.1563841 0.6703366 -0.6896744 -0.273858 0.6394432 -0.7287868 -0.2449126 0.07510161 -0.9964592 -0.03780174 0.6647775 -0.7062337 -0.2435261 0.06832993 -0.9975115 -0.0173726 0.4358009 -0.8899586 -0.1343555 0.5794202 -0.800769 -0.1517935 0.1507653 -0.9879415 -0.03523474 0.7741138 -0.607672 -0.1774335 0.6181213 -0.7799967 -0.09762752 0.8975933 -0.4103511 -0.1610543 0.6979827 -0.709484 -0.09722471 0.1093954 -0.9938928 -0.01448827 0.7556945 -0.6493445 -0.08530944 0.9066291 -0.4147555 -0.07747054 0.03381258 -0.9994186 0.004389286 0.1157242 -0.99326 -0.006518065 0.8706692 -0.4866436 -0.07150661 0.8105691 -0.5846992 -0.03323662 0.2159086 -0.976413 0.001025199 0.6093065 -0.7929129 -0.005888581 0.09893918 -0.9950681 0.007113933 0.1578589 -0.9870747 0.02764362 0.5643337 -0.8219291 0.07720148 0.6688535 -0.7280042 0.1504826 0.7476353 -0.6395929 0.1787801 0.7906536 -0.5510808 0.2667902 0.1792811 -0.9818926 0.06119835 -0.02762579 -0.9991546 -0.03044939 0.06062728 -0.9981017 0.0108357 0.120913 -0.9908242 -0.06039404 0.5412725 -0.809426 -0.2277141 0.09451425 -0.9947692 -0.03874778 0.3901906 -0.9073398 -0.1564795 0.2490307 -0.964353 -0.08948153 0.5704277 -0.7964926 -0.2005285 0.7216154 -0.6568806 -0.2185845 0.08901387 -0.9959609 -0.01176333 0.5762709 -0.8041306 -0.1458967 0.1627168 -0.9856362 -0.04521727 0.4374377 -0.8974308 -0.05715131 0.5916469 -0.7981995 -0.1132763 0.3101061 -0.9467796 -0.08627128 0.7502002 -0.6471608 -0.1355822 0.4986037 -0.8621541 -0.08991461 0.2137878 -0.9762951 -0.03380262 0.7521572 -0.6446546 -0.1366752 0.7845128 -0.6065912 -0.1287896 0.4329354 -0.8985927 -0.07140147 0.3815258 -0.9226558 -0.05607497 0.06002962 -0.9981905 -0.003469884 0.07280838 -0.997338 -0.004000067 0.77437 -0.624938 -0.09901505 0.3823333 -0.9227377 -0.04874736 0.07842803 -0.9968569 -0.01119834 0.2562626 -0.9660813 -0.0318855 0.4556599 -0.8887982 -0.04911178 0.1201249 -0.9927588 1.25088e-4 0.3867586 -0.9218333 -0.02532118 0.1375416 -0.9904917 0.00291866 0.1430529 -0.9897151 1.83337e-4 0.7940805 -0.6068193 -0.03473681 0.3883768 -0.9214994 0.001588284 0.09996443 -0.9949689 0.006633937 0.8260609 -0.5635808 5.05064e-4 0.6418149 -0.7667944 0.01000005 0.1905383 -0.9816684 0.004745483 0.6247975 -0.7807791 0.003502726 0.2901834 -0.9566441 0.02501553 0.6313155 -0.7748568 0.03221553 0.2719851 -0.9622156 0.01286154 0.6421485 -0.7657394 0.035896 0.5961919 -0.8023672 0.0276075 0.8373444 -0.5451212 0.0411995 0.7776733 -0.6261031 0.05673873 0.5648939 -0.8236634 0.04973572 0.1329413 -0.9908944 0.0213344 0.311184 -0.9489783 0.05103725 0.6410162 -0.7596884 0.1094153 0.3200675 -0.9463106 0.04531258 0.1646025 -0.9857882 0.0335806 0.4989748 -0.8608661 0.09966808 0.1400153 -0.9897968 0.0264194 0.2826568 -0.9565119 0.07204395 0.2419446 -0.9690811 0.04842275 0.5153558 -0.8464671 0.1337983 0.7242546 -0.6588985 0.2032443 0.6838387 -0.6985821 0.2105892 0.4878396 -0.8587757 0.1565786 0.5507135 -0.8083611 0.2080079 0.1434444 -0.9888058 0.04107397 0.7382782 -0.6028199 0.3025783 0.5511145 -0.8106204 0.1979076 0.41807 -0.8997311 0.1253058 0.6705988 -0.6775541 0.3020227 0.05529814 -0.9982718 0.01988625 0.6523666 -0.6923473 0.3083394 0.3309222 -0.9295482 0.1625757 0.6255152 -0.7056335 0.3328847 0.330923 -0.9295467 0.1625818 0.2567431 -0.9568563 0.1360486 0.2891252 -0.9464637 -0.1435735 0.01907032 -0.9995832 -0.02167314 0.4348475 -0.8677187 -0.2407734 0.2321771 -0.9683572 -0.09153217 0.6029399 -0.7751687 -0.1886192 0.4458225 -0.8859321 -0.127932 0.7089403 -0.6745021 -0.2060356 0.1178477 -0.9924212 -0.03481644 0.5485574 -0.8231456 -0.146684 0.169596 -0.9850304 -0.03086245 0.1095575 -0.9938923 -0.01324421 0.4001397 -0.9148299 -0.05453997 0.8781186 -0.4615594 -0.1259794 0.2586413 -0.9657314 -0.02162939 0.5542815 -0.8299315 -0.06313359 0.4437505 -0.8952063 -0.04112428 0.5412362 -0.8398777 -0.04085397 0.1336319 -0.9909745 -0.01058596 0.2738234 -0.9617089 -0.01169729 0.7144954 -0.6986427 -0.03734719 0.736127 -0.6750419 -0.04935151 0.4708136 -0.8820653 -0.01718616 0.4731382 -0.8807945 -0.01847428 0.4905011 -0.871159 -0.0221548 0.2206634 -0.9753289 -0.006437301 0.6548014 -0.7555368 -0.01998043 0.6656511 -0.7461808 -0.0110864 0.1766247 -0.9842574 0.00641328 0.5234035 -0.8520578 0.006806015 0.6118505 -0.7907431 0.01909404 0.2960479 -0.9549128 0.02230203 0.2768406 -0.9608557 0.01075428 0.211378 -0.9772651 0.01650452 0.5686358 -0.8216449 0.03941142 0.8138895 -0.5768804 0.06923097 0.3355593 -0.9414007 0.03412789 0.6916493 -0.7193343 0.06464862 0.474278 -0.8774737 0.07141768 0.5235887 -0.8505496 0.04919654 0.1469793 -0.9890227 0.01520687 0.4718552 -0.8770496 0.09020453 0.8062452 -0.5714135 0.1531517 0.1400513 -0.9897897 0.0265001 0.512873 -0.8482022 0.1323425 0.709742 -0.6770135 0.1947283 0.2170951 -0.9747666 0.05195987 0.08471095 -0.9961781 0.0212953 0.3819454 -0.9164649 0.1192059 0.3712303 -0.9225192 0.1055768 0.1273677 -0.9909943 0.04132384 0.483845 -0.8592311 0.1661809 0.1831208 -0.9818037 0.05028218 0.3905653 -0.9047273 0.1700802 0.6695205 -0.6790662 0.3010172 0.4808809 -0.853342 0.2013977 0.4110042 -0.8934711 0.1810669 0.2340539 -0.9678275 0.09235155 0.4118896 -0.8927763 0.182476 0.0772354 -0.9968672 0.01704365 0.6857857 -0.6375808 0.3509827 0.6047668 -0.7417426 -0.289957 0.223246 -0.9711595 -0.08372879 0.2131699 -0.976276 -0.03799527 0.4477154 -0.8914241 -0.07010042 0.7067916 -0.6998202 -0.1034287 0.5563102 -0.8284812 -0.06432574 0.3752276 -0.9255425 -0.05074995 0.7629697 -0.6416404 -0.07858037 0.5442907 -0.8377617 -0.04362392 0.534978 -0.8437014 -0.04434686 0.3363585 -0.9417141 -0.006136655 0.534231 -0.8442067 -0.04373061 0.3953472 -0.9185272 -0.002920746 0.1800622 -0.9835975 0.01065945 0.5235015 -0.8520113 0.004799842 0.239956 -0.9704666 0.02481442 0.5895555 -0.8065013 0.04449903 0.2672106 -0.9634628 0.01838809 -0.07821917 -0.9968829 -0.01030778 0.1556554 -0.9641808 -0.2147714 0.02070051 -0.9045925 -0.4257746 0.08014124 -0.756569 -0.6489845 0.5144008 -0.8037337 -0.2990048 0.5846157 -0.7047387 -0.4019553 0.08946877 -0.9800509 -0.1774701 0.4883567 -0.7303541 -0.4775885 0.4906538 -0.7261147 -0.4816808 -0.02055811 -0.9846233 -0.1734776 -0.02796179 -0.9853482 -0.1682472 0.45629 -0.6742032 -0.5807319 0.2916954 -0.7722563 -0.5643882 0.3358416 -0.726663 -0.599309 0.371459 -0.6019999 -0.7068341 -0.1945608 -0.9124107 -0.3600732 -0.1875337 -0.8249369 -0.5332075 -0.2781008 -0.7325825 -0.6212752 -0.03183847 -0.458566 -0.8880898 0.3853324 -0.8931767 -0.2318502 -0.07811939 -0.9618164 -0.2623102 -0.1595737 -0.973589 -0.1632809 0.2293468 -0.583336 -0.7791786 0.1088295 -0.7088233 -0.6969403 -0.1461139 -0.9118214 -0.383709 0.07854497 -0.5337439 -0.8419906 0.01961266 -0.569359 -0.8218551 -0.2880349 -0.9430881 -0.1661955 -0.2633842 -0.9560968 -0.1284826 -0.2644854 -0.9558663 -0.1279344 -0.2707149 -0.9569363 -0.1048168 -0.2658199 -0.9600478 -0.08745342 -0.2525415 -0.9649112 -0.07189697 -0.2602109 -0.9635112 -0.0627411 -0.2605498 -0.9639691 -0.05364209 -0.2496179 -0.9674749 -0.04102778 -0.2674964 -0.9632192 -0.02558112 -0.2643795 -0.9638729 -0.03244435 -0.2486479 -0.9685709 -0.006690859 -0.2618572 -0.9649431 -0.01776766 -0.2773815 -0.9607444 -0.00545746 -0.2808611 -0.9597363 0.004838824 -0.2739611 -0.9616444 0.01361918 -0.2870342 -0.9578942 0.007086813 -0.3029608 -0.9526697 0.02520561 -0.3027874 -0.9524192 0.03489255 -0.3262001 -0.9441406 0.04681926 -0.3081864 -0.9507953 0.03177386 -0.3260897 -0.9438431 0.05315804 -0.3225908 -0.9446842 0.05922037 -0.3194398 -0.9458858 0.05708312 -0.3368672 -0.9375659 0.08654862 -0.3369503 -0.9372603 0.08948552 -0.3356118 -0.9375224 0.09174227 -0.3263079 -0.9373193 0.1222943 -0.3174762 -0.942601 0.1034996 -0.3263345 -0.9370741 0.1240884 -0.319676 -0.936255 0.1457181 -0.3185141 -0.9365801 0.1461733 -0.3142667 -0.9372612 0.150924 -0.3203691 -0.9359634 0.1460696 -0.3204166 -0.9359454 0.1460806 -0.002308607 -0.002910196 0.9999932 -9.73521e-5 -1.43329e-5 1 2.36947e-5 -9.62186e-6 1 4.82836e-5 6.36029e-5 1 -4.39977e-5 0.002284109 0.9999974 -0.001912355 5.73993e-4 0.9999981 0.00123316 -6.9982e-4 0.999999 -4.35578e-4 -0.001013219 0.9999995 8.80079e-5 6.83724e-5 1 -3.73883e-5 -2.14949e-4 1 8.58375e-5 4.77922e-5 1 5.54406e-5 9.02947e-5 1 -4.41713e-5 -2.1433e-4 1 1.0172e-4 -1.70034e-5 1 1.00259e-5 9.57787e-6 1 2.45273e-6 1.56046e-5 1 -1.58592e-4 1.0111e-4 1 -6.53959e-6 1.3735e-6 1 -2.92733e-5 2.39603e-4 1 3.82785e-5 -7.83585e-5 1 1.09704e-4 2.24717e-5 1 4.10434e-5 2.21244e-4 1 6.0033e-4 -0.001315951 0.9999991 7.27077e-5 1.01677e-4 1 -3.2878e-4 -8.39004e-4 0.9999996 -6.0034e-4 4.13686e-4 0.9999998 2.87064e-5 2.68283e-5 1 4.10411e-5 -1.33644e-5 1 -1.11856e-4 -9.02471e-5 1 -1.78645e-5 1.19015e-5 1 8.51216e-5 -3.70329e-5 1 -4.59446e-5 3.47457e-4 1 2.65637e-4 -2.13521e-4 1 3.26262e-4 4.99421e-4 0.9999999 2.19661e-4 1.52829e-4 1 2.6711e-4 5.55726e-4 0.9999998 -0.3983052 0.8172926 0.4163961 -0.248297 0.9677766 0.04191827 -0.2213156 0.9749454 0.02238368 -0.245787 0.9689297 -0.02764594 -0.192358 0.979353 -0.06217867 -0.198413 0.9774094 -0.07282376 -0.2061927 0.9753592 -0.07848066 -0.2025846 0.9747498 -0.09392708 -0.210716 0.970936 -0.1134998 -0.2322298 0.9642038 -0.1279857 -0.2243271 0.9656813 -0.1309088 -0.1932061 0.9701253 -0.1467254 -0.1715505 0.965311 -0.1968379 0.2087392 0.9775046 0.03021186 0.1830448 0.9816509 -0.05344313 0.181316 0.9820837 -0.05134463 -0.2554847 0.8702813 -0.4211153 0.8687394 0.2005397 0.4528529 0.8596561 0.2153494 0.4632667 0.1811431 0.9776592 -0.1066283 0.8816654 0.08735209 0.4637197 0.8836838 0.1278939 0.4502736 0.8888122 0.07077723 0.4527733 0.1955719 0.972678 -0.1250967 0.8962576 -0.02303832 0.4429351 0.8977459 -0.01643425 0.440207 0.2201626 0.9656541 -0.1379882 0.1925811 0.969995 -0.1483989 0.1618072 0.9715254 -0.1730801 0.8572011 -0.2546252 0.4476297 0.9364475 -0.2715766 0.2220638 0.9439477 -0.2695044 0.1906046 0.9362897 -0.2698835 0.2247771 0.2709507 0.9355552 -0.2265442 0.9476903 -0.2788794 0.1552717 0.9425016 -0.2834428 0.1770619 0.9465426 -0.2924624 0.136099 0.9389843 -0.3200737 0.1259418 0.3707096 0.8447796 -0.3859041 0.9550654 -0.2800167 0.09716391 0.9442886 -0.3188621 0.08152329 0.4805328 0.7862243 -0.3885096 0.4674124 0.7899331 -0.3969022 0.9467012 -0.3179004 0.05192649 0.9366587 -0.347941 0.04009705 0.948983 -0.3149715 0.01497769 0.6129816 0.6723699 -0.4149365 0.6082868 0.6745831 -0.4182402 0.9391034 -0.3436277 -0.002202033 0.9373573 -0.3483693 4.28443e-4 0.9371893 -0.3469977 -0.03562396 0.9477695 -0.3119566 -0.06645429 0.9472779 -0.3128468 -0.06922024 0.953247 -0.2191544 -0.2080666 0.9343279 -0.3543501 -0.03830885 0.9386684 -0.3382229 -0.06713426 0.9419052 -0.3258925 -0.08129495 0.9354816 -0.3337592 -0.1160995 0.9324187 -0.3399443 -0.1226102 0.9338605 -0.3231551 -0.1532166 -0.3318037 0.8655494 0.3751408 -0.3002202 0.872545 0.3854002 -0.2436118 0.9531836 0.179149 -0.3466219 0.8959347 0.2777668 -0.3687037 0.8913186 0.2638348 -0.2751414 0.9269206 0.2551775 -0.3078027 0.938036 0.1592044 -0.2483037 0.9562528 0.1546806 -0.2684917 0.9524357 0.1441478 -0.2605366 0.9590669 0.110957 0.1173502 0.9607844 0.2512415 0.03460252 0.9766425 0.2120662 0.1043293 0.9673502 0.2309742 0.1168351 0.9605898 0.2522238 0.1236591 0.9552699 0.2686408 0.1773396 0.9542768 0.2406381 0.2669047 0.9320536 0.2450266 0.475001 0.8224092 0.3130769 0.3504218 0.885845 0.3041106 0.273181 0.9331983 0.2334808 0.23034 0.9603273 0.1572104 0.5795654 0.7323042 0.3575395 0.4179692 0.8395807 0.346996 0.3137163 0.9225066 0.2248634 0.2358878 0.9601989 0.1495828 0.1684419 0.9820975 0.08433312 -0.1738904 0.9703329 -0.167977 0.5446358 0.7415337 0.3917905 0.4481598 0.842567 0.2987204 0.3253439 0.9242994 0.1995548 0.277961 0.9487147 0.1505932 0.2790083 0.948903 0.1474362 0.1448523 0.9814706 0.1254324 0.205287 0.9772606 0.05309563 0.184743 0.9801738 0.07162004 0.2143141 0.9756072 0.04754269 0.25343 0.9652788 0.06332767 0.5148117 0.809001 0.2837011 0.5456622 0.7755442 0.3174653 0.3908836 0.8989599 0.1976896 0.380046 0.9141124 0.1412928 0.4078799 0.8895899 0.2055822 0.7944765 0.417557 0.4409687 0.5122448 0.8278716 0.2285479 0.4811465 0.8529378 0.2024729 0.1714192 0.984659 -0.0325914 0.2152257 0.9764606 0.01423782 0.8337252 0.3196334 0.4502631 0.7825768 0.430603 0.4496161 0.8200641 0.4832791 0.30649 -0.149768 0.9078038 -0.3917422 -0.2050692 0.8962584 -0.3932781 -0.1711239 0.9442909 -0.2811252 0.847797 0.309401 0.4307101 0.8455243 0.3075108 0.4364929 0.8065353 0.5449034 0.2293059 -0.1458034 0.9097081 -0.3888093 0.1926215 0.9781157 -0.0786544 0.204896 0.9765461 -0.06614834 0.7987674 0.5816925 0.1536377 -0.09089577 0.9131854 -0.397279 -0.03228414 0.9122734 -0.4083076 0.8979395 -0.1323413 0.4197506 0.9039143 -0.1056125 0.4144696 -0.006785392 0.915945 -0.4012466 -0.00842446 0.917163 -0.3984233 0.002644658 0.9465216 -0.3226298 0.8761414 -0.2419889 0.4169144 0.9115561 -0.2113536 0.3526971 0.9002767 -0.1841192 0.3944641 0.8953055 -0.2657302 0.3575132 0.8802815 -0.2536007 0.4009878 0.9034562 -0.1876468 0.3854293 0.1834939 0.9430609 -0.277428 0.9147534 -0.2508249 0.3167222 0.9111219 -0.2685871 0.3125987 0.9205806 -0.2695422 0.2826277 0.9264684 -0.2664182 0.2658526 0.9146196 -0.2493733 0.3182514 0.0324186 0.9054065 -0.4233061 0.126302 0.9027365 -0.4112356 0.07732838 0.9182174 -0.3884547 0.09495925 0.944911 -0.3132507 0.07970547 0.938748 -0.3352602 0.1389198 0.938904 -0.3148978 0.6557651 0.7455967 -0.1185653 0.2106537 0.8996171 -0.3825105 0.1557989 0.9083786 -0.3880403 0.2342238 0.8872517 -0.3973961 0.3001459 0.8673512 -0.3970067 0.2898959 0.872444 -0.3934487 0.3810209 0.8372552 -0.3922079 0.6759259 0.6751406 -0.2954815 0.7273836 0.5437851 -0.4185821 0.8047377 0.3987737 -0.4397462 0.7262188 0.5445908 -0.4195557 0.801778 0.4012517 -0.4428871 0.8917443 0.3018401 -0.3371716 0.8555288 0.2869191 -0.4309848 0.8919676 0.2990773 -0.3390379 0.9260039 0.2060447 -0.3163267 0.9656677 0.1141243 -0.2333701 0.947195 0.2007546 -0.2500389 0.855076 0.2642878 -0.4460907 0.8811337 0.1790036 -0.4376769 0.8802073 0.1716154 -0.4424742 0.9233918 0.1875642 -0.3349138 0.9645792 0.08624017 -0.2492984 0.9732009 0.01649296 -0.2293648 0.9034611 0.07934963 -0.421262 0.9410678 0.08266091 -0.3279615 0.9403389 0.08406251 -0.3296911 0.9687718 -0.03367936 -0.2456564 0.8972124 0.05213439 -0.4385111 0.9543545 -0.04514735 -0.2952446 0.905918 -0.02169537 -0.4228972 0.946499 -0.022623 -0.3219129 0.9050067 -0.02478241 -0.4246748 0.9053034 -0.1219581 -0.4068809 0.8979955 -0.1389881 -0.4174762 0.9427186 -0.119338 -0.3115128 0.8967739 -0.3422063 -0.2805199 0.9165403 -0.3205682 -0.2391443 0.8931229 -0.1984344 -0.4036776 0.8924484 -0.2538636 -0.3729466 0.879932 -0.3025595 -0.3663027 0.8876123 -0.3381642 -0.3127134 0.8648163 -0.2971984 -0.4046801 0.8797404 -0.2889971 -0.3775417 -0.2643706 0.8974909 0.3530133 -0.2529505 0.9223621 0.2920003 -0.1750571 0.9467882 0.2700874 -0.1711401 0.9132872 0.3696182 -0.1350691 0.9434671 0.3026981 -0.08878755 0.9555115 0.2812734 -0.07422679 0.9632722 0.2580643 -0.01788753 0.9469872 0.3207732 0.003058791 0.95607 0.2931228 0.003592252 0.9758666 0.2183383 -0.01634424 0.9684094 0.2488295 0.245881 0.9263817 0.2852361 0.1789645 0.9545265 0.2384343 0.3558846 0.8852339 0.2995117 0.2679486 0.925099 0.2690641 0.6501306 0.6506386 0.3924279 0.7454069 0.5042032 0.4360593 0.7354801 0.5323129 0.41918 0.6726744 0.6059796 0.424615 0.631123 0.7158447 0.2987477 0.6634545 0.6626254 0.3474994 -0.1879857 0.9632093 -0.192066 -0.1657292 0.9687837 -0.1843687 0.6018684 0.7728743 0.2010466 -0.1075278 0.9726575 -0.2058525 -0.1519461 0.9526174 -0.263501 0.7257058 0.6155087 0.3074086 0.6706573 0.6957904 0.2570886 0.7338136 0.6049253 0.309165 0.6682975 0.7129999 0.2121548 0.8194026 0.4822097 0.3099243 0.8405641 0.4162766 0.3466495 0.83689 0.4095868 0.3631169 0.7573325 0.5481891 0.354875 -0.09935593 0.9712678 -0.2162576 -0.1092101 0.9603756 -0.2564215 0.8020344 0.5395169 0.2562472 -0.06831115 0.9745044 -0.2137172 0.6994836 0.6796202 0.2209957 0.7844879 0.5935111 0.1797873 0.7847203 0.5900377 0.1899208 -0.03973424 0.9729322 -0.2276496 0.6807353 0.7209184 0.1299085 0.7084322 0.6879187 0.1577712 0.7438813 0.6505962 0.1528571 -0.06920057 0.9187653 -0.3886924 -0.07152676 0.9553955 -0.2865369 0.6885052 0.716468 0.1124024 0.7883047 0.6056084 0.1086941 0.7584941 0.6428112 0.1071465 0.7813543 0.6157332 0.1017761 0.7519757 0.6507327 0.10526 0.6731984 0.7359128 0.07236236 0.7826266 0.6147406 0.09792762 -0.0200321 0.9655477 -0.2594541 -0.02001994 0.9626881 -0.269872 -0.001038968 0.9542621 -0.2989696 -0.00587356 0.971023 -0.2389141 0.6988598 0.7142947 0.03712415 0.01902514 0.9732318 -0.2290371 0.6953333 0.7170252 0.04885309 0.7608676 0.6481012 0.03233361 0.6492021 0.7606085 -0.003392219 0.03713726 0.9715781 -0.2337881 0.04091864 0.9656059 -0.2567699 0.05166864 0.9742541 -0.2194524 0.7623449 0.6464672 0.03017443 0.09308332 0.9744554 -0.204383 0.08386135 0.9728142 -0.2158703 0.1578371 0.9688438 -0.190864 0.1249026 0.9733183 -0.1924859 0.1713218 0.9646486 -0.2002551 0.6573171 0.7534528 -0.01559334 0.106194 0.9577885 -0.2671403 0.7567749 0.6535031 -0.01501548 0.7472463 0.6640974 -0.0244469 0.7488524 0.6619391 -0.0325089 0.1509709 0.9607512 -0.2327336 0.08584296 0.9637327 -0.2526861 0.6542712 0.7536307 -0.06300759 0.7427797 0.6676978 -0.04957735 0.636966 0.7672225 -0.0751264 0.7631635 0.641757 -0.07569479 0.7638607 0.6325255 -0.1281741 0.7770938 0.621971 -0.09631943 0.8298594 0.5406076 -0.1381198 0.8036598 0.5811887 -0.1278691 0.8444764 0.5019798 -0.1867511 0.772829 0.6115826 -0.1694175 0.7203304 0.6558185 -0.2258898 0.8534114 0.5056746 -0.126421 0.7973973 0.5823293 -0.1582726 0.7937738 0.559342 -0.2388716 0.8620322 0.4738467 -0.1799162 0.9078361 0.3730325 -0.1915218 0.8512402 0.4879991 -0.1929954 0.8335977 0.5007457 -0.2331709 0.7429555 0.5522936 -0.3781388 0.7371127 0.5969559 -0.3167155 0.8506705 0.4533262 -0.2661865 0.9085455 0.3701225 -0.1937901 0.9327355 0.3035089 -0.194646 0.8905216 0.3767856 -0.2549591 0.8274066 0.4457083 -0.3416761 0.8281916 0.4143871 -0.3773353 0.9470069 0.2252811 -0.2289679 0.9012405 0.3389783 -0.2699248 0.9346479 0.2777777 -0.221975 0.9554396 -0.2489481 -0.1586194 0.9639638 -0.1837171 -0.192411 0.8757098 -0.4531313 -0.1667464 0.9258392 -0.331348 -0.1817429 0.9342972 -0.3213269 -0.1543951 0.9333164 -0.2536634 -0.2541167 0.9209558 -0.3276559 -0.2109074 0.9211457 -0.3131912 -0.2310884 0.6966449 0.7047295 -0.1343218 0.7011087 0.6966772 -0.151946 0.6722226 0.7167193 -0.185554 0.7094158 0.6710361 -0.2154988 0.7625766 0.6121599 -0.2091343 0.9634882 -0.1822041 -0.1961944 0.9755858 -0.07363849 -0.2069053 0.9460749 -0.21202 -0.2449281 0.6297111 -0.7156881 0.3020838 0.8385661 -0.4874228 0.243364 0.8012622 -0.5286214 0.2802469 0.7949291 -0.5575536 0.2392112 0.3776315 -0.8509513 0.3650706 0.6291753 -0.7152202 0.3043004 0.8135359 -0.514799 0.2704469 0.6564063 -0.6859719 0.3139642 0.8016776 -0.5282517 0.2797557 0.8067605 -0.5344406 0.2520134 0.6129214 -0.7501938 0.2480661 0.8592599 -0.4788489 0.179934 0.8306035 -0.5195785 0.2003395 0.3789992 -0.8518457 0.3615503 0.3416396 -0.8708069 0.3535218 0.6558041 -0.6844456 0.3185203 0.6904673 -0.6618935 0.2918083 0.3818135 -0.8943339 0.2332071 0.412898 -0.8763263 0.2481284 0.7517498 -0.6426203 0.1480249 0.2671961 -0.8746322 0.4045055 0.1955286 -0.9319869 0.305236 0.4049468 -0.8506516 0.3352761 0.8420408 -0.4799205 0.2462593 0.4822979 -0.8759075 0.01322913 0.716615 -0.6888039 0.1096006 0.8440586 -0.528736 0.08946233 0.3206576 -0.9470613 -0.01592636 0.3778124 -0.9235368 0.06585884 0.9844818 -0.1512621 0.08896929 0.7911686 -0.6076321 0.06953769 0.4384776 -0.8978885 0.03916484 0.4130973 -0.9106132 0.01159179 0.7443652 -0.6643535 0.06749027 0.2571815 -0.9663037 0.010724 0.4074477 -0.9132145 0.005073547 0.8033862 -0.5952298 0.01650303 0.803107 -0.595609 0.01640456 0.8111259 -0.5847235 0.01316046 0.2915056 -0.956569 6.04417e-4 0.254904 -0.9669646 -0.00189495 0.7727933 -0.6341546 -0.02527147 0.5633459 -0.8246952 0.05019348 0.7829186 -0.6205435 0.0443198 0.372699 -0.9275822 0.02620881 0.6171525 -0.7846668 0.05848675 0.3715237 -0.9280721 0.0255407 0.5981284 -0.8006209 0.03533542 0.7829492 -0.6206267 0.04257965 0.7814826 -0.6225084 0.04205262 0.6159114 -0.7872008 0.03111672 0.6166394 -0.7869955 0.01984995 0.6017382 -0.7983606 0.02305567 0.2702997 -0.9627718 -0.00292766 0.5611852 -0.8276849 -0.002975344 0.5704935 -0.8211225 -0.01718264 0.4739786 -0.8805364 -9.24828e-5 0.7338685 -0.6792836 0.003314256 0.8024038 -0.5965483 -0.01668143 0.2721803 -0.9622112 -0.008221805 0.470161 -0.8821715 -0.02687346 0.4620147 -0.8865687 -0.02320539 0.6364894 -0.7711709 -0.01329588 0.6266871 -0.7777506 -0.04865485 0.5964846 -0.8025192 -0.01300907 0.9666131 -0.1820402 -0.1803351 0.3837633 -0.922237 0.04695534 0.7660046 -0.6372166 0.08480572 0.4855882 -0.8741766 -0.004415571 0.7176899 -0.6956092 -0.0323885 0.6011447 -0.798774 0.02419292 0.3708767 -0.9286404 -0.008811056 0.2985376 -0.8953941 0.330371 0.04230511 -0.902727 0.4281288 0.1169036 -0.8607177 0.4954783 0.2258772 -0.8511097 0.4739114 0.5478861 -0.7876958 0.2817026 0.2911013 -0.8925098 0.3445089 0.5712 -0.7828338 0.2467832 0.7948438 -0.561493 0.2301064 0.2443416 -0.6923814 0.6789 0.5580716 -0.591571 0.5818935 0.004743158 -0.7753003 0.6315751 0.2826721 -0.7171998 0.6369624 0.2409069 -0.6966556 0.6757477 0.7908467 -0.5455892 0.2772982 0.587434 -0.7272814 0.354941 0.462895 -0.7735077 0.4329135 0.4463103 -0.7601357 0.4722299 0.7196378 -0.5472139 0.4274091 -0.004756629 -0.9748703 0.2227223 0.03240835 -0.9436705 0.329296 0.0260874 -0.9465838 0.3214011 0.001252353 -0.9219655 0.38727 0.001577556 -0.8695721 0.4938037 0.03205394 -0.8395007 0.5424124 0.009666264 -0.7312099 0.6820841 0.09115946 -0.6906573 0.7174138 0.1198696 -0.3610892 0.9247951 -0.0973097 -0.2293249 0.9684735 0.05265337 -0.05250114 0.9972318 -0.04416716 0.01363438 0.9989312 0.05372619 0.1641717 0.9849676 -0.002447962 0.1985639 0.9800849 0.01129531 0.3866868 0.922142 0.05851811 0.439798 0.8961883 -0.002350509 0.4839309 0.8751032 -0.01273685 0.6168698 0.7869623 0.03152018 0.6743698 0.7377207 0.02473556 0.6840826 0.7289851 0.003124117 0.7670887 0.6415334 0.0281679 0.8266326 0.5620367 0.01410865 0.8384402 0.5448109 -0.004698991 0.8881516 0.4595267 0.008481681 0.9340759 0.3569738 0.02539837 0.9452821 0.325264 0.02037268 0.9492603 0.3138311 -0.00163269 0.9804476 0.1967737 0.001775622 0.9922165 0.124512 0.0354194 0.9966665 0.07349503 0.002471387 0.999997 -2.78187e-4 0.01288926 -0.9999158 0.001492738 0.01965403 -0.9998068 3.5788e-4 0.01193708 -0.9999132 0.005581855 0.009401321 -0.9999557 5.01913e-4 0.0292539 -0.9995661 -0.003447115 0.01200425 -0.9999274 0.001146554 -0.02247202 -0.8703841 -0.4918605 0.09159374 -0.8514508 -0.5163742 -0.1035324 -0.8567776 -0.5051864 -0.03394478 -0.9333168 -0.3574457 -0.06255018 -0.8888014 -0.4540041 0.2391955 -0.9675899 -0.08096522 -0.02720701 -0.9178439 -0.3960078 0.05738198 -0.8927986 -0.4467864 0.09506464 -0.9682204 -0.2313265 0.1158398 -0.961647 -0.2486287 0.126376 -0.9643588 -0.232468 0.6174436 -0.1752047 -0.7668551 0.7587131 -0.2567641 -0.5986875 0.6422774 -0.1364395 -0.7542307 0.7227643 -0.1458863 -0.6755213 0.7791385 -0.2043235 -0.5926172 0.5247689 0.4703513 -0.709498 0.4233657 0.457575 -0.7819122 0.5745328 0.6398184 -0.5104357 0.5953682 0.5749183 -0.5612537 0.409649 0.4762847 -0.7780364 0.4385924 0.5677353 -0.6966444 0.5502719 0.6409627 -0.5351334 0.07256591 -0.03242337 -0.9968366 0.06775844 -0.02849733 -0.9972948 0.2586563 -0.09547472 -0.9612396 0.2688643 -0.09398829 -0.9585815 0.3849427 -0.1488793 -0.9108535 0.4876613 -0.1568484 -0.8588278 0.3810309 -0.09689277 -0.9194712 0.2931561 -0.037427 -0.9553317 0.3258865 -0.01144039 -0.9453397 0.209828 0.02625966 -0.9773857 0.8383874 0.1530281 -0.5231531 0.2179334 0.09863412 -0.9709668 0.2044075 0.1397781 -0.9688549 0.2565467 0.1775058 -0.9500924 0.2008123 0.1358438 -0.9701654 0.1590949 0.1726647 -0.9720472 0.2302903 0.2679197 -0.9355136 0.6843625 0.5229197 -0.5081369 0.1208707 0.2287403 -0.9659546 0.1656668 0.2955707 -0.9408468 0.446766 0.7249928 -0.5242 0.07676953 0.255596 -0.9637308 0.09766483 0.3448632 -0.9335583 0.02202212 0.2262292 -0.9738252 0.03847289 0.7325145 -0.6796635 0.03614372 0.8173414 -0.575019 0.03306609 0.824763 -0.5645112 -0.00267297 0.8063564 -0.5914239 -0.01871609 0.276951 -0.9607018 -0.08718758 0.8290592 -0.5523217 -0.153132 0.8518933 -0.5008277 0.2712336 -0.1031496 -0.9569705 0.5499883 -0.229573 -0.803 0.1261285 -0.03361082 -0.9914444 0.1669893 -0.04323911 -0.9850102 0.4860847 -0.176687 -0.8558641 0.4165973 -0.1079213 -0.9026626 0.06955963 -0.009654819 -0.9975312 0.2092339 -0.01208376 -0.9777911 0.3942366 -0.01931864 -0.9188059 0.09115928 -0.001924633 -0.9958345 0.3960397 -0.03343111 -0.9176247 0.06185525 0.002118408 -0.9980829 0.220822 0.0187236 -0.9751344 0.645255 -0.02125245 -0.7636717 0.7559377 -0.0234344 -0.654224 0.7454261 -0.02803921 -0.6659983 0.6434859 -0.02038252 -0.7651866 0.06903076 0.01015138 -0.9975629 0.6399536 0.04025685 -0.7673584 0.05555742 0.01247769 -0.9983776 0.7258238 0.07621097 -0.683646 0.4992329 0.1055687 -0.8600128 0.08055877 0.02683013 -0.9963887 0.4916746 0.12725 -0.8614311 0.05240511 0.0225746 -0.9983708 0.7407349 0.1659683 -0.6509734 0.5525724 0.1716738 -0.815593 0.6270787 0.1872534 -0.7561141 0.05060887 0.03359967 -0.9981532 0.05980539 0.0427342 -0.9972949 0.3883975 0.2193263 -0.8950102 0.6803885 0.388352 -0.6214935 0.04970335 0.05704283 -0.9971337 0.2987116 0.2775715 -0.9130858 0.1152746 0.1425995 -0.9830449 0.03853625 0.04783749 -0.9981115 0.3835791 0.3475947 -0.8555963 0.1107886 0.2029516 -0.9729011 0.03072595 0.07087445 -0.9970119 0.03372806 0.08064556 -0.996172 0.2258135 0.4502756 -0.8638635 0.4203601 0.7075815 -0.5680017 0.34258 0.7466461 -0.5702269 0.1903675 0.4913351 -0.8499119 0.02803319 0.118988 -0.9924999 0.04914349 0.1980314 -0.978963 0.3126654 0.7320644 -0.6052455 0.02319628 0.1086738 -0.9938068 0.2682594 0.7690165 -0.5802162 0.1279692 0.5107215 -0.8501691 0.2092028 0.7561425 -0.6200668 0.01607942 0.1104263 -0.9937543 0.009821593 0.0934543 -0.9955752 0.1186793 0.6542481 -0.7469101 0.119464 0.6646429 -0.7375488 0.1006584 0.7942172 -0.5992388 0.09387469 0.7436539 -0.6619414 0.0581054 0.7005038 -0.7112792 0.004811048 0.1040807 -0.9945572 0.01093393 0.2166325 -0.976192 -5.02097e-4 0.08834081 -0.9960902 0.008266448 0.5079481 -0.861348 0.008179068 0.6141668 -0.789134 0.007730782 0.6118988 -0.7908984 0.01208186 0.6948223 -0.71908 0.006472051 0.7274801 -0.6860983 -0.002818584 0.1178877 -0.993023 0.00324428 0.2396067 -0.9708647 0.008491635 0.7924129 -0.6099259 -0.003685653 0.6169081 -0.7870265 8.39004e-4 0.1066856 -0.9942924 -0.006135821 0.109933 -0.9939201 -0.01693874 0.425509 -0.9047957 -0.01120865 0.08041799 -0.9966983 -0.02392178 0.6244801 -0.7806743 -0.05731058 0.7918248 -0.6080533 -0.1057482 0.6345502 -0.7656131 -0.02369499 0.1116888 -0.9934608 -0.03642725 0.1655042 -0.9855362 -0.0776925 0.6308223 -0.772028 -0.09804737 0.5329633 -0.8404385 -0.01924824 0.0680654 -0.9974952 -0.1100305 0.3981432 -0.9107004 -0.1165711 0.3731287 -0.9204272 0.6543455 -0.2095171 -0.7265911 0.4935416 -0.1547036 -0.8558526 0.6277124 -0.2331575 -0.7427078 0.6581861 -0.2293272 -0.7170775 0.2702093 -0.07507234 -0.9598704 0.5701964 -0.09038674 -0.8165209 0.57247 -0.09971243 -0.81384 0.1606305 -0.001646935 -0.9870132 0.5083941 -0.00389862 -0.8611158 0.3222793 0.01926046 -0.9464487 0.3798909 0.03539007 -0.924354 0.5538277 0.05738788 -0.8306513 0.4774471 0.0317679 -0.8780861 0.2802059 0.06796389 -0.957531 0.2925986 0.05335205 -0.9547459 0.3635522 0.0603066 -0.9296199 0.8020045 0.06764578 -0.5934754 0.8044196 0.06840008 -0.5901107 0.569779 0.09228289 -0.8166001 0.7001066 0.151206 -0.6978449 0.1441763 0.04847538 -0.988364 0.3664343 0.1086155 -0.9240826 0.3464372 0.1345415 -0.928375 0.4095712 0.1872504 -0.8928542 0.6970134 0.2571293 -0.6693705 0.7698811 0.2483046 -0.5879012 0.7272667 0.2636326 -0.6337042 0.5113197 0.2131789 -0.8325305 0.5932154 0.2840731 -0.7532584 0.6023154 0.28755 -0.7446685 0.7810879 0.3877718 -0.489423 0.4712585 0.301213 -0.828967 0.5609842 0.4270858 -0.7091506 0.4734402 0.3279019 -0.8175175 0.6433223 0.4410074 -0.6258186 0.2259534 0.3090471 -0.9238156 0.309069 0.4346167 -0.8459224 0.1748607 0.3458423 -0.9218552 0.3968795 0.6447454 -0.6532917 0.2635497 0.4811789 -0.8360673 0.1362305 0.3989469 -0.9067981 0.1534534 0.448082 -0.8807239 0.2841223 0.6036761 -0.7448824 0.295552 0.6190495 -0.7276172 0.2212864 0.5823431 -0.7822461 0.1923729 0.6191444 -0.7613494 0.07811123 0.3950735 -0.9153228 0.09513092 0.4684846 -0.8783349 0.2133908 0.7656518 -0.6068294 0.1500239 0.5886616 -0.7943364 0.03368055 0.3303857 -0.9432449 0.05191993 0.3341403 -0.9410923 0.08168423 0.559222 -0.8249839 0.03634071 0.4052281 -0.9134931 0.119363 0.8328267 -0.540511 0.03973948 0.4974304 -0.8665933 0.0513041 0.5472267 -0.8354106 0.04614424 0.6064562 -0.7937769 0.004037082 0.4784705 -0.8780944 0.00509727 0.3642392 -0.9312915 -0.01458996 0.5593844 -0.8287801 -0.00423932 0.4799974 -0.8772598 -0.01448404 0.3641365 -0.9312329 -0.01967549 0.2779686 -0.9603887 0.0109604 0.3823752 -0.9239422 -0.01371401 0.7593079 -0.6505872 -0.01574426 0.7234063 -0.6902431 -0.01603543 0.5599732 -0.8283556 -0.04350894 0.6238887 -0.7803012 -0.03613108 0.3986711 -0.916382 -0.02302211 0.24387 -0.9695346 -0.03920984 0.4057368 -0.9131486 -0.04840737 0.5239385 -0.8503795 -0.06277775 0.3737061 -0.9254203 -0.06008058 0.3970906 -0.9158109 -0.03412336 0.239846 -0.9702112 -0.0588054 0.6743922 -0.736028 -0.1241371 0.8057701 -0.5790721 -0.124597 0.7134773 -0.6895112 -0.06148499 0.2100356 -0.9757586 -0.1313841 0.5325458 -0.8361419 -0.178248 0.7033309 -0.688152 -0.1617975 0.5886226 -0.7920511 -0.1958259 0.7245358 -0.6608329 -0.2067357 0.8217761 -0.5309846 0.752568 -0.2509048 -0.6088419 0.820451 -0.2900567 -0.4926735 0.7883614 -0.09990143 -0.6070471 0.6733652 0.1207141 -0.7293884 0.2020534 0.7891578 -0.580004 0.004499435 0.2465979 -0.9691075 0.006451666 0.3539961 -0.9352247 -0.01246941 0.3589718 -0.9332652 -0.02176082 0.7478135 -0.6635522 -0.03335082 0.8095139 -0.5861527 -1 -2.47568e-4 2.28247e-4 -1 -4.25296e-4 -4.08745e-5 -1 -2.16335e-4 -1.91079e-7 -1 -1.71398e-5 -1.05252e-4 -1 8.28126e-6 -8.0664e-6 -0.9999991 0.00116384 -7.95983e-4 -0.9999995 0.001056969 4.08674e-5 -0.9999994 0.00118184 -2.0553e-5 -1 4.51938e-6 -7.44536e-6 -1 6.92185e-6 -3.56084e-6 -1 1.45901e-5 1.84464e-5 -1 4.91941e-6 -6.0374e-6 -1 2.59294e-6 -2.66801e-7 -1 -2.62745e-6 5.79246e-6 -1 3.05714e-6 8.49512e-7 -1 2.12487e-6 2.21045e-6 -1 -9.43193e-7 2.94461e-5 -1 6.48081e-7 0 -1 1.67601e-6 7.20669e-6 -1 2.01092e-4 2.41929e-4 -1 1.17511e-6 0 -1 -4.31344e-5 -1.1447e-5 -1 7.95442e-6 1.56598e-5 -1 1.24421e-5 1.0251e-5 -0.9999954 -0.002903163 9.45479e-4 -1 -1.95911e-7 0 -0.9999958 0.002646565 -0.001199126 -0.9999998 -5.57787e-4 -4.5694e-4 -1 -7.04361e-7 0 -1 -7.80815e-6 -1.5729e-4 -0.9999984 -0.001739978 -4.91896e-4 -1 1.41828e-4 -6.92929e-5 -1 2.21744e-6 0 -1 2.67602e-6 1.86841e-5 -1 -1.14587e-6 0 -1 -9.82481e-7 0 -1 1.4068e-6 0 -1 3.58908e-7 0 -1 3.43582e-7 0 -1 -1.51626e-6 0 -1 2.69197e-6 0 -1 -7.45548e-7 0 -1 2.41964e-7 0 -1 -3.38881e-6 0 -1 9.77298e-7 0 0 0.8660261 -0.4999988 0 0.8660263 -0.4999985 0 0.8660263 0.4999985 0 0.8660261 0.4999988 0 -0.8660263 0.4999985 0 -0.8660261 0.4999988 0 -0.8660261 -0.4999988 0 -0.8660263 -0.4999985 -0.3535626 0.09434455 0.930641 -0.4353598 0.1721226 0.8836491 -0.7933875 0.07725441 0.6037948 -0.9769511 0.01891636 0.2126235 -0.5697384 0.1902918 0.7994918 -0.9393665 0.05975151 0.3376688 -0.5996254 0.2343305 0.765205 -0.2962756 0.397832 0.8683032 -0.7885264 0.2363499 0.5677719 -0.9196778 0.1411076 0.3664445 -0.4603859 0.4489157 0.7658457 -0.675179 0.3797018 0.6324239 -0.972841 0.1091295 0.2041354 -0.2791685 0.5661625 0.7755804 -0.7619071 0.3960846 0.5124593 -0.3944433 0.5916243 0.7031323 -0.8088374 0.3734068 0.454257 -0.3149597 0.6904036 0.6512629 -0.8268443 0.4011659 0.3942008 -0.5450707 0.6615523 0.5150209 -0.5295418 0.6990178 0.4805825 -0.9289577 0.2904759 0.2294811 -0.3551118 0.8045327 0.4760493 -0.8538433 0.4689968 0.2258179 -0.890793 0.4067927 0.2025036 -0.4070251 0.8493103 0.3361586 -0.5156769 0.8080267 0.2849041 -0.7501217 0.6216002 0.2256784 -0.4525755 0.876053 0.1664533 -0.9889782 0.1434788 0.03655123 -0.6105397 0.7874907 0.08426004 -0.79384 0.5946387 0.1273696 -0.9580621 0.2836341 0.04085248 -0.6098413 0.7877097 0.08721894 -0.3123314 0.9491714 -0.03902328 -0.8059027 0.5920073 -0.006955146 -0.8536596 0.5207617 -0.0085271 -0.5440646 0.8219335 -0.1685802 -0.51875 0.8384839 -0.1668627 -0.5912678 0.7820085 -0.1971427 -0.8645157 0.4765007 -0.1598745 -0.9391395 0.3284849 -0.1005725 -0.3605185 0.8372132 -0.4112183 -0.4584857 0.8050148 -0.3764865 -0.9718758 0.2221391 -0.07817828 -0.7078191 0.6235182 -0.3319898 -0.4683748 0.7000868 -0.5389838 -0.3862133 0.7142885 -0.5836363 -0.7249839 0.5530595 -0.4105163 -0.7503914 0.5386071 -0.383165 -0.93028 0.2971074 -0.2151894 -0.9575479 0.219456 -0.1869253 -0.424054 0.6071415 -0.6719803 -0.8010828 0.3945246 -0.4501297 -0.5976468 0.4915013 -0.633439 -0.795299 0.3948032 -0.4600328 -0.5100868 0.4582831 -0.7278654 -0.5761638 0.3810594 -0.7230693 -0.9295641 0.1731236 -0.3254826 -0.8644841 0.199366 -0.4614331 -0.4980834 0.3194581 -0.8061386 -0.5779507 0.2436723 -0.7788434 -0.8253432 0.1723415 -0.5376868 -0.5055217 0.2077821 -0.8374213 -0.4393269 0.0776208 -0.8949676 -0.5279847 0.1120923 -0.8418239 -0.8412787 0.04875904 -0.5383985 -0.8851787 0.07039731 -0.4598945 -0.438436 -0.01699084 -0.8986018 -0.5029414 -0.0420795 -0.8632956 -0.8241707 -0.005129396 -0.5663185 -0.4911956 -0.1578401 -0.856629 -0.6300643 -0.1951395 -0.7516247 -0.8996421 -0.07284599 -0.4305087 -0.8688889 -0.1083886 -0.4829949 -0.5671128 -0.2880956 -0.7716113 -0.3525812 -0.5007808 -0.7905095 -0.8972508 -0.1882432 -0.3993816 -0.7106983 -0.3311178 -0.6207005 -0.691496 -0.3556388 -0.6287722 -0.9897632 -0.08363825 -0.1156442 -0.3646349 -0.6121705 -0.7016329 -0.4144983 -0.6077397 -0.67738 -0.7447878 -0.4222944 -0.5166805 -0.8062291 -0.3943386 -0.4410125 -0.9755151 -0.1438269 -0.1663859 -0.4618687 -0.6812996 -0.567898 -0.5634241 -0.6548873 -0.5036625 -0.7755089 -0.4754669 -0.415352 -0.5630373 -0.6718548 -0.4812486 -0.9033205 -0.3484795 -0.2501482 -0.3417156 -0.8300971 -0.4406465 -0.4180958 -0.8252295 -0.3797264 -0.727464 -0.6103079 -0.3135609 -0.343074 -0.8835453 -0.3188231 -0.8674557 -0.4545977 -0.2021428 -0.9179039 -0.3545615 -0.1781535 -0.487205 -0.8470215 -0.21257 -0.8555927 -0.4862807 -0.1774612 -0.6887484 -0.7066078 -0.1622692 -0.2462115 -0.9602545 -0.1314962 -0.767553 -0.6372929 -0.06870466 -0.4380249 -0.8988885 -0.01156073 -0.915596 -0.4012664 -0.02587515 -0.9481503 -0.3161486 -0.03257536 -0.5992256 -0.8005803 -1.68325e-4 -0.2541157 -0.9645937 0.07060086 -0.694698 -0.7140658 0.08663028 -0.8576532 -0.5110602 0.05699545 -0.6060916 -0.7827194 0.1414334 -0.5094039 -0.8299863 0.2272235 -0.5776443 -0.7933236 0.1922624 -0.9434505 -0.3176973 0.09470885 -0.5197849 -0.7784414 0.3519273 -0.8453172 -0.4919143 0.2084687 -0.4950504 -0.7877838 0.3664995 -0.885645 -0.4290629 0.1775902 -0.8165549 -0.526523 0.2366682 -0.5178332 -0.6976938 0.4950476 -0.4949333 -0.7008283 0.5136933 -0.487806 -0.7038549 0.5163658 -0.7119596 -0.5800394 0.3958129 -0.8700037 -0.3623427 0.3343674 -0.9712364 -0.1921921 0.1405779 -0.6551958 -0.522532 0.5455996 -0.8441678 -0.3786298 0.3795003 -0.5871112 -0.5298179 0.6120404 -0.5818346 -0.4654191 0.6669735 -0.422338 -0.4888237 0.7633361 -0.9122535 -0.231016 0.3382679 -0.2879592 -0.42238 0.8594618 -0.7676301 -0.318427 0.5561909 -0.8652805 -0.2531952 0.4326453 -0.640884 -0.3040314 0.7048636 -0.3913352 -0.3586348 0.8474891 -0.3127134 -0.256693 0.9145048 -0.3763737 -0.2304121 0.897359 -0.694531 -0.1941026 0.6927849 -0.428247 -0.1174253 0.8959999 -0.9456058 -0.09366261 0.3115398 -0.8383491 -0.09801936 0.5362491 -0.8700292 -0.09105294 0.484519 -0.6405017 -0.03762763 0.7670344 -0.6389198 -0.03036642 0.7686739 -0.999871 -0.007353842 -0.01428836 -0.9999541 0.0020563 -0.009364664 -0.9998114 -0.0194202 -2.25112e-4 -0.999903 -0.01376432 -0.002140641 -0.999998 -0.00176841 -0.001020669 -0.9998182 -0.01906841 2.97132e-4 -0.9999186 0 -0.01276743 -0.9999147 1.86102e-4 -0.01306837 -0.9997202 0.01202237 -0.02037632 -0.9997303 0.01211261 -0.01981538 -0.9998041 -0.01219385 0.01559406 -0.999995 -0.002737343 0.001580953 -0.9998323 -0.01215207 0.0137 -0.9998663 -0.007801055 0.01437711 -0.9999946 0.002873778 -0.001659274 -0.999958 0.008968293 -0.001943886 -0.9999368 0.01103901 0.002122163 -0.9999887 0 0.00476706 -0.9999899 -1.08921e-4 0.004514157 -0.9999016 0.009001672 0.01076704 -0.9999924 0.003376483 0.00194931 -0.9998853 0.008957087 0.01222056 1 -3.09822e-4 6.08594e-5 0.9999995 -4.28354e-4 9.8487e-4 1 -4.55089e-4 -6.13899e-5 1 -8.12797e-5 2.61324e-5 1 -6.90073e-5 -1.72809e-6 1 -6.43777e-5 -2.00754e-5 1 6.40333e-5 2.7611e-4 0.9996252 -0.02071589 0.01790148 0.9999597 -0.003335952 -0.008342862 0.9998699 0.01122522 -0.01159358 0.9999997 6.07568e-4 -6.78809e-4 0.9999701 0.00135833 0.007615506 1 2.01412e-5 1.34448e-4 0.999994 0.002192318 -0.002715349 0.9999975 6.06089e-4 -0.002179801 1 1.75483e-5 -2.14621e-5 0.9998573 -0.001567602 -0.01682704 0.999955 7.4618e-4 -0.009469091 1 1.67338e-5 2.93335e-5 0.9996224 -7.68446e-4 0.02747303 1 -2.61949e-4 -3.04567e-4 0.9999582 0.006209611 -0.006731986 0.9998993 0.01259005 -0.00655502 0.9999244 0.01182091 -0.003422796 0.9998632 0.01654613 2.5592e-4 1 7.54223e-6 6.81604e-5 0.9999999 3.49933e-4 3.20383e-4 0.9999095 0.01341801 -0.001037359 0.9998804 0.009802162 0.01196724 0.9999996 8.68708e-4 2.51525e-4 0.9999995 3.00674e-4 9.94758e-4 0.9999955 -0.001049935 -0.00285691 0.9999993 -0.001189112 3.24687e-4 0.9999815 -0.005619287 -0.002348482 0.9999942 0.003068804 0.00152719 1 -9.387e-5 -5.09758e-5 0.9999992 0.001133799 5.98266e-4 0.9982506 0.05214107 0.02787947 0.05940771 -0.8982309 -0.4354906 0.1623041 -0.9387172 -0.3040848 0.3085085 -0.893664 -0.3258636 0.5286336 -0.7791458 -0.3368658 0.2850462 -0.8488302 -0.4452369 0.4659773 -0.7423121 -0.4814956 0.7941749 -0.5677501 -0.2166708 0.7964838 -0.5784304 -0.1761589 0.4479596 -0.8756039 -0.1806937 0.3735757 -0.9101015 -0.1793224 0.4842331 -0.8044755 -0.3440024 0.6220004 -0.6744516 -0.3977822 0.6461607 -0.7342385 -0.2082555 0.4564904 -0.8737174 -0.1680312 0.7213468 -0.6845061 -0.1054053 0.2493597 0.9654595 0.07554876 0.8077383 -0.3319634 0.4871954 0.7106752 -0.5217798 0.4718969 0.8497354 -0.3317 0.4097864 0.5005934 -0.5671116 0.6540572 0.2965571 -0.7084534 0.6404277 0.3266599 -0.5842475 0.7429322 0.2857766 -0.5565691 0.7801043 0.2858592 -0.4455853 0.848374 0.5567365 -0.3692927 0.7440883 0.32835 -0.3964784 0.8573163 0.2801365 -0.3059062 0.9099149 0.3235653 -0.2270303 0.9185656 0.2819536 -0.1853762 0.941349 0.3129509 -0.1174319 0.9424816 0.2625358 -0.07183063 0.9622451 0.3180097 0.04450178 0.9470425 0.3342896 0.05490833 0.9408696 0.6512186 0.2363518 0.7211465 0.7141937 0.2514252 0.6532326 0.4660784 0.170925 0.8680759 0.2467399 0.1612368 0.9555743 0.349169 0.2453326 0.9043744 0.7668698 0.2839278 0.5755829 0.5796118 0.3441577 0.7386513 0.5740933 0.34281 0.7435712 0.2559272 0.3077593 0.9163981 0.4725223 0.3032869 0.82749 0.70087 0.3820837 0.6023233 0.7409213 0.395922 0.5424772 0.3168795 0.4098315 0.8553512 0.5536324 0.4641544 0.6914131 0.6325458 0.4108783 0.6565552 0.7601985 0.4347584 0.4827874 0.4598158 0.4288681 0.7775871 0.2497144 0.4446264 0.8602035 0.5572226 0.5372848 0.6331099 0.5320979 0.5526015 0.6414853 0.3494155 0.4965 0.7946047 0.3292575 0.5342629 0.7785581 0.6798751 0.517114 0.5199645 0.1273616 0.5154889 0.8473786 0.06256914 0.5308153 0.8451748 0.4529955 0.5476832 0.7034474 0.2455309 0.5732159 0.7817533 0.5838556 0.5494121 0.5977116 0.4548245 0.5464699 0.7032109 0.3230676 0.6472709 0.6904113 0.4260999 0.6593423 0.6194406 0.1733064 0.6293266 0.7575704 0.2659397 0.6771416 0.6861162 -6.77043e-4 0.6753584 0.7374894 0.2586069 0.7548079 0.6028164 0.2592926 0.7544108 0.6030188 0.260612 0.820797 0.5083049 0.2478377 0.8182032 0.518768 0.2176609 0.8722134 0.438027 0.2421218 0.8748515 0.419538 0.2670171 0.9093157 0.3191344 0.2425278 0.9200363 0.3077555 -0.07600462 0.9353931 0.3453448 0.2490044 0.9465332 0.2051143 0.5056248 0.8582376 0.08815813 0.4312413 0.893518 0.1251267 0.2417116 0.9492993 0.201013 0.6978102 -0.3644278 0.616647 0.5619379 -0.4828119 0.6716536 0.6788272 -0.3670145 0.6359986 0.506115 -0.4584341 0.730538 0.4073722 0.2454232 0.8796678 0.3738877 0.3810349 0.8455888 0.4783316 0.6899401 0.5433062 0.4513897 0.708202 0.5428604 0.4679039 0.7660431 0.4407313 0.4310774 0.7701038 0.470226 0.4927221 0.7913329 0.3619631 0.4210091 0.8602572 0.2875918 0.4142022 0.8641859 0.285691 0.4806219 0.8572419 0.1847675 0.8064323 -0.3296529 0.4909136 0.8344833 -0.2727266 0.4788089 0.7084874 -0.4637829 0.5319314 0.8398091 -0.2739772 0.4686761 0.811892 -0.1514857 0.5638117 0.7811601 -0.1868901 0.5957021 0.7062596 -0.2090073 0.6763974 0.4708034 -0.2722957 0.8391659 0.5720499 -0.2841877 0.7694129 0.7380737 -0.06034499 0.6720162 0.7754161 -0.07606041 0.6268531 0.5255985 -0.1304033 0.8406791 0.5339316 -0.1356136 0.8345813 0.5575098 -0.03971171 0.8292201 0.7862624 0.03442734 0.6169329 0.7353001 0.06071633 0.6750165 0.5492172 0.0275923 0.8352242 0.4725869 0.06374508 0.8789757 0.8060346 0.1367048 0.5758647 0.7473104 0.1685587 0.6427405 0.590069 0.1572294 0.7918949 0.5023539 0.196395 0.8420628 0.7490218 0.5524265 0.365775 0.6633027 0.5941056 0.4550475 0.7154045 0.617444 0.3270465 0.6305593 0.7111414 0.310923 0.7075103 0.6704078 0.223568 0.6899155 0.7147591 0.1146132 0.6309332 0.7520009 0.1908345 0.6816018 0.7232422 0.111085 0.05728375 -0.6689784 0.7410712 0.07519423 -0.5441046 0.835641 0.3346984 -0.5062581 0.7947828 0.0863167 -0.5493986 0.8310901 0.02954834 -0.4059339 0.9134247 0.1079006 -0.4347343 0.8940715 0.2983984 -0.3111911 0.9022852 0.06532067 -0.3496906 0.9345853 0.07450109 -0.3392823 0.9377298 0.05860716 -0.2417626 0.968564 0.1044108 -0.1439123 0.984067 0.105982 -0.1445264 0.9838089 0.1026645 0.03278446 0.9941757 0.06898915 0.01595205 0.9974899 0.09306401 0.2393586 0.9664608 0.02867913 0.3787792 0.9250426 0.4983911 0.8653879 0.05205845 0.2463639 0.9661336 0.07675224 -0.5100516 0.8572363 -0.07066297 0.2436317 0.9698527 -0.005420804 0.3412783 0.9372566 0.07126849 0.5104761 0.8569694 0.07083517 0.3467082 0.9334772 0.09172695 0.2291166 0.9666519 0.1144101 0.6866368 0.7193796 0.1049901 0.6471406 0.7620089 0.02348369 0.6309046 0.7751532 0.03312087 0.6598147 0.7462639 0.0879482 0.6276561 0.7655306 0.1414595 0.4350106 0.8912357 0.128315 0.4933276 0.8635833 0.1041714 0.6311037 0.7751541 -0.02905678 0.6359412 0.7708557 -0.03688234 0.426977 0.9042618 0.001113414 0.5369786 0.8432574 0.02389717 0.3395386 0.9404615 0.01567691 0.1910999 0.981568 0.002261519 0.206447 0.9784534 -0.002946496 0.3105978 0.5818993 -0.7516131 0.8127729 0.3422536 -0.4714475 0.7038373 0.4021363 -0.5855762 0.5994715 0.508046 -0.6184846 0.7825078 0.4414018 -0.4391425 0.661652 0.5274181 -0.5329606 0.6397856 0.6321915 -0.437045 0.6071188 -0.4549697 -0.6514672 0.744173 -0.2356318 -0.6250473 0.7818211 -0.03655523 -0.6224305 0.6077356 -0.1329833 -0.782926 0.6949618 0.01690936 -0.7188478 0.6472597 0.06699663 -0.7593197 0.7316663 -0.4394735 -0.5210829 0.8080936 -0.3638392 -0.4632558 0.5414634 -0.5727405 -0.6154557 0.4288301 -0.6474164 -0.6300451 0.5485118 -0.6440898 -0.5331822 0.6362547 -0.5631472 -0.5273001 0.5945452 0.0866782 -0.7993766 0.5262863 0.302272 -0.794767 0.05639696 0.7911313 -0.609041 0.275046 0.7716354 -0.573523 0.3687053 0.7832229 -0.5006179 0.4163163 0.7541055 -0.5079427 0.456807 0.6848114 -0.5677682 0.7034431 -0.5357499 -0.4670545 0.4981929 -0.4736955 -0.7262344 0.8419868 -0.4104731 -0.3501002 0.7519989 -0.516906 -0.4090306 0.5729283 -0.4754062 -0.6676391 0.9145945 -0.3384432 -0.2212987 0.848232 -0.4084131 -0.3371964 0.6024105 -0.291063 -0.7432254 0.566659 -0.3170423 -0.7605142 0.7687748 -0.3761913 -0.5171706 0.9394247 -0.2217463 -0.2613614 0.9443374 -0.2237936 -0.2411295 0.8837383 -0.2964448 -0.3621148 0.8915745 -0.284801 -0.3521127 0.5842124 -0.1282075 -0.8014105 0.8836641 -0.1884432 -0.4285172 0.9637268 -0.124167 -0.2362484 0.8989788 -0.1849004 -0.3970504 0.6466645 -0.07809823 -0.7587659 0.9450614 -0.1023448 -0.3104588 0.5129649 0.007532954 -0.8583766 0.8115712 -0.04614114 -0.5824288 0.9055039 -0.02576428 -0.4235551 0.6728652 0.1591531 -0.7224423 0.4728038 0.1731175 -0.8639948 0.9559408 0.008498132 -0.2934369 0.9635491 -0.001095414 -0.2675294 0.9014915 -0.02502346 -0.432073 0.5876383 0.2781772 -0.7598018 0.9479332 0.1191554 -0.2953382 0.8547011 0.113963 -0.5064568 0.8922991 0.127105 -0.4331819 0.940195 0.1101663 -0.3223301 0.6097013 0.372963 -0.6994019 0.4085633 0.4679813 -0.783626 0.8242088 0.2371938 -0.5142169 0.4123004 0.4639075 -0.7840908 0.9414605 0.1939651 -0.2757349 0.5718304 0.5429235 -0.6150155 0.9175882 0.2483955 -0.3103731 0.3759056 0.6206147 -0.6881369 0.809867 0.3395217 -0.4783729 0.9231914 0.273941 -0.2695815 0.2099872 0.692264 -0.6904172 0.2760748 0.7127966 -0.644751 0.5310698 0.5574257 -0.6381548 0.609188 0.5799428 -0.5408849 0.8984904 0.3380029 -0.2801237 0.3843426 0.6595011 -0.6460178 0.7788963 0.4350418 -0.4517292 0.9024984 0.3448178 -0.2580648 0.7433797 0.532507 -0.4047505 0.7905265 0.4876139 -0.370541 0.8780856 0.4223703 -0.2248756 0.6739892 0.5940871 -0.4390889 0.7986049 0.5261866 -0.2921611 0.6259916 0.6796771 -0.3823264 0.5819885 0.7215425 -0.3750547 0.7596817 0.5942894 -0.2640148 0.7448282 0.596285 -0.299458 0.8157411 -0.3100252 -0.4883144 0.7399535 -0.2869912 -0.6083626 0.7827991 -0.2468333 -0.571226 0.8364473 -0.2232321 -0.5005231 0.7606024 -0.2128818 -0.6133233 0.7228882 -0.1432479 -0.6759533 0.8655195 -0.1020026 -0.490379 0.8081577 -0.04963797 -0.5868708 0.7518062 0.1754791 -0.6356057 0.8262219 0.07656085 -0.5581182 0.5041413 0.2956652 -0.8114331 0.6549935 0.3207333 -0.6841884 0.6910924 0.1349948 -0.7100477 0.3863506 0.4338418 -0.8139501 0.5668387 0.408547 -0.7153903 0.7406859 0.2613983 -0.6189147 0.8356055 0.2564008 -0.4858211 -3.01883e-4 0.9981651 -0.06055235 0.01564812 0.9838037 -0.1785655 0.03666234 0.9782009 -0.2043988 -0.01559799 0.9424694 -0.3339284 0.07804089 0.920861 -0.3820008 0.02580487 0.9996662 0.00134772 1.49304e-5 0.9999992 0.001299262 0.003239274 0.9999922 -0.002261638 0.01162642 0.9999282 -0.002920687 0.106675 0.8138689 -0.5711724 0.184861 0.861027 -0.4737712 0.3946489 0.82028 -0.4139963 0.3665081 0.8202401 -0.4391789 0.08816981 0.9245483 -0.3707244 0.5846021 0.7273741 -0.3593987 0.4637253 0.833789 -0.2995911 0.1546 0.9534558 -0.2588843 0.692194 0.703527 -0.1609885 0.06558644 0.9949517 -0.07595753 0.3528195 0.9356824 -0.004099309 -0.03682154 0.8786749 -0.4759986 0.7036852 0.6712541 -0.2329058 0.7344322 0.6544601 -0.1796982 0.3142149 0.894187 -0.3189023 0.6767719 0.6982663 -0.2332464 0.5398036 0.7888206 -0.2938953 0.3135241 0.8944993 -0.3187063 0.4897204 0.8532371 -0.1793336 0.2660759 0.9579322 -0.107562 0.2551739 0.9633076 -0.08321464 0.5925012 0.7909677 -0.1526848 0.4789211 0.8763687 -0.05111289 0.6674677 0.7428819 -0.05112183 0.4524886 0.8908048 -0.04148459 0.1730378 0.8589701 -0.4819008 0.3220674 0.9266776 -0.1937556 0.2105327 0.9390767 -0.2716814 0.4986396 0.8308178 -0.2471846 0.560616 0.7886529 -0.2524608 0.4961139 0.8491596 -0.181105 0.7193551 0.6810059 -0.1369642 0.6253621 0.7757161 -0.08477652 0.001235544 0.8938698 0.448325 0.0130729 0.8941694 0.4475381 -0.002721428 0.6344353 -0.7729713 0.002490043 0.6347897 -0.7726811 0.005720734 0.6379374 -0.770067 9.71676e-4 0.6384163 -0.7696907 8.05947e-4 0.8868939 0.4619726 -0.004991292 0.887156 0.4614427 -0.6009554 0.03959476 0.7983013 -0.7910884 -0.07543629 0.6070327 -0.8616021 0.03091645 0.5066421 -0.9954121 -0.0276547 0.0915966 -0.9986283 0.04982703 -0.01608514 -0.9681299 -0.03936076 -0.2473365 -0.8708575 0.04398983 -0.489563 -0.758382 -0.0663014 -0.6484296 -0.6249554 0.03596675 -0.7798315 -1 2.33195e-5 1.62599e-5 -1 4.05246e-5 9.13034e-5 -1 -7.98553e-5 -1.65135e-4 -0.9999998 -7.74934e-4 2.07747e-5 -0.9905806 0.1331696 0.03187662 -7.07567e-4 0.9999997 -4.19359e-4 -3.16403e-4 1 -3.64699e-4 0 1 -2.39536e-6 8.5689e-5 1 0 7.49187e-5 1 2.44146e-5 5.96779e-5 1 5.2029e-5 1.07371e-4 1 3.1042e-5 2.92058e-4 1 -2.52629e-5 2.79127e-4 1 -2.48592e-5 5.86524e-5 1 -4.46993e-5 0.009724259 0.9999287 0.006935536 2.91768e-7 1 4.99479e-6 -0.9999915 0 -0.004124999 -0.9397957 0.08569747 -0.3308175 0.6529752 -0.02674317 -0.7569071 0.6687331 -0.04099375 -0.7423716 0.8833507 0.0524199 -0.4657722 0.9535368 -0.06381517 -0.2944406 0.9972599 0.06061232 -0.04241365 0.9736284 -0.06485325 0.2187281 0.890787 0.04524475 0.4521633 0.8010165 -0.02793341 0.5979902 0.6616374 0.03215545 0.7491341 0.5979896 -0.006483495 0.8014777 0.9999499 -0.002003967 -0.009804427 0.9999933 -0.001888751 -0.003126561 0.9999988 -0.001384317 -7.73453e-4 0.9999997 -7.52492e-4 4.00877e-4 0.9999455 0.009699702 0.003883957 0.9999986 -0.0014835 7.34035e-4 0 1 1.33784e-6 -1.32444e-4 1 1.17603e-4 -5.20503e-4 1 1.06977e-4 -2.73495e-4 1 0 -1.33508e-4 1 1.49295e-4 -2.7146e-4 1 -1.09123e-5 0.04444402 0.9989027 0.01477032 3.27845e-7 1 -7.7377e-6 -0.001782417 0.9999965 0.001971065 -0.00346148 0.9999938 7.53417e-4 -1.97788e-4 0.999993 0.003723919 0 1 4.06404e-6 0 1 1.08184e-6 -0.002470672 0.9999961 0.00131309 0 1 0 0 1 -1.43577e-6 0 1 -5.58788e-6 0 1 1.0615e-6 0 1 1.07279e-6 0 1 2.78609e-6 0 1 3.16203e-6 1.01516e-5 1 -4.71732e-6 -2.10199e-7 1 -4.3487e-6 0 1 3.88545e-6 0 1 -6.00294e-6 5.8285e-5 0.9999917 0.004094064 0 1 1.33055e-6 0 1 -1.68443e-6 0 1 4.81571e-6 -2.76581e-4 0.9999967 0.00256133 0.001031041 0.999999 0.001049935 5.40872e-4 0.9999987 0.001557946 -6.2623e-4 0.999995 0.003097236 0.001778721 0.9999984 4.79623e-4 0 1 -3.50222e-6 0 1 1.16979e-6 0 1 1.07007e-6 0 1 -4.53917e-7 0 1 7.28513e-6 0 1 -8.722e-6 0 1 -6.93991e-7 0 1 -1.25762e-6 0.001375436 0.9999988 7.21698e-4 0 1 -7.66437e-6 0 1 8.69633e-6 0 1 3.43397e-6 0 1 2.05962e-7 0 1 3.77522e-6 0 1 1.6588e-6 0 1 -7.8203e-6 0 1 4.61351e-6 0 1 2.91251e-6 0 1 -8.28052e-6 -0.003612339 0.01011204 0.9999424 0.06416201 -0.08586007 0.994239 0.00147444 9.05816e-4 0.9999985 -1.62804e-6 -1 -5.45867e-5 0 -0.1304119 -0.9914599 -0.01675552 0 -0.9998597 0.9990856 0.04155659 -0.01006096 0.002141058 0.873094 0.4875473 -0.002837061 0.8171817 0.5763732 0.001960217 0.5171591 0.8558871 -0.001890659 0.3888728 0.9212895 0.002753734 0.09088099 0.995858 0.001529932 0.1878247 0.9822015 2.77638e-4 0.2331658 0.972437 0.002271354 0.116483 0.9931901 0.001644492 0.2003255 0.9797281 -0.001926362 0.03955167 0.9992158 0.9575805 0.009730517 -0.2880015 0.9862128 -0.01191633 0.1650531 0.9489601 0.009968936 0.3152387 0.7289262 -0.009066104 0.6845324 0.675448 0.004181265 0.7373958 0.1713384 -9.86609e-4 0.9852117 0.1004338 -0.01430642 0.9948409 -0.2496754 0.01365101 0.9682334 -0.5914973 -0.01629662 0.8061423 -0.7014003 0.009945392 0.7126982 -0.9591622 -0.007749557 0.2827504 -0.9767733 0.004107236 0.2142363 -0.9850319 -0.002820372 -0.17235 -0.9750626 0.004258215 -0.2218898 -0.8225928 -0.00638163 -0.5685953 -0.7437704 0.009681999 -0.6683651 -0.5296741 -0.009904921 -0.8481436 -0.2803347 0.01261377 -0.9598194 -0.102751 -0.01004391 -0.9946564 0.2714576 0.008857488 -0.9624097 0.443839 -0.01372957 -0.8960015 0.6708184 0.01337945 -0.741501 0.9076493 -0.0123803 -0.4195469 -0.005166232 0.02472341 -0.999681 -0.1948726 0.02915292 -0.9803953 -0.1402175 -0.01431673 -0.9900172 -0.08394652 0 -0.9964703 -0.2074975 0.01750844 -0.978079 -0.2960002 -0.02595549 -0.9548352 -0.3996731 0.02215576 -0.91639 -0.4783343 -0.02096682 -0.8779275 -0.5860081 0.02941763 -0.8097711 -0.6536279 -0.02293598 -0.7564684 -0.7555891 -0.001896798 -0.6550432 -0.7900091 0.02878338 -0.6124192 -0.8440456 -0.01538884 -0.5360507 -0.9174609 0.01384812 -0.3975849 -0.9315727 -0.008929252 -0.3634457 -0.9857894 0.01040935 -0.1676632 -0.9879931 3.95446e-4 -0.1544979 -0.9990601 -0.01184266 0.04169899 -0.9962169 0.01753479 0.08511424 -0.9713242 -0.01641452 0.2371919 -0.95726 0.01622062 0.2887737 -0.88902 -0.01477193 0.45763 -0.8655802 0.02244162 0.5002674 -0.7659547 -0.02609318 0.6423648 -0.6836112 0.02505677 0.7294162 -0.6392028 -0.01117062 0.7689571 -0.4998567 0.01556819 0.8659683 -0.4353923 -0.01831638 0.9000546 -0.3661337 0.01264661 0.9304763 -0.2436563 -0.02277696 0.9695941 -0.1347752 0.02574169 0.9905418 -0.03320908 -0.02802103 0.9990556 0.0999003 0.03075891 0.994522 0.2994571 0.01175701 0.9540374 0.246856 -0.02164232 0.9688104 0.4526497 -0.01642203 0.8915373 0.5200906 0.03054815 0.8535646 0.6526456 -0.0403397 0.7565888 0.7470939 0.04033923 0.6634935 0.8423374 -0.02708494 0.5382696 0.8903338 0.02323108 0.4547155 0.9372938 -0.02196949 0.3478471 0.9744288 0.02055382 0.2237542 0.9873812 -0.01465314 0.1576828 0.9995453 0.01404261 0.02668482 0.9994177 -0.01420831 -0.03102535 0.9859742 0.01595324 -0.166134 0.9763412 -0.01376032 -0.2157973 0.9278551 0.01022702 -0.3728008 0.9189688 -0.005806028 -0.3942876 0.8350678 0.006491065 -0.5501088 0.8253753 -0.007416307 -0.564536 0.6785441 0.01056218 -0.7344838 0.677439 0.008871972 -0.7355254 0.51896 -0.0251432 -0.8544287 0.4401252 0.03137332 -0.8973883 0.3357628 -0.03338485 -0.9413549 0.2098541 0.04300695 -0.9767864 0.214354 0.03638935 -0.976078 -0.5843896 -0.44304 -0.6798563 0.04932683 -0.05510538 -0.9972614 0.9988266 0.007154464 -0.04789769 0.9991853 -0.0059852 0.03991377 0.9068923 0.005774378 0.4213231 0.879412 -0.003748357 0.4760469 0.5118269 0.001155316 0.8590878 0.5215144 -0.001312196 0.8532416 -0.06112962 0.004394352 0.9981203 -0.06553494 0.003428339 0.9978444 -0.5486525 -0.01117867 0.8359758 -0.7159991 0.01729542 0.697887 -0.8702249 -0.01078087 0.4925369 -0.9933972 0.01027542 0.1142653 -0.9996542 -0.009074687 -0.02468228 -0.9051613 0.009185969 -0.424969 -0.8178474 -0.01168072 -0.5753167 -0.5609073 0.01439338 -0.8277536 -0.3866793 -0.01158678 -0.9221415 0.06298059 0.00306797 -0.99801 0.0525735 0.001032471 -0.9986165 0.4867599 0.004699766 -0.8735232 0.5626529 -0.007348775 -0.8266606 0.8289254 0.006680548 -0.5593192 0.8747497 -0.006422996 -0.4845327 0.9670479 -0.002253592 0.2545847 0.97685 0.004084587 0.2138865 0.9772726 -0.003381133 -0.2119594 0.969408 0.002258181 -0.2454446 0.675951 -0.004182517 -0.7369347 0.6709633 -0.002733647 -0.7414855 0.2180073 0.007923185 -0.975915 0.05302381 -0.01468449 -0.9984853 -0.2221273 0.01087111 -0.9749571 -0.5891731 -0.01582843 -0.8078518 -0.6808262 0.005831182 -0.7324219 -0.9580323 0.005971908 -0.2865982 -0.9774528 -0.0109995 -0.2108679 -0.9184129 0.005396306 0.3955863 -0.9375145 -0.007501184 0.3478654 -0.6172505 0.01191073 0.7866767 -0.4923887 -0.01470726 0.8702512 0.008232712 0.01259481 0.9998869 0.104589 -0.008093655 0.9944826 0.6835121 0.008436083 0.7298905 0.7183176 -0.002108573 0.6957122 0.9950166 0.01699185 0.09825032 0.9911825 -0.01483261 -0.1316716 0.8385713 -0.01464635 -0.5445952 0.7781639 0.01215004 -0.6279438 0.4838644 0.01447814 -0.8750233 0.1982235 -0.01482045 -0.9800449 -0.03661048 0.01202237 -0.9992574 -0.3279536 -0.01048159 -0.9446357 -0.5862185 0.008117675 -0.8101124 -0.7011069 -0.00700438 -0.7130218 -0.8950028 0.01041942 -0.445939 -0.9652283 -0.01036584 -0.2612028 -0.9908235 0.01038497 0.1347633 -0.9807828 1.05292e-4 0.1951034 -0.762755 -0.007582247 0.6466432 -0.6749269 0.01092922 0.7378036 -0.3354735 -0.01110124 0.9419842 -0.1885524 0.01198273 0.98199 0.3656271 -0.01101511 0.9306963 0.4077378 -0.001310646 0.9130982 0.7998014 0.007528066 0.6002176 0.8817241 -0.01537632 0.4715148 0.01086437 0.1846959 -0.9827357 0.005671143 0 0.999984 0 0.07409763 0.997251 0 1 -8.60662e-7 0 1 4.27997e-7 -0.002053022 0 0.999998 0 0.02359306 0.9997217 -0.06345796 -0.1151186 0.9913228 0.01265317 -0.1389983 0.9902118 0.6514452 -0.02454537 0.7582987 0.3558761 -0.1295794 0.9255061 0.7289699 0.01712691 0.6843315 0.2127819 -0.3425486 0.9150871 0.4717667 -0.2248991 0.8525589 0.879887 -0.01901829 0.4748023 0.6534172 -0.1610299 0.7396725 0.08524036 -0.4428359 0.8925416 0.03524923 -0.4536996 0.8904573 0.4124885 -0.3070509 0.8576556 0.7376468 -0.1760175 0.6518399 0.4834677 -0.3683909 0.7940701 0.8721714 -0.1091925 0.4768586 0.3946456 -0.4859517 0.7798114 0.9096655 -0.1304147 0.3943358 0.6970131 -0.3167575 0.6433021 0.09141141 -0.6393926 0.7634272 0.4194857 -0.5416294 0.7284706 0.9546487 -0.1058142 0.2782971 0.1944527 -0.6504864 0.7342041 0.7530129 -0.3367775 0.5652898 0.5524829 -0.5291554 0.6440164 0.7845002 -0.3222153 0.529846 0.04642099 -0.8137175 0.5794041 0.2227633 -0.7363987 0.6388219 0.5996572 -0.5747253 0.5568682 0.9751651 -0.1202539 0.1859899 0.1590293 -0.8530735 0.496966 0.4551469 -0.7093235 0.5382393 0.8752635 -0.3297902 0.3537687 0.7700085 -0.4905343 0.4079988 0.03182226 -0.926696 0.3744621 0.4225546 -0.7891127 0.4458125 0.9252665 -0.262039 0.2742581 0.4784739 -0.7537104 0.450537 0.5887213 -0.7049037 0.3956236 0.7625344 -0.5307122 0.3699811 0.2080672 -0.9332879 0.2927145 0.2920168 -0.9121194 0.287688 0.02619946 -0.9911534 0.1301098 0.6836715 -0.6936891 0.2266909 0.8683959 -0.4539678 0.1995043 0.5005664 -0.8485682 0.1713631 0.5137987 -0.8410566 0.1692178 0.8278136 -0.5339879 0.1719936 0.9581069 -0.2508075 0.1382996 0.237708 -0.97004 0.0501756 0.9890131 -0.1381167 0.05269765 0.2961394 -0.9520459 -0.07687687 0.8707213 -0.4873052 0.06616604 0.4118112 -0.9057601 -0.1000512 0.02172964 -0.9803274 -0.1961789 0.6552608 -0.7553639 -0.007665455 0.7446858 -0.6668791 -0.02674537 0.1696018 -0.9274769 -0.3331997 -0.08363145 -0.883532 -0.4608438 0.9483373 -0.3166878 0.01911115 0.4929665 -0.8324936 -0.2528604 0.6588076 -0.7137204 -0.2378566 0.790935 -0.6032577 -0.1024796 0.9553555 -0.2942336 -0.02688205 0.3594758 -0.8704304 -0.3363453 0.8803959 -0.4622808 -0.1058284 0.2167209 -0.8215963 -0.527268 0.3585025 -0.807594 -0.4682607 0.7181213 -0.6262567 -0.3034869 0.9874944 -0.1521967 -0.04112219 0.896595 -0.4136117 -0.158249 0.5981986 -0.656793 -0.4591095 0.6993439 -0.6132073 -0.3672805 0.2214118 -0.7357599 -0.6400268 -0.04065686 -0.6672391 -0.7437332 0.9393733 -0.3023056 -0.1618307 0.5864213 -0.6231375 -0.5175034 0.4685785 -0.6321939 -0.6170617 0.2332974 -0.5407842 -0.8081614 0.9365131 -0.2925339 -0.1933062 0.8965534 -0.3430792 -0.2801586 0.2126041 -0.4758251 -0.8534577 0.4698967 -0.5426558 -0.6962197 0.7795215 -0.4130129 -0.470921 0.8772162 -0.3294693 -0.3492016 0.6458263 -0.411746 -0.6429414 0.295874 -0.3806691 -0.8760991 0.6508997 -0.3812631 -0.6564816 0.4173471 -0.3416766 -0.842068 0.9315078 -0.2016202 -0.3027251 0.02150791 -0.2233347 -0.9745046 0.1366578 -0.1650232 -0.9767764 0.923917 -0.1804939 -0.3373416 0.7817122 -0.2141646 -0.5857129 0.993565 -0.07626962 -0.08373636 0.5180438 -0.2288746 -0.8241644 0.6820582 -0.2828038 -0.6744025 0.4625698 -0.1222496 -0.8781142 0.9401265 -0.1047879 -0.3243172 0.08416175 0.03517699 -0.995831 -0.1361357 0.1029098 -0.9853308 0.4704617 -0.1119157 -0.8752948 0.8209184 -0.1247774 -0.5572465 0.3894592 0.05674326 -0.9192942 0.9651353 -0.06264901 -0.2541439 0.784973 -0.03443926 -0.6185721 0.2188463 0.2300601 -0.9482503 0.4119641 0.08514976 -0.9072128 0.3026755 0.2191047 -0.9275671 0.7996079 0.002041816 -0.600519 0.6560807 0.1234432 -0.7445267 0.05017209 0.4420648 -0.8955789 -0.03563427 0.4671857 -0.8834409 0.4781838 0.3046267 -0.8237371 0.9581168 0.02107644 -0.2856014 0.9017519 0.04526585 -0.4298772 0.6681959 0.2147274 -0.7123247 0.6362832 0.2463483 -0.7310651 0.3986415 0.4045667 -0.8230496 0.9873618 0.03539347 -0.15448 0.8551567 0.1694871 -0.4898788 0.233893 0.6065698 -0.7598469 0.3009617 0.5974234 -0.7433085 0.4654111 0.4926986 -0.7352827 -0.0485481 0.7257885 -0.6862028 0.8868828 0.2110668 -0.4109622 0.6325122 0.4545821 -0.6271232 0.7259114 0.373497 -0.5775402 0.8610992 0.2749702 -0.4276678 0.4129008 0.6621304 -0.625377 0.6019129 0.5801905 -0.5487076 0.2636371 0.7791992 -0.5686335 0.8931584 0.2968869 -0.3378255 0.2759438 0.800186 -0.5325012 0.163487 0.8657842 -0.4729585 0.6699464 0.5791917 -0.4644448 0.4697713 0.759041 -0.4507461 0.6395018 0.6413903 -0.4238585 0.9924747 0.0986132 -0.07259172 0.02087801 0.9671161 -0.2534771 0.8853566 0.3595511 -0.2947319 0.8866974 0.3569152 -0.2939039 0.2258107 0.9090593 -0.3501723 0.4615306 0.8410714 -0.2821141 0.4651873 0.8387256 -0.2830908 0.7462092 0.6021332 -0.2839146 0.8419831 0.4805513 -0.2452245 0.9718376 0.2003419 -0.124076 0.699899 0.6709423 -0.2449039 0.2900853 0.951084 -0.1062539 0.4208165 0.8955065 -0.1448512 0.2372291 0.9713996 -0.01025718 0.7808901 0.6138033 -0.1160013 0.92796 0.357707 -0.1045746 0.9460081 0.3098477 -0.09520018 0.6623921 0.7476339 -0.04775297 0.8851209 0.4587948 -0.07789993 0.0535283 0.971136 0.2324431 0.2927914 0.9532427 0.07484412 0.2105847 0.9620324 0.1736308 0.5515519 0.8283435 0.09817129 0.8998249 0.4362061 -0.006277382 0.6700167 0.7413721 0.03801363 0.7822135 0.6188097 0.07222634 0.5501858 0.8054434 0.2203559 0.9903784 0.1380265 -0.009969711 0.02129763 0.8819659 0.4708318 0.4611216 0.847715 0.2621953 0.1605397 0.8984587 0.4086551 0.3754957 0.8416323 0.3881473 0.6883453 0.6867617 0.2335362 0.9570274 0.2887794 0.02655327 0.7975426 0.5843793 0.1497554 0.1917233 0.7961153 0.5739709 0.4571371 0.7776759 0.4315622 0.6892244 0.6476117 0.3249135 0.8879162 0.4316914 0.1588947 0.7604823 0.5608846 0.3272235 -0.08540725 0.697255 0.7117171 0.3801398 0.7402636 0.5545302 0.4090948 0.7404418 0.5332799 0.9470584 0.3062575 0.09636813 0.8790546 0.4388431 0.186225 0.1636548 0.6451365 0.746335 0.3776845 0.6432552 0.6660158 0.4778233 0.5784613 0.6611108 0.7618468 0.4970329 0.4153887 0.9849763 0.1508288 0.08409798 0.7662342 0.4875753 0.4185161 0.9631006 0.2124138 0.1652811 0.220846 0.512941 0.8295291 0.7196338 0.4723803 0.5089048 0.396044 0.4429065 0.8043526 0.4708666 0.4541688 0.7563171 -0.08159625 0.4199197 0.9038858 0.1403979 0.3437814 0.928495 0.3803502 0.359191 0.8522415 0.9492507 0.2107736 0.2334473 0.9345527 0.2385725 0.2639971 0.7680648 0.3462492 0.5386911 0.33281 0.3292524 0.8836461 0.7516854 0.3320135 0.5698562 0.02359271 0.182757 0.982875 0.9696231 0.1317048 0.2061188 0.3948606 0.202359 0.8961786 0.1593971 0.1336229 0.9781296 0.7844337 0.2222405 0.5790275 0.7095368 0.2010074 0.6753914 0.2001544 0.04323446 0.9788101 0.4919748 0.1532533 0.8570148 0.4389992 0.005458533 0.8984709 0.6648612 0.1540957 0.7308995 0.9057842 0.1284264 0.403809 0.4377443 0.005071938 0.8990853 0.9323689 0.0251547 0.360632 0.9911876 -0.007840454 0.1322339 0.9999782 -0.004464566 0.004887104 0.9999759 -0.005428373 0.004324316 0.9999854 -0.005342602 9.25025e-4 0.9999979 -2.8961e-4 0.002050042 0.999995 -0.003101408 6.29271e-4 0.9999938 -0.003364384 -0.001090347 0.9999406 0.004944324 0.009712815 0.9999934 -0.003509044 -0.001018822 0.99994 0.005475997 0.009492993 0.999994 -0.002624869 -0.00224173 0.9999723 -5.88372e-4 0.007419943 0.9999562 -0.002397298 -0.009052157 0.9999809 0.005849659 0.002024769 0.9999779 0.006091117 0.002693951 0.9999557 -0.003136217 -0.008887827 0.9999703 -0.005082905 -0.005805671 0.9999778 0.006437897 0.001735329 0.9999665 0.003596365 -0.007369816 0.9999943 0.00334227 -5.07335e-4 0.9999529 0.002854168 -0.009287774 0.9999595 0.006359279 -0.006391584 0.9999754 0.002299785 -0.006632328 -0.02032178 0.06141352 0.9979056 -0.004865348 0.2585678 0.9659809 0.02033442 0.3430745 0.9390882 -0.002762496 0.3997079 0.9166385 -0.01391196 0.584164 0.8115165 0.01953625 0.6876919 0.7257397 -0.005881726 0.7381204 0.6746435 -0.0136345 0.8530634 0.5216292 6.87602e-4 0.8791726 0.4765031 0.003768384 0.9607349 0.2774427 -0.002945601 0.9411031 0.3381069 -0.007739186 0.9824448 0.1863933 0.008068263 0.9969937 -0.07706159 -0.001636147 0.999534 -0.03048372 -0.008531272 0.9703218 -0.241667 -4.81974e-4 0.9041086 -0.4273025 0.008588135 0.8869844 -0.4617199 -0.01145476 0.773544 -0.6336392 4.74037e-4 0.645772 -0.7635301 0.003288388 0.6516651 -0.7584998 -0.01917809 0.5301949 -0.8476589 0.0122388 0.3506131 -0.9364405 0.006855487 0.3642356 -0.9312817 -0.01098221 0.2487894 -0.9684954 -0.01483607 0.1250079 -0.9920448 0.013767 -0.03627926 -0.9992468 0.01403021 -0.03689724 -0.9992207 -0.01888459 -0.2167279 -0.9760494 -0.005226373 -0.3705765 -0.9287873 0.01244688 -0.4216787 -0.9066599 -0.007900416 -0.4876277 -0.8730159 -0.0105617 -0.6634067 -0.7481846 0.0202701 -0.7403078 -0.6719626 -0.005246579 -0.7903935 -0.6125772 -0.01717931 -0.8671326 -0.497781 0.01494115 -0.943782 -0.3302306 0.01402854 -0.943122 -0.3321509 -0.01832395 -0.9897813 -0.1414114 0.01768004 -0.9980563 0.05975919 4.78451e-5 -0.9950178 0.0996983 -0.0190764 -0.9672854 0.2529724 0.002457797 -0.9106591 0.4131513 0.01505345 -0.8967348 0.4423125 -0.007257521 -0.8454358 0.5340276 -0.01180964 -0.7353997 0.6775307 0.001903712 -0.6748504 0.7379522 0.01200115 -0.6549224 0.7556009 -0.00636202 -0.589288 0.8078981 -0.01452696 -0.4527531 0.8915176 0.01190435 -0.3424463 0.939462 -0.007548093 -0.2664939 0.9638071 0.01021265 -0.06940501 0.9975364 0.007794976 -0.06392759 0.9979242 0.0114665 0.8892613 -0.457256 -0.0111069 0.9003348 -0.4350562 0.002205729 0.9955068 -0.09466415 -0.008939087 0.9940382 -0.1086658 0.01618337 0.9869209 0.1603908 -0.01915544 0.9743533 0.2242074 -0.1935535 -0.5049921 0.8411422 -0.1991954 -0.4985088 0.8436884 -0.2950377 -0.4467007 0.8446367 -0.2732933 -0.4510926 0.8496036 -0.3419996 -0.4013772 0.8496662 -0.4589451 -0.2225407 0.8601425 -0.439413 -0.2980447 0.8473994 -0.3532413 -0.3788089 0.8554089 -0.4185692 -0.3646398 0.8317679 -0.4449002 -0.3097802 0.8402976 -0.9999902 0.001718103 -0.004095673 -0.9999997 4.41638e-4 -6.44735e-4 -0.9999994 -0.001056194 1.96755e-4 -0.9999998 2.62666e-4 6.88264e-4 -0.9999995 -8.1224e-4 -7.81436e-4 -1 -6.31367e-5 -7.62006e-6 -0.9999998 3.91223e-4 4.9749e-4 -1 -2.85595e-5 -9.92768e-5 -1 -8.97006e-5 -1.44168e-4 -0.9999999 1.76182e-4 -5.62321e-4 -0.9999994 0.001097679 5.68208e-5 -0.9999994 0.001115679 3.48001e-4 -1 1.45852e-4 2.5718e-5 -0.9998167 0.008625268 0.01709747 -0.9999998 -1.87819e-4 -6.31577e-4 -0.9999974 -6.63834e-4 0.002203166 -1 8.2483e-5 -4.19366e-4 -1 2.25525e-5 -2.08541e-4 -0.9999877 0.004649221 0.00176841 -0.002469956 -0.002858638 0.999993 0.002262413 0.001726925 0.999996 0.002695322 -0.002364158 0.9999936 0.0177257 0.05053573 0.998565 -1 6.97415e-6 -7.6868e-6 -1 9.02642e-6 -4.36819e-6 -1 2.98935e-6 -2.17423e-5 -1 4.84093e-6 -1.3103e-5 -1 1.80168e-6 -2.25042e-5 -1 2.70674e-6 -7.02803e-6 -1 1.50858e-5 -7.74987e-7 -1 1.18137e-4 6.91692e-5 -1 -1.16998e-6 -2.64219e-7 -1 1.89768e-6 9.15872e-6 -1 3.13482e-5 2.53441e-5 -1 -3.85216e-7 -6.03495e-7 -1 -6.1317e-7 -4.64008e-6 -1 -1.8066e-6 -3.42457e-6 -1 4.8991e-5 -8.9177e-5 -1 -1.30479e-6 -5.45188e-6 -1 2.18776e-5 -5.7668e-5 -1 1.74137e-5 1.90796e-5 0.001355588 -3.95414e-4 -0.9999991 6.8285e-4 5.7258e-4 -0.9999997 -1.56747e-4 1.23523e-4 -1 2.08488e-5 1.80796e-4 -1 1.25983e-4 9.11743e-5 -1 -3.50847e-5 5.35702e-5 -1 8.72291e-4 -6.15551e-4 -0.9999995 1 1.67165e-5 2.79749e-5 1 -5.62346e-6 -5.50168e-6 1 1.48732e-5 7.61705e-6 1 9.58804e-5 -1.40038e-4 1 2.29905e-5 -1.0683e-5 1 2.35253e-5 -4.37773e-6 1 2.53114e-6 0 0.3969777 -0.49728 0.7714412 0.4481076 -0.7699736 0.4542471 0.8149816 -0.5044769 0.2851462 0.7855463 -0.5369374 0.3075961 -0.6980993 -0.676525 -0.2344595 -0.4409726 -0.8974259 0.01304149 0.002593398 -0.9338535 -0.3576466 -0.009522199 -0.9963793 -0.08448559 0.2805137 0.4198311 0.8631651 -0.4759677 -0.3218048 0.818472 -0.6927304 -0.4099779 0.593332 -0.005562067 -0.5526418 0.8334004 0.002699673 -0.4166445 0.9090656 0.6445248 0.3405319 -0.6845626 0.6441299 0.001865804 -0.7649139 0.6471307 0.002130389 -0.7623762 -0.6557427 -0.4704553 -0.5904857 -0.4837967 -0.3923183 -0.7823216 0.004405617 -0.6638091 -0.7478891 -0.002658486 -0.566962 -0.8237397 -0.702113 -0.6180582 -0.3536122 -0.6561328 -0.6528282 -0.3785567 0.4840518 0.869934 0.09438639 0.638314 0.6685639 -0.3815464 0.7371516 0.5840941 -0.339767 0.88593 0.4033091 -0.2290631 -0.6068005 0.3024789 0.7350509 -0.5276314 0.3628398 -0.7680836 -0.9035311 0.001699149 -0.4285192 -0.8621826 -3.49341e-4 -0.5065976 -0.622884 0.006226718 -0.7822895 -0.4128694 -0.003155469 -0.9107849 -0.5127024 0.8563253 -0.06199377 -0.3689554 0.9215809 0.1206672 -0.8328113 0.5535207 0.00634551 -0.8899448 0.3948724 -0.2281978 -0.8996103 0.3786888 -0.217477 -0.611257 0.6819304 -0.4016666 -0.3829256 0.8012928 -0.4596714 -0.8474027 0.4608902 0.2636077 -0.6936103 0.6200184 0.3667178 -0.3915082 0.7982852 0.4576704 0.003305912 0.9993156 0.03684443 1.53707e-4 0.9958418 0.09109944 0.005076289 0.6062973 -0.795222 -0.00340718 0.4557009 -0.8901264 -0.8281373 -0.004557132 0.5605068 -0.6343103 0.005707859 0.7730576 -0.4180217 -0.002938807 0.9084324 -0.001295447 0.4584448 0.888722 -0.002112507 0.4467927 0.894635 0.5143278 0.7417526 0.4304303 0.5604786 0.7173308 0.4138846 0.7533844 0.5677 0.3318568 0.9014839 0.3764033 0.2136526 -0.8170756 -0.5008973 0.2854638 -0.6839374 -0.6296458 0.3684779 -0.4732693 -0.7644035 0.4378395 0.471253 0.003412306 0.8819915 0.6162568 -0.002289652 0.787542 0.7802579 -5.96584e-5 0.625458 0.8439798 -0.00344932 0.536364 -0.005341708 -0.8666149 -0.4989491 -0.00695008 -0.8659511 -0.5000805 0.003947138 -0.8675338 0.4973626 -0.004561781 -0.864527 0.5025657 0.001880586 3.78366e-4 0.9999982 -0.002460062 -0.002802073 0.9999932 -4.93761e-4 0.001681327 -0.9999985 0.001511454 2.49125e-4 -0.9999989 -0.9991676 0.03523164 0.0205658 -0.9999342 -0.009847462 0.005884826 -0.9999574 -0.008560657 0.003462731 -0.9986279 -0.02665269 -0.04507702 -0.9999148 -0.00528419 -0.01194864 -0.9999898 0.00176835 0.004194974 -0.99971 -0.0128867 0.02034682 -0.9998918 0.0115664 0.009100496 -0.9997971 0.01995623 -0.002741456 -0.999374 -0.02743327 0.02234256 -0.9993544 0.03541439 -0.006061792 -0.9999893 -0.003635108 -0.002899944 -0.9999356 0.006765663 0.009125769 -0.9997765 -0.006279945 0.02019095 -0.9996717 -0.006622374 -0.02475243 -0.9999949 0.003123164 -6.99933e-4 -0.999998 -7.64382e-5 -0.002008199 -0.999997 0.002338051 -7.11805e-4 -0.9999601 -0.004122376 -0.00793308 6.29884e-4 0.8654493 -0.5009963 4.83399e-4 0.8655025 -0.5009043 -0.003413796 0.8640908 0.5033246 0.001983284 0.8660217 0.5000025 0.7581229 -0.3648055 -0.5405245 -0.7139876 -0.5659912 -0.4121598 0.5844478 -0.7483654 -0.3136401 -0.519917 -0.8530274 -0.04506242 0.01556158 -0.9980656 0.06019097 -0.2636092 -0.9050778 0.3336831 0.2015088 -0.8790162 0.4321166 -0.3223814 -0.7240844 0.6097312 0.3672425 -0.5454398 0.7534111 -0.4958429 -0.38846 0.7766845 0.6190605 -0.09378528 0.7797234 -0.636666 0.1242731 0.7610603 0.6141902 0.3244301 0.7193855 -0.6968961 0.4858701 0.5275095 0.7420625 0.5740141 0.3461953 -0.6320474 0.7602742 0.1499975 0.4770923 0.8742846 -0.0894953 -0.5516377 0.6724992 -0.4933971 0.4618266 0.5647693 -0.6839239 -0.4844345 0.3041622 -0.8202491 0.2064943 -0.1036467 -0.9729427 0.07739609 -0.6034035 -0.7936713 -0.2912366 -0.6133321 -0.7341696 0.3109041 -0.8812765 -0.3559362 0.02443587 -0.9414111 -0.3363751 -0.4197964 -0.9019026 0.1016989 0.4661113 -0.8690352 0.1658861 0.03085833 -0.8172881 0.5754026 -0.4559885 -0.4105275 0.7896466 0.5809079 -0.1697318 0.7960761 -0.5795641 0.04224014 0.8138313 0.3519082 0.3781605 0.8562448 0.498994 0.3600578 0.788266 -0.5419705 0.6451395 0.5385751 0.6521266 0.6500012 0.3901659 -0.6542767 0.7508847 0.08996903 0.5632455 0.8260378 -0.02040386 -0.3966398 0.8232115 -0.4062018 0.3635751 0.7985594 -0.4797044 -0.5248986 0.5204147 -0.6735355 0.7020861 0.3355085 -0.6280997 -0.6350424 0.05536574 -0.7704907 0.479023 -0.1209769 -0.8694261 -0.4334169 -0.3208619 -0.8421387 0.5226629 -0.4630835 -0.7158052 -0.4432551 -0.716586 -0.5385438 0.3186939 -0.9301839 -0.1821874 -0.1603929 -0.9443004 0.2873518 -0.2042173 -0.7107636 0.6731347 0.538936 -0.385232 0.7490957 -0.534063 -0.2196221 0.8164209 0.1993187 0.07884061 0.9767581 0.1991136 0.5021985 0.8415169 -0.4724636 0.7051224 0.5287539 0.4414985 0.7712816 0.4584799 -0.2300279 0.9591865 0.1644642 0.1820389 0.9537063 -0.2393873 -0.3829147 0.7578854 -0.5281912 0.0772764 -0.2474913 -0.9658035 0.008045732 -0.628857 -0.7774794 -0.3510044 -0.6307356 -0.6920755 0.4391459 -0.8038167 -0.4012851 -0.2038911 -0.9171426 -0.3424585 -0.2772 -0.9599155 0.04150342 0.5190465 -0.8487629 0.1009581 -0.5285454 -0.7405323 0.415032 0.6826323 -0.5709919 0.4560497 -0.70688 -0.3098881 0.635838 0.675823 -0.1687324 0.7174906 -0.5116925 0.05581086 0.8573541 0.4629406 0.2887564 0.8380369 -0.3337572 0.4503077 0.8281481 0.1725212 0.715698 0.6767665 -0.3758001 0.8969196 0.2330443 0.3770691 0.8888475 -0.2603249 0.03148341 0.9462566 -0.3218808 -0.2616026 0.633185 -0.728451 0.3476763 0.5795184 -0.737075 -0.415201 0.2202231 -0.882672 0.285097 0.1779427 -0.9418366 0.1899392 -0.258865 -0.9470544 -0.652266 -0.3135924 -0.690079 0.4772356 -0.5363386 -0.696123 -0.3448514 -0.8040917 -0.4842666 0.3410747 -0.9056509 0.2519218 -0.3323129 -0.7682731 0.5471056 0.2975315 -0.7330062 0.6117001 -0.3344026 -0.420687 0.8433253 -0.3497279 -0.4192536 0.8378049 0.5766322 -0.08915436 0.812125 -0.5826372 0.1235311 0.8032895 0.4152734 0.3851012 0.8241633 -0.350399 0.893647 0.2803847 0.3390254 0.9406778 0.01367878 -0.2959204 0.9481601 -0.1158603 0.3875995 0.8302824 -0.400497 -0.1767776 0.8463911 -0.5023661 -0.1330078 0.5112756 -0.8490621 0.3614355 0.09075993 -0.9279693 -0.4817672 -0.2078744 -0.8512865 0.5355635 -0.3488897 -0.7690565 -0.5951874 -0.5394436 -0.595611 0.7013224 -0.5721591 -0.4251833 -0.6515228 -0.7384011 -0.1740173 0.6348152 -0.7725954 0.01030141 -0.4981336 -0.5389299 0.6792772 0.4990724 -0.3530145 0.791396 -0.4778133 -0.08782666 0.87406 0.1834375 -0.02141422 0.9827982 -0.2425739 0.3625172 0.8998551 0.4133598 0.3881453 0.8236971 -0.4773956 0.6917338 0.5418466 0.4310973 0.8893818 -0.152168 -0.4524226 0.7174738 -0.5296653 -0.05900371 0.7845318 -0.6172751 0.475022 0.4135984 -0.7767177 -0.4682413 0.2810072 -0.8377261 0.1098615 -0.03417533 -0.9933592 0.102782 -0.4841814 -0.86891 -0.472921 -0.8014079 -0.3661848 -0.06409406 -0.8814147 -0.4679746 0.5764958 -0.8154429 -0.0520159 -0.5897845 -0.7899397 0.1677784 0.3507311 -0.8382488 0.4175245 -0.3652042 -0.7480604 0.5541044 0.474811 -0.594582 0.6488657 -0.4060764 -0.3652974 0.8376514 0.2003645 0.3649035 0.9092302 -0.4605905 0.6151969 0.6398354 0.6562828 0.6016611 0.4552987 -0.5178474 0.8031398 0.2946196 0.3902179 0.9206861 -0.008200228 -0.0223881 0.9996445 0.01448088 -0.01261156 0.8870149 -0.4615687 0.2675145 0.8710686 -0.4119171 -0.3259083 0.5887163 -0.7397276 0.5314124 0.4539399 -0.7152199 -0.2609507 0.2960649 -0.918831 0.3426604 0.0203647 -0.9392387 -0.01547902 -0.05862224 -0.9981603 0.3320626 -0.3266642 -0.884887 -0.3691748 -0.4386992 -0.8193004 0.2142218 -0.7402378 -0.6373046 0.5215235 -0.6604053 -0.5402575 -0.6634131 -0.7347654 -0.1414316 0.2107518 0.9759382 -0.05593228 0.8692299 0.461835 -0.1764875 0.699654 0.540481 -0.4672951 0.8193315 0.4050135 -0.4057835 0.8308497 0.1681973 -0.5304701 0.8371788 0.1617496 -0.5224642 0.7963626 -0.07783627 -0.5997902 0.8654595 -0.110886 -0.4885533 0.7363596 -0.380649 -0.5593576 0.8527696 -0.3462344 -0.3910319 0.8393431 -0.4878335 -0.2398367 0.8130154 -0.5309454 -0.2389626 0.8286241 -0.5597854 0.004751622 0.8017542 -0.5975367 -0.0118364 0.8201004 -0.5240095 0.2298901 0.8011362 -0.551718 0.2319228 0.8547506 -0.3905808 0.3418304 0.7631158 -0.3945485 0.5118457 0.8579106 -0.2442218 0.4520456 0.8009037 -0.08281749 0.5930384 0.7993546 -0.08384484 0.594981 0.8678332 0.1297459 0.4796161 0.7696527 0.253232 0.5860958 0.8813315 0.3101337 0.3564715 0.7417955 0.5742778 0.3463301 0.8356728 0.4917207 0.2446666 0.8621909 0.5034701 0.05607777 0.7348912 0.6739871 -0.0753408 0.7947282 0.5938623 -0.1254391 0.7733619 0.580005 -0.2559409 0.8531243 0.4486724 -0.2662181 0.8085627 0.3884499 -0.4419649 0.861834 0.2976592 -0.4106593 0.7719045 0.1842836 -0.6084432 0.8432452 0.04774647 -0.5354046 0.7875655 -0.008019447 -0.6161788 0.8756467 -0.1099587 -0.4702681 0.768854 -0.3678137 -0.5230457 0.8358752 -0.3452144 -0.4267783 0.8430744 -0.4550908 -0.2865628 0.748831 -0.606424 -0.2673987 0.8723881 -0.4789798 -0.09755742 0.7409308 -0.648209 0.1756319 0.8642436 -0.4975742 0.07418107 0.7559812 -0.5258945 0.389779 0.8253828 -0.4090619 0.3891163 0.7890543 -0.3878604 0.4764007 0.8557783 -0.1983662 0.4778017 0.7565543 -0.1471166 0.6371675 0.8868108 0.04943305 0.4594812 0.8860206 0.05739748 0.4600794 0.7189774 0.278823 0.6366548 0.8503571 0.2750466 0.4486003 0.8425007 0.4262816 0.329358 0.7598208 0.5534808 0.3410738 0.8655678 0.4830053 0.1322817 0.7669255 0.6417236 -0.004027307 0.8799278 0.4685637 -0.0785824 0.7690547 0.557424 -0.3127835 0.879559 0.3697716 -0.2994076 0.8789523 0.358754 -0.3142269 0.7127267 0.3312069 -0.6183224 0.8733193 0.1556841 -0.4616017 0.8030663 -0.06569254 -0.5922577 0.8021639 -0.06643903 -0.5933961 0.8544156 -0.1893104 -0.4838755 0.7959753 -0.3155276 -0.5165907 0.8580347 -0.3315572 -0.3922326 0.7693938 -0.5266991 -0.361416 0.8272564 -0.513206 -0.2286188 0.7359643 -0.6556153 -0.1688939 0.8740774 -0.485167 0.0245319 0.7521909 -0.626895 0.2030065 0.8196074 -0.5046752 0.2711951 0.7709001 -0.5192123 0.3689604 0.8580286 -0.3046348 0.413503 0.7736663 -0.3023245 0.5568128 0.868296 -0.050502 0.4934691 0.7181719 0.008608102 0.6958125 0.8192157 0.06255722 0.5700636 0.7619658 0.258831 0.5936452 0.796586 0.2516981 0.5496352 0.8681154 0.3417438 0.3599819 0.7653526 0.5454659 0.3416174 0.8583791 0.4764875 0.1901186 0.7554465 0.6503468 0.07968538 0.8092212 0.5853742 -0.04998028 0.7746929 0.6254488 -0.09308469 0.8596487 0.4307898 -0.274635 0.8151156 0.4399412 -0.3768797 0.7926963 0.4852734 -0.3689748 0.7415704 0.3790988 -0.5534957 0.8345048 0.2495976 -0.491226 0.737516 0.1194104 -0.664689 0.8121386 -0.01177948 -0.5833458 0.7609449 -0.09410285 -0.6419561 0.8643774 -0.1853535 -0.4674353 0.7889506 -0.3634378 -0.4954494 0.8610444 -0.3578395 -0.3613218 0.7862337 -0.544941 -0.2913349 0.8239034 -0.5088688 -0.2494714 0.8689582 -0.4920553 -0.05285042 0.7461099 -0.6625228 0.0662086 0.8596955 -0.4904396 0.1428031 0.7526001 -0.5178242 0.4067569 0.8472402 -0.3939875 0.3563114 0.8664166 -0.2019861 0.4566443 0.7368054 -0.158378 0.6572932 0.8612455 -0.01853024 0.5078513 0.799157 0.1771824 0.5744166 0.8106428 0.1786627 0.5576182 0.8531474 0.3192752 0.4125565 0.752657 0.491194 0.4384474 0.8140671 0.4969381 0.3005783 0.7477527 0.6112299 0.2593531 0.8705413 0.4839769 0.08901768 0.7339909 0.6559355 -0.1760854 0.8280484 0.5320993 -0.1766535 0.8662092 0.3879698 -0.3148987 0.7643184 0.4139526 -0.4944297 0.8549551 0.2612562 -0.448104 0.8138315 0.1275343 -0.5669333 0.8102791 0.1307736 -0.5712672 0.8581073 -0.06286865 -0.5096071 0.8022436 -0.1324526 -0.582118 0.7770969 -0.3279796 -0.5371685 0.854126 -0.3015033 -0.4237505 0.8588937 -0.423089 -0.288613 0.795107 -0.5308163 -0.2933243 0.7628893 -0.6382065 -0.1034038 0.8056034 -0.5893383 -0.06069391 0.756047 -0.6416277 0.1292551 0.8458046 -0.5097405 0.1574151 0.7401295 -0.4808293 0.4701187 0.8423898 -0.4298329 0.3249974 0.8717894 -0.3244028 0.367078 0.8009787 -0.2987065 0.5188522 0.8529326 -0.1595707 0.4970345 0.7775649 -0.08126914 0.6235288 0.8520534 -0.00216335 0.5234506 0.8241869 0.2026146 0.528832 0.7526165 0.2850908 0.5935419 0.8049592 0.3760133 0.4589715 0.7469552 0.4866198 0.4530553 0.8213201 0.5112595 0.2530752 0.8527559 0.4505473 0.2642246 0.8066456 0.590305 0.02937501 0.8538983 0.5203759 -0.008165478 0.8051753 0.5469951 -0.2291053 0.7885319 0.5624777 -0.2486691 0.8827533 0.3368241 -0.3275611 0.7380839 0.3342916 -0.5860729 0.8159631 0.1914315 -0.545489 0.7327004 0.1094153 -0.6716983 0.8632535 -0.04360073 -0.502884 0.8417436 -0.2554183 -0.4756356 0.7641423 -0.2558546 -0.5921359 0.8179724 -0.437651 -0.3733403 0.7672047 -0.5115364 -0.3869463 0.8748781 -0.4620283 -0.1453216 0.7121122 -0.7001526 0.05179399 0.8016108 -0.5977445 0.01103258 0.7967644 -0.554173 0.2409541 0.8395017 -0.4843834 0.2461903 0.8065272 -0.4553923 0.3770037 0.8183131 -0.4362078 0.3742814 0.8112719 -0.2538423 0.5266897 0.8418481 -0.2159945 0.4946091 0.792738 -0.03788375 0.6083844 0.8614224 0.02130341 0.5074421 0.7844211 0.2474906 0.5687109 0.831845 0.2433347 0.4988209 0.8576597 0.3734691 0.3534696 0.7681348 0.5223579 0.3702852 0.7842019 0.5901734 0.1916319 0.7656478 0.6171645 0.18136 0.7988424 0.6003043 -0.03854268 0.7731603 0.6308367 -0.06533271 0.8520041 0.4540609 -0.2606106 0.8179259 0.4691985 -0.3329414 0.807883 0.4852983 -0.334381 0.7956879 0.3009001 -0.5256804 0.8376965 0.2544664 -0.4832303 0.85403 0.05394113 -0.5174199 0.7516025 -0.03846442 -0.6584938 0.8140769 -0.1672574 -0.556151 0.7390133 -0.2760663 -0.6145297 0.8697072 -0.2999522 -0.391967 0.7854731 -0.5331944 -0.3142227 0.7858037 -0.5329177 -0.313865 0.8287934 -0.5570976 -0.05238145 0.8268506 -0.5598686 -0.0535292 0.8570225 -0.4927005 0.1508597 0.7857026 -0.5619371 0.2586473 0.8517359 -0.4082729 0.3284196 0.799636 -0.4182174 0.4309021 0.8567804 -0.2466002 0.4528971 0.7645784 -0.2106093 0.6091501 0.7655587 -0.0513519 0.6413134 0.7874049 -0.0333364 0.615534 0.7773748 0.1778085 0.6033843 0.785777 0.1780771 0.5923202 0.8457512 0.3660017 0.3882626 0.7321451 0.5404359 0.4145995 0.8675115 0.4438838 0.2244797 0.8202419 0.5705122 0.04145973 0.8636048 0.5039202 0.0158478 0.8792232 0.4306771 -0.2036759 0.8598993 0.4653205 -0.2098809 0.8127482 0.3338284 -0.4774923 -0.9461179 -0.1766143 0.2714194 -0.8329679 -0.2314421 0.5025925 -0.881826 0.05997514 0.4677457 -0.812139 0.1065652 0.5736498 -0.7614203 0.442402 0.4738351 -0.852591 0.324679 0.4094779 -0.8532627 0.4427956 0.2754541 -0.7542909 0.6457236 0.1186864 -0.870527 0.4921054 -0.003894567 -0.7573529 0.6293065 -0.1743274 -0.8110446 0.5136024 -0.2800346 -0.7133923 0.5653824 -0.414022 -0.8707444 0.2897627 -0.3972935 -0.753622 0.1983526 -0.6266659 -0.8174807 0.1182719 -0.5636818 -0.7281109 -0.06439846 -0.6824275 -0.88362 -0.163598 -0.4386931 -0.8877804 -0.1837263 -0.422008 -0.7330533 -0.4490942 -0.5108301 -0.8372625 -0.4105201 -0.3611992 -0.8452563 -0.5056318 -0.1728532 -0.8044878 -0.5690897 -0.1701068 -0.8060544 -0.5874601 0.07188123 -0.7875222 -0.6102472 0.08606559 -0.8771946 -0.4179048 0.2364006 -0.7556436 -0.4912958 0.4331644 -0.8064858 -0.3869146 0.447077 -0.705937 -0.276191 0.6522051 -0.8154493 -0.2742246 0.5097485 -0.8486729 -0.006106674 0.5288827 -0.7852243 0.044959 0.6175772 -0.8651103 0.1889941 0.4646133 -0.8319282 0.2575119 0.4915111 -0.7846007 0.2363689 0.5731768 -0.818488 0.4518231 0.3548708 -0.8029889 0.46201 0.3765048 -0.8667436 0.4739648 0.1552833 -0.7425358 0.6656797 0.07423663 -0.8318364 0.5550208 4.09243e-4 -0.8617619 0.4756432 -0.1764379 -0.7810173 0.5509684 -0.2940168 -0.8553499 0.4067041 -0.3208871 -0.7786003 0.3735337 -0.5042362 -0.8654216 0.2389046 -0.4404204 -0.803651 0.02145099 -0.5947141 -0.8199988 0.02712434 -0.5717224 -0.8179756 -0.2218688 -0.5307449 -0.8773995 -0.1497446 -0.4557925 -0.8639278 -0.3655025 -0.3464633 -0.7297417 -0.5669424 -0.3821694 -0.8020353 -0.5438089 -0.2470048 -0.7570375 -0.6353623 -0.152345 -0.8639613 -0.502487 -0.03282672 -0.7802455 -0.5773293 0.2406408 -0.8193741 -0.5342061 0.2079669 -0.7463018 -0.49169 0.4486362 -0.8636285 -0.3172165 0.3918157 -0.8310762 -0.1330049 0.5400206 -0.8191738 -0.1317149 0.5582163 -0.8257402 0.1295264 0.5489774 -0.8286001 0.1315965 0.5441547 -0.7659636 0.314897 0.5604818 -0.8509301 0.3349812 0.4046056 -0.7954981 0.4946796 0.3499643 -0.8467008 0.4587259 0.2695706 -0.8154695 0.5736834 0.07679152 -0.7597786 0.6478013 0.0555883 -0.7926146 0.5916491 -0.1473552 -0.8172661 0.5655681 -0.1104944 -0.8561282 0.4881736 -0.1695029 -0.7649237 0.5045527 -0.4003978 -0.8527771 0.3375233 -0.3985591 -0.7358493 0.314935 -0.5994512 -0.8199437 0.115507 -0.5606697 -0.7637957 0.07420849 -0.641178 -0.7956382 -0.1208841 -0.5935882 -0.7806457 -0.1400188 -0.6090872 -0.8610261 -0.2567647 -0.4389831 -0.8318797 -0.390668 -0.3941507 -0.7565357 -0.482033 -0.4419255 -0.8347057 -0.5258766 -0.1634634 -0.841842 -0.5142192 -0.1639532 -0.7977653 -0.6009279 0.04956281 -0.862226 -0.4961692 0.1018944 -0.7870396 -0.5315243 0.3131305 -0.8468758 -0.4341015 0.3071767 -0.8380709 -0.247269 0.486308 -0.7968599 -0.2579551 0.5463273 -0.8658894 0.02214246 0.4997452 -0.821755 0.05378788 0.5672968 -0.8402608 0.2660142 0.4724386 -0.8174299 0.2955284 0.4944403 -0.8166555 0.4557616 0.3540554 -0.7816095 0.5062718 0.3643839 -0.7776679 0.6081165 0.1594592 -0.773947 0.6130712 0.1585866 -0.8716763 0.4778138 -0.1089704 -0.7495778 0.6180269 -0.2370145 -0.8829122 0.3507742 -0.3121275 -0.7849684 0.3886374 -0.4824787 -0.8644213 0.1797986 -0.4695192 -0.8213716 0.119601 -0.5577136 -0.7110112 0.2094917 -0.6712499 -0.8819755 -0.0801804 -0.4644249 -0.73814 -0.2845075 -0.611723 -0.8168667 -0.2837219 -0.5022258 -0.8652852 -0.391401 -0.3131883 -0.7214232 -0.6128141 -0.3225019 -0.8023141 -0.5687593 -0.1811214 -0.7574378 -0.6507007 -0.05363464 -0.8043549 -0.5941371 0.003774821 -0.7634558 -0.6316958 0.1345208 -0.8569387 -0.4666364 0.2188758 -0.7786211 -0.4983805 0.381269 -0.8692118 -0.3189936 0.3777753 -0.7507111 -0.2799686 0.5983732 -0.8620096 -0.1390699 0.4874413 -0.8452699 0.0582183 0.5311587 -0.7825491 0.1079912 0.6131517 -0.8537905 0.226305 0.4688583 -0.7793802 0.3649634 0.5092821 -0.8100247 0.4045066 0.4245405 -0.7460437 0.5239867 0.410922 -0.8114469 0.5295516 0.2472429 -0.7410119 0.6378671 0.2098258 -0.8508108 0.5254722 -2.84952e-4 -0.7772206 0.6218159 -0.09629786 -0.8667957 0.4506878 -0.2134148 -0.7870191 0.5168552 -0.3368405 -0.8673807 0.3357324 -0.3673343 -0.7601094 0.2865279 -0.5832114 -0.7870534 0.2473025 -0.5651448 -0.7875584 0.06408387 -0.612899 -0.8186203 0.0896908 -0.5672888 -0.8370242 -0.1344574 -0.5303881 -0.818303 -0.1533301 -0.5539586 -0.8305479 -0.344982 -0.4372387 -0.7518707 -0.4501239 -0.4817461 -0.8877794 -0.4118492 -0.2054947 -0.8865587 -0.4182474 -0.197694 -0.7477604 -0.6476183 -0.1464411 -0.8633484 -0.5042932 0.01783818 -0.7798404 -0.6055086 0.1587719 -0.8140291 -0.5236153 0.2513636 -0.7677189 -0.5587581 0.3136834 -0.7828757 -0.3914363 0.4836149 -0.8338176 -0.3245298 0.4465745 -0.847698 -0.08921897 0.5229227 -0.7674874 -0.04838234 0.6392358 -0.8599454 0.08605992 0.5030783 -0.8103663 0.2405257 0.5342791 -0.8207845 0.2422641 0.5173211 -0.8374087 0.403657 0.3685212 -0.7332709 0.5536718 0.3946663 -0.8238173 0.5255507 0.212419 -0.7965373 0.5929614 0.1180045 -0.7180707 0.6658719 0.2024582 -0.7963267 0.6002933 -0.07424187 -0.825241 0.5575792 -0.0899043 -0.8511542 0.4546363 -0.2623787 -0.7429512 0.5306633 -0.4079462 -0.8805644 0.2871665 -0.3770168 -0.8635679 0.1373499 -0.4851655 -0.7437911 0.1391437 -0.653769 -0.7919901 -0.1045895 -0.6015089 -0.7990261 -0.1115423 -0.59086 -0.7332454 -0.3270863 -0.5961256 -0.8381978 -0.3173574 -0.4435186 -0.8566882 -0.4332041 -0.2800351 -0.6859734 -0.6656193 -0.2939243 -0.8548703 -0.5094102 -0.09847974 -0.832029 -0.5358763 0.1434029 -0.8543918 -0.5039637 0.1266313 -0.8408063 -0.4219075 0.339174 -0.8846508 -0.3402108 0.3188256 -0.7594617 -0.1941072 0.6209191 -0.8138119 -0.189072 0.5495107 -0.7487724 0.005884349 0.6628012 -0.8231256 0.09409624 0.5600091 -0.7626514 0.2219631 0.6075322 -0.8595119 0.2844257 0.4246662 -0.7919873 0.4352785 0.4281222 -0.8661649 0.4102083 0.2854605 -0.7949774 0.5746797 0.194304 -0.8483587 0.5170939 0.1135851 -0.7906748 0.610642 -0.04416006 -0.8688598 0.4813327 -0.1157654 -0.8031781 0.5235427 -0.2842673 -0.8863129 0.3567388 -0.2952747 -0.7857385 0.3676103 -0.4974715 -0.8658089 0.1805915 -0.4666497 -0.8117742 0.1568498 -0.562513 -0.8488212 -0.01067394 -0.5285724 -0.8009539 -0.06295788 -0.595407 -0.8619022 -0.199773 -0.4660639 -0.7805468 -0.3126939 -0.5412665 -0.833166 -0.4034551 -0.3782307 -0.7757621 -0.4982306 -0.387246 -0.8587088 -0.4741687 -0.194379 -0.7684617 -0.6301855 -0.1110539 -0.8601457 -0.5099565 0.009695112 -0.7782111 -0.6136051 0.1337031 -0.8724091 -0.4392839 0.2143175 -0.7850618 -0.4298622 0.4459783 -0.7774042 -0.4344968 0.4548137 -0.8545134 -0.186545 0.484776 -0.5807158 -0.1698614 0.7961886 -0.8967652 0.03452318 0.4411582 -0.702114 0.3050641 0.6434065 0.9999721 0.00396043 0.006334364 0.9998079 -0.01452046 0.01316791 0.999908 0.01280468 0.00448358 0.9998912 0.01321333 0.006565153 0.9999244 -0.009088814 0.008288025 0.9993741 0.01518535 -0.03195208 0.9999504 0.001941204 -0.009776175 0.9998226 0.01805984 0.005367696 0.9986497 -0.05194979 7.57089e-5 0.9999874 -0.003202795 0.003894209 0.999967 -0.007327914 0.003510713 0.9998712 0.008439004 0.01365584 0.999977 -0.006730914 -9.07023e-4 0.999962 -0.005597889 -0.006681621 0.9999945 -0.002086341 0.002628982 0.9994035 0.02146679 -0.02705132 0.9984934 -0.04717844 0.02802026 0.9998404 0.01768296 0.00257194 0.9999916 0.00165838 0.003750979 0.939428 0.3295466 0.09420168 -0.9191584 -0.1552892 -0.3619851 -0.8395115 0.1961852 0.5066873 -0.7766519 0.02952235 -0.629238 0.7735416 -0.1789516 -0.6079554 0.8974836 0.04923385 0.4382914 -0.9001666 0.4129852 -0.1383592 0.9053106 0.3298606 -0.2675908 0.8988115 -0.03803777 0.4366819 0.8944841 0.3745169 -0.2442036 -0.8968929 0.1448155 -0.4178655 -0.902094 -0.389358 -0.1860831 0.9005715 -0.2968214 0.3175973 -0.8961492 0.4205438 0.1416323 0.6693744 -0.7408512 0.05547428 -0.5774008 -0.6905856 0.4355458 0.8402588 -0.4167993 0.3467618 0.8909392 0.3909912 -0.2309832 0.07885932 -0.04934567 -0.9956638 0.004703164 -0.5969275 -0.8022814 -0.0618481 -0.6209212 -0.7814294 0.05563145 -0.9104497 -0.4098618 -0.07956469 -0.9369725 -0.3402235 0.09960711 -0.9799557 0.1725265 -0.08887195 -0.9590766 0.2688382 0.06737262 -0.7425321 0.6664137 -0.02620857 -0.7042481 0.70947 0.002617776 -0.3015632 0.9534426 0.02060633 -0.2937569 0.9556581 -0.001384139 0.3737259 0.9275382 0.1212659 0.3305441 0.9359675 -0.1764366 0.793716 0.5821384 0.2820533 0.8842321 0.3722628 -0.2509307 0.963051 -0.09780913 0.1867514 0.9121087 -0.3649407 -0.1713224 0.7084292 -0.6846728 0.1588448 0.5553767 -0.8162873 -0.1741135 0.05979347 -0.9829086 0.1498438 0.2574247 -0.9546095 -0.2369658 0.4022971 -0.88431 0.2089344 0.6343335 -0.7442899 -0.1789897 0.793946 -0.5810444 0.1864848 0.8853282 -0.4259312 -0.2539625 0.951202 -0.1752652 0.2035229 0.9779115 0.04762029 -0.1380221 0.9414861 0.3074965 0.02084845 0.9277423 0.3726391 -0.02634727 0.7249066 0.6883431 -0.1051294 0.736688 0.668011 0.147547 0.4824162 0.863426 -0.1680691 0.3349684 0.9271186 0.1172006 0.1348661 0.9839082 -0.1509888 -0.05260711 0.9871348 0.1425758 -0.1958069 0.9702226 -0.1173105 -0.5319951 0.8385819 0.03078806 -0.5700206 0.8210535 -0.03079324 -0.8855671 0.4634897 0.04762876 -0.8949067 0.4437045 -0.05604922 -0.9967582 0.05772125 0.02267491 -0.9992812 0.03037935 -0.1092911 -0.9310344 -0.3481819 0.02201884 -0.951874 -0.3056981 0.1376931 -0.7553445 -0.6406991 -0.1549921 -0.6719259 -0.724219 0.1352317 -0.447326 -0.8840882 -0.09321242 -0.3456774 -0.9337123 -0.0782901 -0.03006726 -0.9964771 0.05907744 -0.09394407 -0.9938231 -1 -3.09596e-6 0 -1 5.60092e-6 0 -1 1.87114e-6 0 -1 -2.30995e-6 0 -1 -3.34326e-6 0 -1 -2.55796e-6 0 -1 5.47288e-6 0 -1 4.92685e-6 0 -1 -5.52489e-6 0 -1 -2.376e-6 0 -1 2.6963e-6 0 -1 -3.94793e-6 0 -1 6.22339e-6 0 -1 3.17834e-6 0 -1 -4.70741e-6 0 -1 -2.4285e-6 0 1 5.49636e-6 0 1 -2.66343e-6 0 1 -5.00313e-6 0 1 -1.02051e-6 0 1 -4.61802e-6 0 1 3.12537e-6 0 1 4.52901e-6 0 1 6.93581e-7 0 1 -6.12259e-6 0 0.2024663 -0.03190314 -0.9787694 -0.1974368 -0.342026 -0.9187149 0.1661905 -0.5632612 -0.8093933 -0.2071486 -0.8432154 -0.4960619 0.1588275 -0.9406672 -0.2998654 -0.13177 -0.97459 0.1811379 -0.07608807 -0.9755535 0.2061699 0.1531495 -0.7354473 0.6600475 -0.1483597 -0.5923488 0.7919042 0.1273739 -0.2914243 0.9480759 -0.09803086 -0.1400191 0.985284 0.08168601 0.3724836 0.9244368 -0.02160257 0.4122432 0.9108178 -0.02518546 0.9276257 0.3726611 0.02464127 0.921374 0.3878953 -0.1018685 0.9037889 -0.4156785 0.02215665 0.9282154 -0.371383 0.1335518 0.5574778 -0.8193794 -0.22245 0.3782097 -0.8985953 -0.1080335 0.1724658 -0.9790733 0.132257 0.2743165 -0.9525012 -0.2022919 0.5042592 -0.8395241 0.235082 0.7066408 -0.6673793 -0.2222761 0.8149499 -0.5352104 0.221018 0.9408201 -0.2569214 -0.180345 0.9823619 -0.04940456 0.1307611 0.9840664 0.120478 -0.1482555 0.9291539 0.3386643 0.1902367 0.8361405 0.5144699 -0.2090745 0.70913 0.6733666 0.2151181 0.506989 0.8346775 -0.1680806 0.3349676 0.9271168 0.1171939 0.1348667 0.9839089 -0.1509774 -0.05260717 0.9871364 0.142576 -0.1958072 0.9702225 -0.1173102 -0.5319939 0.8385826 0.03079891 -0.57002 0.8210535 -0.03006881 -0.8829154 0.4685685 0.06518834 -0.8940131 0.4432731 -0.08298623 -0.9933434 0.07988953 0.05330395 -0.9981172 0.03034484 -0.1133421 -0.9325944 -0.3426681 0.007291078 -0.9520791 -0.3057653 0.1377057 -0.7553433 -0.6406978 -0.1549986 -0.6719178 -0.7242251 0.135238 -0.4473283 -0.884086 -0.1865048 -0.2967828 -0.9365555 0.1699246 -0.09274059 -0.9810835 -1 -3.09597e-6 0 -1 2.45349e-6 0 -1 2.42455e-6 0 -1 1.70168e-6 0 -1 -2.01687e-6 0 -1 2.90364e-6 0 1 2.78626e-6 0 1 3.44196e-6 0 1 -1.86132e-6 0 1 2.2908e-6 0 1 -3.51492e-6 0 1 -2.8745e-6 0 1 5.3936e-6 0 1 5.73785e-6 0 1 -3.36995e-6 0 1 -3.41068e-6 0 1 -5.7293e-6 0 1 2.4554e-6 0 -0.9987224 -0.04779487 0.01641255 -0.9853883 -0.1619953 0.05260556 -0.9944227 -0.04968225 0.09303414 -0.9958267 -0.03704172 0.08340913 -0.9892277 -0.1313164 0.06468796 -0.9990525 -0.04304593 0.006426334 -0.9872987 0.04770296 0.1515445 -0.9999708 -4.86163e-4 0.00764048 -0.9965921 -0.08187973 -0.009999394 -0.9968152 -0.0794878 0.006415367 -0.9999563 0.004762411 0.008047163 -0.9966781 0.02782964 0.07653999 -0.9716862 -0.1160126 -0.2058326 -0.9902164 0.131737 0.04600816 -0.9963005 -0.0852651 0.01073265 -0.9174788 0.3963251 -0.03404724 -0.4424268 0.8799103 0.1732528 -0.8443737 0.3823791 0.3752593 -0.844353 0.3823955 0.3752891 -0.8172761 0.1677692 0.5512834 -0.8467792 0.1306491 0.5156508 -0.795135 -0.05494576 0.6039383 -0.8521942 -0.1332286 0.5059795 -0.7437604 -0.2997947 0.5974477 -0.862183 -0.3982545 0.3131038 -0.791221 -0.5134106 0.3322333 -0.8549162 -0.5128698 0.07799404 -0.8190256 -0.5703493 0.06243962 -0.8124775 -0.5397912 -0.2202409 -0.8328281 -0.5057315 -0.2250182 -0.7566905 -0.4647713 -0.4597905 -0.8266205 -0.3436056 -0.4456836 -0.7579554 -0.1560085 -0.633376 -0.8342227 -0.1695283 -0.5247216 -0.6986342 0.03397738 -0.7146719 -0.8557747 0.1772795 -0.4860265 -0.7485395 0.3691578 -0.5508277 -0.866571 0.3961892 -0.3034616 -0.9021537 0.3610666 -0.2361137 -0.8252661 0.5471885 -0.1397164 -0.8491184 0.5251008 0.05715847 -0.8432552 0.5340174 0.06120479 -0.8037276 0.4859382 0.3433455 -0.8274049 0.4483475 0.3382097 -0.7439081 0.2403423 0.6235675 -0.8134938 0.161942 0.558572 -0.775726 -0.126909 0.6181775 -0.7245218 -0.09667718 0.6824381 -0.7900998 -0.3900536 0.4728643 -0.8376597 -0.3753871 0.3967504 -0.832081 -0.5302233 0.1628021 -0.8466129 -0.5065937 0.1631237 -0.8178155 -0.5701314 -0.07828152 -0.7316842 -0.6815258 -0.01268541 -0.7852154 -0.5309441 -0.3186458 -0.7254373 -0.5702099 -0.3854887 -0.8284863 -0.2218448 -0.5141941 -0.8468742 -0.2212342 -0.4835904 -0.7911944 -0.01332086 -0.6114196 -0.834355 0.1117128 -0.5397889 -0.7450073 0.2112554 -0.6327205 -0.7792045 0.4335476 -0.4526333 -0.8042753 0.3997235 -0.4397298 -0.8602057 0.4793403 -0.1740093 -0.8162646 0.5524178 -0.1689576 -0.703205 0.689993 0.1715006 -0.8173081 0.5694358 0.08803635 -0.7375543 0.581057 0.3440734 -0.8246988 0.4294185 0.3680649 -0.6650797 0.3069202 0.6807856 -0.855944 0.2653615 0.4437829 -0.7609657 0.104731 0.6402834 -0.8622766 -0.02249544 0.5059377 -0.749341 -0.19293 0.6334558 -0.8153153 -0.3471215 0.4634305 -0.8007124 -0.3476924 0.4878215 -0.7463698 -0.5796694 0.3269798 -0.8241545 -0.5279329 0.2050761 -0.7464305 -0.66235 0.06429702 -0.8385419 -0.5325014 -0.1152811 -0.7749567 -0.604423 -0.184703 -0.8261336 -0.4063298 -0.390384 -0.8964554 -0.2790234 -0.3442583 -0.7513124 -0.1562815 -0.6411754 -0.8706412 0.01844924 -0.4915724 -0.8098914 0.09282922 -0.5791882 -0.8411891 0.2079994 -0.4991365 -0.747159 0.3590733 -0.559303 -0.7880827 0.5018528 -0.3564682 -0.8528804 0.4602242 -0.2465539 -0.7988166 0.5974937 -0.06995272 -0.852378 0.5226413 -0.01726394 -0.8214869 0.5373581 0.1908026 -0.8744782 0.4275826 0.2290437 -0.785178 0.4673976 0.4062453 -0.8293418 0.296624 0.4735046 -0.8707218 0.2280742 0.4356901 -0.7916538 0.09294825 0.6038585 -0.8164656 0.05314886 0.574943 -0.727359 -0.1732589 0.6640258 -0.8424941 -0.2791442 0.4607411 -0.7898127 -0.3595331 0.4969223 -0.7705487 -0.5880753 0.2458094 -0.8286479 -0.506591 0.2381351 -0.7919453 -0.6015732 0.1045577 -0.8828217 -0.4666596 -0.05342894 -0.7870746 -0.591929 -0.1735908 -0.8518487 -0.4147759 -0.3198667 -0.877803 -0.3646437 -0.3106396 -0.7903018 -0.2461646 -0.5610936 -0.8444839 -0.1552523 -0.5125855 -0.7115333 -0.006411552 -0.7026231 -0.8369103 0.1727116 -0.5193766 -0.7319964 0.3193283 -0.6018395 -0.8411512 0.4527938 -0.2957066 -0.8248724 0.4653221 -0.3210309 -0.7890862 0.6135298 -0.0304048 -0.8410673 0.5408649 0.008421063 -0.7355566 0.5817266 0.3472043 -0.8790212 0.3202617 0.3532058 -0.7874252 0.3368932 0.5162023 -0.7956708 0.1079185 0.5960383 -0.8772982 0.02266204 0.4794105 -0.7589054 -0.2418398 0.6046291 -0.8892673 -0.2630336 0.3741888 -0.7461239 -0.551549 0.3729516 -0.8772643 -0.4530159 0.1586943 -0.7643367 -0.6397361 0.08079177 -0.7492262 -0.6352386 -0.1874358 -0.7990587 -0.5854613 -0.1368952 -0.7823501 -0.4639886 -0.4155032 -0.7946853 -0.4555302 -0.4012078 -0.8316628 -0.1456892 -0.5358281 -0.814942 -0.1634311 -0.5560214 -0.7677809 0.1816906 -0.6144111 -0.7650182 0.1805079 -0.6181942 -0.7810747 0.4225252 -0.4597771 -0.7629444 0.4481643 -0.4659022 -0.8235735 0.5120681 -0.2439532 -0.7873942 0.5715917 -0.2308533 -0.756281 0.6537069 -0.02658152 -0.8126018 0.5820074 0.03075617 -0.7658668 0.5994961 0.2324917 -0.8598501 0.4005515 0.31657 -0.8412853 0.4133663 0.3483784 -0.7990382 0.3112905 0.5144281 -0.8756777 0.1227609 0.4670314 -0.8434655 0.1139805 0.5249518 -0.778401 -0.1713864 0.6039195 -0.8188277 -0.190874 0.5413765 -0.7304503 -0.4301159 0.5305117 -0.7790585 -0.4324119 0.4539692 -0.7446688 -0.6205825 0.2456539 -0.8695382 -0.4887242 0.07107746 -0.7536153 -0.6491222 -0.1034623 -0.825645 -0.5420194 -0.1566058 -0.7422688 -0.5614107 -0.3658621 -0.8328161 -0.3672841 -0.4141495 -0.7182055 -0.349835 -0.601495 -0.8184716 -0.1120152 -0.5635219 -0.7611249 -0.07146924 -0.6446557 -0.787907 0.1825972 -0.5880995 -0.7609134 0.1685495 -0.6265796 -0.7783292 0.4529659 -0.4347708 -0.8544548 0.3502092 -0.3837458 -0.8051315 0.5451954 -0.2335066 -0.8774874 0.4720588 -0.08471298 -0.7572585 0.6529428 -0.01501113 -0.8245331 0.5057405 0.2537159 -0.8755696 0.4094879 0.2563154 -0.8237262 0.3830828 0.4179985 -0.8843305 0.2390198 0.4010353 -0.7859731 0.1998792 0.5850595 -0.7321819 -0.06422841 0.678074 -0.7770029 -0.0319643 0.6286851 -0.8219357 -0.1001204 0.5607118 -0.7263786 -0.3498411 0.5915958 -0.8497418 -0.3893375 0.3554648 -0.8071288 -0.4666717 0.3616085 -0.8271721 -0.540224 0.1547404 -0.8690465 -0.4861488 0.09174734 -0.8062937 -0.5904203 -0.03597837 -0.8499523 -0.5137369 -0.1168564 -0.7532457 -0.599395 -0.2708263 -0.8258016 -0.355975 -0.437417 -0.7798336 -0.3764358 -0.5001558 -0.8317986 -0.04708832 -0.5530766 -0.7681438 -0.09673833 -0.6329272 -0.8555067 0.2730039 -0.4399743 -0.7853707 0.2477147 -0.5673009 -0.7764549 0.4432961 -0.4478912 -0.8651394 0.4696292 -0.1760178 -0.8197862 0.5229033 -0.2335013 -0.8532592 0.5176059 0.063506 -0.8054196 0.583738 0.1027097 -0.7342205 0.5820533 0.3494772 -0.8414705 0.3739004 0.3900333 -0.7849134 0.3697735 0.4971706 -0.8557925 0.09996861 0.5075682 -0.898988 0.1066404 0.4247924 -0.7606006 -0.06537413 0.6459203 -0.8212857 -0.2460099 0.5147513 -0.8700602 -0.2524216 0.4234131 -0.7093928 -0.5463472 0.4452714 -0.8445428 -0.5085754 0.1676269 -0.7030946 -0.706674 0.07918339 -0.87445 -0.4785786 -0.07937037 -0.6850922 -0.6377032 -0.3521128 -0.806672 -0.4120939 -0.4236258 -0.738022 -0.3919853 -0.5492458 -0.8198215 -0.1538113 -0.5515748 -0.7809365 -0.1382177 -0.6091257 -0.7491717 0.1199663 -0.6514213 -0.85877 0.1959145 -0.4734254 -0.7761591 0.3816611 -0.5019084 -0.8760544 0.3861698 -0.2887935 -0.7854082 0.5472055 -0.2893096 -0.7561445 0.6541156 0.01944977 -0.8293143 0.5586531 -0.01202142 -0.7892608 0.5518144 0.2693851 -0.8556031 0.435388 0.2799654 -0.7500672 0.4492502 0.4853591 -0.7969648 0.2076219 0.5672217 -0.7751268 0.2365146 0.5858665 -0.8418399 -0.1083202 0.5287461 -0.7608091 -0.01645696 0.648767 -0.7851591 -0.2478804 0.5675213 -0.8667058 -0.303292 0.3960241 -0.8203783 -0.3951713 0.4133028 -0.8425915 -0.4904163 0.2225563 -0.8521524 -0.4803025 0.2077158 -0.7241365 -0.6878769 -0.04951584 -0.8638718 -0.4743795 -0.1693803 -0.7570358 -0.5642198 -0.3294738 -0.8559401 -0.2729043 -0.4391924 -0.7870218 -0.370673 -0.4931514 -0.7757118 -0.07842874 -0.6261951 -0.8138433 -0.09523296 -0.5732277 -0.7281282 0.1143736 -0.6758314 -0.8068478 0.2366262 -0.5412992 -0.7196697 0.3752636 -0.5841684 -0.8471897 0.4109545 -0.3367284 -0.7209933 0.6242679 -0.3007627 -0.8443382 0.534406 -0.03877347 -0.7984417 0.6020285 0.007266223 -0.8245436 0.53881 0.1726607 -0.8713674 0.4510551 0.19305 -0.7523704 0.474525 0.4569081 -0.8934539 0.1993018 0.4025158 -0.7855525 0.1839667 0.5908161 -0.8222847 -0.05846506 0.5660651 -0.8482251 -0.08013427 0.5235388 -0.7341313 -0.318116 0.599878 -0.857784 -0.3897669 0.3350949 -0.7978761 -0.4899864 0.3511512 -0.7991303 -0.5754845 0.173806 -0.8833201 -0.4666768 0.04425406 -0.7968655 -0.6020885 -0.04995059 -0.8359732 -0.4907449 -0.245598 -0.8092482 -0.5371349 -0.2379151 -0.7226564 -0.4546105 -0.5206699 -0.8255236 -0.2995476 -0.4783118 -0.7524271 -0.1131165 -0.6488901 -0.7897485 -0.07163399 -0.6092339 -0.7931787 0.1564118 -0.5885601 -0.7534772 0.1992065 -0.6265692 -0.7824675 0.4031838 -0.4745395 -0.75615 0.4071122 -0.5123445 -0.8261737 0.5228441 -0.2099317 -0.8182783 0.5349775 -0.2102854 -0.7954373 0.6055348 0.02464389 -0.8887876 0.4401682 0.1277054 -0.7210549 0.5964474 0.3526052 -0.8503273 0.3882043 0.355304 -0.7500824 0.2874504 0.595608 -0.8595027 0.08727735 0.5036248 -0.7992821 -0.003436088 0.6009463 -0.861364 -0.1333482 0.490174 -0.8229193 -0.1814865 0.5383926 -0.8075568 -0.38861 0.4436601 -0.8683827 -0.3700491 0.3301139 -0.7485432 -0.5995678 0.2831987 -0.7882863 -0.609786 0.08225536 -0.7668069 -0.6384991 0.06577312 -0.7833502 -0.5904933 -0.194114 -0.770624 -0.6020358 -0.2090256 -0.8671073 -0.3871752 -0.3134013 -0.80672 -0.4192239 -0.4164785 -0.8377202 -0.1969841 -0.5093351 -0.7561859 -0.3032007 -0.5798726 -0.7715759 -0.05222868 -0.6339897 -0.8748036 0.08915203 -0.4762045 -0.8167002 0.1778191 -0.5489819 -0.8344682 0.3386176 -0.4347425 -0.8205573 0.3418735 -0.4580485 -0.6424614 0.7290718 -0.2360036 -0.8826204 0.4192028 -0.2127215 -0.7879558 0.6094254 -0.08789962 -0.8781277 0.4681155 0.09879189 -0.8389284 0.5250844 0.1431286 -0.7713982 0.5004428 0.3930673 -0.8850344 0.2872703 0.3663195 -0.7723748 0.2685095 0.5756214 -0.8466762 0.02935463 0.5312982 -0.833433 0.04266715 0.550971 -0.8340866 -0.2029533 0.512942 -0.8419293 -0.1944298 0.5033411 -0.7894405 -0.387697 0.475894 -0.7928991 -0.4903972 0.3616927 -0.8794669 -0.4175183 0.2285094 -0.7669231 -0.6277952 0.1330498 -0.8368584 -0.5468603 0.02474027 -0.7102678 -0.678706 -0.1867562 -0.8557103 -0.4252738 -0.2947917 -0.7745314 -0.4655229 -0.4282402 -0.8574316 -0.2459326 -0.4520267 -0.7549453 -0.2234659 -0.6165394 -0.8093932 0.0575639 -0.5844393 -0.8201145 0.06637156 -0.5683372 -0.6950755 0.4594596 -0.5529621 -0.8309321 0.3253527 -0.4513286 -0.8039553 0.5413928 -0.2460688 -0.8967671 0.4291501 -0.1078851 -0.7820919 0.6223356 0.03210592 -0.8582243 0.4780001 0.1869946 -0.8021172 0.5365484 0.2621526 -0.7538188 0.4467979 0.4817977 -0.8154894 0.3094426 0.4891038 -0.720415 0.2548733 0.645013 -0.8286765 0.07546263 0.5546177 -0.7106902 -0.1371933 0.6899982 -0.8649285 -0.2414088 0.4400233 -0.7386283 -0.4522304 0.4999159 -0.8820858 -0.4107407 0.2306876 -0.733249 -0.6536663 0.1872603 -0.8225032 -0.5625531 -0.08380061 -0.7633916 -0.6261332 -0.1587159 -0.8863363 -0.3827852 -0.2605445 -0.8234168 -0.4334483 -0.366207 -0.8053869 -0.2163584 -0.5518524 -0.8617635 -0.1478484 -0.4852882 -0.7945892 0.1033684 -0.5982835 -0.8574239 0.1456426 -0.4935714 -0.7198533 0.414662 -0.5566568 -0.8367188 0.4475803 -0.315553 -0.7918986 0.5573679 -0.2494749 -0.6615045 0.6425589 -0.3866908 -0.8205877 0.5680339 0.06303524 -0.7874444 0.6105394 0.08469277 -0.8342265 0.4288559 0.3466248 -0.7881171 0.4986776 0.3608217 -0.7660397 0.2342873 0.5985756 -0.7457888 0.2301806 0.6251528 -0.835977 -0.01284056 0.5486145 -0.7434927 -0.1091114 0.6597828 -0.8216733 -0.3422579 0.455755 -0.8639706 -0.2842977 0.4156078 -0.7805696 -0.5335059 0.3257035 -0.8592863 -0.4860655 0.1592715 -0.7512666 -0.6518008 0.1037028 -0.7918964 -0.5708795 -0.2167872 -0.8160716 -0.5460618 -0.1893249 -0.8314675 -0.4023109 -0.383155 -0.8425862 -0.3837901 -0.3778277 -0.8127279 -0.1369203 -0.5663269 -0.6541333 -0.2686613 -0.7070578 -0.8177539 0.04492747 -0.5738122 -0.7176321 0.1895494 -0.6701308 -0.838607 0.3356882 -0.4290124 -0.7810851 0.4232627 -0.4590803 -0.8744733 0.4455261 -0.1918412 -0.796545 0.574787 -0.1874463 -0.8340494 0.5378929 0.1226086 -0.8691899 0.4736136 0.1421237 -0.7721229 0.4989303 0.3935669 -0.8782683 0.2904105 0.3798773 -0.8055894 0.2848963 0.5194804 -0.812781 0.1304232 0.5677824 -0.9029932 0.001820445 0.429651 -0.8441728 -0.1000333 0.5266551 -0.8306037 -0.2755057 0.4839363 -0.8685654 -0.2295153 0.4392229 -0.7423616 -0.52254 0.4193465 -0.8784025 -0.4498985 0.1612468 -0.8125082 -0.565865 0.1400975 -0.855179 -0.4827355 -0.1887736 -0.8736623 -0.4558351 -0.170084 -0.7649828 -0.5058867 -0.3985975 -0.8488178 -0.2554851 -0.4628561 -0.8854319 -0.1878312 -0.4251235 -0.7642593 -0.1023097 -0.6367421 -0.8663406 0.1401681 -0.479382 -0.7128949 0.08989059 -0.6954859 -0.8291745 0.4065077 -0.3836941 -0.8075459 0.4361097 -0.3970872 -0.7370294 0.6569227 -0.1588719 -0.8206512 0.566725 -0.0731737 -0.7714689 0.5976216 0.2183672 -0.7716759 0.5974218 0.2181823 -0.8089814 0.4240571 0.4070932 -0.7535865 0.4405402 0.4878849 -0.8030356 0.1527902 0.5760113 -0.7985305 0.1518728 0.5824809 -0.819737 -0.1096528 0.5621455 -0.8297089 -0.1157677 0.5460596 -0.748339 -0.3582342 0.5582625 -0.8236862 -0.3905246 0.4111346 -0.7253317 -0.5776274 0.3744871 -0.7982811 -0.5672348 0.2024651 -0.7601467 -0.6328064 0.1474222 -0.8408483 -0.5401426 -0.03493028 -0.7537689 -0.6433362 -0.1339811 -0.85376 -0.3949834 -0.3392378 -0.7938578 -0.5009485 -0.3447324 -0.7746578 -0.2811229 -0.5664585 -0.8499372 -0.1827405 -0.4941788 -0.6318592 0.1994671 -0.7489772 -0.8471754 0.0784077 -0.5254962 -0.7315375 0.4102445 -0.5445663 -0.8607117 0.4145135 -0.2955574 -0.7717241 0.5700969 -0.2818359 -0.8542131 0.5173349 -0.05181467 -0.8576018 0.5121044 -0.04762554 -0.8060871 0.5695238 0.1608302 -0.8920695 0.4006683 0.2089906 -0.7761287 0.4621779 0.4289708 -0.8585831 0.242136 0.4518908 -0.8226268 0.2393811 0.5157345 -0.7351636 0.02579593 0.6773989 -0.8634563 -0.1135598 0.4914747 -0.7389943 -0.3237008 0.5908514 -0.8776685 -0.3333866 0.344313 -0.7751339 -0.5501931 0.3105723 -0.8269693 -0.5173267 0.2202161 -0.7383931 -0.6676226 0.09516179 -0.8187266 -0.5592423 -0.1301337 -0.82822 -0.5437011 -0.1357975 -0.7556965 -0.5294192 -0.3855364 -0.8164384 -0.4150879 -0.4014108 -0.7057304 -0.3643687 -0.607602 -0.8462245 -0.0687291 -0.5283755 -0.7193372 -0.188942 -0.6684721 -0.8079975 0.2245343 -0.5447242 -0.688427 0.2064138 -0.6953141 -0.8376131 0.3893582 -0.3831509 -0.7016192 0.6048723 -0.3766431 -0.8045531 0.5504961 -0.2228195 -0.8569366 0.5067065 0.09438467 -0.7598033 0.6496813 -0.02476358 -0.7808387 0.5816538 0.227969 -0.8731935 0.3577928 0.3309345 -0.8180394 0.3932055 0.4197631 -0.8244172 0.1482432 0.5462238 -0.8225986 0.1503615 0.5483822 -0.7031236 -0.2254312 0.6743872 -0.8033098 -0.1499294 0.5763806 -0.8225027 -0.3453494 0.4519104 -0.8561776 -0.3388965 0.3900117 -0.8125463 -0.5174001 0.2684505 -0.804892 -0.5227379 0.2808809 -0.7429738 -0.6661618 0.06495118 -0.8338333 -0.5502398 -0.04425257 -0.82554 -0.5434008 -0.1523135 -0.8995566 -0.3812382 -0.2132028 -0.8189834 -0.4526565 -0.3526592 -0.8284052 -0.3638816 -0.4258346 -0.668025 -0.3515709 -0.6558511 -0.8338522 -0.0324257 -0.5510347 -0.7459083 0.04112404 -0.664778 -0.8041775 0.2729632 -0.5280055 -0.856429 0.2888224 -0.4279147 -0.7561321 0.5035712 -0.4179481 -0.8901783 0.4196345 -0.1774529 -0.7319711 0.6785352 -0.06171202 -0.7821385 0.6228095 -0.01918023 -0.7723152 0.5562446 0.3067918 -0.7544823 0.5699732 0.3254029 -0.7890834 0.3619639 0.4963161 -0.8039858 0.3369883 0.4899448 -0.7491924 0.1357831 0.6482853 -0.8131356 0.05772846 0.5792045 -0.7434524 -0.1262534 0.6567637 -0.8352617 -0.2503318 0.4895631 -0.7236216 -0.4154103 0.5511863 -0.858174 -0.4482225 0.2502678 -0.7802976 -0.5846665 0.2220379 -0.86626 -0.4986415 0.03082728 -0.7787909 -0.6260301 -0.03963881 -0.8477326 -0.4492939 -0.2819304 -0.7578963 -0.5850757 -0.2885822 -0.8069778 -0.3347708 -0.486534 -0.7358609 -0.3379732 -0.5867562 -0.8051874 -0.05724561 -0.5902512 -0.7727524 -0.03296762 -0.6338509 -0.7909047 0.1851146 -0.5832688 -0.8641841 0.2377713 -0.4434532 -0.7611764 0.430019 -0.4854837 -0.835721 0.4368859 -0.332718 -0.7579593 0.5801842 -0.2981346 -0.7145999 0.6892531 -0.1194874 -0.8056014 0.5912151 -0.03835475 -0.8172397 0.5558666 0.1520909 -0.7387382 0.6270072 0.2472406 -0.7886416 0.4438745 0.4254643 -0.8558313 0.3163277 0.4092552 -0.7702143 0.2300687 0.5948432 -0.8762531 0.08001899 0.4751606 -0.7639376 -0.130844 0.6318855 -0.8374572 -0.1714867 0.5189006 -0.7681527 -0.3801242 0.5152158 -0.8552632 -0.4219319 0.3008294 -0.7701373 -0.5581308 0.3088344 -0.86732 -0.4977145 -0.006027936 -0.8482768 -0.5293017 -0.01631844 -0.7809215 -0.574142 -0.2460135 -0.8723505 -0.3708074 -0.3186011 -0.8048388 -0.4062952 -0.4326183 -0.8435035 -0.2632114 -0.4682113 -0.8998415 -0.1435345 -0.4119262 -0.8170426 -0.04605424 -0.5747351 -0.827193 -0.01457524 -0.561729 -0.7331455 0.1289473 -0.6677352 -0.7904288 0.3185814 -0.5231906 -0.750755 0.3683146 -0.5483715 -0.8324727 0.4698326 -0.2936776 -0.6995787 0.6639103 -0.2642213 -0.8630582 0.5030847 0.04512917 -0.7814611 0.6135139 0.1136636 -0.8372265 0.4395799 0.3253021 -0.8179959 0.4744958 0.3251715 -0.7276376 0.4055199 0.5532605 -0.8531542 0.1251358 0.5064279 -0.8133629 0.1127765 0.5707207 -0.8292211 -0.1784607 0.5296643 -0.824697 -0.1770275 0.5371557 -0.7406489 -0.4605734 0.4891947 -0.8447486 -0.4483183 0.292251 -0.725849 -0.6550002 0.210043 -0.7927144 -0.5992479 0.1118293 -0.7184517 -0.6911839 -0.07805126 -0.8373052 -0.504188 -0.2114586 -0.7614889 -0.55254 -0.3388721 -0.7952059 -0.3479179 -0.4965891 -0.8333676 -0.3338738 -0.4404847 -0.8056689 -0.1118942 -0.5817021 -0.8440865 -0.05514508 -0.5333638 -0.7254432 0.08496874 -0.6830173 -0.8104357 0.3296878 -0.4842519 -0.7698068 0.4052814 -0.4930968 -0.8629415 0.3873954 -0.3244332 -0.7496865 0.5892049 -0.3013435 -0.8002321 0.597318 -0.05329036 -0.7744812 0.6268055 -0.08540326 -0.744715 0.6344248 0.2071349 -0.8143456 0.5627336 0.142029 -0.7342275 0.5668096 0.3736802 -0.859046 0.3292004 0.3920041 -0.8078969 0.2575732 0.5300553 -0.882219 0.1516542 0.4457475 -0.8297378 -0.03452897 0.5570843 -0.8804867 -0.1183403 0.459063 -0.7897713 -0.2476211 0.5611997 -0.849755 -0.331785 0.4096769 -0.7209072 -0.5382267 0.4365832 -0.7994435 -0.5715893 0.1848669 -0.74804 -0.6445375 0.1581383 -0.7725561 -0.6319661 -0.06144887 -0.8104035 -0.5782921 -0.09393823 -0.7694638 -0.5448989 -0.3331827 -0.8512573 -0.4032652 -0.3357655 -0.7884123 -0.3042665 -0.5346288 -0.8251435 -0.2479493 -0.5076016 -0.7513835 -0.08190661 -0.6547627 -0.8457678 0.1019904 -0.5237126 -0.8297172 0.1202517 -0.5450772 -0.8124967 0.3374034 -0.4754031 -0.8363893 0.338295 -0.4312882 -0.704757 0.6035929 -0.3728179 -0.8640273 0.4943631 -0.09519523 -0.7357072 0.6770802 0.01724225 -0.8569566 0.4943819 0.1456434 -0.7623847 0.5733016 0.3001583 -0.8013204 0.39758 0.4470077 -0.817761 0.3688724 0.4418146 -0.7496504 0.2038084 0.6296717 -0.8015168 0.1261318 0.5845183 -0.7459665 -0.02840387 0.6653775 -0.8271918 -0.1625304 0.5379014 -0.8057771 -0.2266156 0.5471461 -0.8873673 -0.2842729 0.3629992 -0.7936882 -0.4401095 0.4199559 -0.8071763 -0.5440089 0.229174 -0.8711575 -0.4724559 0.1336787 -0.7550823 -0.6555845 -0.007735073 -0.8346503 -0.4980936 -0.2350779 -0.7767284 -0.5531472 -0.3011996 -0.8332434 -0.3353295 -0.439613 -0.8205141 -0.3553954 -0.4477174 -0.7639154 -0.1734012 -0.621583 -0.8479247 -0.05333197 -0.5274273 -0.7594904 0.1885454 -0.6225954 -0.8285512 0.2156164 -0.5167326 -0.7290713 0.5067151 -0.4601033 -0.8951168 0.397852 -0.2011967 -0.9032829 0.4223025 -0.07576727 -0.7638519 0.6446214 -0.03152143 -0.9721758 0.1952595 0.1294136 0.7306612 -0.4387944 0.5230619 -0.4741445 -0.7432582 0.4719685 0.5222101 -0.8249043 0.2164017 0.1150093 -0.9841461 0.135016 0.1167992 -0.9177612 -0.3795685 0.09050822 0.1726397 -0.980818 -0.5245552 0.5552383 -0.6454086 0.7360644 0.5032212 -0.4527446 -0.7180597 0.6930193 -0.06414508 0.4809135 0.8767574 0.00433129 -0.1929176 0.7783446 0.5974634 0.6560135 -0.3586785 0.6640753 -0.5024225 -0.7201696 0.4784637 0.5020356 -0.7972915 0.3350922 -0.6318039 -0.774674 -0.02653336 0.8479198 -0.2972053 -0.4389773 -0.6410567 0.5031312 -0.5795734 0.6942715 0.6776493 -0.2424429 -0.6519241 0.3144724 0.6900016 0.5970154 -0.02803945 0.8017397 -0.3745598 -0.9233924 -0.08397406 -0.07521718 -0.7666874 -0.6375992 0.6435962 -0.559716 -0.5220173 -0.6389212 -0.2322486 -0.733376 0.6442915 -0.06499272 -0.7620136 -0.7098258 0.2860623 -0.6436736 -0.3086562 0.7639049 -0.5667281 0.5147609 0.8490512 -0.1188845 -0.5903604 0.8007631 0.1012578 0.4882197 0.8116158 0.3208138 -0.5839287 0.610217 0.5354089 0.6414234 0.4359574 0.6312823 -0.8049917 0.05328488 0.5908885 0.9013165 -0.148023 0.4070848 -0.7874937 -0.5703223 0.2336367 0.6335192 -0.7736319 0.01212435 -0.7025966 -0.6418753 -0.3071712 0.5879106 -0.6745396 -0.4464946 -0.6416457 -0.2219032 -0.7342001 0.7790607 0.4266923 -0.4593455 -0.4365592 0.8006401 -0.4103556 0.4572026 0.8893315 0.00744754 0.5090764 0.702842 0.4968444 -0.597216 0.2344216 0.7670591 0.6455347 0.1324142 0.7521645 -0.5138214 -0.2793924 0.8111273 0.5586087 -0.3863819 0.7339383 -0.5479933 -0.6280108 0.5525449 0.7215187 -0.6534258 0.2290101 -0.5677982 -0.6434463 -0.5134025 0.4533544 -0.2536988 -0.8544629 0.3910355 0.8185181 0.4208555 -0.1942883 0.3245998 0.925682 0.3286952 0.3741644 0.8671566 -0.5558028 -0.2765597 0.7839632 0.6751684 -0.672021 0.3041965 -0.671319 -0.7096602 -0.2138066 -0.04024749 0.6246026 -0.7799051 0.2222529 0.9382633 -0.2650767 0.06755477 0.9659192 -0.2498728 -0.4638395 0.8210468 0.3327689 0.4625711 0.80093 0.3801832 -0.1700362 0.4718158 0.865146 -0.8294354 -0.09707123 0.5501039 0.637993 -0.4249535 0.6421678 -0.5906389 -0.7348723 0.3333293 0.513466 -0.8200829 0.2526201 -0.3566305 -0.9058896 -0.2284266 0.03941065 -0.7407253 -0.6706512 -0.2370237 -0.1439833 -0.960775 0.5667364 0.2672866 -0.7793381 -0.5458593 0.5965293 -0.5883796 0.5528894 0.7229633 -0.4142917 -0.5098557 0.8344438 -0.2091673 0.7232104 0.6857869 0.08162838 -0.7334938 0.4950122 0.4657788 0.57991 0.2443366 0.777177 0.08551335 0.2066026 0.974681 -0.4346738 -0.287357 0.8535131 0.8195381 -0.274984 0.5027338 -0.6155297 -0.7252498 0.3084414 0.333616 -0.928215 -0.1646732 -0.5596433 0.2391728 -0.7934707 0.6722105 0.5930413 -0.4432101 -0.537211 0.8431036 -0.02410215 0.2626117 0.8149146 0.5166714 -0.4704029 -0.07238322 0.8794782 0.5272877 -0.4381616 0.7279988 -0.5875183 -0.5887626 0.5551405 0.6908132 -0.6599909 0.2952781 -0.2928024 -0.932969 -0.2093696 -0.1133564 -0.5907586 -0.798846 -0.2952302 0.9326481 -0.2073807 0.4789583 0.8407908 0.2523291 -0.5128997 0.7613325 0.3966192 -0.02446371 0.4872872 0.8728991 0.3860789 0.5018215 0.7740275 -0.1018189 -0.1542444 0.9827725 0.09836536 -0.6298154 0.7704913 -0.3620697 -0.8945041 0.2622368 0.5370204 -0.8239049 0.1810797 -0.5683631 -0.7489176 -0.3407136 0.4714443 0.7369793 -0.4843573 -0.6115401 0.7894079 0.05342292 0.5448481 0.828684 0.1281538 -0.3453638 0.6778064 0.649078 -0.2606476 0.3174554 0.9117484 0.4711622 -0.1397686 0.8709024 -0.5857533 -0.3015539 0.7523021 0.6530252 -0.5633904 0.5061122 -0.7354874 -0.6489194 -0.1948385 0.6052926 -0.6744508 -0.4227732 -0.6539425 -0.3449276 -0.6733381 -0.2190452 0.01355975 -0.9756205 0.09768706 0.6172659 -0.7806665 -0.8075971 0.5723597 -0.1420966 0.7234579 0.6886335 0.04891544 -0.7067111 0.5927144 0.3863277 0.6361038 0.5532032 0.5379018 -0.6449929 0.2636364 0.7172726 0.5304777 0.1509799 0.8341454 -0.2609538 -0.3011779 0.9171669 -0.3375437 -0.30514 0.8904796 0.2073423 -0.790291 0.5765845 0.1746197 -0.8966337 -0.4068857 0.001667082 -0.4723997 -0.881383 -0.6571919 0.4752481 -0.5850112 0.5717726 0.7625381 -0.3026748 -0.3190879 0.9261021 -0.2012909 0.1047767 0.9252768 0.3645337 0.6718236 -0.1792727 0.7186894 -0.5799829 -0.5605633 0.5910912 0.7810534 -0.5419256 0.310278 -0.767153 -0.6372419 -0.07347929 0.6601451 -0.6721597 -0.3352759 -0.6023014 -0.5528071 -0.5758796 0.554511 -0.3320586 -0.7630562 -0.4491814 -0.1775022 -0.8756306 0.5180818 0.2574254 -0.8156737 -0.8491919 0.4353806 -0.2988593 -0.1266322 0.9914853 -0.03035354 0.2264402 0.784691 0.5770484 -0.4233381 -0.473159 0.7725965 0.5701764 -0.7798397 0.2583586 -0.7623431 -0.6086598 -0.2199235 0.6458203 -0.6004882 -0.471519 -0.747018 -0.2413082 -0.619463 -0.445801 0.4639232 -0.7655304 0.5623404 0.7148566 -0.4156363 -0.6789655 0.7100004 -0.18683 0.6195462 0.7736135 0.1329841 -0.5808166 0.7357646 0.3482853 0.5774847 0.5703458 0.584138 -0.6753236 0.3239867 0.6625486 0.6439234 0.1118978 0.7568631 -0.6521065 -0.2152796 0.7269194 0.5142468 -0.3471555 0.7842407 -0.532417 -0.7023612 0.4724625 0.6134945 -0.7047795 0.3562449 -0.5264629 -0.8481024 0.05966001 0.5675188 -0.7955669 -0.2121218 0.1581916 -0.928572 -0.3357523 -0.5359284 -0.5232419 -0.6625698 0.7010966 -0.3748386 -0.6065968 -0.7603545 0.08227217 -0.6442767 0.9099441 0.2402375 -0.3380647 -0.402433 0.3237159 0.8563035 0.346526 -0.1984753 0.9168028 0.1795456 -0.8486024 -0.4976317 0.01025563 -0.3360234 -0.9417978 0.5873221 0.5374253 -0.6051669 -0.5615893 0.7959493 -0.2260136 0.401753 0.8988595 -0.1750611 0.1174339 0.922737 0.3671048 -0.4877957 0.7764438 0.3989868 0.3926591 0.4340433 0.8108177 0.5836847 0.01244562 0.8118851 -0.5294994 -0.4155558 0.7395566 0.5074201 -0.5235042 0.6844475 -0.5963343 -0.7429986 0.3038727 -0.2355729 0.9714676 0.02749788 0.4768046 0.7062041 0.5233864 -0.55425 0.5654081 0.6108362 0.5525735 0.2103492 0.8064836 -0.7857059 -0.219544 0.578331 0.5212635 -0.485731 0.7016764 -0.3837366 -0.827683 0.4094962 -0.5529736 -0.8326811 0.02936768 0.6748878 -0.6886023 -0.2652423 -0.8321563 -0.3607276 -0.4211789 0.6722482 0.2546098 -0.6951664 -0.5703279 0.6243773 -0.5337408 0.5895161 0.6988286 -0.4051041 -0.6885812 0.7250586 -0.01208388 -0.5153643 -0.692632 0.504639 0.5696301 -0.8091326 0.144313 -0.545688 -0.8353226 -0.06679034 0.4762133 -0.7830687 -0.4000304 0.262933 0.2776625 -0.9239967 -0.3156027 0.7662304 -0.5597197 -0.6354895 0.5271052 0.5641926 0.6135796 0.2244098 0.7570736 -0.6215816 -0.02922397 0.7828041 0.6428828 -0.2348502 0.7290729 -0.4964998 -0.6536108 0.57121 0.4285904 -0.8995751 0.08411467 -0.5058133 -0.861097 -0.05162179 0.5263485 -0.7055962 -0.474438 -0.6044282 -0.532337 -0.592692 0.4976039 -0.3834383 -0.7780523 -0.7101258 -0.002484381 -0.7040705 0.3749208 0.9211529 -0.1044603 -0.4870104 0.7160767 0.5000551 0.228881 0.3968207 0.888902 -0.1046543 -0.3217316 0.9410294 -0.3489478 -0.6079356 -0.713197 0.432669 -0.06695097 -0.8990635 -0.7267271 0.3481271 -0.5921785 0.7903419 0.463594 -0.4005502 -0.7282573 0.4787437 0.4903526 0.5393835 0.3641276 0.7592605 -0.6386188 0.04448115 0.7682367 0.6063053 -0.0988903 0.7890594 -0.6655601 -0.4798798 0.5716164 0.2091156 -0.8504009 -0.4827929 -0.4291278 -0.3842887 -0.8174176 0.4628042 -0.01500052 -0.8863337 -0.3871119 0.577017 -0.7191633 -0.06200224 0.934154 -0.3514429 0.2527571 0.9246787 0.2847511 -0.5606547 -0.1412339 0.8159162 0.6002671 -0.4080474 0.6878786 -0.6259939 -0.5806896 0.5205107 0.6229537 -0.750071 0.2220862 -0.3705228 -0.8793814 -0.2990003 0.4795424 -0.5335315 -0.6966946 -0.5894976 0.6496243 -0.4800843 0.5697372 0.7820593 -0.2525529 -0.628281 0.7699434 0.1115806 0.3342189 0.9160668 0.2216292 -0.4265664 0.6149954 0.6631906 0.1920554 0.61331 0.7661368 -0.3471778 0.1131952 0.9309428 0.6915551 -0.695248 -0.1959132 0.8425059 -0.3818221 -0.3799946 -0.1353468 -0.2873718 -0.9482082 0.8709874 -0.2767527 -0.4059422 0.6487115 -0.02628695 -0.7605804 0.8682837 0.1026187 -0.485338 0.8407125 0.2731062 -0.4675636 0.8910548 0.2511665 -0.3780698 0.7879695 0.5736138 -0.2237665 0.9010288 0.4211887 -0.1036692 0.7462841 0.6581719 0.09934735 0.8719959 0.4024175 0.2787172 0.7339521 0.5851033 0.3449181 0.8119012 0.2502654 0.5274313 0.7783461 0.240803 0.5798202 0.7357687 -0.06485605 0.6741203 0.7995998 -0.005892455 0.6005043 0.7474871 -0.232692 0.6221878 0.8502478 -0.2554426 0.4602475 0.8319472 -0.4299046 0.3507793 0.8294499 -0.4340334 0.3516076 0.8070015 -0.5768389 0.1265138 0.8277378 -0.5505125 0.1085646 0.7574584 -0.6236788 -0.1930847 0.8187093 -0.5308756 -0.218829 0.7197731 -0.5203468 -0.459528 0.8295981 -0.3143534 -0.4614639 0.8060613 -0.2926132 -0.5144346 0.7994916 -0.3066254 -0.5165212 0.6995883 -0.01660102 -0.7143533 0.8264838 0.06309282 -0.559414 0.7566522 0.3136562 -0.57367 0.8663003 0.3270017 -0.3776158 0.7237737 0.5758538 -0.3801895 0.8453302 0.489451 -0.2141368 0.7216652 0.6922299 0.004145383 0.8012471 0.5947309 0.06556141 0.7260148 0.590982 0.351629 0.7917096 0.5035681 0.3458544 0.7900372 0.3933648 0.4702187 0.8849255 0.1906159 0.4249382 0.805635 0.1453683 0.5742999 0.8030884 -0.02123582 0.5954816 0.7307426 0.006252348 0.6826245 0.8198087 -0.2820903 0.4983359 0.7332248 -0.4020164 0.5484198 0.8038251 -0.5210592 0.286989 0.7614879 -0.5863527 0.2762733 0.795233 -0.6062968 0.002953171 0.8635386 -0.5019062 -0.04890054 0.7730256 -0.5556797 -0.3060258 0.8702121 -0.4055982 -0.27968 0.8085387 -0.235043 -0.5394627 0.7823957 -0.2350392 -0.5767267 0.8508906 0.09996867 -0.5157438 0.8439363 0.09824842 -0.5273698 0.7375594 0.429133 -0.5213933 0.8611309 0.4045366 -0.307902 0.7496182 0.6019615 -0.2751635 0.8706178 0.4918213 0.01169222 0.8584808 0.5128234 0.00481069 0.7982518 0.5447587 0.2569671 0.8818804 0.3899472 0.2650066 0.7933663 0.3897559 0.4676113 0.8721749 0.1863112 0.4523266 0.7887468 0.143312 0.5977795 0.7135765 -0.2071954 0.6692375 0.8269603 -0.09078651 0.5548825 0.8272614 -0.3061108 0.4710995 0.7546071 -0.3074259 0.5797048 0.7424198 -0.5433092 0.391954 0.8830931 -0.4323535 0.1822559 0.7817084 -0.615297 0.1016941 0.807366 -0.5803889 -0.1063438 0.8931066 -0.428484 -0.1369758 0.7245941 -0.5393401 -0.4290406 0.872792 -0.2518062 -0.4181244 0.7863397 -0.2250277 -0.5753543 0.7454431 0.1211736 -0.6554629 0.8188242 0.05438005 -0.5714628 0.706335 0.3277928 -0.6274096 0.8088988 0.4044641 -0.4267222 0.7957618 0.4440295 -0.4118266 0.8821017 0.391785 -0.2615358 0.7647454 0.6316473 -0.1272253 0.8373264 0.543954 -0.05475926 0.7366693 0.6590082 0.1517451 0.8116146 0.5031867 0.2967913 0.8714423 0.3980455 0.2866151 0.8098695 0.328669 0.485889 0.8781628 0.1949488 0.4368356 0.8046535 0.1464021 0.5754121 0.801653 -0.07013386 0.5936614 0.8751929 -0.1037063 0.4725276 0.7967624 -0.327643 0.5077596 0.8614818 -0.3400865 0.3770813 0.7916495 -0.4918596 0.3624436 0.8625448 -0.4645171 0.2006006 0.7711202 -0.6256178 0.1182209 0.7673754 -0.6342742 -0.09397429 0.7525385 -0.6527084 -0.08750838 0.7963966 -0.4657099 -0.3858327 0.8519151 -0.4258022 -0.3048495 0.7681944 -0.3648476 -0.5260832 0.868983 -0.2036097 -0.4510118 0.7237765 -0.03470951 -0.6891611 0.819101 0.1096459 -0.563073 0.7460384 0.2446455 -0.6193345 0.8169676 0.3025185 -0.4909648 0.7210979 0.5268614 -0.4499277 0.8270108 0.4793437 -0.2937392 0.7430004 0.6628124 -0.09289848 0.7814235 0.6204819 -0.0661807 0.7787411 0.5553234 0.2918534 0.8034058 0.5337441 0.2639253 0.7680043 0.4267131 0.477583 0.8882375 0.2134656 0.4067759 0.7982221 0.1723906 0.5771683 0.8726823 -0.03701633 0.4868833 0.7295755 -0.2076209 0.6516234 0.7925387 -0.411913 0.449678 0.7070662 -0.5511162 0.4430894 0.8463821 -0.4850335 0.2199544 0.7811889 -0.6063895 0.1484447 0.8661841 -0.4961919 -0.05931973 0.8223709 -0.5674922 -0.0407288 0.7710952 -0.5785629 -0.2658517 0.8446511 -0.4129994 -0.3405823 0.7834246 -0.4243358 -0.4540761 0.7385665 -0.2520316 -0.6252996 0.7948789 -0.1996854 -0.572969 0.76994 0.1044462 -0.6295105 0.7435983 0.1308351 -0.655701 0.8121517 0.3655672 -0.4547201 0.8171944 0.3579847 -0.4517082 0.8033779 0.507171 -0.3120283 0.8899036 0.4297473 -0.1529346 0.7892491 0.6106665 -0.06459462 0.8501582 0.5102757 0.1298062 0.8676595 0.4783819 0.1353443 0.7898767 0.5153049 0.3324993 0.8438225 0.3376401 0.4170886 0.8591653 0.3123048 0.4053402 0.7459945 0.2005522 0.6350364 0.8444212 0.00608164 0.5356454 0.7702472 -0.08544677 0.6319953 0.8209162 -0.3223626 0.4713588 0.8011088 -0.3533955 0.4830491 0.8578044 -0.4410141 0.2639667 0.8305686 -0.4901726 0.2643615 0.8156898 -0.5774533 -0.03461378 0.8201991 -0.570905 -0.03662037 0.7527868 -0.572282 -0.3252779 0.8491629 -0.3886212 -0.3576254 0.7651132 -0.389396 -0.5128084 0.8603687 -0.1729284 -0.4794387 0.784954 -0.1183579 -0.6081436 0.7521237 0.1279116 -0.6464895 0.8458415 0.1863104 -0.4998407 0.8102585 0.3425075 -0.4755732 0.8505505 0.3318098 -0.4080026 0.8085189 0.4996671 -0.310854 0.8850625 0.4340736 -0.1680614 0.770169 0.6338475 -0.07125341 0.8326315 0.552919 0.03171014 0.7194941 0.6477796 0.2504197 0.8563855 0.3733381 0.3566827 0.732143 0.4100448 0.5439026 0.8802587 0.1373044 0.454194 0.7832639 0.03413915 0.6207513 0.8772869 -0.1025096 0.4688917 0.7935316 -0.2510395 0.5543347 0.8203006 -0.2741471 0.5019465 0.7332624 -0.5104486 0.4491865 0.8313792 -0.5155576 0.2073867 0.8361054 -0.507166 0.2090702 0.8031218 -0.5949239 0.03257447 0.8542844 -0.519106 -0.02696579 0.7492288 -0.6279923 -0.2104324 0.8321061 -0.3884031 -0.3959075 0.534923 -0.6649465 -0.521252 0.8457457 -0.2109974 -0.4900965 0.7067245 -0.1145331 -0.6981566 0.843497 0.1509007 -0.5155015 0.8461884 0.147473 -0.5120712 0.7668511 0.4082808 -0.4952234 0.7199531 0.6215403 -0.3087964 0.84469 0.4063027 -0.3484493 0.8463089 0.5325165 -0.0136938 0.8064392 0.5907607 0.02564525 0.841984 0.4796447 0.2469903 0.8200605 0.5160958 0.247277 0.7380261 0.4721128 0.4821068 0.8230757 0.2725796 0.4982436 0.7595279 0.2324659 0.6075172 0.8016512 0.01924234 0.5974824 0.868181 -0.03723686 0.4948486 0.7753142 -0.2318058 0.5874981 0.8660635 -0.3215385 0.3828145 0.821678 -0.4006936 0.4053269 0.8441817 -0.4666684 0.2637766 0.6582467 -0.7404393 0.135871 0.87072 -0.4792958 -0.1101014 0.7519691 -0.6017344 -0.2691805 0.8517881 -0.3541632 -0.3860384 0.8067976 -0.4189694 -0.4165843 0.7649003 -0.2136299 -0.6076923 0.8281806 -0.1294111 -0.5453162 0.7411906 0.06639695 -0.668003 0.8182694 0.1263818 -0.5607699 0.7342196 0.3610454 -0.5749503 0.8381779 0.3801789 -0.3910526 0.746992 0.5637173 -0.3524568 0.8341367 0.5386103 -0.1188063 0.789642 0.6068601 -0.09047907 0.8309159 0.5253937 0.1831403 0.8614889 0.4731634 0.1842641 0.7922857 0.4530614 0.4086793 0.871288 0.2760145 0.4057996 0.8221127 0.2666 0.503046 0.8115024 0.04127818 0.5828893 0.8490367 0.008010447 0.5282732 0.7516779 -0.1874378 0.632335 0.8424424 -0.3471826 0.4120135 0.8454595 -0.3417118 0.4104038 0.8028653 -0.5140624 0.3019061 0.8772935 -0.4438165 0.182711 0.7401844 -0.6719058 0.0258786 0.8753544 -0.4749458 -0.09045058 0.7605531 -0.5809203 -0.2899839 0.7743627 -0.3927144 -0.4961228 0.7953388 -0.3907625 -0.4634013 0.7634283 -0.183333 -0.6193273 0.7945603 -0.1450378 -0.5896086 0.7699292 0.03335213 -0.6372571 0.8150023 0.07744657 -0.5742588 0.7488408 0.3245046 -0.5778704 0.7834509 0.3250476 -0.5296685 0.7932496 0.5142613 -0.3260224 0.7842382 0.5277996 -0.3261874 0.8396536 0.5372443 -0.07968962 0.8871589 0.4604648 -0.03035438 0.7787542 0.6105256 0.1442236 0.8475297 0.4223592 0.3214126 0.7838527 0.5112525 0.3524146 0.7784677 0.2012425 0.5945499 0.8508852 0.2111242 0.4810625 0.7750326 -0.003086924 0.6319138 0.812286 -0.2188574 0.5406411 0.8741886 -0.1236765 0.4695728 0.8288353 -0.4037017 0.387372 0.8084343 -0.4141834 0.4181939 0.7447794 -0.6182634 0.2511058 0.8113253 -0.5655019 0.1481858 0.7435297 -0.6686995 -0.002141654 0.8453006 -0.5119506 -0.1528846 0.8404016 -0.5177112 -0.1603136 0.775951 -0.4493204 -0.4427315 0.8556205 -0.3360434 -0.3936857 0.7222512 -0.1769917 -0.6686009 0.8568567 0.007598459 -0.5154988 0.7937372 0.09777784 -0.6003506 0.8692371 0.2417164 -0.4312773 0.7964085 0.3660718 -0.4813783 0.7496589 0.5910241 -0.2978292 0.8683707 0.4772897 -0.1346361 0.7892688 0.6114706 -0.05620265 0.810672 0.5720146 0.1249416 0.9152944 0.3673714 0.1651498 0.8398634 0.434395 0.3254697 0.8105065 0.2602049 0.5247595 0.8758718 0.2527567 0.4110507 0.7662632 0.09429186 0.6355706 0.863274 -0.1100807 0.4925854 0.8695062 -0.1117774 0.481108 0.7717337 -0.3754334 0.5133001 0.8473365 -0.3786219 0.3723793 0.7614467 -0.5514244 0.3407787 0.7864367 -0.6019768 0.1383515 0.8137417 -0.5707583 0.1098163 0.7413711 -0.6502457 -0.1659802 0.8592994 -0.4640243 -0.215142 0.7692909 -0.490917 -0.4088912 0.7852399 -0.308288 -0.5369887 0.8476874 -0.3247579 -0.4194741 0.7820359 9.49756e-4 -0.6232327 0.7711467 0.008361935 -0.6366027 0.7827782 0.3212437 -0.5329736 0.8684032 0.3056299 -0.3904694 0.7913343 0.4996126 -0.3523879 0.8788489 0.4619926 -0.1191121 0.8349925 0.5252246 -0.1640942 0.8109139 0.58019 0.07614654 0.8595371 0.4990128 0.1103733 0.7293326 0.5786471 0.3650229 0.8339267 0.3632832 0.4154415 0.7496592 0.3320307 0.5725092 0.8122196 0.1491494 0.5639626 0.7584218 0.09630489 0.6446099 0.7990663 -0.1512339 0.581912 0.8207818 -0.1230552 0.5578304 0.853388 -0.3141561 0.4159747 0.869975 -0.2838091 0.4032317 0.7851374 -0.4956927 0.3712789 0.8208049 -0.4883602 0.2962832 0.7377332 -0.6495396 0.1839787 0.8322485 -0.5508004 -0.0630986 0.8175461 -0.5705271 -0.07821244 0.8313372 -0.4441418 -0.3340907 0.864313 -0.3893518 -0.3183841 0.7946015 -0.2612611 -0.548043 0.8803356 -0.1458368 -0.4513764 0.7893859 0.009370207 -0.6138259 0.8525691 0.1040762 -0.5121466 0.7029927 0.3488936 -0.6197375 0.8534846 0.3830857 -0.353284 0.7195199 0.6093989 -0.3330531 0.8228431 0.5655685 -0.05533194 0.8583096 0.5124263 -0.02690881 0.7817364 0.5848501 0.2164226 0.9000884 0.3469526 0.2635619 0.7770371 0.5408121 0.3220806 0.7840321 0.26919 0.5593126 0.6836574 0.362541 0.6333851 0.8177411 0.05010753 0.573401 0.7045519 -0.07260602 0.7059285 0.8651978 -0.2569193 0.4306102 0.763905 -0.4030234 0.5040055 0.7968145 -0.5562953 0.235844 0.8159943 -0.535295 0.2182032 0.761717 -0.6397269 -0.1026485 0.8728736 -0.4620013 -0.156992 0.7795363 -0.5215558 -0.3468471 0.8490131 -0.3401035 -0.4043594 0.879212 -0.2918138 -0.3766046 0.7774136 -0.1699357 -0.605599 0.8006869 -0.02017557 -0.5987433 0.7417626 0.04408657 -0.6692121 0.8369663 0.2784895 -0.4710956 0.8189525 0.3045892 -0.486356 0.7709156 0.5432223 -0.3325638 0.8953238 0.4101942 -0.1735979 0.7325466 0.6800587 0.02992933 0.8880356 0.4369941 0.1429297 0.7662148 0.5408093 0.347045 0.8835826 0.2588354 0.3902384 0.7871565 0.2577695 0.5603031 0.8088127 -0.03029727 0.5872854 0.8852035 -0.06963187 0.4599633 0.7747083 -0.2908913 0.5614352 0.8555648 -0.3765929 0.3552277 0.890035 -0.3450288 0.2979815 0.8220893 -0.5613589 0.09510773 0.8469924 -0.5210133 0.1055886 0.8040804 -0.5698558 -0.1694678 0.8572703 -0.5040469 -0.1049981 0.780658 -0.5028328 -0.3711231 0.8855955 -0.3302288 -0.3266032 0.7361817 -0.2191919 -0.6403056 0.8739467 -0.07331228 -0.4804608 0.716556 0.1386021 -0.6836206 0.7872098 0.3396117 -0.5147472 0.7678785 0.370092 -0.5228716 0.8259922 0.3765221 -0.4194856 0.7059134 0.6603133 -0.2562667 0.8024845 0.5784429 -0.146364 0.7207441 0.6917465 0.04488509 0.8255565 0.5504741 0.1242378 0.8042489 0.4934808 0.3311501 0.7386184 0.5309475 0.4153766 0.7636151 0.3731552 0.5269224 0.8560813 0.1816511 0.4838674 0.745703 0.1135331 0.6565344 0.8560649 -0.03447157 0.5157176 0.7466488 -0.2327211 0.6231825 0.8242901 -0.348523 0.446181 0.7613448 -0.4592601 0.4576399 0.8208391 -0.4849341 0.301765 0.7191706 -0.6649934 0.2014384 0.8293673 -0.5577988 0.0317893 0.7187006 -0.6806836 -0.1419131 0.8421606 -0.4633174 -0.2758669 0.8207438 -0.4786685 -0.3118594 0.7908521 -0.3599549 -0.4949603 0.8597534 -0.2440788 -0.4486084 0.7595523 -0.1684086 -0.6282665 0.8228614 0.06973391 -0.5639472 0.7653086 0.1379291 -0.6287117 0.7444849 0.4491305 -0.4939879 0.7913888 0.3875629 -0.4727568 0.8679624 0.4584527 -0.1909515 0.8112227 0.5565433 -0.1793805 0.7816839 0.6067408 0.1443465 0.8895184 0.4284828 0.1586176 0.7638413 0.4758873 0.4359792 0.8521226 0.3047809 0.4254361 0.7456374 0.2439141 0.6201055 0.8382689 -0.005005717 0.5452342 0.7945769 -0.06279528 0.6039075 0.862542 -0.1973662 0.4659056 0.8249744 -0.2593262 0.5021628 0.8097289 -0.4510827 0.3753179 0.8587058 -0.4158194 0.2995308 0.7394776 -0.6481519 0.1818574 0.7919868 -0.6095808 -0.03418201 0.8134363 -0.5798334 -0.04598593 0.7283468 -0.5915064 -0.3458775 0.8135241 -0.460523 -0.3551017 0.705482 -0.3694469 -0.6048175 0.8299943 -0.2186843 -0.5131149 0.7094869 0.0248543 -0.7042802 0.8240825 0.09572857 -0.5583226 0.7470949 0.3379192 -0.5724158 0.8209932 0.3413141 -0.4576843 0.7376362 0.6007623 -0.3081843 0.8015806 0.5091781 -0.3133786 0.7843214 0.6118453 -0.1023986 0.8528042 0.5221464 0.009396433 0.752397 0.6473345 0.1218892 0.8148636 0.4740105 0.3336337 0.8851649 0.3547968 0.3010023 0.8123255 0.3189496 0.4882606 0.8556514 0.185785 0.4830576 0.7290471 0.07665121 0.6801581 0.8433399 -0.1831042 0.5052236 0.8124533 -0.2220136 0.5391008 0.8309155 -0.4514018 0.3252938 0.8128374 -0.4667222 0.3485198 0.7793887 -0.6125028 0.1318851 0.8553456 -0.517729 0.01845657 0.7616866 -0.639589 -0.1037276 0.8024414 -0.5251005 -0.2834739 0.8759512 -0.4002003 -0.2693499 0.7522291 -0.4022157 -0.5218948 0.8407741 -0.1364023 -0.5239213 0.8030697 -0.1108494 -0.585484 0.70031 0.2474101 -0.6695925 0.77537 0.1801184 -0.6052759 0.8711413 0.3320919 -0.3617014 0.7506617 0.5273569 -0.3979973 0.8555045 0.5005239 -0.1326198 0.7939918 0.6019957 -0.08472579 0.7697013 0.6169365 0.1641629 0.8261031 0.5299286 0.1916489 0.7343492 0.510116 0.4477868 0.8181124 0.3783369 0.4330745 0.7406244 0.2430899 0.6264046 0.8305929 0.1350188 0.5402644 0.7285631 -0.08903956 0.6791669 0.8415959 -0.166989 0.513645 0.7428269 -0.3804939 0.5508473 0.8305134 -0.4516577 0.3259646 0.8360732 -0.4417769 0.3252916 0.7780178 -0.615318 0.1267766 0.8880492 -0.4593163 0.01993066 0.7474012 -0.6143781 -0.2528457 0.7486773 -0.6128379 -0.2528087 0.81593 -0.385578 -0.4307993 0.7092885 -0.3806464 -0.5933111 0.8316857 -0.1310709 -0.539555 0.731395 -0.01320642 -0.6818263 0.8316971 0.1681052 -0.5291697 0.8233201 0.1812545 -0.5378578 0.833188 0.3984065 -0.3834971 0.7932493 0.4243179 -0.4367036 0.7862891 0.5904806 -0.1818853 0.6973648 0.7044207 -0.1321893 0.8393332 0.5374357 0.0817489 0.7076065 0.6433246 0.292278 0.87304 0.3422583 0.3473623 0.8410518 0.3532554 0.4096862 0.7468725 0.2051021 0.6325462 0.8890373 0.04189175 0.4559141 0.8139085 -0.06904292 0.5768761 0.8200901 -0.1057691 0.5623747 0.6827148 -0.3929415 0.6160337 0.8617137 -0.3905335 0.323934 0.7673225 -0.5645336 0.304168 0.8729569 -0.4869849 0.0281437 0.872654 -0.4875162 0.02833628 0.7472944 -0.5938937 -0.2980629 0.8899677 -0.3454554 -0.2976877 0.7824172 -0.3643161 -0.5050713 0.8623105 -0.1278825 -0.489966 0.8101164 -0.08798193 -0.57963 0.7579107 0.154842 -0.6337156 0.8212029 0.215078 -0.5285522 0.7325636 0.3812931 -0.563885 0.8195775 0.4428191 -0.3635988 0.7556707 0.5595273 -0.3404279 0.7952073 0.6026984 -0.06633359 0.8533135 0.5117967 -0.09960085 0.7901759 0.5891839 0.1687737 0.8642539 0.464799 0.1924247 0.7538013 0.5013877 0.4247282 0.7746733 0.3047775 0.5540688 0.8566341 0.2106929 0.4709424 0.7876727 -0.0668618 0.6124551 0.8504228 -0.08799183 0.5186892 0.7549689 -0.355613 0.5509641 0.819935 -0.4082245 0.4013221 0.7221587 -0.5685837 0.3939537 0.7949327 -0.592865 0.1288151 0.721527 -0.6896066 0.06198054 0.8353615 -0.5384448 -0.1106737 0.7845919 -0.589628 -0.1917144 0.7612428 -0.4951607 -0.4187187 0.8721275 -0.31447 -0.3748363 0.7444734 -0.2215483 -0.629822 0.7812682 0.03767108 -0.6230577 0.8567043 -0.09031873 -0.5078389 0.8365269 0.2630053 -0.4806777 0.8085659 0.3012874 -0.5054178 0.8250035 0.4959495 -0.2709308 0.5167576 0.6994899 -0.4936351 0.8236502 0.5550279 -0.1163812 0.727554 0.6827521 0.06719261 0.7913115 0.6008093 0.1133772 0.7462785 0.5893869 0.3093407 0.861565 0.3530583 0.3647681 0.8218926 0.3648466 0.4374695 0.7982846 0.1819005 0.574155 0.8815051 0.08960348 0.4635947 0.7456017 -0.1406552 0.6513788 0.9006213 -0.2460023 0.3582792 0.781504 -0.3062508 0.5435643 0.8030264 -0.5499482 0.229577 0.727702 -0.6152186 0.3032423 0.7840718 -0.620427 -0.0173766 0.7744622 -0.6325197 -0.01126962 0.7822611 -0.5756176 -0.2381852 0.866359 -0.4240067 -0.2638947 0.8046324 -0.3855187 -0.4515993 0.8371146 -0.3336791 -0.4334715 0.7469933 -0.2207266 -0.6271212 0.8315209 -0.002135634 -0.5554894 0.7822405 0.04754835 -0.6211593 0.8393297 0.2769405 -0.4677925 0.8049531 0.2892222 -0.5180743 0.7693134 0.5454594 -0.3326123 0.8581073 0.4808931 -0.1799825 0.805871 0.5759398 -0.1373509 0.8118499 0.5778741 0.08343422 0.8309948 0.5482069 0.09442919 0.7271494 0.5970891 0.3387307 0.8217565 0.4245345 0.3801141 0.7949643 0.4162813 0.4412955 0.729561 0.130368 0.6713755 0.8283572 0.1805092 0.5303213 0.8530388 -0.09467732 0.5131871 0.7916594 -0.1825099 0.5830657 0.826345 -0.4017888 0.3946133 0.8700863 -0.3231838 0.3721589 0.8180627 -0.5331071 0.2158015 0.8305067 -0.5196158 0.2006444 0.7499572 -0.6606198 -0.03385043 0.8477293 -0.5010809 -0.173992 0.7840045 -0.5623552 -0.2628568 0.847647 -0.3697958 -0.3804544 0.7567532 -0.3672893 -0.5407617 0.7861917 -0.1487579 -0.5998116 0.7739325 -0.1614266 -0.612348 0.7505807 0.08758974 -0.6549479 0.8292604 0.1548348 -0.5369856 0.7510814 0.3078495 -0.5840423 0.8292709 0.4452265 -0.337762 0.8361629 0.4337326 -0.3357197 0.8108612 0.5838205 -0.04071676 0.8831724 0.4690188 0.005309462 0.7771935 0.5816012 0.2402299 0.8700565 0.3718037 0.3236726 0.8470202 0.3829481 0.3686564 0.7822228 0.2711377 0.5609027 0.8623219 0.1555634 0.4818723 0.7640867 0.02827316 0.6444938 0.7938932 -0.1838226 0.5796059 0.7804117 -0.203288 0.5912965 0.8062185 -0.3613505 0.4684416 0.8620428 -0.3391458 0.3766463 0.7523469 -0.5889036 0.2952406 0.8747237 -0.4796826 0.06901681 0.8627445 -0.5018007 0.06219422 0.7419779 -0.6271518 -0.2369588 0.007956147 -0.9713261 -0.2376181 0.4574298 -0.4710306 -0.7542469 0.9572201 -0.1927304 -0.215835 -0.8387885 0.358642 -0.4096459 0.5870787 0.7572062 -0.2863171 0.8809538 0.3862683 -0.2733449 -0.8816223 0.1583518 0.4445976 0.9256235 -0.1587557 -0.3435373 -0.8758258 -0.3559175 -0.325963 0.9382458 0.2255709 0.2623215 -0.9311386 0.3025362 0.2035998 0.868582 -0.008017241 -0.4954808 -0.9140416 -0.1351783 -0.3824328 0.8627286 0.09785825 0.4961081 0.8933433 -0.4207389 -0.1578496 0.8459527 -0.1856052 -0.4999147 -0.8173 0.2512689 0.5185409 0.8389783 0.1071062 0.5335202 -0.3688274 -0.2539477 -0.8941348 0.4505494 -0.05607026 -0.8909891 -0.2113698 0.2353156 -0.9486566 0.8887133 0.1320624 0.4390311 0.645359 0.1456714 0.7498611 0.7358123 0.1908229 0.6497438 -0.1018831 0.05326944 0.9933692 0.2907988 0.2094154 0.9335852 0.9781331 0.1094548 0.1768489 0.5930711 0.3848623 0.7072113 0.2438635 0.4327352 0.8679118 0.6523485 0.4815636 0.5852675 -0.1499886 0.5539001 0.8189617 0.7879433 0.4408044 0.4299269 0.2929137 0.6658072 0.6862233 0.6846827 0.6368142 0.35451 0.9792833 0.2000503 0.03137224 0.7657049 0.6069299 0.2129137 0.2719498 0.8391063 0.4711094 0.7574895 0.6384752 0.1362318 0.2153892 0.862176 0.4585413 0.9262011 0.376234 0.02448749 0.6491429 0.7527244 0.1096335 0.2485498 0.9373315 0.2441982 0.5599659 0.8284726 0.008453547 0.07759845 0.9818814 0.1728804 0.6751429 0.7257947 -0.1319247 0.8731073 0.4670388 -0.1398518 0.2839413 0.9587633 -0.01226258 0.8806351 0.4545454 -0.1336802 -0.009566366 0.9781067 -0.2078844 0.3944311 0.8614546 -0.3198753 0.3286591 0.8885396 -0.3201261 0.6868398 0.6108607 -0.3938278 0.9962701 0.06631952 -0.05520713 0.5825653 0.6961641 -0.4194918 0.7682053 0.4618536 -0.443342 0.9122141 0.2431842 -0.3297381 -0.003398478 0.7614553 -0.6482086 -0.1158931 0.7266583 -0.6771532 0.884018 0.2353547 -0.4038817 0.368384 0.5277414 -0.7653643 0.6409197 0.2600851 -0.7222035 0.4072604 0.4013063 -0.8204219 0.6426503 0.2484189 -0.724768 0.9332299 0.006264209 -0.3592255 0.8621561 -0.01249259 -0.5064889 0.435081 0.04941177 -0.8990346 0.7455742 -0.1056015 -0.6580027 0.7567401 -0.07223057 -0.6497132 0.0558604 0.03255873 -0.9979076 0.8018925 -0.2001062 -0.5629617 0.2655926 -0.3077394 -0.9136504 0.2935541 -0.3121064 -0.9035573 0.4609952 -0.4498987 -0.7649018 0.9628959 -0.1650053 -0.2135527 0.4361665 -0.5184196 -0.735527 0.740419 -0.5255907 -0.418968 0.0951246 -0.6600081 -0.7452118 0.7172058 -0.5394471 -0.4411494 0.8444945 -0.5081618 -0.1691172 0.7900124 -0.5700892 -0.2255632 0.2541552 -0.8031334 -0.538871 0.4042822 -0.8814545 -0.2441188 0.08978527 -0.8937999 -0.4393866 0.3236334 -0.9404454 -0.1040386 0.8270648 -0.558843 0.06048625 0.8515923 -0.5185911 0.07651114 0.4674358 -0.8820473 0.05913203 0.10912 -0.9485608 0.2971956 0.7396456 -0.5680685 0.3608638 0.5179909 -0.7180087 0.4649183 0.8755234 -0.3491459 0.3339999 0.7915412 -0.330278 0.5141781 0.3098734 -0.6968476 0.6468245 0.6084057 -0.4269844 0.6689745 0.3326207 -0.563981 0.7558367 -0.07680976 -0.4762997 0.8759219 0.8878117 -0.1154692 0.4454854 0.8983383 -0.1072318 0.4260158 0.3444342 -0.2383836 0.908041 0.6240077 -0.05835193 0.7792366 0.4064638 -0.1195877 0.9058069 0.9999468 -0.007904589 0.006622314 0.9998311 0.01447951 0.01132243 0.9999899 -0.003914654 -0.002236008 0.9999737 -0.005562365 -0.004669666 0.9999547 -0.00744462 0.005927681 0.9998952 -0.003056466 -0.01415365 0.9999952 -0.002869367 0.001146733 -0.07155561 0.5001372 -0.8629848 -0.07185786 0.500338 -0.8628432 -0.07241094 0.9973703 -0.003032743 -0.07134002 0.9974498 -0.002123355 -0.07097816 0.499648 0.8633157 -0.07193213 0.5003068 0.8628551 -0.07161247 -0.4975239 0.8644893 -0.07199597 -0.4972332 0.8646247 -0.07148623 -0.9974359 0.003391146 -0.06950241 -0.9975802 0.001768589 -0.03767788 -0.5009314 -0.8646665 -0.03613102 -0.4998105 -0.865381 -0.9999299 0.009297072 0.00733298 -0.9999341 0.01116847 0.002676129 -0.9999304 2.9086e-4 0.01180285 -0.999939 0.004459083 0.01010823 -0.9999379 -0.003904759 0.01044154 -0.9999478 0.005129039 0.008844077 -0.9999282 0.01162272 -0.002921342 -0.999947 0.01029038 4.49379e-4 -0.9999268 0.009340882 -0.007700622 -0.9999325 -0.007838249 0.008585929 -0.9999467 -0.004917562 0.009082138 -0.9999437 0.0050233 -0.009352207 -0.999942 0.004925489 -0.009579241 -0.999925 -0.01162427 0.003893494 -0.9999479 -0.01021069 1.51213e-4 -0.9999306 6.26088e-4 -0.01177132 -0.9999377 -0.003880381 -0.01046407 -0.9999259 -0.01167064 -0.003483355 -0.9999469 -0.004751384 -0.009148299 -0.9999284 -0.008702218 -0.008221924 -0.9999939 0.002485752 0.002449214 -0.9999706 -0.006885826 -0.003384351 -0.9999998 -6.12666e-4 7.54255e-5 -0.9999995 -1.07028e-4 9.63798e-4 0.0162267 0.04980278 -0.9986273 -0.01872795 0.3500383 -0.9365482 0.03387737 0.5358072 -0.8436605 -0.02446955 0.6743088 -0.738044 0.01724433 0.9480949 -0.3175196 -0.01724725 0.9303782 -0.3661952 0.02714574 0.9858596 0.1653601 -0.02646648 0.9578977 0.2858873 0.01923263 0.7513114 0.6596676 0.002146422 0.7270249 0.6866078 -0.01277804 0.3473463 0.93765 0.02284753 0.260547 0.9651908 -0.0209732 -0.05281269 0.9983842 0.01966005 -0.198247 0.979955 -0.01390606 -0.473309 0.8807867 0.01709622 -0.5638638 0.825691 -0.02427595 -0.7714684 0.6358045 0.02709406 -0.8868873 0.4611907 -0.02599263 -0.9695057 0.2436863 0.02884054 -0.9993446 0.02187693 -0.02780795 -0.9721037 -0.2328974 0.02343446 -0.8922116 -0.4510092 -0.02381241 -0.7847307 -0.6193792 0.0218296 -0.640444 -0.7676947 -0.01462405 -0.4038309 -0.9147167 0.005084216 -0.3446853 -0.9387046 -0.007973074 -0.02447193 -0.9996687 0.9999621 0.005221545 0.006976902 1 -2.64046e-5 4.0268e-5 0.9961555 -0.08681505 -0.01172792 0.9999917 -0.003632307 0.001889228 0.9998658 -3.39458e-4 0.0163815 0.9998639 -0.00327897 0.01617383 0.9995407 0.02999627 0.004316926 0.999958 -0.009165167 2.0074e-4 0.9999925 0.001020431 0.003767669 0.9998647 -0.003248333 -0.01612681 0.9999648 0.007368981 -0.004043698 0.9999999 -4.32405e-4 -2.16653e-4 0.9999956 0.002710878 -0.001281797 0.9999988 -0.001179933 -0.001036286 1 -3.0154e-4 -3.70592e-4 0.9999984 -0.001834571 -2.19347e-5 0.9999991 -4.83602e-4 -0.001306354 0.9999899 -0.004360854 -0.00112468 0.9999986 -0.001666903 -2.7911e-4 0.9999903 2.24567e-4 -0.00441575 0.9999464 0.002991735 0.009914278 0.9999717 0.007012426 -0.002758502 0.9999891 0.002508461 -0.003945767 0.9999719 0.001688063 -0.007312715 -0.996582 -0.05048882 0.06538605 -0.9966303 -0.05449855 0.06130284 -0.999839 -0.01793068 -8.57014e-4 -0.9941147 -0.0753163 0.07786774 -0.9999705 0.007101476 -0.002931833 -0.9727237 0.03984773 0.2285186 -0.9999439 -0.001565396 0.01048433 -0.9998754 0.01535177 0.003667175 -0.9998167 0.005993127 0.01818603 -0.9999629 -0.008264183 0.00244832 -0.9999657 0.007205188 0.004078567 -0.9887824 0.07115072 0.1313288 -0.9957795 0.09172874 0.003020048 -0.9084295 0.4176115 -0.01888084 -0.7242029 0.6736475 0.1474081 -0.8488462 0.4511723 0.2755064 -0.8911249 0.3725821 0.258996 -0.7556242 0.3902452 0.5260616 -0.8705331 0.1380046 0.4723631 -0.8657189 0.1448227 0.4791215 -0.7739916 -0.0342949 0.6322667 -0.8486208 -0.1343178 0.5116654 -0.7321073 -0.3121169 0.6054767 -0.7955567 -0.3509183 0.4939088 -0.717787 -0.5833957 0.3800415 -0.8643752 -0.4831452 0.1393784 -0.7955483 -0.5988577 0.0920462 -0.833549 -0.5391297 -0.1205624 -0.8843904 -0.4411656 -0.1524034 -0.7345721 -0.5222401 -0.4332081 -0.8601241 -0.316135 -0.4003066 -0.6767464 -0.1912137 -0.7109513 -0.8467655 9.36872e-4 -0.5319657 -0.7427889 0.2195993 -0.6324878 -0.7900389 0.2428997 -0.5628839 -0.7546126 0.4681839 -0.4597433 -0.8476706 0.458386 -0.2670897 -0.7728371 0.5814583 -0.2542229 -0.874721 0.4836338 -0.03100973 -0.6985573 0.7000492 0.1481515 -0.8657534 0.3999117 0.3009017 -0.7670838 0.4626539 0.4444477 -0.8294222 0.1907418 0.5250492 -0.8605436 0.1486253 0.4872117 -0.8009431 -0.05717885 0.596004 -0.8719958 -0.1323995 0.4712683 -0.7798804 -0.2925835 0.5533367 -0.8577911 -0.3953524 0.3284674 -0.8620169 -0.3925188 0.3207117 -0.8010581 -0.5687042 0.1867656 -0.8431517 -0.5271378 0.1059292 -0.7637314 -0.645534 -5.12653e-4 -0.8188948 -0.5439385 -0.1831454 -0.7383906 -0.6112598 -0.2848524 -0.7714744 -0.4421976 -0.4574808 -0.8049102 -0.3914914 -0.4459307 -0.8038581 -0.222536 -0.5516247 -0.7520671 -0.2032169 -0.6269752 -0.750643 -0.02180373 -0.6603483 -0.8276067 0.06316971 -0.5577425 -0.729716 0.2741491 -0.6263841 -0.8204447 0.3691706 -0.4365592 -0.7963581 0.4158487 -0.4391853 -0.8762995 0.4440202 -0.1869368 -0.8694267 0.457043 -0.1876407 -0.756038 0.6537636 -0.03162062 -0.8735288 0.4665778 0.1387535 -0.7819973 0.5696966 0.2528363 -0.7693071 0.4270429 0.4751853 -0.8023153 0.3715835 0.4671359 -0.7337996 0.228097 0.6399296 -0.8085582 0.105983 0.5787931 -0.7460153 -0.02263444 0.6655442 -0.813076 -0.1325725 0.5668615 -0.7175691 -0.3142815 0.6215479 -0.844922 -0.3963323 0.3592041 -0.8364788 -0.4103106 0.3632474 -0.793896 -0.5722823 0.2054804 -0.8947001 -0.4457759 0.02820956 -0.7930825 -0.6059929 -0.0615862 -0.8665354 -0.4190509 -0.2711327 -0.8585442 -0.4279047 -0.2824882 -0.7743082 -0.3086878 -0.5524118 -0.8772075 -0.1699525 -0.4490247 -0.778724 -0.01745092 -0.627124 -0.7970206 0.1849074 -0.57495 -0.816603 0.165374 -0.553002 -0.7990212 0.3468962 -0.49115 -0.8720243 0.3440183 -0.3481738 -0.7889875 0.5276376 -0.3147976 -0.8755547 0.4662732 -0.1264646 -0.7845116 0.6187765 -0.04071187 -0.848733 0.5255132 0.059062 -0.7097003 0.6475111 0.2775877 -0.8097595 0.4278675 0.4015208 -0.7999078 0.4217968 0.4268898 -0.8766454 0.2560205 0.4073652 -0.8016381 0.2054811 0.5613857 -0.8712838 0.02233529 0.4902711 -0.7960817 -0.03599286 0.604118 -0.8508889 -0.2897835 0.4381936 -0.8876838 -0.236137 0.3952935 -0.7882669 -0.4859724 0.377447 -0.8691999 -0.4612355 0.1781951 -0.7948172 -0.5854134 0.1598653 -0.8335366 -0.5356007 -0.135457 -0.8695127 -0.4700751 -0.1515818 -0.75614 -0.5101312 -0.4099008 -0.8601168 -0.2660117 -0.4352435 -0.8810441 -0.2290731 -0.4138682 -0.7756289 -0.05290597 -0.6289682 -0.8753152 0.07309579 -0.4779962 -0.7686919 0.2196345 -0.6007274 -0.8448622 0.2746153 -0.4591235 -0.7062802 0.5753695 -0.4124541 -0.8738076 0.4658602 -0.139408 -0.782793 0.6162573 -0.08638316 -0.83793 0.5227977 0.1567038 -0.7850072 0.606392 0.1266979 -0.7387514 0.5715838 0.3571251 -0.8228695 0.407409 0.3961107 -0.7265436 0.3939023 0.5630058 -0.8491506 0.1245138 0.5132638 -0.7613859 0.05497747 0.6459637 -0.818401 -0.1861516 0.5436613 -0.8279308 -0.1764639 0.5323449 -0.7395588 -0.4588096 0.4924903 -0.8126711 -0.4294241 0.3939043 -0.7859605 -0.5702214 0.2389851 -0.9020241 -0.4300151 0.0379436 -0.7769658 -0.6263939 -0.06288892 -0.8887263 -0.3910918 -0.2391924 -0.8470093 -0.4369308 -0.3027653 -0.7178086 -0.4212407 -0.5543529 -0.8043375 -0.1708117 -0.569091 -0.7600574 -0.155134 -0.6310677 -0.8194419 0.09414875 -0.5653768 -0.8220843 0.09565091 -0.5612738 -0.7652095 0.3749412 -0.5233293 -0.8026946 0.3762358 -0.4627401 -0.7668433 0.575416 -0.2843376 -0.763973 0.5773947 -0.2880289 -0.777643 0.6287062 6.36493e-5 -0.8656936 0.4923856 0.09017229 -0.7575914 0.5770186 0.305131 -0.8941443 0.3197891 0.3134341 -0.7077364 0.3365863 0.6211433 -0.8810415 0.06204324 0.4689527 -0.7194257 -0.06753742 0.6912781 -0.8559095 -0.31334 0.4113842 -0.7710576 -0.419404 0.4791353 -0.8188592 -0.5428889 0.1863901 -0.8786207 -0.4660243 0.1041498 -0.7925272 -0.6077765 -0.05008453 -0.8590662 -0.4772915 -0.1849272 -0.8232848 -0.5165004 -0.2354348 -0.8184995 -0.4183341 -0.3937706 -0.8701717 -0.3131771 -0.3804226 -0.7900797 -0.234327 -0.5664496 -0.844254 -0.151884 -0.5139715 -0.7309663 0.05405408 -0.6802694 -0.8583055 0.2321665 -0.457614 -0.8280317 0.2719141 -0.4903329 -0.7882202 0.4915097 -0.370307 -0.8785582 0.4312325 -0.2053638 -0.7981439 0.5841767 -0.1473227 -0.8540868 0.5158811 0.06635099 -0.8218496 0.5621714 0.09233963 -0.7955484 0.4751818 0.3759055 -0.8884662 0.3132102 0.3354509 -0.771887 0.1834105 0.6087291 -0.8438823 0.09328645 0.5283564 -0.7255536 -0.1291544 0.6759372 -0.8366601 -0.2251112 0.4993244 -0.7262639 -0.4391343 0.5288686 -0.8184692 -0.4612652 0.3425529 -0.7492985 -0.5942027 0.292361 -0.8117467 -0.564936 0.1480361 -0.7400956 -0.6709262 0.04600566 -0.8482168 -0.5072541 -0.1523863 -0.783154 -0.5687589 -0.2513628 -0.8827422 -0.3601008 -0.3018175 -0.7672618 -0.3835118 -0.5140311 -0.8691269 -0.1311035 -0.4768965 -0.837832 -0.1212697 -0.5322886 -0.769569 0.1020693 -0.6303535 -0.8982549 0.1775035 -0.4020334 -0.7732823 0.4266919 -0.469008 -0.7995941 0.4234624 -0.4258276 -0.7284496 0.6518398 -0.2108699 -0.8122969 0.5731985 -0.1077833 -0.722582 0.6858131 0.08680856 -0.8545179 0.4590282 0.2430894 -0.7335566 0.5471374 0.4031568 -0.8921952 0.2069217 0.4014613 -0.7742635 0.2018442 0.5998126 -0.8686 -0.0771954 0.4894639 -0.8704853 -0.07541877 0.4863821 -0.7743511 -0.2846223 0.565129 -0.8692791 -0.3784352 0.3180264 -0.8736687 -0.3707108 0.3150818 -0.7409771 -0.62273 0.2513173 -0.8628265 -0.5050909 0.0203374 -0.8823555 -0.4705821 0.001191914 -0.7774148 -0.5860504 -0.2284106 -0.8038884 -0.4671902 -0.3680991 -0.7868573 -0.4774175 -0.3910603 -0.7674338 -0.2643834 -0.5840779 -0.797678 -0.2222738 -0.5606284 -0.7745139 0.04921418 -0.6306396 -0.8408215 0.01008707 -0.5412187 -0.8200332 0.2584116 -0.5106555 -0.8690468 0.2762544 -0.4104159 -0.773833 0.4813352 -0.4117028 -0.892348 0.4151367 -0.1771345 -0.7375665 0.6657902 -0.1127792 -0.8372447 0.526642 0.1472066 -0.8756853 0.4554727 0.160374 -0.7830384 0.4697803 0.4076243 -0.8693978 0.2786667 0.4080349 -0.7849438 0.2622779 0.5613144 -0.7802417 0.05160939 0.6233454 -0.7928988 0.0381971 0.6081551 -0.7962012 -0.1980704 0.5716922 -0.7829622 -0.2132678 0.5843691 -0.7514169 -0.4394785 0.4921701 -0.8579353 -0.4058728 0.3149834 -0.7750988 -0.6050207 0.1821316 -0.7948266 -0.5860248 0.1575613 -0.7348064 -0.6755368 -0.0609076 -0.8643929 -0.4596571 -0.2038146 -0.7371029 -0.5592674 -0.3793406 -0.8529407 -0.3424323 -0.3939953 -0.7565838 -0.3150306 -0.5730066 -0.7857085 -0.09587901 -0.6111214 -0.7674469 -0.08388221 -0.6356014 -0.8172791 0.1751002 -0.5489943 -0.7787026 0.2142136 -0.5896906 -0.7459416 0.434278 -0.5049494 -0.8345421 0.4260677 -0.3492937 -0.7563576 0.5967669 -0.2679413 -0.8206807 0.5601167 -0.1129269 -0.7390182 0.6721432 -0.04556012 -0.8040317 0.5601815 0.199323 -0.7365902 0.6185964 0.2734474 -0.8199859 0.3538106 0.4499348 -0.7601989 0.360136 0.54074 -0.8780637 0.1112977 0.4654213 -0.787746 0.06208795 0.6128633 -0.8586452 -0.1776208 0.4808114 -0.8166555 -0.2286161 0.5299138 -0.7222302 -0.5577479 0.4090242 -0.8380454 -0.4075151 0.3627829 -0.8159955 -0.549768 0.1786244 -0.8796932 -0.4697319 0.07410746 -0.7812014 -0.6237687 -0.02523761 -0.8340861 -0.4930225 -0.2474454 -0.9006869 -0.354098 -0.2517496 -0.6795216 -0.4176189 -0.6031956 -0.9017235 -0.07423847 -0.4258915 -0.8002398 0.004679918 -0.599662 -0.8556401 0.2028056 -0.4761827 -0.8475551 0.2127056 -0.4862167 -0.7716615 0.4137019 -0.483104 -0.8782367 0.4179568 -0.232406 -0.8440823 0.4819976 -0.2349544 -0.797431 0.6023882 -0.03510808 -0.7866792 0.6156024 -0.04657989 -0.7213885 0.6538522 0.2282019 -0.8456462 0.447636 0.2906965 -0.7581361 0.4613978 0.4608055 -0.800232 0.3177902 0.5085648 -0.711501 0.2840161 0.6427295 -0.8364266 0.01259911 0.5479343 -0.7086412 -0.1148 0.6961671 -0.8174393 -0.2157423 0.5340864 -0.7147817 -0.4276627 0.553346 -0.8322813 -0.453593 0.3186867 -0.6977269 -0.65702 0.2854853 -0.8462209 -0.532793 0.006467461 -0.7330782 -0.670296 -0.1153242 -0.6568586 -0.7501637 -0.07610088 -0.8041233 -0.4120591 -0.4284777 -0.8357075 -0.3900498 -0.3865932 -0.6943072 -0.2145537 -0.6869528 -0.8209497 -0.1117039 -0.5599676 -0.6530718 0.1162461 -0.7483208 -0.8342925 0.1821101 -0.5203768 -0.8200333 0.4018234 -0.4075334 -0.768056 0.416664 -0.4862932 -0.7825645 0.5797122 -0.2269946 -0.8556654 0.5049608 -0.1133643 -0.7639959 0.6447178 0.02548599 -0.8790974 0.4372344 0.1897739 -0.84496 0.4800447 0.235796 -0.7797566 0.3897083 0.4900075 -0.8848022 0.180544 0.4295684 -0.8032563 0.1500393 0.5764267 -0.863606 -0.08243131 0.4973829 -0.8132224 -0.1313381 0.5669388 -0.8371491 -0.3292494 0.4367796 -0.8725941 -0.3291445 0.3608926 -0.8078681 -0.4880289 0.3304195 -0.8815 -0.4478757 0.1495505 -0.7845114 -0.6133156 0.09157466 -0.8470419 -0.5179602 -0.1193204 -0.8596416 -0.4950473 -0.1262724 -0.8266795 -0.4462013 -0.342791 -0.8559081 -0.3863799 -0.3437032 -0.7694991 -0.3203575 -0.5524873 -0.8781875 -0.1293561 -0.4604929 -0.7904396 -0.04515582 -0.6108734 -0.8516811 0.1140585 -0.5114978 -0.8109505 0.1659585 -0.5610857 -0.7307149 0.4906997 -0.4746258 -0.8505129 0.3487803 -0.393675 -0.7767996 0.6056234 -0.172635 -0.8371021 0.5356041 -0.1113042 -0.845318 0.5148013 0.142889 -0.8043362 0.565685 0.1817799 -0.8143634 0.4135625 0.407159 -0.8589383 0.3363178 0.3861548 -0.8027857 0.178669 0.5688695 -0.8032227 0.1781781 0.5684066 -0.7853074 -0.1153134 0.6082722 -0.7524797 -0.14267 0.6429772 -0.8145923 -0.3962577 0.4235792 -0.7657283 -0.4566031 0.4529612 -0.8370185 -0.5245574 0.155691 -0.8312554 -0.5315384 0.1627308 -0.660243 -0.7125487 -0.237389 -0.8616872 -0.4970455 -0.1021815 -0.7779814 -0.5324738 -0.3334921 -0.8779733 -0.2866361 -0.3834095 -0.8738426 -0.2947117 -0.3867095 -0.7772347 -0.199413 -0.5967752 -0.8900626 0.02633029 -0.4550774 -0.8309144 0.0828076 -0.5502038 -0.7738384 0.296477 -0.5597103 -0.8529552 0.3004316 -0.4268587 -0.8199049 0.4685358 -0.3289836 -0.8758258 0.4308017 -0.2175754 -0.7755568 0.6196727 -0.1204891 -0.7846102 0.6177552 0.05258697 -0.8760375 0.471693 0.1003195 -0.7797197 0.4938843 0.3848582 -0.7794946 0.4940156 0.3851452 -0.8300699 0.2093932 0.5168545 -0.7511569 0.3247517 0.5747171 -0.8305819 -0.02532964 0.5563203 -0.8170475 -0.01552832 0.5763612 -0.7340635 -0.3003804 0.6090341 -0.8338403 -0.3694828 0.4101136 -0.8284767 -0.3883055 0.4035407 -0.9002896 -0.3873068 0.1986759 -0.8403221 -0.5042228 0.1990431 -0.8168194 -0.5743724 -0.05387437 -0.8707575 -0.4911282 -0.02397304 -0.7556967 -0.5713104 -0.3201984 -0.811562 -0.4819347 -0.3303123 -0.7454553 -0.42041 -0.5172542 -0.8528555 -0.1561095 -0.4982643 -0.8421519 -0.153109 -0.5170473 -0.7974357 0.03847962 -0.6021759 -0.8536445 0.1065476 -0.5098419 -0.746127 0.2659654 -0.6103745 -0.8205888 0.4473894 -0.3556356 -0.8507137 0.428922 -0.3038292 -0.7870522 0.5891407 -0.1829265 -0.8804803 0.4734732 0.02403461 -0.8187338 0.5692671 0.07490003 -0.7406917 0.5803089 0.3385521 -0.8260344 0.4247402 0.3704902 -0.730901 0.4186554 0.538991 -0.8279718 0.1752359 0.5326868 -0.6959325 0.06212496 0.715415 -0.8739982 -0.1280092 0.4687651 -0.7377678 -0.3125391 0.5983461 -0.8872424 -0.3712186 0.2738574 -0.8080078 -0.5052174 0.3031156 -0.8229457 -0.5674414 0.02776104 -0.8428986 -0.5379977 0.008968949 -0.8085741 -0.5534008 -0.1998891 -0.8522915 -0.4682331 -0.2331463 -0.7359457 -0.5248638 -0.4276705 -0.7766569 -0.2926083 -0.5578392 -0.7685907 -0.2917006 -0.5693675 -0.7838047 -0.02206254 -0.6206155 -0.8690208 0.05888837 -0.4912587 -0.7933766 0.2641857 -0.5484154 -0.8573022 0.2952229 -0.4217542 -0.7627494 0.4752752 -0.4385509 -0.797728 0.5542567 -0.2375487 -0.7837896 0.5752299 -0.2340608 -0.8049079 0.5825453 0.11298 -0.8801554 0.4705664 0.06240117 -0.760717 0.5899391 0.2707061 -0.8592699 0.3331292 0.3881757 -0.8548537 0.3409178 0.3911526 -0.818382 0.1310023 0.5595438 -0.8145256 0.1300862 0.5653547 -0.7389034 -0.1423301 0.6586076 -0.7998872 -0.1890679 0.5695911 -0.7442501 -0.3898815 0.5422953 -0.8452624 -0.405338 0.3481848 -0.8004896 -0.538035 0.2640737 -0.8560771 -0.4840302 0.1812368 -0.8365783 -0.5475403 0.01834487 -0.818816 -0.572633 0.04039919 -0.8042206 -0.5364251 -0.2558856 -0.7795642 -0.5759356 -0.2461258 -0.7546277 -0.4485782 -0.4788681 -0.8202636 -0.3373329 -0.4619246 -0.8072278 -0.1222987 -0.5774309 -0.7638521 -0.1926066 -0.6159811 -0.7945715 0.1131595 -0.5965325 -0.7486565 0.07804232 -0.6583487 -0.778751 0.3442985 -0.5244097 -0.8186539 0.3568609 -0.4499515 -0.7004066 0.5933373 -0.3967134 -0.855719 0.4975191 -0.1421962 -0.7638395 0.6454059 -7.97106e-4 -0.868765 0.4866985 0.09149819 -0.7707461 0.5538819 0.3149056 -0.8787246 0.3526349 0.3217014 -0.7914074 0.3175113 0.5223609 -0.783547 0.3310213 0.5258128 -0.7277112 0.09838736 0.6787905 -0.8169919 -0.01362305 0.5764881 -0.7322457 -0.2122365 0.647126 -0.8700482 -0.2933734 0.3961669 -0.7843194 -0.4396863 0.4376291 -0.8547005 -0.4863103 0.1816297 -0.8782089 -0.456234 0.1435264 -0.791324 -0.6113417 0.008222103 -0.8497917 -0.5028145 -0.1582141 -0.7975211 -0.5631113 -0.2164853 -0.750245 -0.4027007 -0.5243707 -0.8605646 -0.2428846 -0.4477004 -0.8058182 -0.02816855 -0.5914927 -0.7126568 -0.1030378 -0.6939046 -0.807879 0.2448228 -0.5360907 -0.6907349 0.2236297 -0.6876592 -0.8232669 0.45907 -0.3338958 -0.8291087 0.4498757 -0.3319497 -0.8150798 0.565388 -0.1264182 -0.8375362 0.5376119 -0.09750199 -0.7529207 0.6547675 0.06625753 -0.7970933 0.5529444 0.2426825 -0.7562397 0.5825909 0.2978075 -0.8038804 0.3889919 0.4499574 -0.7366764 0.4051921 0.5414124 -0.824832 0.06350433 0.5618003 -0.7904133 0.02761369 0.6119511 -0.8586483 -0.07085806 0.5076439 -0.7840695 -0.197687 0.5883494 -0.8513063 -0.2745753 0.4470863 -0.727832 -0.4883275 0.4814531 -0.8229554 -0.5038574 0.2624354 -0.6847461 -0.7019757 0.1958392 -0.8208726 -0.5690504 -0.04847538 -0.8203111 -0.5697956 -0.04922115 -0.7930598 -0.5352078 -0.2908759 -0.8514239 -0.3928655 -0.3474681 -0.8036026 -0.4200205 -0.4216701 -0.7878073 -0.2293567 -0.5716251 -0.8811359 -0.0949071 -0.4632411 -0.7430995 0.1048892 -0.6609095 -0.8719701 0.1805976 -0.4550304 -0.7860396 0.3919798 -0.4780101 -0.7567215 0.3865365 -0.5272213 -0.7264939 0.5936839 -0.3460435 -0.8811328 0.4650745 -0.08550351 -0.7961303 0.6050677 -0.0083431 -0.8459238 0.5109437 0.1528057 -0.7638813 0.5991938 0.2396919 -0.7647528 0.3713954 0.5265157 -0.7315739 0.3754374 0.5690751 -0.8801577 0.1031136 0.4633468 -0.7906042 0.03592419 0.6112728 -0.8525694 -0.186675 0.4881372 -0.8765018 -0.1930871 0.4409785 -0.7524526 -0.4947948 0.4347338 -0.8787308 -0.4311667 0.2047622 -0.8001114 -0.5748878 0.1712484 -0.8475975 -0.5267769 -0.06391221 -0.8327448 -0.548321 -0.07668292 -0.82221 -0.443699 -0.3565135 -0.8493965 -0.4183886 -0.321678 -0.79321 -0.1987136 -0.5756135 -0.844568 -0.1402107 -0.5167647 -0.6239123 0.2684048 -0.7339566 -0.8704426 0.1011797 -0.4817597 -0.8049519 0.3269972 -0.4951013 -0.8729484 0.3568727 -0.3325707 -0.7991182 0.4921923 -0.3451912 -0.8290802 0.5233973 -0.1966758 -0.7452437 0.649079 -0.1526705 -0.7895523 0.6017653 0.1203573 -0.7457461 0.64656 0.1606947 -0.7969925 0.4602389 0.3911307 -0.8035572 0.4501885 0.389392 -0.7763213 0.173411 0.6060149 -0.830416 0.1765678 0.5284253 -0.7006368 -0.0363776 0.7125903 -0.8187159 -0.1526985 0.5535228 -0.7350661 -0.3663502 0.5704959 -0.853055 -0.390416 0.3462263 -0.7823252 -0.514611 0.3509172 -0.8344569 -0.545872 0.07553547 -0.8037945 -0.5855342 0.1051868 -0.7421178 -0.6429391 -0.1894477 -0.8661814 -0.4201382 -0.2705798 -0.7817972 -0.4588244 -0.4222244 -0.731546 -0.4041333 -0.5491054 -0.8523544 -0.2484647 -0.4601709 -0.8100938 -0.06230753 -0.5829803 -0.7868356 -0.04874426 -0.6152349 -0.719934 0.1756684 -0.6714429 -0.8260588 0.272461 -0.4933478 -0.7663165 0.3770397 -0.5201925 -0.8693968 0.4334304 -0.2372494 -0.8416516 0.4592338 -0.2841254 -0.8200771 0.5630633 -0.1021446 -0.8683342 0.4951618 -0.02847069 -0.7890494 0.6049352 0.1070256 -0.8490377 0.4589599 0.2617077 -0.8650493 0.4270286 0.2633179 -0.8033642 0.3882056 0.4515554 -0.8188243 0.3579359 0.4487859 -0.745992 0.2116884 0.6314142 -0.8655228 0.005341112 0.5008412 -0.8271789 -0.05060142 0.5596559 -0.865529 -0.2193343 0.4502802 -0.83126 -0.2648127 0.4887546 -0.8050993 -0.4531756 0.3826841 -0.7607448 -0.4639246 0.4539178 -0.7381232 -0.6193493 0.2675455 -0.8513547 -0.5226817 0.04471147 -0.8209652 -0.5704959 0.02346509 -0.8103701 -0.5329456 -0.2434534 -0.8876653 -0.3818542 -0.2573667 -0.8238475 -0.4168847 -0.3840345 -0.8095038 -0.2209652 -0.5439468 -0.8160415 -0.2116346 -0.5378543 -0.7268307 -0.01087695 -0.6867306 -0.8683072 0.1567948 -0.4705932 -0.8019146 0.2628223 -0.5365234 -0.8538884 0.3460461 -0.3887503 -0.7410218 0.5302098 -0.4120247 -0.8375095 0.535642 -0.1080075 -0.8100782 0.5777312 -0.1000009 -0.805506 0.5800763 0.1211264 -0.8513475 0.4993124 0.1609187 -0.7645295 0.5568551 0.3246645 -0.7955375 0.3976984 0.4571171 -0.7711462 0.4012451 0.4943036 -0.7949157 0.1196837 0.5947982 -0.8632012 0.04005843 0.5032686 -0.7873067 -0.1442678 0.5994457 -0.9094738 -0.2324891 0.3446828 -0.8578464 -0.3333926 0.3910868 -0.7931455 -0.5264773 0.306173 -0.8353258 -0.4640843 0.2947144 -0.5951129 -0.8032392 -0.02544927 -0.8584422 -0.5085965 0.0663824 -0.773845 -0.6133592 -0.1579701 -0.8523072 -0.4809585 -0.2055518 -0.7405591 -0.5036764 -0.4448398 -0.8443221 -0.297377 -0.4457434 -0.7296776 -0.244373 -0.6386333 -0.8170873 -0.02849948 -0.5758092 -0.7504941 0.04058492 -0.6596299 -0.81831 0.2664639 -0.5092798 -0.8044366 0.2841269 -0.5216836 -0.8337361 0.4576451 -0.308942 -0.8652061 0.4055177 -0.2949134 -0.7936689 0.5862712 -0.1624066 -0.8622341 0.5048925 -0.04045021 -0.7350102 0.6707229 0.09945273 -0.8441505 0.4344972 0.3140415 -0.8582939 0.421418 0.2928115 -0.7614081 0.3723167 0.5306958 -0.8699686 0.1821089 0.4582478 -0.732717 0.09614711 0.6737074 -0.7981034 -0.179723 0.5750918 -0.7774794 -0.1700459 0.6054837 -0.7641497 -0.4239575 0.4861432 -0.8123482 -0.4136649 0.4110617 -0.7572713 -0.6064156 0.2424878 -0.8386139 -0.5340575 0.1072816 -0.7505948 -0.6607421 -0.005232155 -0.8403631 -0.4780935 -0.2553752 -0.8425707 -0.4755381 -0.2528598 -0.7375904 -0.3310148 -0.5885487 -0.7322215 -0.3372787 -0.5916882 -0.7042265 -0.1293273 -0.6980971 -0.8361049 0.08140391 -0.5424961 -0.7663558 0.1680688 -0.6200417 -0.8412341 0.2644788 -0.4715679 -0.8159434 0.3136179 -0.4856751 -0.7913962 0.4693006 -0.3917258 -0.897054 0.4186298 -0.1415746 -0.8005577 0.5351276 -0.2697145 -0.9391326 0.3424828 0.02712082 -0.9322472 0.36133 0.01886188 -0.8841977 0.3905103 0.2563126 0.6186942 -0.6801344 0.3932364 -0.5767726 -0.8127108 -0.08267277 0.5833507 -0.7946829 -0.1678722 -0.5738685 -0.5053771 -0.6444138 0.4908519 0.6363371 -0.5950962 -0.4228029 0.9048771 -0.04934775 0.6860178 0.6710283 0.2812487 -0.6896511 0.4010182 0.6029643 0.6466747 0.3077979 0.6979057 -0.451967 -0.07507026 0.8888704 0.3353857 -0.157966 0.9287428 -0.5203638 -0.5232053 0.6748909 0.5808067 -0.5680609 0.5830699 -0.5377906 -0.828509 0.1560586 -0.6869436 0.4307188 -0.5853117 0.6728616 0.6395451 -0.3718054 -0.5888736 0.785277 -0.191228 0.466904 0.852513 0.2349942 0.337976 -0.5694243 0.7493519 -0.4417794 -0.8784332 0.1821706 0.2569373 -0.9525861 0.1629814 0.09750634 -0.8799325 -0.4649854 -0.4267361 -0.7639715 -0.4839876 0.4410733 -0.3157598 -0.8400894 -0.6416705 0.1924706 -0.742438 0.6071177 0.4857127 -0.6288811 -0.6865815 0.6317519 -0.3598547 0.4162231 0.8462789 -0.3325211 -0.1210968 0.9813638 0.1492002 -0.68868 0.5654276 0.4538848 0.4962777 0.5409571 0.6790243 -0.4006003 0.1936004 0.895566 0.3245916 0.1369141 0.9358926 -0.454098 -0.3039017 0.8375195 0.5527865 -0.3791068 0.7420952 -0.5372883 -0.6542467 0.532243 0.6108257 -0.6986586 0.372516 -0.6217731 -0.78086 0.06046551 0.6943459 -0.7073869 -0.1322409 -0.6910306 -0.6140005 -0.3814188 0.690079 -0.4353001 -0.5781912 -0.6879836 -0.2108727 -0.6944144 0.6599979 0.01882594 -0.7510316 -0.8139045 0.3009425 -0.4969842 0.8056755 0.4962505 -0.323454 -0.7842846 0.6072849 0.1268972 0.6130892 -0.09883272 0.7838073 -0.6617336 -0.5121931 0.5475097 0.788217 -0.5728417 0.2248699 -0.6207903 -0.7833965 -0.03015804 0.7388169 -0.578314 -0.3459805 -0.5587248 -0.3013047 -0.7726851 0.191165 0.1663906 -0.9673522 0.7438235 0.6644701 -0.07215392 -0.5564435 0.7691285 0.3143441 0.6436161 0.6137555 0.4572336 -0.5884507 0.4657196 0.6609321 0.6100357 0.1251865 0.7824225 0.7957008 -0.2334485 0.5588937 -0.7042854 -0.5698369 0.4234007 0.6859972 -0.6830334 0.2507454 -0.5487587 -0.8359673 0.004763364 0.4630392 -0.8558069 -0.2306281 -0.5585644 -0.6999015 -0.4451335 0.52788 -0.6127614 -0.5881039 -0.5804966 -0.2217134 -0.7834967 0.7572147 0.1372202 -0.6385896 -0.6375418 0.5679111 -0.5205934 0.5624535 0.6984363 -0.4425303 -0.4457104 0.8767978 -0.1804657 0.5636101 0.8259495 0.01229572 -0.6067845 0.7486588 0.267063 0.6018151 0.6150506 0.5094423 -0.462037 0.5330153 0.7088136 0.4888169 0.1559523 0.8583339 -0.5745716 -0.8049028 -0.1483204 0.6189497 -0.6600348 -0.425741 -0.6587011 -0.4361981 -0.6130613 0.6284241 -0.2978097 -0.7186047 -0.6608859 0.009239614 -0.7504295 0.6639632 0.204264 -0.7193254 -0.7780003 0.4448555 -0.443643 0.09106725 0.9484798 0.3034681 -0.4013943 0.5879257 0.7023006 0.5781639 0.4663924 0.669481 -0.4975894 0.08008635 0.8637078 0.5857527 -0.03161412 0.8098732 -0.6235965 -0.3714103 0.6878821 0.696156 -0.4845663 0.5296814 -0.6445796 -0.6826308 0.3442854 0.7394723 -0.6729222 0.01888173 -0.2755542 -0.0243709 -0.9609766 0.4901297 0.400488 -0.774198 -0.5793461 0.5329762 -0.6166803 0.5864006 0.6986091 -0.4099754 -0.6261773 0.7573821 -0.1851338 0.6015667 0.7801877 0.1715368 -0.3853379 0.8510408 0.3567132 0.3020824 0.5361841 0.788196 0.1808458 -0.6491377 0.7388606 -0.5361014 -0.8195334 0.2023866 0.4238686 -0.8892161 -0.1721344 -0.4305735 -0.5793913 -0.6920349 -0.4594882 0.6315844 0.6244773 0.5238004 0.2916061 0.8003745 -0.6248553 0.07654595 0.7769793 0.6963055 -0.2489881 0.6731743 -0.7021338 -0.5708659 0.4255824 0.6477193 -0.7313575 0.2134854 -0.68138 -0.7300284 -0.05272364 0.700639 -0.6354671 -0.3244791 -0.5073317 -0.6513239 -0.5642621 0.3221304 -0.2724625 -0.9066401 -0.3694211 -0.1639462 -0.9146856 0.4967094 0.2532275 -0.830154 -0.7172265 0.3819251 -0.5828545 0.7428209 0.5345482 -0.4030824 -0.8387876 0.5424534 -0.04668998 -0.8582364 -0.513253 0.001349568 0.702817 -0.6055706 -0.3732729 -0.6712916 -0.2205024 -0.7076343 -0.3155301 0.8904017 -0.3280635 0.4896262 0.8341122 0.2540137 -0.2335758 0.8936344 0.3832231 -0.3046289 0.4841135 0.8202655 0.2877963 0.4622864 0.838728 0.2444512 -0.06578445 0.9674276 -0.6778883 -0.1872811 0.7109102 0.6226481 -0.4528948 0.638119 -0.5994222 -0.6788856 0.4240372 0.400005 -0.8325757 0.3831627 -0.5258552 -0.8453271 -0.09433197 0.1720983 -0.9725697 -0.156494 0.3775709 -0.7492892 -0.5440644 -0.5841724 -0.5464764 -0.6000886 0.4951043 -0.3294198 -0.8039616 -0.4813028 -0.1343011 -0.8662048 0.624184 0.1707405 -0.7623924 -0.4112126 0.6151421 -0.6726846 0.1530815 0.9636658 -0.2188934 -0.4850292 0.8467184 -0.2186654 0.5764781 0.8064417 0.1316242 -0.7455357 0.5585085 0.3636549 0.5724551 0.6056979 0.5526528 -0.2545717 0.2616984 0.9309712 -0.3356203 -0.5652762 0.7535396 0.2834965 -0.9195079 0.2722774 -0.6063901 -0.7580804 -0.2400106 0.32509 -0.6567294 -0.680458 0.4260213 -0.6238142 -0.6552571 -0.5043899 -0.1462031 -0.8510085 0.5433642 -0.0565198 -0.8375924 -0.5312209 0.3715112 -0.7614354 0.2407982 0.4855189 -0.8404093 0.2127361 0.8262557 -0.5215793 -0.50034 0.785092 -0.3650897 0.4616683 0.8835775 0.07844161 -0.5540347 0.3911803 0.7348629 0.6307484 -0.03070253 0.7753798 -0.838168 -0.3667612 0.4036841 0.6173904 -0.6450808 0.450222 -0.4156757 -0.9087861 0.03635495 0.2645127 -0.9643331 -0.009740114 -0.487082 -0.7123547 -0.5052743 0.5397385 -0.42175 -0.7285667 -0.3262378 0.1990592 -0.9240912 0.6352302 0.5117881 -0.5784079 -0.6264786 0.7584995 -0.1794526 0.8264382 0.5630263 -0.001125693 0.3565642 -0.0700224 0.9316432 -0.5583053 -0.4937844 0.6666874 0.6896906 -0.5169807 0.5070089 -0.6891142 -0.6999477 0.1876029 0.5359185 -0.8381822 0.1012037 -0.315725 -0.8417046 -0.4380084 0.02804177 -0.03758871 -0.9988998 0.1243603 0.5801538 -0.8049573 0.6129063 0.7901524 -0.002276539 -0.6209071 0.6091126 0.4934129 0.3941106 0.6711837 0.6278449 0.07890146 0.2137726 0.9736919 -0.580374 -0.5509944 0.5996426 0.4993507 -0.7739541 0.3894149 -0.692519 -0.7204717 0.03658115 -0.4181779 0.8296302 -0.3699203 0.392946 0.9165005 0.07496964 -0.5505224 0.8027092 0.2293102 0.5591073 0.6757233 0.4804137 -0.7192542 0.3599946 0.5942031 0.6005183 -0.3129574 0.735823 -0.528149 -0.7011662 0.4789831 0.5946654 -0.7322145 0.3320166 -0.3968994 -0.9086563 0.1296718 0.4965279 -0.8331868 -0.2434338 0.6907699 -0.4839415 -0.5372501 -0.6634717 -0.1053231 -0.7407513 -0.4240822 0.66957 -0.609779 0.4683477 0.8726215 -0.1385001 -0.7163467 0.1265995 0.6861633 0.4694496 -0.03112745 0.8824104 -0.5751858 -0.4386647 0.6904597 0.4455564 -0.774921 -0.448305 -0.58425 -0.4214755 -0.6935491 0.6498212 -0.2485616 -0.7182964 -0.5079002 0.01988047 -0.8611865 0.4872813 0.2290698 -0.8426648 -0.708468 0.4254999 -0.5630479 -0.2474269 0.9066787 -0.3416338 0.553423 0.7945809 0.2497286 -0.7336018 0.4012115 0.5485052 0.5834661 0.2710719 0.7655636 -0.6253411 -0.03171598 0.7797068 0.7118205 -0.1924846 0.6754711 -0.7348526 -0.4601827 0.4982206 0.6453506 -0.6411061 0.415338 -0.5469269 -0.8207011 0.1652899 0.5037072 -0.8637618 -0.01395243 -0.4806039 -0.8243802 -0.2990274 0.5673116 -0.6904132 -0.4488732 -0.5587186 -0.5282489 -0.6393643 0.6607372 -0.1913905 -0.7258071 -0.7669409 0.2543455 -0.5891605 0.6085113 0.5106754 -0.6073917 -0.6786397 0.691876 -0.246487 0.08787798 -0.6180587 0.7812049 -0.4290944 -0.8892983 0.1581981 0.5148479 -0.8088999 -0.2839235 -0.3908692 -0.5282661 -0.7537615 -0.6178492 0.3251504 -0.7159187 0.2744393 0.7690923 -0.5772174 -0.3846997 0.8058605 -0.4501058 0.5684392 0.8099598 -0.1443682 -0.6854022 0.7151295 0.1371634 0.5914927 0.730533 0.3412596 -0.7011259 0.4358194 0.5643439 0.6688628 0.2045748 0.714683 -0.4452345 -0.1663311 0.8798296 0.4694272 -0.2978766 0.8312087 -0.6860046 -0.5265535 0.5021345 -0.4696381 -0.8652133 0.1756305 0.4841386 -0.7784097 -0.3996101 -0.01431989 -0.8518123 -0.5236515 -0.4487578 -0.3195974 -0.8345502 0.6125882 0.05890977 -0.788204 -0.641438 0.5148683 -0.5687424 0.6962567 0.653024 -0.2979705 -0.5474762 0.8360602 0.03568404 0.6754083 0.6969692 0.2409513 0.5058511 0.2425646 0.8278146 -0.6019577 -0.2796434 0.7479616 0.5370172 -0.3702542 0.7579739 -0.253629 -0.8473879 0.4664829 -0.6339883 -0.7725497 -0.03501266 0.6305314 -0.7136701 -0.3051313 -0.1155826 0.3178208 -0.9410796 0.09288364 0.8150781 -0.5718569 -0.4954542 0.697672 -0.5174736 0.6318919 0.7722337 -0.06608986 -0.525583 0.7311677 0.4349213 0.3821574 0.3469406 0.8564976 0.736472 -0.6520922 -0.1799581 -0.7646387 -0.3211682 -0.5587295 -0.1196878 -0.01771914 -0.9926534 0.4644148 0.4573636 -0.7583782 -0.5898236 0.6927425 -0.4149893 0.5598105 0.8237391 -0.08981239 -0.5607122 0.8172516 0.1330488 0.2002936 0.9023762 0.3815755 -0.5398994 0.6022034 0.5880984 0.524956 0.5149472 0.6776803 -0.6603897 0.02878659 0.7503712 0.9654051 -0.2582243 0.03624117 -0.007071256 -0.8259277 -0.5637318 0.845094 -0.4123836 -0.3402292 0.7679284 -0.1104809 -0.6309359 0.6708431 -0.08117336 -0.7371434 0.8176746 0.1995188 -0.5400003 0.7341074 0.3411256 -0.5871283 0.8294669 0.409543 -0.3798147 0.7693696 0.5111438 -0.383148 0.7836455 0.5919334 -0.1884532 0.8369851 0.5292086 -0.1392633 0.7491261 0.6567786 0.08632516 0.8247172 0.5179796 0.227022 0.7935855 0.539138 0.2820504 0.8292247 0.3961626 0.394261 0.8761082 0.3178764 0.3624762 0.7921499 0.2553516 0.5543413 0.8449779 0.0249027 0.5342212 0.8637471 0.01146537 0.5037952 0.7901871 -0.2261635 0.5696091 0.8862552 -0.2381506 0.3972858 0.7479474 -0.5246156 0.4066366 0.8589714 -0.4676808 0.2084293 0.7852078 -0.59951 0.1550371 0.7576338 -0.6479412 -0.07850784 0.8107889 -0.5731781 -0.1186953 0.7198616 -0.5746853 -0.3892764 0.7968438 -0.474785 -0.3736565 0.8099245 -0.2835127 -0.5134617 0.680722 -0.2387761 -0.6925342 0.8420497 -0.003096699 -0.5393911 0.7223901 0.168248 -0.670705 0.8572174 0.2955716 -0.4216821 0.8349272 0.3361443 -0.4357793 0.7824105 0.5526159 -0.2871405 0.8766085 0.4504789 -0.1691934 0.7563293 0.650177 0.07236117 0.8242177 0.5581001 0.09586173 0.7181326 0.5485056 0.4282842 0.8130085 0.4078763 0.415517 0.7360775 0.2915953 0.6108701 0.8219614 0.1752153 0.5419219 0.8147293 0.004775881 0.5798219 0.7346128 -0.06031864 0.6758 0.7432896 -0.2422724 0.6235581 0.861274 -0.3101621 0.4025006 0.7952997 -0.4329673 0.4243087 0.8221435 -0.5132561 0.2462688 0.8905042 -0.4314255 0.1444802 0.7955406 -0.6038042 0.05035597 0.7983427 -0.5708917 -0.1916546 0.8916134 -0.4079857 -0.1964008 0.7748598 -0.4567202 -0.4370345 0.8227962 -0.2650864 -0.5027282 0.8410317 -0.2425247 -0.4835777 0.7616095 -0.05074256 -0.6460466 0.8587222 0.1218214 -0.4977506 0.8293038 0.1624692 -0.5346578 0.7818363 0.3943344 -0.4829416 0.8853737 0.3698282 -0.2816749 0.8331627 0.4765046 -0.2806838 0.7700958 0.6308102 -0.09503203 0.8570149 0.5152269 -0.008175253 0.7353556 0.6412841 0.2191047 0.8515436 0.4143899 0.3211771 0.825944 0.4270521 0.3680261 0.807614 0.248417 0.5348353 0.8752288 0.1524794 0.4590476 0.8091474 0.05766105 0.58477 0.876384 -0.1121895 0.468364 0.8076865 -0.2177092 0.5479464 0.8453536 -0.360884 0.3938785 0.8667223 -0.3490217 0.3563377 0.7898285 -0.5615754 0.2465844 0.8670231 -0.4882912 0.09921079 0.7732999 -0.6339745 0.009147763 0.8590531 -0.4639696 -0.2162408 0.8554881 -0.4702071 -0.2168996 0.8173063 -0.4140546 -0.400711 0.8247416 -0.1754364 -0.5376089 0.8991612 -0.1862019 -0.3960277 0.8190939 0.09156495 -0.5663048 0.8745239 0.1197936 -0.4699546 0.7499223 0.3470826 -0.563161 0.7582914 0.5449711 -0.3577722 0.8125897 0.4654796 -0.3507519 0.7788241 0.616374 -0.1162595 0.8772397 0.4788697 -0.03368192 0.7354743 0.6449981 0.2074973 0.8217944 0.455327 0.3425368 0.7652326 0.4726375 0.4370732 0.7682296 0.2987463 0.5661928 0.8098232 0.2455409 0.5328192 0.7161024 0.01759916 0.6977734 0.832312 -0.08826106 0.5472356 0.8137334 -0.2141345 0.5403559 0.8685132 -0.2282449 0.4399878 0.7456206 -0.4798925 0.4623345 0.7913637 -0.5692688 0.2228828 0.7872914 -0.5758991 0.2202559 0.8839313 -0.4656733 0.04258948 0.7732046 -0.6288595 -0.08179628 0.8518771 -0.4624826 -0.2457953 0.7986228 -0.5003007 -0.3345161 0.7474234 -0.3957735 -0.5335934 0.8588458 -0.1875258 -0.4766738 0.7853784 -0.1291756 -0.6053879 0.8522123 7.19199e-4 -0.5231959 0.7230472 0.1926899 -0.6633803 0.8196484 0.2965151 -0.4901585 0.6785138 0.556313 -0.4797237 0.8018965 0.5085051 -0.313663 0.7135242 0.696318 -0.07761818 0.8284639 0.5442294 -0.1321439 0.8079119 0.5856013 0.06595283 0.8835738 0.4520831 0.1221404 0.8021929 0.5189916 0.2951852 0.8405714 0.3496444 0.4137494 0.8224452 0.3745071 0.4281688 0.8169007 0.1306831 0.5617785 0.8139337 0.1335663 0.5653955 0.7238137 -0.1431989 0.6749726 0.8441261 -0.2123329 0.4923066 0.8106893 -0.3825843 0.443184 0.8792283 -0.3406749 0.3330138 0.7499755 -0.6265352 0.2121092 0.9084374 -0.4138619 0.05882209 0.785033 -0.5842546 -0.2058398 0.8737021 -0.4386091 -0.2103971 0.7784066 -0.4251101 -0.4619141 0.8667253 -0.2433795 -0.4353778 0.797386 -0.2137211 -0.5643572 0.7424343 0.1401403 -0.655097 0.8603839 0.03699463 -0.5083021 0.7806476 0.3182942 -0.5378459 0.8810793 0.3051589 -0.3613551 0.7663187 0.5482756 -0.3348875 0.8618559 0.4830842 -0.1543827 0.7845172 0.615791 -0.07303601 0.8698614 0.4813624 0.1078487 0.776089 0.5845146 0.2367042 0.8744682 0.3324229 0.353271 0.7633247 0.3538364 0.5404952 0.8496341 0.1598803 0.5025537 0.6890174 -0.008643031 0.7246932 0.8383557 -0.1603862 0.5209953 0.6971087 -0.4150381 0.584622 0.82657 -0.3985932 0.3973736 0.7562741 -0.6102995 0.2357632 0.7893298 -0.5633186 0.2441939 0.7645817 -0.6443911 0.0132305 0.8549779 -0.51064 -0.0908823 0.8089383 -0.5653777 -0.1611424 0.8138509 -0.4463372 -0.3720616 0.878509 -0.3253016 -0.3498585 0.7720235 -0.3055829 -0.5573141 0.8693147 -0.05553883 -0.4911288 0.8284638 -0.01966595 -0.5596973 0.7897305 0.234659 -0.5667989 0.8726583 0.2424585 -0.4238886 0.751273 0.4861232 -0.4464004 0.8031494 0.5567791 -0.2120102 0.8256537 0.5330275 -0.184872 0.7255548 0.6870774 0.03866338 0.8680691 0.4712284 0.1562044 0.7641125 0.5317415 0.3652166 0.8672661 0.358406 0.3455353 0.746632 0.2836668 0.6017258 0.8974782 0.09453314 0.4308089 0.7853869 -0.08317059 0.6133923 0.8792633 -0.1717197 0.4443068 0.7832001 -0.348002 0.5152595 0.8620253 -0.4206781 0.2827408 0.8560371 -0.4324491 0.2831755 0.7800475 -0.6203111 0.082098 0.821655 -0.5686933 0.03835266 0.6919772 -0.6865063 -0.2233309 0.8318787 -0.4754108 -0.2862911 0.725159 -0.4720755 -0.5012875 0.8249634 -0.2843643 -0.4884389 0.7557474 -0.2052854 -0.6218551 0.8307573 -0.004697442 -0.556615 0.7587932 0.06051546 -0.6485143 0.8398066 0.3032208 -0.4503133 0.8520744 0.2969332 -0.4310454 0.8176717 0.5223469 -0.2420057 0.8767604 0.4495782 -0.1707946 0.7870295 0.6150485 0.04795747 0.8797422 0.4559507 0.1347698 0.7408955 0.574377 0.3480879 0.8586326 0.3483273 0.3760562 0.7017369 0.2891745 0.6511094 0.8166437 0.1005107 0.5683228 0.7669388 -0.00831443 0.6416665 0.8204042 -0.1084092 0.5614129 0.7520053 -0.2427931 0.612813 0.8160904 -0.3690043 0.4447835 0.848989 -0.3571137 0.3894708 0.8245116 -0.5038393 0.2575392 0.833777 -0.4944424 0.2456473 0.7274876 -0.6846353 -0.04512792 0.8473489 -0.5207889 -0.1038217 0.8029136 -0.4972694 -0.3287141 0.8644539 -0.3935633 -0.3127739 0.7390083 -0.3319702 -0.5862274 0.8112089 -0.1889249 -0.5533966 0.7187499 -0.05340015 -0.693215 0.8334647 0.09829598 -0.5437597 0.7603884 0.2180244 -0.61178 0.7890276 0.4283355 -0.4404139 0.7694448 0.4376742 -0.4651839 0.8080472 0.5554491 -0.1963067 0.7760112 0.6040151 -0.1815837 0.775993 0.6200299 0.1157498 0.8196648 0.5571946 0.1329814 0.7611818 0.4615125 0.455641 0.8907365 0.3744291 0.2576654 0.7818837 0.3146123 0.5382164 0.8602644 0.1081575 0.4982442 0.8429114 0.0971809 0.5292037 0.781989 -0.1254042 0.6105466 0.8310165 -0.1594198 0.5329136 0.7195063 -0.4237897 0.5501937 0.8684697 -0.399905 0.292979 0.7710983 -0.5845009 0.2525196 0.87101 -0.4904248 0.02872568 0.8295934 -0.5582484 -0.01156789 0.8058848 -0.5682069 -0.1664056 0.90636 -0.353562 -0.2313128 0.8645063 -0.3873461 -0.3203002 0.7856932 -0.3406448 -0.5163793 0.8661777 -0.1362953 -0.4807908 0.8436368 -0.1242347 -0.5223435 0.7767815 0.1285411 -0.6165125 0.901998 0.1783965 -0.3931597 0.7879419 0.3829039 -0.4822161 0.7639926 0.5464366 -0.3431072 0.8832463 0.4388713 -0.1651304 0.7926499 0.6023612 -0.09416633 0.7560692 0.6216245 0.2047985 0.8198398 0.5321151 0.2114624 0.7096552 0.406892 0.5751768 0.7710998 0.3981807 0.4968474 0.7892578 0.1299281 0.6001589 0.7694989 0.1181419 0.6276257 0.7859033 -0.1701491 0.5944791 0.7588122 -0.2015002 0.619356 0.7797337 -0.4127961 0.4707598 0.8286794 -0.3958289 0.3957398 0.7357869 -0.6221423 0.2675008 0.8563733 -0.514997 0.03745841 0.8236387 -0.5636141 0.06291764 0.7438176 -0.6259259 -0.2344186 0.8520897 -0.4464086 -0.2732443 0.8203989 -0.4462558 -0.3574932 0.8862166 -0.25752 -0.385102 0.8229759 -0.2483294 -0.5109241 0.7049673 -0.08221405 -0.7044587 0.806446 0.05442339 -0.5887979 0.7526895 0.1674388 -0.6367282 0.8334987 0.2879909 -0.4715308 0.787876 0.3665148 -0.4948924 0.764326 0.5538779 -0.3301896 0.8544778 0.4866844 -0.1816762 0.7707354 0.6258658 -0.1194121 0.8226049 0.5501208 0.1438344 0.8694722 0.470144 0.1516009 0.8016639 0.4779433 0.359034 0.8824867 0.2796107 0.3782001 0.7971078 0.2821239 0.5338777 0.8147296 0.08990609 0.5728287 0.9165201 -0.03912353 0.3980708 0.8481621 -0.1359431 0.5119966 0.7413075 -0.3593257 0.5668759 0.8819299 -0.366164 0.2968563 0.7837998 -0.5437771 0.299941 0.8616979 -0.5074211 8.43485e-4 0.8144211 -0.579022 -0.03810548 0.809453 -0.4543945 -0.3719026 0.8491809 -0.3963283 -0.349021 0.8205246 -0.2979509 -0.4878163 0.9041846 -0.1194863 -0.4100894 0.8370063 -0.05687284 -0.5442297 0.7990629 0.1344109 -0.5860311 0.7441825 0.1153216 -0.6579464 0.770861 0.3918749 -0.5022026 0.8504643 0.3672758 -0.3765888 0.7948108 0.5403299 -0.2762596 0.8774503 0.4578446 -0.1430366 0.794917 0.6035182 -0.06223332 0.902073 0.4036785 0.1526697 0.8613733 0.4598689 0.21577 0.7653328 0.4491943 0.4609667 0.8452634 0.1990768 0.4958813 0.7844684 0.256971 0.5644249 0.809205 -0.02685493 0.5869125 0.759773 -0.08083617 0.6451438 0.8117828 -0.3526318 0.465467 0.891267 -0.2207481 0.3961231 0.7858958 -0.4784404 0.3917432 0.8591074 -0.4679265 0.2073147 0.7827073 -0.6006312 0.1631303 0.7647382 -0.6362235 -0.1019574 0.8469019 -0.5066224 -0.1615269 0.7998163 -0.5353022 -0.2715618 0.8791923 -0.3552605 -0.3175073 0.7792505 -0.3542959 -0.5169556 0.8689934 -0.1376119 -0.4753037 0.8204522 -0.1037839 -0.5622164 0.8068644 0.1069167 -0.5809808 0.8803686 0.1557827 -0.4479765 0.7541524 0.3722347 -0.5410135 0.8790194 0.4063635 -0.2493865 0.7699301 0.5924546 -0.2370767 0.8607761 0.5085695 -0.02053594 0.7319732 0.6655379 0.1458579 0.8162792 0.4956344 0.2967066 0.7530192 0.5173349 0.4066038 0.8500811 0.2437479 0.4668502 0.7828755 0.2301417 0.5780492 0.8371546 -0.05121475 0.5445635 0.7065983 -0.01475608 0.7074611 0.8217569 -0.3462935 0.4525445 0.8663902 -0.3207099 0.3827705 0.7800187 -0.5851509 0.2217414 0.8918582 -0.4465628 0.07190716 0.7968402 -0.6020456 -0.05086296 0.8422288 -0.4980486 -0.2063936 0.8246861 -0.5140651 -0.2358602 0.6698336 -0.3702962 -0.6435865 0.8980507 -0.3031871 -0.3187201 0.7572559 -0.2525402 -0.6023181 0.8100689 -0.03517478 -0.5852788 0.8687613 0.008835613 -0.4951522 0.7259108 0.2710089 -0.6321454 0.8580218 0.344171 -0.3812413 0.7982403 0.4646729 -0.3832645 0.8591838 0.4807087 -0.1752782 0.8322036 0.5297451 -0.1637299 0.7813274 0.6227038 0.04204273 0.7599631 0.649295 0.0295335 0.7560389 0.5561529 0.3451077 0.8144392 0.4690178 0.3416298 0.7353547 0.385466 0.5573773 0.8071799 0.2886316 0.5149295 0.7411017 0.03947895 0.6702312 0.8588206 -0.05109083 0.5097225 0.8212738 -0.2075687 0.5314365 0.8788302 -0.2349595 0.415273 0.6873771 -0.5713299 0.448436 0.8983488 -0.4035583 0.173523 0.7631017 -0.6437942 0.05661147 0.8773154 -0.4453914 -0.1787299 0.8178339 -0.544238 -0.186957 0.7659193 -0.434099 -0.4742634 0.803192 -0.3712489 -0.4658937 0.7277991 -0.2641509 -0.6328765 0.829419 -0.01509964 -0.5584229 0.84267 -0.02641975 -0.5377818 0.7628699 0.1914787 -0.617548 0.8607078 0.2268955 -0.455742 0.7437668 0.4799145 -0.4652882 0.8254511 0.480392 -0.2964018 0.7507804 0.6199749 -0.2279479 0.7908175 0.6120418 0.00353825 0.8183884 0.5743293 -0.01965558 0.8250162 0.5117802 0.2396446 0.8891852 0.3903647 0.2386738 0.7736669 0.4290553 0.4662094 0.8497057 0.1931171 0.490618 0.7143095 0.1188336 0.689667 0.8230919 -0.1177002 0.5555776 0.7216627 -0.2731545 0.6360737 0.8517948 -0.3544444 0.385765 0.7639214 -0.5056889 0.400878 0.8643383 -0.4784452 0.1549506 0.7864055 -0.609562 0.1000032 0.7793074 -0.5943822 -0.1984692 0.8137992 -0.5597834 -0.1561198 0.7382006 -0.5674375 -0.364794 0.8297575 -0.391678 -0.3976066 0.7493774 -0.3511326 -0.5613727 0.8182494 -0.1880697 -0.5432291 0.7383765 -0.08535379 -0.6689655 0.82368 0.02354019 -0.5665661 0.7437181 0.231257 -0.627219 0.830756 0.2909159 -0.4745657 0.7521818 0.4459133 -0.485164 0.7990283 0.5326962 -0.2789064 0.8454863 0.4871021 -0.2188256 0.7926139 0.608468 -0.03911375 0.8926928 0.4456278 0.06719911 0.7969002 0.5634647 0.2178482 0.805922 0.4376146 0.3987272 0.8538548 0.3637728 0.3722921 0.7404131 0.2354339 0.6295708 0.8409487 0.09680128 0.5323861 0.7336726 -0.08730536 0.6738712 0.8410041 -0.2210977 0.4937893 0.7855912 -0.3223165 0.5281652 0.8666759 -0.3783988 0.3250961 0.8040807 -0.4979633 0.3247875 0.8784165 -0.4629387 0.1186262 0.8107908 -0.5837256 0.04339176 0.7647307 -0.6197659 -0.1762878 0.8247526 -0.5563185 -0.1014542 0.734358 -0.5104428 -0.4473998 0.8354435 -0.3582288 -0.4167808 0.8261359 -0.2335785 -0.5127773 0.8506468 -0.20114 -0.4857394 0.7349767 0.03168761 -0.6773517 0.8260396 0.1125147 -0.5522674 0.7574107 0.2827189 -0.5885569 0.8509679 0.3859582 -0.356216 0.7969334 0.4751821 -0.3729603 0.8496407 0.5226538 -0.07031291 0.7162928 0.6828547 -0.1436458 0.8247073 0.5500863 0.1313892 0.7049329 0.6373834 0.3111465 0.8206692 0.4169878 0.3906703 0.7392466 0.4118319 0.5328312 0.8071311 0.1642768 0.5670562 0.8746292 0.09444636 0.4755035 0.7990353 -0.155961 0.5807054 0.8490818 -0.1723108 0.4993687 0.7241853 -0.4450302 0.5267864 0.8107558 -0.4855048 0.3270479 0.758534 -0.5750823 0.3064419 0.785676 -0.6118023 0.09171217 0.8281716 -0.5585934 0.04588371 0.7210686 -0.6684276 -0.1823864 0.8668652 -0.4247009 -0.2611016 0.784401 -0.4163206 -0.4597741 0.8545026 -0.3180081 -0.4107264 0.8002648 -0.0962724 -0.5918683 0.8616108 -0.04393655 -0.5056645 0.7887932 0.1924514 -0.5837532 0.8626381 0.2025768 -0.4634849 0.7418695 0.5056032 -0.4404487 0.850467 0.4861876 -0.2008177 0.8444169 0.4972926 -0.1991491 0.7824408 0.6223581 0.02137464 0.8486018 0.5165308 0.1143286 0.7723314 0.5917899 0.2308445 0.7760448 0.4168277 0.4732961 0.8473523 0.3207235 0.4232383 0.8049058 0.1121718 0.5827041 0.8782355 0.04200118 0.4763805 0.7630949 -0.1643033 0.6250526 0.8733124 -0.2963458 0.3866584 0.8378111 -0.3182232 0.443629 0.8067323 -0.5487395 0.2192443 0.869315 -0.470018 0.1528879 0.7955148 -0.5942199 -0.1185705 0.8454851 -0.5180532 -0.1295221 0.8219031 -0.4415675 -0.3598523 0.8671104 -0.3592623 -0.3450368 0.782141 -0.2993177 -0.5465019 0.8645846 -0.1687611 -0.4733005 0.7046064 0.05465656 -0.7074904 0.884771 0.1712821 -0.4334083 0.79118 0.3419604 -0.5070478 0.8316058 0.4673143 -0.3000822 0.8371854 0.4622156 -0.2923653 0.7465163 0.6526123 -0.129656 0.8319718 0.5545123 0.0184195 0.6980771 0.6834374 0.2135456 0.8445947 0.4478965 0.2933403 0.6862524 0.4489153 0.5723048 0.8446146 0.2142698 0.4906269 0.7284787 0.09428822 0.6785489 0.8085232 -0.08309811 0.5825675 0.7487983 -0.1720445 0.6400796 0.8306281 -0.3480822 0.4346214 0.8000373 -0.3967549 0.4500289 0.8386359 -0.5037392 0.2072119 0.850282 -0.4897248 0.1928475 0.7168805 -0.6965385 -0.03027474 0.8395111 -0.5104122 -0.1862805 0.7392174 -0.5779538 -0.345727 0.8641406 -0.370072 -0.3410392 0.7142601 -0.2847233 -0.6393476 0.8315859 -0.1365247 -0.5383549 0.7336984 0.05212759 -0.6774729 0.867629 0.2166704 -0.4475198 0.8435658 0.2180085 -0.4907841 0.821249 0.4213887 -0.3846839 0.8846826 0.3797146 -0.2704693 0.7714796 0.6056005 -0.1951086 0.8714761 0.4896374 0.02801609 0.831471 0.5508411 0.0723192 0.8141856 0.4621121 0.3515027 0.8280633 0.4406492 0.3466118 0.7285398 0.3326206 0.5988267 0.8427973 0.1315517 0.5219072 0.7970517 0.01482915 0.6037291 0.8718271 -0.03786289 0.4883484 0.7984308 -0.2786487 0.5337257 0.8548635 -0.2792788 0.4372779 0.7499789 -0.5157799 0.414129 0.8669066 -0.4772604 0.1438595 0.8263201 -0.5482639 0.128848 0.7457531 -0.6525666 -0.1341987 0.8783074 -0.4270581 -0.2149362 0.8225039 -0.4684709 -0.3225251 0.8457406 -0.2950817 -0.4445781 0.8244253 -0.2941266 -0.4835416 0.7345685 -0.1426542 -0.6633694 0.8234771 0.05168479 -0.5649906 0.7981653 0.08702588 -0.5961198 0.8572433 0.2333115 -0.4590206 0.8166298 0.3023055 -0.4916576 0.6503077 0.689314 -0.3192904 0.8608067 0.404383 -0.3090086 0.7879683 0.5901445 -0.1756001 0.8702586 0.4913208 -0.03541105 0.8240088 0.5655102 0.03475534 0.8353559 0.5329601 0.1346626 0.7772981 0.5801009 0.2434967 0.8027646 0.4559576 0.3842808 0.7622407 0.4638421 0.4514861 0.7630465 0.2696075 0.5874283 0.8682451 0.1332251 0.4779136 0.8165113 -0.01009511 0.5772411 0.8770042 -0.1114299 0.4673835 0.8133329 -0.205107 0.5444453 0.7840645 -0.4140567 0.4623851 0.8749352 -0.3776202 0.3031361 0.7993252 -0.5349659 0.2736619 0.7761414 -0.6252397 0.08173054 0.8581264 -0.5131962 -0.01577329 0.7775799 -0.6047489 -0.1721868 0.804144 -0.5647606 -0.1854673 0.7637147 -0.4887897 -0.4216925 0.82003 -0.3740714 -0.4331529 0.7351095 -0.3385131 -0.5873865 0.7725126 -0.06499218 -0.6316647 0.8081402 -0.09669601 -0.5809987 0.8336299 0.1840136 -0.520769 0.8150098 0.2099691 -0.5400667 0.8097957 0.4206129 -0.4090427 0.873178 0.374714 -0.3116886 0.7528835 0.6275913 -0.198231 0.8346881 0.542509 -0.09476208 0.7417084 0.6644505 0.09151083 0.8021199 0.5422297 0.2501815 0.8675869 0.42525 0.2577899 0.7895622 0.4338994 0.4339622 0.8634775 0.2486816 0.4388214 0.7443199 0.1957079 0.6385032 0.8087729 -0.08199554 0.5823773 0.6706849 -0.2217997 0.7078041 0.8427091 -0.3337309 0.4224513 0.7381221 -0.5288414 0.4189303 0.8337566 -0.5131212 0.2038549 0.7698736 -0.6181271 0.1587883 0.7570841 -0.6463316 -0.09528517 0.8555897 -0.4981706 -0.140685 0.7704917 -0.5005177 -0.3947466 0.8633625 -0.3480263 -0.3653532 0.7500175 -0.3055745 -0.5865986 0.8339863 -0.01853239 -0.551474 0.8362814 -0.02032881 -0.5479236 0.7737455 0.2411987 -0.5857826 0.810704 0.2472869 -0.5306678 0.7562561 0.4748941 -0.4500585 0.8618664 0.4376647 -0.2561951 0.792956 0.5677686 -0.2210428 0.8472629 0.5300653 0.03430056 0.8366586 0.5469268 0.02955466 0.8170446 0.5240783 0.2403749 0.8910349 0.362779 0.272852 0.7927371 0.4011109 0.4589966 0.8367311 0.129385 0.5321095 0.8560052 0.1111633 0.5048741 0.7632414 -0.1160574 0.6356047 0.8629255 -0.2008772 0.4636896 0.7509881 -0.409911 0.5176775 0.8733073 -0.4333817 0.2225188 0.9021194 -0.3728591 0.2171558 0.68121 -0.7289114 0.06812655 0.8289746 -0.5247294 -0.1935464 0.9391731 -0.3083904 -0.1511599 -0.6226098 -0.3963291 -0.6747446 -0.8223256 -0.2762247 -0.4974741 0.8153833 -0.1791532 -0.5505036 0.8230192 -0.5342936 0.1927946 -0.7680023 -0.637338 -0.06303095 0.8404496 -0.511896 -0.1777837 0.908891 -0.4169433 -0.008695781 -0.8854032 -0.3740153 -0.275996 -0.9037103 -0.2306423 -0.3607102 -0.8673413 -0.09583324 0.4884006 -0.9008377 -0.07254374 -0.4280524 0.9473451 -0.2339361 0.2186576 0.8751258 -0.4761563 -0.08619719 0.9402843 -0.07579886 0.3318437 -0.1982057 0.2180593 -0.9555966 0.7278777 0.03000187 0.6850504 0.9961999 0.03191697 0.08103746 0.6538217 0.1932129 0.7315642 0.6520343 0.1910765 0.7337173 0.210686 0.2117146 0.9543524 0.9375044 0.185477 0.2944214 -0.1281707 0.312519 0.9412249 0.8127066 0.3807991 0.4410216 0.5972731 0.4336698 0.6746817 0.3227564 0.553443 0.7678081 0.7683548 0.5069531 0.3906785 0.1061608 0.6931108 0.7129708 0.8239052 0.4986254 0.2693567 0.3678376 0.7533728 0.5450918 0.9790751 0.1969531 0.05119961 0.2970464 0.8741236 0.3842804 0.643366 0.7319359 0.224388 0.6415036 0.7566413 0.126361 0.0324589 0.9470168 0.3195399 0.8565951 0.5159802 -0.003047704 0.3571122 0.932936 0.04584187 0.2665333 0.9624223 0.05199605 0.1142369 0.9932415 0.02052557 0.8149622 0.5677728 -0.1160643 0.607607 0.7720813 -0.186291 0.9130061 0.3669931 -0.1781455 0.05869168 0.9402149 -0.3354867 0.4129914 0.8453184 -0.3389323 0.2990249 0.8797178 -0.3697037 0.7865406 0.4877722 -0.3787243 0.744798 0.4704808 -0.4732059 0.1669197 0.7651597 -0.6218267 0.8438668 0.3178083 -0.432304 0.4482125 0.5946486 -0.6674568 0.3269627 0.525554 -0.7854224 0.7697144 0.1977969 -0.606973 0.8865076 0.05410844 -0.4595397 0.4784916 0.2593893 -0.8389059 0.4124688 0.2959807 -0.8615481 0.4071005 0.02783805 -0.9129591 0.7217651 -0.08565849 -0.6868172 0.3423067 0.01752132 -0.9394249 0.7221722 -0.2020348 -0.6615507 0.8692918 -0.2234247 -0.4409231 0.04992389 -0.1958562 -0.9793611 0.3274489 -0.3811213 -0.8645946 0.2681078 -0.440173 -0.8569515 0.7702381 -0.4682127 -0.4330244 0.2921438 -0.5919954 -0.751128 0.742988 -0.4969368 -0.4483555 -0.1219685 -0.7195478 -0.6836481 0.6338299 -0.6595779 -0.404001 0.9899204 -0.1355181 -0.04113912 0.3988602 -0.8121026 -0.4259106 0.7661526 -0.6276686 -0.1379945 0.8588198 -0.5099548 -0.04873156 0.2206469 -0.9478908 -0.229822 0.1119473 -0.974655 -0.1936893 0.7303361 -0.674323 0.1090762 0.3300198 -0.9406998 0.07855594 0.7642504 -0.5985189 0.240201 0.8612727 -0.44803 0.2397466 -0.07499164 -0.95854 0.2749134 0.3480619 -0.8223846 0.4500407 0.2252427 -0.7734113 0.5925375 0.6937643 -0.4228996 0.5829641 0.869253 -0.2144674 0.4454245 0.4017773 -0.5958689 0.6953527 0.7426655 -0.3392855 0.5773503 0.02260172 -0.5119209 0.8587352 0.494708 -0.3081667 0.8125869 0.2858539 -0.348236 0.8927595 0.8422868 -0.01066219 0.5389243 0.5281657 -0.05484592 0.8473682 -0.04191613 -0.1223942 0.9915961 0.2170253 -0.04068893 0.9753176 0.9999576 0.001833498 0.009034335 0.9999924 -0.001756966 0.003509104 0.999895 -0.01322102 -0.005924642 0.9999887 0.003525078 0.003231108 0.9996531 6.9342e-4 -0.02633106 0.9995055 0.00246936 -0.03134876 0.9999741 8.63492e-4 0.007158875 -0.07155847 0.5001368 -0.8629847 -0.07185506 0.500339 -0.8628428 -0.07240998 0.9973704 -0.003032028 -0.07133895 0.9974499 -0.002124428 -0.0709784 0.4996466 0.8633166 -0.07193028 0.5003061 0.8628556 -0.07161253 -0.4975246 0.8644889 -0.07200247 -0.4972335 0.8646239 -0.07148623 -0.9974359 0.003390371 -0.06950169 -0.9975804 0.001768052 -0.03767991 -0.500932 -0.864666 -0.03612154 -0.4998083 -0.8653826 -0.9999261 0.01039081 0.006319403 -0.9999411 0.0108186 8.7158e-4 -0.9999349 0.004493653 0.01048535 -0.9999269 -0.002306759 0.01187187 -0.999947 0.005167305 0.008912265 -0.9999291 0.01144665 -0.003289997 -0.999944 0.01057261 4.46632e-4 -0.9999268 0.009340882 -0.007700622 -0.9999238 -0.009208381 0.0082255 -0.9999495 -0.004778981 0.008846819 -0.9999437 0.00502783 -0.009352207 -0.999942 0.004921615 -0.009579241 -0.999933 -0.01144218 0.001792907 -0.9999448 -0.01050847 1.51725e-4 -0.9999305 6.26086e-4 -0.01177126 -0.9999378 -0.003880381 -0.01046407 -0.9999273 -0.01142269 -0.003874242 -0.999947 -0.004751384 -0.009148359 -0.9999284 -0.008706748 -0.008221864 -0.9999939 0.002485692 0.002449214 -0.9999706 -0.006885826 -0.003384351 -0.9999999 -6.12668e-4 7.54264e-5 -0.9999995 -1.07028e-4 9.63796e-4 -0.05153065 0.1905113 -0.9803317 0.05981636 0.5061905 -0.8603449 -0.0517053 0.7447463 -0.6653417 0.04097163 0.9297352 -0.3659424 -0.03054469 0.9874873 -0.1547125 0.02975368 0.9857866 0.1653473 -0.02263069 0.9468049 0.3210115 0.01923292 0.7513116 0.6596673 0.002148687 0.7270286 0.6866039 -0.01277798 0.3473449 0.9376504 0.02284747 0.2605466 0.9651909 -0.0209732 -0.05281269 0.9983842 0.01966017 -0.1982455 0.9799552 -0.01390612 -0.4733086 0.880787 0.02454888 -0.584692 0.810884 -0.03214508 -0.7712969 0.6356633 0.02677011 -0.9400123 0.3400888 2.97169e-5 -0.9610902 0.2762347 -0.008766651 -0.9967311 -0.08031374 0.01048827 -0.9907841 -0.1350443 -0.02230525 -0.8541391 -0.5195662 -0.00449413 -0.8767389 -0.4809457 0.03394079 -0.6140732 -0.788519 -0.04164731 -0.3936445 -0.9183189 0.04191941 -0.1344937 -0.9900274 0.9996201 -0.02388888 -0.01375538 0.9998998 -0.008283615 0.01148527 0.9997184 -0.02146822 0.01011443 0.9999923 -0.003705501 0.001339316 0.9999642 -0.002872824 -0.007976233 0.9998639 -0.003271818 0.01617401 0.9995406 0.02999818 0.004316747 1 -1.48477e-4 -1.95379e-5 0.9999925 0.001020431 0.003767669 0.999973 0.006643712 -0.003145933 1 -1.22325e-4 -6.69275e-5 0.9999989 -0.001386225 6.40698e-4 1 -1.71106e-4 -1.52915e-4 0.9999992 -8.37508e-4 -0.001076221 1 -2.13337e-4 2.07341e-4 0.9999913 -0.004163146 2.73637e-4 0.999989 -6.36614e-4 -0.004655718 1 -5.41669e-5 -9.59585e-6 0.999653 0.009437441 0.0245977 0.9998252 0.01739668 -0.006847083 0.9999864 0.002649366 -0.004498362 0.999709 -0.001777052 -0.02405953 0.9998415 0.002275824 -0.01766163 -0.9947386 -0.08484673 0.05741363 -0.9997146 0.01766079 0.01609021 -0.9927396 -0.09424209 0.07474339 -0.9999199 -0.01137363 -0.005574405 -0.9995138 0.02263408 0.02144742 -0.9875307 -0.08588451 0.1319355 -0.9999409 0.01084959 -8.1513e-4 -0.980997 -0.002174794 0.194011 -0.9980538 0.03802698 0.04942172 -0.9997841 0.01988112 -0.006064713 -0.9983814 0.03274095 0.04650485 -0.9963659 -0.08181118 -0.02370369 -0.9969978 0.03165864 0.07066291 -0.9885208 0.1271293 0.08163803 -0.9928154 0.1168935 0.0255661 -0.8962799 0.4433992 -0.008918285 -0.6569672 0.7272652 0.1986943 -0.9020278 0.3544728 0.2463638 -0.7499647 0.4679915 0.4674794 -0.8740624 0.1341722 0.4669182 -0.8939508 0.1048253 0.4357335 -0.7387012 -0.06242424 0.6711363 -0.8404752 -0.2548981 0.4781514 -0.8068721 -0.3005158 0.5085743 -0.7520482 -0.5363414 0.3830948 -0.8730591 -0.4618064 0.156534 -0.7416655 -0.6622198 0.1067585 -0.8383495 -0.5117675 -0.1877885 -0.8805847 -0.4325858 -0.193495 -0.7491359 -0.3811184 -0.5417974 -0.7307591 -0.4009469 -0.5524789 -0.8089122 -0.02698385 -0.5873101 -0.7506923 0.01011478 -0.6605747 -0.8503556 0.2643983 -0.4549604 -0.8075067 0.2555502 -0.5316268 -0.7590125 0.5019872 -0.4146191 -0.8333888 0.4732434 -0.285489 -0.7227779 0.6673502 -0.1795435 -0.8199098 0.5722681 0.01603603 -0.7541494 0.6494 0.09766465 -0.8198422 0.5126093 0.2551284 -0.7712013 0.5421428 0.3336616 -0.8090814 0.3638342 0.4615323 -0.7903541 0.3972671 0.4663897 -0.7252438 0.2141696 0.654334 -0.8238801 0.06938737 0.5625007 -0.836665 -0.2337049 0.4953523 -0.716447 -0.1126193 0.6884916 -0.719205 -0.4097597 0.561107 -0.8906782 -0.4100404 0.1963654 -0.8296827 -0.5186728 0.2064101 -0.8101783 -0.5832025 -0.05904304 -0.8896967 -0.43603 -0.1353428 -0.7759619 -0.5522099 -0.3048725 -0.8240433 -0.3857003 -0.4149554 -0.8748485 -0.2974932 -0.3822802 -0.6824559 -0.07607746 -0.7269569 -0.8989771 -0.0958144 -0.4273871 -0.78366 0.03805518 -0.6200233 -0.8552573 0.2211865 -0.4686272 -0.851889 0.2259709 -0.4724643 -0.7396247 0.4838438 -0.4678148 -0.8432289 0.4802673 -0.2414714 -0.7916839 0.5752586 -0.205704 -0.8538615 0.5202069 -0.0174728 -0.8197109 0.5727128 0.008621811 -0.7398106 0.6221026 0.256259 -0.8307825 0.4525545 0.324029 -0.7554168 0.475796 0.4505148 -0.8086274 0.2258845 0.5432293 -0.7153806 0.2034702 0.6684539 -0.8383747 -0.09609997 0.5365564 -0.8457976 -0.1014765 0.5237644 -0.8036802 -0.3616065 0.4725875 -0.7340093 -0.3722463 0.5680345 -0.7760472 -0.5667721 0.2766228 -0.8552278 -0.4977024 0.1444918 -0.785353 -0.6165777 0.05525237 -0.8615738 -0.4976667 -0.100093 -0.7847226 -0.5895702 -0.1913567 -0.7911748 -0.3994439 -0.4631277 -0.7864238 -0.4062168 -0.4653233 -0.7316483 -0.09397393 -0.6751739 -0.7844181 -0.1103292 -0.6103408 -0.8735304 0.1440392 -0.4649704 -0.8277481 0.1942737 -0.5263943 -0.8036844 0.458079 -0.3798094 -0.872077 0.4137594 -0.2613141 -0.7684831 0.6164601 -0.171496 -0.8672985 0.4966873 0.03309422 -0.7882425 0.6048396 0.1133261 -0.7866427 0.4732363 0.3965359 -0.7501876 0.523576 0.4038401 -0.8135344 0.2393158 0.5299904 -0.7362604 0.221455 0.639436 -0.8286733 -0.0874961 0.5528517 -0.8259174 -0.08998435 0.556564 -0.8015542 -0.3040424 0.5148489 -0.8909717 -0.2974887 0.3430305 -0.6737235 -0.6674011 0.3172894 -0.8493398 -0.5158994 0.1116691 -0.717486 -0.6917443 -0.08187633 -0.8305281 -0.5136956 -0.2152672 -0.7706248 -0.5453243 -0.3297864 -0.8218716 -0.3293179 -0.4648408 -0.8644282 -0.257767 -0.4316482 -0.7828667 -0.08942794 -0.6157292 -0.8842992 0.06273126 -0.4626876 -0.8270643 0.1305002 -0.5467488 -0.7847312 0.3050053 -0.5396006 -0.8196892 0.3149626 -0.4784435 -0.7430698 0.5468408 -0.3857623 -0.7789546 0.5310202 -0.3335376 -0.7734665 0.6306671 -0.06331419 -0.7638643 0.6413476 -0.07200556 -0.7763541 0.5889496 0.2245274 -0.8155372 0.5250979 0.2432516 -0.7588717 0.4840798 0.4356381 -0.8207403 0.3616562 0.4422559 -0.7103287 0.28712 0.642647 -0.8435689 0.04252481 0.5353346 -0.7630598 -0.08965498 0.6400795 -0.8682044 -0.1497324 0.4730765 -0.8096028 -0.3377798 0.4800502 -0.8703076 -0.3679731 0.327354 -0.7540808 -0.5565062 0.3488022 -0.7707617 -0.6264547 0.1161077 -0.8433741 -0.5371836 0.0124185 -0.7733684 -0.6126155 -0.1631066 -0.8629435 -0.4585272 -0.2123234 -0.7047867 -0.5306541 -0.4708313 -0.8330423 -0.2664927 -0.484791 -0.7267407 -0.1968155 -0.6581123 -0.8308147 0.01921403 -0.5562176 -0.7836979 0.06959998 -0.6172306 -0.8748035 0.2535834 -0.412813 -0.7757552 0.3921582 -0.4943843 -0.8724254 0.4251711 -0.2410464 -0.7885056 0.5716244 -0.2269458 -0.8458661 0.5332732 0.01142346 -0.7079937 0.7009723 -0.08592343 -0.8349367 0.4709936 0.2846857 -0.8566926 0.446433 0.2584094 -0.7565231 0.4170765 0.5037064 -0.8585273 0.1761166 0.4815744 -0.8872018 0.1305747 0.4425193 -0.7807682 -0.01205426 0.6247044 -0.8246599 -0.1843576 0.5347414 -0.8652186 -0.1958066 0.4615806 -0.7315962 -0.479274 0.4848334 -0.8131415 -0.4683403 0.3456274 -0.7324641 -0.6420047 0.226553 -0.8405118 -0.539178 0.05317157 -0.7219932 -0.6863046 -0.08781784 -0.8404393 -0.4662858 -0.2761147 -0.7359403 -0.6243478 -0.2618811 -0.7926288 -0.3631157 -0.4897823 -0.7691438 -0.3972208 -0.500633 -0.7818303 -0.121091 -0.6116196 -0.788635 -0.123382 -0.6023553 -0.7945784 0.2473018 -0.5545152 -0.8788504 0.1670017 -0.4469144 -0.7701214 0.4326922 -0.4687116 -0.8542335 0.4571743 -0.2475418 -0.7862384 0.5662252 -0.2474232 -0.7744773 0.6302335 0.05468863 -0.739572 0.6681761 0.08107978 -0.7836937 0.5324579 0.3198637 -0.7746642 0.5459355 0.3191393 -0.8128877 0.3311238 0.4791352 -0.7406467 0.3378983 0.5807472 -0.7867165 0.06891137 0.6134561 -0.8551928 -0.02276247 0.51781 -0.7573602 -0.2034394 0.6204983 -0.8634763 -0.2493634 0.4384364 -0.7307718 -0.5004873 0.4642037 -0.8549799 -0.483528 0.187644 -0.7863141 -0.61202 0.08450967 -0.8436987 -0.5358531 0.03215569 -0.8145211 -0.5248198 -0.247224 -0.8450396 -0.4711769 -0.2527856 -0.7167953 -0.4680211 -0.5168761 -0.8266458 -0.2218308 -0.5171536 -0.7882393 -0.1801301 -0.5884149 -0.7968032 -0.1653754 -0.5811675 -0.7011044 0.08242046 -0.7082793 -0.8162207 0.178724 -0.5494012 -0.7192625 0.3907482 -0.5744366 -0.8151688 0.4004153 -0.4185301 -0.7689111 0.5825591 -0.2634403 -0.8615038 0.4915459 -0.1272551 -0.790672 0.6118736 0.02118426 -0.865557 0.4814106 0.13804 -0.7793902 0.5726393 0.2542347 -0.7552297 0.4512102 0.4754339 -0.8627785 0.2771743 0.4228329 -0.7365952 0.1021859 0.6685698 -0.8559935 -0.001634061 0.5169842 -0.7084303 -0.2886198 0.6440693 -0.8194446 -0.3340024 0.4657821 -0.7387841 -0.5350691 0.4097551 -0.8625356 -0.4743774 0.1760641 -0.7514105 -0.651081 0.1071262 -0.8826719 -0.4612549 -0.09019082 -0.7767369 -0.5801737 -0.2451085 -0.8507669 -0.4399754 -0.2874323 -0.7330011 -0.4435849 -0.5156956 -0.8206764 -0.2183182 -0.5280411 -0.7706358 -0.1898108 -0.6083521 -0.7788993 0.03016787 -0.6264232 -0.729861 0.06687855 -0.6803163 -0.8380044 0.3329018 -0.4323482 -0.8165802 0.3616336 -0.4499089 -0.7920093 0.5280155 -0.3064653 -0.8687196 0.4627274 -0.1766627 -0.7788885 0.621576 -0.08352321 -0.8456203 0.5000111 0.1868563 -0.8211515 0.5301042 0.2114237 -0.7679017 0.4877068 0.415294 -0.8449887 0.3521324 0.4024887 -0.7465918 0.2983607 0.5946273 -0.7060156 0.1528888 0.6914963 -0.8042249 0.06694895 0.5905423 -0.8204647 -0.1125553 0.5605077 -0.7493195 -0.2103016 0.627928 -0.792792 -0.4010754 0.458933 -0.8627027 -0.3781894 0.3357334 -0.7699164 -0.5863343 0.2518751 -0.8773736 -0.4785471 0.03475964 -0.8303245 -0.5572711 -0.003186821 -0.8387567 -0.4960762 -0.2244897 -0.8303619 -0.5113306 -0.2214505 -0.7370892 -0.4921529 -0.4631253 -0.8138129 -0.2857812 -0.5060018 -0.762161 -0.2755107 -0.5858366 -0.7580613 -0.06262809 -0.6491693 -0.8078478 -0.002734959 -0.5893849 -0.7492976 0.2114912 -0.6275544 -0.8047093 0.2474398 -0.5396451 -0.7513945 0.4462243 -0.4860969 -0.8452866 0.422768 -0.326738 -0.6811197 0.7219029 -0.1221974 -0.8487546 0.5095358 -0.1413827 -0.7346383 0.6780727 0.02289295 -0.8333755 0.4912856 0.253227 -0.8365297 0.4878039 0.2495309 -0.7897452 0.3347249 0.514064 -0.8303177 0.2772513 0.4834297 -0.7680937 0.1441397 0.6239036 -0.8292512 -0.09039765 0.5515168 -0.8476922 -0.1049084 0.5200117 -0.7629674 -0.3418197 0.5486712 -0.8929911 -0.3684092 0.2585376 -0.8741744 -0.3854748 0.2953443 -0.7999043 -0.5740209 0.1750808 -0.885378 -0.464739 -0.0111199 -0.8321753 -0.5512261 -0.0602858 -0.7015013 -0.636125 -0.3213111 -0.8519962 -0.3742262 -0.3661384 -0.7001222 -0.3582429 -0.6176494 -0.8568318 -0.1614567 -0.4896644 -0.7319962 0.05068147 -0.679421 -0.8509907 0.2168016 -0.4783429 -0.8255143 0.2501629 -0.5059097 -0.7931049 0.4548871 -0.4050463 -0.8907704 0.4037029 -0.2086914 -0.7657676 0.6152039 -0.187415 -0.8168607 0.5644523 0.1188795 -0.8506888 0.5087032 0.1324753 -0.7515013 0.526209 0.3979322 -0.8520362 0.3079563 0.4233171 -0.7483959 0.3102172 0.5862329 -0.8681761 0.04769593 0.4939591 -0.7338253 -0.04962885 0.6775231 -0.8336178 -0.3064329 0.4595437 -0.7725793 -0.3844717 0.5052751 -0.8478 -0.479113 0.227346 -0.8125032 -0.5143406 0.2743945 -0.86159 -0.5075956 0.00308156 -0.8104432 -0.5849499 -0.03186529 -0.8096702 -0.5143133 -0.2826945 -0.8781201 -0.3823903 -0.287546 -0.8132326 -0.394586 -0.4277323 -0.8825194 -0.1210119 -0.45444 -0.8195523 -0.104599 -0.5633766 -0.8437765 0.05181509 -0.5341876 -0.7698498 0.1326498 -0.6242878 -0.774147 0.3963953 -0.4935255 -0.8496059 0.3904416 -0.3545776 -0.7526689 0.5765414 -0.3179461 -0.9030297 0.426849 -0.04834663 -0.7814711 0.6212349 0.05805337 -0.8441835 0.5034906 0.1839877 -0.7133595 0.598366 0.3647965 -0.830435 0.331189 0.4479861 -0.7406551 0.3158023 0.5930421 -0.8119736 0.1323556 0.5684902 -0.7133123 0.022403 0.7004882 -0.8350837 -0.1533312 0.5283226 -0.7463225 -0.2981892 0.5950511 -0.8043064 -0.4017266 0.4378436 -0.7534019 -0.4781883 0.4513554 -0.7773118 -0.601065 0.1857616 -0.8013323 -0.5669195 0.1909683 -0.748459 -0.6618392 -0.04216849 -0.8258017 -0.5506015 -0.1220234 -0.6655745 -0.5911802 -0.4555398 -0.8665738 -0.4280105 -0.2566262 -0.7808666 -0.2692673 -0.5636866 -0.8673403 -0.1670354 -0.4688496 -0.8190248 0.1198586 -0.5610994 -0.8448461 0.1336368 -0.5180506 -0.7639403 0.3791787 -0.5221291 -0.8288822 0.4069918 -0.3838124 -0.716336 0.5945553 -0.3651942 -0.7901174 0.6053189 -0.09645557 -0.7760705 0.6257203 -0.0786699 -0.8011979 0.5965778 -0.04665815 -0.7469809 0.6328184 0.2038643 -0.867962 0.4125251 0.276523 -0.7780294 0.4589318 0.4290127 -0.8657054 0.1833546 0.4657632 -0.8303236 0.1829702 0.5263883 -0.7606112 -0.03136569 0.6484495 -0.8348435 -0.08675044 0.5436092 -0.8536943 -0.3394567 0.3949372 -0.7746896 -0.323939 0.5430651 -0.7968583 -0.4628793 0.3882777 -0.8483226 -0.4723791 0.2391794 -0.7269873 -0.658802 0.1935703 -0.8088639 -0.5776234 -0.1099574 -0.7138006 -0.6737235 -0.191273 -0.891474 -0.3482992 -0.2897616 -0.7718225 -0.3952606 -0.4980553 -0.8792597 -0.135045 -0.456799 -0.8020439 -0.1092799 -0.5871828 -0.8448032 0.1935498 -0.4988447 -0.8517872 0.186168 -0.4896939 -0.7867037 0.5112691 -0.3459785 -0.9072557 0.3234888 -0.2687792 -0.7814223 0.5892927 -0.205216 -0.7988388 0.6011943 -0.02054685 -0.8892699 0.451147 0.0752694 -0.8016176 0.5616082 0.2049526 -0.8122281 0.4424961 0.3801087 -0.7546425 0.5253201 0.3931333 -0.7679975 0.2406146 0.5935357 -0.7787732 0.2280519 0.5843842 -0.7704086 -0.05116802 0.6354938 -0.8129706 -0.09376889 0.5747055 -0.7395942 -0.3151388 0.5947168 -0.8483345 -0.341489 0.4046157 -0.8833856 -0.4299181 0.1865482 -0.828362 -0.4743866 0.2979492 -0.7741907 -0.6159799 0.1455945 -0.8108437 -0.5739181 -0.114676 -0.8481907 -0.5126041 -0.1334531 -0.7257706 -0.5298256 -0.4387959 -0.8176748 -0.3870694 -0.4261282 -0.7990219 -0.217073 -0.5607525 -0.7445697 -0.2055822 -0.6351 -0.7912274 0.05982857 -0.6085886 -0.7476838 0.1003723 -0.6564254 -0.8276888 0.3241792 -0.4580823 -0.7716512 0.3978895 -0.4962242 -0.8581446 0.4556428 -0.236596 -0.7654321 0.6006945 -0.2308248 -0.8003249 0.5968153 0.05737203 -0.7065755 0.6954004 0.1310318 -0.8214799 0.4585363 0.3389915 -0.7279116 0.4960651 0.4733541 -0.8323345 0.2304706 0.504086 -0.722043 0.1844256 0.6668142 -0.8289145 -0.0117765 0.5592516 -0.6759746 -0.2304996 0.6999488 -0.8176566 -0.2904925 0.4970431 -0.7443398 -0.5320715 0.403557 -0.815244 -0.4956552 0.2995052 -0.7166125 -0.6880356 0.1143403 -0.8631719 -0.4992658 -0.07528501 -0.7334907 -0.6346636 -0.2432973 -0.8864725 -0.3346759 -0.3196228 -0.8088696 -0.3720749 -0.4552915 -0.8580634 -0.1255602 -0.4979576 -0.7879786 -0.1088045 -0.6060127 -0.8012118 0.16029 -0.5765125 -0.8163394 0.1665004 -0.553053 -0.7708294 0.4169158 -0.4816675 -0.8234746 0.4187095 -0.3828471 -0.7462918 0.5999745 -0.2882347 -0.8606026 0.5056444 -0.06072247 -0.8097897 0.5862876 -0.02253156 -0.8323773 0.5041961 0.2300748 -0.8302392 0.5079019 0.2296489 -0.7304379 0.4720305 0.493607 -0.832453 0.2813331 0.4773613 -0.7561653 0.179238 0.6293551 -0.8594783 0.005982398 0.5111375 -0.7996599 -0.106963 0.5908495 -0.8633627 -0.1865854 0.4688184 -0.7806783 -0.3198349 0.5368865 -0.7112629 -0.5891563 0.3834058 -0.8669908 -0.3742289 0.329059 -0.7932318 -0.5596113 0.2400385 -0.8751707 -0.4808326 0.053631 -0.7984066 -0.6021158 0.001894354 -0.786643 -0.5765919 -0.2207589 -0.7870923 -0.5759325 -0.220879 -0.7608369 -0.4223883 -0.4926614 -0.7813559 -0.3931273 -0.4846999 -0.8592321 -0.03653472 -0.5102798 -0.7809527 -0.1452617 -0.6074637 -0.7985411 0.0955401 -0.5943101 -0.869327 0.2341756 -0.4352383 -0.8304226 0.2851042 -0.4786583 -0.79289 0.5161624 -0.3238857 -0.8896056 0.439911 -0.1228026 -0.8021315 0.5899266 -0.09258455 -0.8337373 0.5331121 0.1437836 -0.7529368 0.6154812 0.2329571 -0.778434 0.4492173 0.4384568 -0.7733684 0.4568144 0.4395704 -0.8036947 0.221846 0.5521407 -0.802021 0.2215105 0.5547031 -0.7550904 -0.01580709 0.6554303 -0.7957078 -0.05331867 0.6033294 -0.8180891 -0.3094435 0.4847422 -0.7629404 -0.2711933 0.5868358 -0.7355093 -0.469877 0.4881003 -0.8200985 -0.5273913 0.2220294 -0.827547 -0.5151932 0.2230292 -0.8585785 -0.5117462 -0.03096586 -0.8676257 -0.496616 -0.0244618 -0.7639198 -0.5975878 -0.2435478 -0.8799504 -0.3543888 -0.3163796 -0.7775176 -0.4157347 -0.4718381 -0.832129 -0.08079457 -0.5486654 -0.8150408 -0.09816068 -0.5710281 -0.7622708 0.1087886 -0.6380503 -0.8576181 0.2843211 -0.4285475 -0.8411722 0.3070152 -0.445164 -0.7756523 0.502056 -0.3824962 -0.8874355 0.4338285 -0.1557278 -0.782559 0.6125442 -0.1113141 -0.8592046 0.4913321 0.1426896 -0.8452384 0.5162611 0.1380095 -0.798831 0.4162194 0.4343161 -0.8828239 0.2577543 0.3926638 -0.7567799 0.1994977 0.6224828 -0.8196992 -0.002275824 0.5727899 -0.8651849 -0.03526908 0.5002112 -0.8577006 -0.2284854 0.4605913 -0.7742142 -0.3368517 0.5358389 -0.7790418 -0.5480123 0.3045923 -0.8642601 -0.4731998 0.1706942 -0.7669559 -0.6383326 0.06565326 -0.8714057 -0.467565 -0.1484427 -0.8209975 -0.5316008 -0.2082399 -0.8397156 -0.291745 -0.4579984 -0.7476986 -0.4797892 -0.4590744 -0.7710383 -0.2642664 -0.5793646 -0.8744259 -0.0122919 -0.4850035 -0.8200786 0.02817952 -0.5715568 -0.8171344 0.2379894 -0.5250262 -0.8729851 0.2666633 -0.4083967 -0.7834545 0.4276821 -0.4508737 -0.8188909 0.5214905 -0.2397196 -0.8839801 0.4443717 -0.1453028 -0.7689152 0.6302397 0.1075513 -0.8853543 0.4333574 0.1683726 -0.7596808 0.5148532 0.3972551 -0.7998269 0.328983 0.5020431 -0.871952 0.2179001 0.4384282 -0.7625613 0.1034335 0.6385937 -0.870813 -0.04929113 0.4891372 -0.8172143 -0.1326007 0.5608726 -0.8648845 -0.3087027 0.3958252 -0.8287589 -0.310736 0.4654051 -0.7585622 -0.564709 0.325096 -0.8824523 -0.4470638 0.146329 -0.7554509 -0.6527264 -0.05694162 -0.8478078 -0.5112198 -0.1409833 -0.7456843 -0.5894293 -0.3106898 -0.8469744 -0.3509346 -0.3993484 -0.702303 -0.3442105 -0.623129 -0.8466378 -0.05718374 -0.5290884 -0.8106887 -0.0292558 -0.584746 -0.7967419 0.1935449 -0.5724883 -0.7513495 0.1818734 -0.6343471 -0.7931762 0.431788 -0.429454 -0.7892269 0.4374465 -0.4310008 -0.7794734 0.5920972 -0.2045534 -0.7662731 0.6101771 -0.2012699 -0.8128152 0.5799432 0.05474817 -0.7628542 0.6382353 0.1034859 -0.7803792 0.5293202 0.332909 -0.8136262 0.4764984 0.3331093 -0.7813282 0.2563732 0.5690335 -0.7962392 0.2545285 0.5488337 -0.7827624 -0.04885119 0.6204005 -0.8106551 -0.07226431 0.5810475 -0.8494683 -0.355785 0.389642 -0.7502022 -0.3525152 0.5594012 -0.7536607 -0.5659044 0.3342871 -0.8892032 -0.4520546 0.07045859 -0.6812436 -0.6874036 0.2517611 -0.8526936 -0.4917851 -0.1762416 -0.8428851 -0.5047266 -0.1865363 -0.8032884 -0.4478762 -0.3926001 -0.8180406 -0.4194888 -0.3934959 -0.7350587 -0.3322151 -0.5910345 -0.8238479 -0.1880103 -0.5347212 -0.7351241 0.003391146 -0.6779241 -0.8449152 0.1437733 -0.5152162 -0.7688118 0.2707036 -0.5793514 -0.8822231 0.3197266 -0.3456262 -0.7704939 0.5178369 -0.3717312 -0.8835238 0.4578282 -0.09888982 -0.7468973 0.6641812 -0.031744 -0.8259272 0.5193189 0.2194362 -0.7769326 0.5594588 0.2887588 -0.7819434 0.3754764 0.4975762 -0.8601913 0.3365545 0.3831478 -0.7761937 0.191942 0.6005678 -0.8832002 0.03680205 0.4675502 -0.7563042 -0.1214423 0.6428497 -0.8803198 -0.2338079 0.4127601 -0.7703356 -0.4032379 0.4939457 -0.6645658 -0.6977055 0.267506 -0.7800432 -0.5598137 0.2795377 -0.8761949 -0.4817489 0.01416164 -0.842437 -0.5360969 0.05385357 -0.7621936 -0.6139063 -0.205378 -0.8737131 -0.3712859 -0.3142805 -0.8446783 -0.3961271 -0.3600026 -0.8029674 -0.1506443 -0.5766712 -0.8685246 -0.07472693 -0.4899807 -0.7846909 0.2115707 -0.5826647 -0.8523713 0.1545223 -0.4995858 -0.8000543 0.4456889 -0.4015902 -0.6730537 0.489889 -0.5540827 -0.7971211 0.5842862 -0.1523411 -0.8170932 0.5545515 -0.1575803 -0.7311182 0.6780374 0.07570755 -0.8527464 0.4836817 0.1971687 -0.794386 0.5133 0.3247678 -0.8765955 0.3429517 0.3375862 -0.7567847 0.3089238 0.5760582 -0.8744395 0.1083967 0.4728698 -0.7873777 3.16194e-4 0.6164708 -0.8766718 -0.1275824 0.4638636 -0.7785613 -0.2725881 0.5652771 -0.81735 -0.3798729 0.4331691 -0.9078737 -0.3346387 0.252552 -0.83095 -0.5059885 0.231296 -0.8101343 -0.5801562 0.0842688 -0.774396 -0.6208512 0.1218802 -0.7570111 -0.6320774 -0.1655671 -0.8194471 -0.5358419 -0.2034209 -0.7283583 -0.5193727 -0.4469299 -0.8505132 -0.2802549 -0.4450671 -0.7937341 -0.2576047 -0.5510228 -0.8630713 -0.02799004 -0.5043061 -0.868133 -0.02254605 -0.4958195 -0.7649402 0.2535442 -0.5920995 -0.8480281 0.2786418 -0.4507853 -0.7533193 0.4774401 -0.4522842 -0.7976453 0.5235496 -0.2994292 -0.7348027 0.6202906 -0.2744167 -0.8087197 0.5878706 -0.01950705 -0.7907504 0.6121235 -0.004342317 -0.7677992 0.5937018 0.2408372 -0.8509517 0.4389867 0.2883952 -0.7559014 0.4709013 0.4548243 -0.8720708 0.1691474 0.4592186 -0.8418691 0.1691694 0.5124824 -0.7919936 -0.03001683 0.6097911 -0.8510432 -0.1176403 0.5117483 -0.7656205 -0.252015 0.591873 -0.8400561 -0.4068107 0.3589022 -0.7390685 -0.543856 0.3974903 -0.8770636 -0.4739633 0.07821965 -0.8094019 -0.5855291 0.04499191 -0.8501648 -0.4852618 -0.2043061 -0.8357515 -0.5112072 -0.2004661 -0.7365182 -0.4849195 -0.4715868 -0.8024377 -0.2755303 -0.5293173 -0.7236641 -0.2683613 -0.6358399 -0.8296158 0.03191059 -0.5574221 -0.7921506 0.05613231 -0.607739 -0.849267 0.2720592 -0.4524703 -0.931487 0.2873694 -0.2230488 0.1244504 0.4658389 -0.8760743 -0.894248 0.4034156 -0.1938463 -0.8526999 0.5071918 -0.1251374 -0.9453212 0.3253808 0.02225363 -0.6675177 0.6552676 0.3536165 0.6188633 -0.6719062 0.4068788 -0.6818094 -0.7268103 -0.08296209 0.7533762 -0.6318666 -0.1821236 -0.7694718 -0.3773381 -0.5152952 0.4896037 0.2885828 -0.8228051 -0.6310846 0.6717301 -0.3879573 -0.3079768 -0.2883015 0.9066601 -0.1788643 -0.8012766 0.5709322 0.5755947 -0.6853821 0.4460294 -0.5567066 -0.8300875 -0.03213405 0.6382889 -0.7586559 -0.1304945 -0.6080436 -0.6310545 -0.481719 0.7351269 -0.427384 -0.5262429 -0.7435984 -0.05711066 -0.6661831 0.6965751 0.300224 -0.6516508 -0.6704455 0.6358505 -0.3823572 0.6842211 0.7284954 -0.03370457 0.5471762 0.01895076 0.836803 -0.6356753 -0.4292308 0.6416213 -0.2378673 -0.8809193 0.4091458 0.5311219 -0.8309814 -0.1654674 -0.705191 -0.1056942 -0.7010952 0.600072 0.1437964 -0.7869157 -0.6669023 0.3768189 -0.6428444 0.712085 0.5373248 -0.4519039 -0.5984511 0.7441996 -0.2966874 0.6036893 0.7955677 0.05129808 -0.1082028 -0.005523025 0.9941135 0.3930764 -0.5213388 0.7574279 -0.3438471 -0.6161931 0.7085727 -0.04567158 -0.9767386 0.2095137 0.7067644 -0.497921 -0.5025523 -0.6135029 -0.0690869 -0.7866647 0.5429337 0.01313585 -0.8396729 -0.5815786 0.4594811 -0.6712999 -0.5505065 0.1700093 0.8173369 0.4445297 -0.1772817 0.8780459 -0.5367287 -0.3501256 0.7676813 0.7188529 -0.5215247 0.4596331 -0.6817746 -0.7280204 0.07190114 0.5358278 -0.7656904 -0.3558187 -0.4761449 -0.0647211 -0.876982 0.3723132 0.4008793 -0.8370656 -0.5575143 0.4967172 -0.665169 0.5615013 0.6680167 -0.4883338 -0.7594912 0.6453864 -0.08154517 0.7815384 0.5966178 0.1823322 -0.6839588 0.4749513 0.5537343 0.6844068 0.3018701 0.663673 -0.4814673 0.1244556 0.867583 0.4367608 -0.2982025 0.848714 0.7652372 0.1247972 -0.631536 -0.6598418 0.5010465 -0.5599654 0.7620617 0.5674405 -0.3118871 -0.4948526 0.05956178 0.8669334 0.5122466 -0.4333934 0.7414672 -0.6034968 -0.7010362 0.379921 0.5490667 -0.8240452 0.1395545 -0.6405372 -0.7528379 -0.1514842 0.7925565 -0.5378586 -0.2873365 -0.8986242 -0.1401117 -0.4157443 0.6176434 0.6870106 -0.3827964 -0.557702 0.8299727 0.01067918 0.693625 0.694754 0.1902663 -0.2150245 0.6423467 0.7356325 -0.07700884 -0.00226736 0.9970279 0.6437259 -0.628113 0.4371398 -0.6250956 -0.775049 0.09249079 0.5814638 -0.8116862 -0.05536866 -0.495541 -0.7185121 -0.4880363 0.5792359 0.3469137 -0.7376562 -0.4469712 0.7388287 -0.5043301 0.6983952 0.6684824 -0.2556862 -0.04222631 0.9781877 0.2033856 -0.3604807 0.6073311 0.7079567 0.7777284 -0.3427221 0.5269537 -0.7354806 -0.6424748 0.2151616 0.5747179 -0.8032593 0.1564419 -0.2250332 -0.8851556 -0.4072588 -0.1334705 0.9316356 0.3379951 0.2884882 0.4745042 0.8316372 0.288415 -0.02060502 0.9572838 -0.3737061 -0.6581662 0.6535757 0.3167282 -0.6887718 0.6521324 -0.06363874 -0.9976688 -0.0246433 -0.1011667 -0.8131626 -0.5731771 -0.2561175 -0.2976504 -0.9196783 0.7273023 0.1188585 -0.6759468 -0.5714742 0.5332174 -0.6237761 0.6419411 0.6288465 -0.4387069 -0.5386884 0.7962586 -0.2752944 0.5996249 0.7851164 0.1550564 -0.4746492 0.5933263 0.6501324 0.3607507 0.09214937 0.9280989 -0.520116 -0.4039999 0.7525048 0.4919334 -0.7260037 0.4805417 -0.5713694 -0.7787516 0.2590041 0.4862242 -0.8683943 0.09735161 -0.5799643 -0.7810707 -0.2314517 0.6536552 -0.6591733 -0.3717871 -0.6608259 -0.4771399 -0.5793504 0.6343146 -0.2936297 -0.7151411 -0.7241892 0.07550311 -0.6854555 0.3797483 0.547796 -0.7454602 -0.487521 0.8287024 -0.2749104 0.5033156 0.8394002 -0.2051357 -0.3601974 0.8698821 0.3369913 -0.7134562 -0.5483504 -0.4362248 0.6940205 -0.3293071 -0.6402285 -0.6629049 -0.08935946 -0.7433519 0.6606526 0.1786206 -0.7291316 -0.8545982 0.5172643 -0.04582154 0.7433606 0.6341578 0.2127413 -0.6557365 0.5427095 0.5248583 0.7176153 0.3380587 0.6088882 -0.8063983 -0.02444189 0.5908675 0.6066076 -0.3544453 0.7116149 -0.5818402 -0.7319554 0.3545467 -0.7754842 -0.6222772 -0.1067496 0.6360846 -0.6538752 -0.4096873 -0.562664 -0.5135414 -0.6478307 0.5655002 -0.3283837 -0.7565538 -0.5488547 -0.1004058 -0.8298658 0.4656029 0.2371751 -0.8526207 -0.409727 0.3924766 -0.8234598 0.5601679 0.6406554 -0.5251405 -0.3960933 0.8038139 -0.4438395 -0.07019972 0.9975112 -0.006604433 0.5321757 0.8460778 0.03068321 -0.607156 0.630308 0.4838114 -0.6254588 -0.434478 0.6480974 0.5209122 -0.7371965 0.4303391 -0.3291634 -0.878733 0.3456585 0.2310296 -0.9429055 -0.2399052 -0.3913093 0.4429579 -0.8066384 0.4292883 0.7989876 -0.4211061 -0.08644586 -0.9961943 0.01114904 -0.2470321 -0.7723628 -0.5851761 0.07813787 -0.7854773 -0.613938 0.3613995 -0.3144828 -0.8777762 -0.4143114 -0.1922038 -0.8896088 0.1350294 0.3011632 -0.943964 0.2255447 0.929342 -0.2923235 -0.1073529 0.9068782 0.4074888 0.1437731 0.2092564 0.9672337 0.3382738 -0.3570949 0.870663 -0.8278025 -0.4879792 0.276802 0.676369 -0.7156483 0.1742776 -0.7554321 -0.6108704 -0.2369806 0.04459351 -0.2469904 -0.9679914 0.2325422 0.3773844 -0.8963845 -0.1836434 0.4328907 -0.8825423 -0.2627474 0.8722897 -0.4124012 0.5445202 0.7738919 -0.3234027 -0.5457997 0.8060467 0.228892 -0.04553413 -0.8514072 0.5225251 0.3917769 -0.9193183 0.03694409 -0.5235433 -0.8436152 -0.1192302 0.4681569 -0.7211598 -0.5106444 -0.02403151 -0.7657191 -0.6427262 -0.3251298 -0.164246 -0.9312969 0.6401825 0.2696098 -0.7193587 -0.5675771 0.6963501 -0.4392641 0.5146525 0.7650404 -0.3870995 -0.481025 0.8720127 0.09060204 0.4850845 0.8604226 0.1560963 -0.4984134 0.6266501 0.5990775 0.5444728 0.544055 0.6383992 -0.5788502 0.1720749 0.7970715 0.4941776 0.07953858 0.8657148 -0.2297654 -0.4411516 0.8675214 0.6617178 -0.6276583 0.410091 -0.6142233 -0.7876759 -0.04792076 0.7952413 -0.5823557 -0.1686808 -0.5867351 -0.4916596 -0.6434383 0.4675832 -0.1218131 -0.8755156 -0.4786093 0.04459834 -0.8768947 0.5367909 0.376765 -0.7549198 -0.6252006 0.5146093 -0.5867722 0.6174975 0.7096024 -0.3393545 -0.550539 0.8202478 -0.1552427 0.53884 0.8162834 0.2081661 -0.1698484 0.9158726 0.3637703 -0.2548339 0.5300236 0.808786 0.6248751 0.1113043 0.7727499 -0.6428864 -0.3544179 0.6790324 0.3968232 -0.4870875 0.7779956 0.1827506 -0.9002474 0.3951669 -0.6089207 -0.7631678 0.2163113 0.6157327 -0.760333 -0.2068017 -0.2477328 -0.2422333 -0.9380573 -0.322678 0.2851722 -0.9025275 0.8231134 0.2946505 0.4854539 0.06979256 -0.5410587 0.8380839 -0.4794114 -0.8248196 0.2997288 0.6597577 -0.7471672 -0.08037996 -0.6128663 -0.5679389 -0.5494 0.2854099 0.06747025 -0.9560278 0.1997597 0.5918198 -0.7809261 -0.6147827 0.5650185 -0.5502694 0.6883381 0.705961 -0.1667631 -0.08158355 0.6954391 0.7139388 0.3313586 0.1727116 0.9275625 -0.5312709 0.02965819 0.8466827 0.6275467 -0.3952844 0.6707723 -0.7026967 -0.6694656 0.2409007 0.5677065 -0.8143988 0.1202664 -0.6839234 -0.6968396 -0.2160174 0.7653118 -0.5459314 -0.3409649 -0.6758686 -0.4095693 -0.6127436 0.5088251 -0.2251662 -0.8309015 -0.4304044 -0.02984553 -0.9021426 0.528845 0.2166649 -0.8205969 -0.7723439 0.4131306 -0.4825018 0.3091415 0.9364066 0.1660555 0.2734445 0.7483912 0.6042672 -0.5627478 0.549535 0.6175162 0.4138785 0.2996695 0.8595946 -0.4555217 0.1131811 0.8830006 0.5498495 -0.1241718 0.8259824 -0.7283864 -0.3664443 0.5789403 0.7150406 -0.4876648 0.5008991 -0.7287186 -0.6725876 0.1288218 0.1864758 -0.6682996 -0.7201406 0.366568 -0.1469743 -0.9187092 -0.5092116 -0.01233392 -0.860553 0.1109344 0.5401093 -0.8342514 -0.5818359 0.7185131 0.3810589 0.4549041 0.3973267 0.7969906 -0.1769992 0.3480816 0.9206034 -0.01544046 -0.2403346 0.9705674 -0.433865 -0.603162 0.6692957 0.5284016 -0.8153983 0.2364688 -0.6328322 -0.773532 0.03422915 0.7317604 -0.6278592 -0.2651784 -0.8260114 -0.2531095 -0.5036277 0.6915621 -0.04096144 -0.7211548 -0.7049354 0.236361 -0.6687299 0.2051395 0.7320626 -0.649617 0.1941133 0.97744 -0.08325374 -0.4357895 0.8998581 0.01851767 0.1973603 0.9027542 0.3822092 -0.6046392 0.6075746 0.5150386 0.2316438 0.6429445 0.7300435 0.1956958 0.2375292 0.9514636 -0.9776207 -0.09841817 0.1859347 0.9654189 -0.2581725 0.03624165 -0.007180631 -0.8259508 -0.5636965 0.8483254 -0.4080138 -0.3374446 0.8099552 -0.1388095 -0.5698286 0.6335603 -0.08239322 -0.7692937 0.856552 0.1823583 -0.4827673 0.7593755 0.3348094 -0.5578992 0.7616398 0.5429507 -0.3537082 0.8530418 0.3846963 -0.3526026 0.7261371 0.6562924 -0.204952 0.8277688 0.5537348 -0.09042572 0.7352953 0.6643298 0.1341897 0.8188143 0.5411775 0.1914945 0.7111485 0.4920321 0.5021677 0.7968113 0.4571838 0.3950631 0.7339615 0.292033 0.6132025 0.8375654 0.1398426 0.5281365 0.7428184 -0.007864832 0.6694468 0.8500759 -0.1607609 0.5015247 0.8000201 -0.2422034 0.5489129 0.8436242 -0.3949169 0.3637841 0.8704432 -0.3731037 0.3211265 0.7785352 -0.6077936 0.156429 0.8841835 -0.4654949 0.03916728 0.7552864 -0.6337035 -0.1672199 0.8858188 -0.4017391 -0.2322301 0.7110371 -0.4533458 -0.5374979 0.7346451 -0.427572 -0.5267626 0.8077583 -0.04014492 -0.5881455 0.8429395 -0.06092 -0.5345484 0.7879489 0.2055057 -0.5804344 0.8183968 0.2111108 -0.5344708 0.7543572 0.4803275 -0.4474715 0.8555583 0.4464856 -0.2620509 0.780067 0.5824372 -0.2286096 0.8509939 0.5241283 0.03314882 0.6991412 0.7140443 -0.0366404 0.7728765 0.5774105 0.2631712 0.8247949 0.4950769 0.2731526 0.7587337 0.4732349 0.4476292 0.8376719 0.2289704 0.4958614 0.7090664 0.355658 0.608878 0.8267138 -0.00106734 0.5626217 0.7859368 -0.04491269 0.6166735 0.866966 -0.1719092 0.4677789 0.7592729 -0.3445136 0.5521006 0.8056114 -0.5331485 0.2583472 0.8466112 -0.4667768 0.2556738 0.7679042 -0.6405097 0.008396387 0.8992643 -0.4197384 -0.1230583 0.6442712 -0.7533687 -0.1317205 0.8557788 -0.3817365 -0.3491706 0.652221 -0.4149747 -0.6343531 0.8679096 -0.0785765 -0.490468 0.8173192 -0.02611887 -0.5755928 0.8394466 0.1634195 -0.518289 0.8844335 0.1786007 -0.4311373 0.767973 0.4200384 -0.4835137 0.8720995 0.4341725 -0.2256917 0.8614116 0.4472241 -0.2407506 0.799489 0.5976179 -0.06058144 0.8379225 0.5455725 -0.01538056 0.7400435 0.6408386 0.2041118 0.8165292 0.4965577 0.2944664 0.7498087 0.5141528 0.4164538 0.8108142 0.3050612 0.4995179 0.7285853 0.2762733 0.6267667 0.8731019 -0.00594145 0.4875016 0.8165014 -0.07294523 0.5727168 0.8090345 -0.3040177 0.5030274 0.8712502 -0.2822009 0.4016044 0.7845295 -0.5221472 0.3344786 0.8594727 -0.4739266 0.1915733 0.7762997 -0.6187812 0.1202859 0.7729897 -0.6159487 -0.1519677 0.7789483 -0.6099923 -0.1454268 0.7360402 -0.4757055 -0.481611 0.8007658 -0.4464471 -0.3993234 0.803275 -0.1595653 -0.5738364 0.869029 -0.1006689 -0.4844116 0.7750542 0.1478197 -0.6143618 0.8523868 0.1789286 -0.4913464 0.7385919 0.4446067 -0.5067613 0.8416234 0.4225666 -0.3363149 0.7707608 0.6213548 -0.140876 0.8270589 0.5387041 -0.1605347 0.727938 0.6829687 0.06049752 0.8281044 0.5408971 0.1472195 0.7010923 0.5873445 0.4043465 0.8270556 0.3945853 0.4003519 0.7292653 0.2812061 0.623775 0.8650972 0.1059724 0.4902825 0.7941167 -0.02137857 0.6073892 0.8699173 -0.1512194 0.469443 0.8110882 -0.2407513 0.5330806 0.8467288 -0.3756285 0.3767672 0.6781266 -0.6337994 0.3720789 0.873077 -0.4852478 0.04765683 0.8033953 -0.5949574 -0.02412253 0.8577379 -0.4875382 -0.1630718 0.7937525 -0.5426887 -0.2746747 0.7451248 -0.434834 -0.5056763 0.8005645 -0.3603397 -0.4788024 0.7546926 -0.1701915 -0.6336197 0.8559058 -0.03556978 -0.5159072 0.80923 0.0380097 -0.586261 0.836467 0.2345081 -0.495307 0.8832379 0.2340158 -0.4063589 0.7554468 0.4957773 -0.428375 0.8727571 0.4466331 -0.1970123 0.753708 0.6453665 -0.1242032 0.7828704 0.5949818 0.1819632 0.797814 0.5800744 0.164337 0.8029596 0.4885535 0.3414257 0.8782534 0.3567581 0.3184254 0.7681191 0.3055654 0.5626927 0.8738831 0.1239261 0.4700752 0.8659325 0.1132305 0.4871755 0.8455756 -0.1135568 0.5216386 0.8473327 -0.1150672 0.5184468 0.7597308 -0.3192806 0.5664531 0.8086149 -0.419522 0.4124844 0.7413894 -0.5294796 0.4123024 0.8134791 -0.5617806 0.1505141 0.8092376 -0.5685728 0.1478493 0.7027782 -0.7028424 -0.1100699 0.8116785 -0.5548694 -0.1824775 0.715795 -0.5615717 -0.41506 0.8255134 -0.4058622 -0.3921779 0.7667975 -0.2139947 -0.6051677 0.8031033 -0.223163 -0.5524703 0.8493341 0.007952451 -0.5277957 0.6889183 0.1341348 -0.7123198 0.795264 0.3223635 -0.5134562 0.8489879 0.3023989 -0.4333294 0.8072253 0.5198892 -0.2794686 0.7875773 0.5362671 -0.3035449 0.7615418 0.646559 -0.04489642 0.780447 0.6245481 -0.02902173 0.7612351 0.5995632 0.2470733 0.7756461 0.5797508 0.2495242 0.7740336 0.4581438 0.4370084 0.8249596 0.3752176 0.4226743 0.7465509 0.2669102 0.6094431 0.8351055 0.04181098 0.5484987 0.8570704 0.05939102 0.5117649 0.7794451 -0.1798123 0.6001108 0.840127 -0.2252957 0.493385 0.7400335 -0.4197317 0.5255243 0.8477172 -0.4674638 0.2507055 0.8125935 -0.5292622 0.2440764 0.8309017 -0.5562849 -0.01223278 0.8715133 -0.4891046 -0.03523236 0.7945099 -0.5497611 -0.2579087 0.8103315 -0.5201641 -0.2698004 0.7130321 -0.460668 -0.5285548 0.8369516 -0.2418094 -0.4909584 0.7566882 -0.2033166 -0.6213577 0.8246843 0.07589298 -0.5604784 0.7570997 0.1540379 -0.6348799 0.7841572 0.3606411 -0.5050105 0.7963387 0.3595992 -0.4863466 0.7810145 0.5496274 -0.2965237 0.7927205 0.5321197 -0.2973936 0.8650439 0.4992253 -0.04973357 0.8067929 0.5907858 0.00758624 0.8373283 0.5379195 0.09759175 0.7365578 0.607534 0.2972964 0.8488234 0.3437898 0.4016311 0.7927541 0.3558834 0.4948617 0.8283271 0.119675 0.5473135 0.859412 0.08443367 0.5042638 0.7140403 -0.1548328 0.6827689 0.8345155 -0.2487047 0.4916605 0.7292198 -0.4675108 0.4996721 0.8449818 -0.4490205 0.2904935 0.7891868 -0.5998104 0.1319546 0.8335008 -0.5334923 0.1437444 0.7987578 -0.5699312 -0.1927808 0.8528752 -0.483026 -0.1982164 0.722648 -0.4917195 -0.48579 0.8097271 -0.295551 -0.5069434 0.7710349 -0.2710353 -0.5762335 0.8116053 -0.055251 -0.5815876 0.7489734 0.007574379 -0.6625568 0.8316117 0.2443823 -0.4986975 0.7813368 0.3174471 -0.5373457 0.8657242 0.3813735 -0.3241543 0.7691055 0.5604174 -0.3072609 0.8071405 0.5386974 -0.241515 0.7395114 0.6693955 -0.07094144 0.8521312 0.5108698 0.1135098 0.8212985 0.5474388 0.1605599 0.8447166 0.3985823 0.3571923 0.7909154 0.4731436 0.3880568 0.7799611 0.1988506 0.5933963 0.7077561 0.1639229 0.6871759 0.8168464 -0.03003382 0.5760729 0.6996279 -0.2234123 0.6786809 0.8504003 -0.290756 0.4384977 0.7680477 -0.4827727 0.4207533 0.8905326 -0.4065592 0.2041114 0.7793686 -0.6051294 0.1624895 0.8265305 -0.5395384 -0.1604548 0.8102452 -0.5638082 -0.1600726 0.7343382 -0.4855796 -0.4742994 0.8270022 -0.3362873 -0.4505311 0.7630879 -0.2729302 -0.5858379 0.8222364 -0.0783661 -0.5637252 0.7319551 0.01367503 -0.6812157 0.8338591 0.1431789 -0.5330845 0.7255296 0.3729496 -0.5783732 0.8286426 0.3990647 -0.3925546 0.7624052 0.5289819 -0.3727151 0.8258966 0.53712 -0.1714558 0.7504981 0.651538 -0.1106839 0.7657172 0.6317725 0.1205847 0.8709358 0.4623324 0.1664924 0.7528662 0.5268068 0.3945469 0.8378041 0.3187648 0.4432531 0.8259407 0.3345848 0.4537345 0.7511306 0.1105536 0.650831 0.8497318 -0.01531273 0.5269929 0.7825459 -0.1168367 0.6115318 0.8420922 -0.3051167 0.4447296 0.8968431 -0.2747758 0.3466565 0.7508489 -0.5874937 0.3017899 0.8401767 -0.5382319 0.06640475 0.8429148 -0.5341885 0.0643239 0.7337582 -0.649143 -0.2005299 0.834907 -0.4441254 -0.3250892 0.8414111 -0.4404618 -0.3130829 0.8230801 -0.2924697 -0.4868271 0.8468086 -0.2563252 -0.4660608 0.7408315 -0.1237671 -0.6601897 0.8147784 0.1050977 -0.5701674 0.794916 0.1309817 -0.5924122 0.8628504 0.2829438 -0.4188463 0.8029429 0.3844239 -0.4555227 0.8280306 0.4909859 -0.2707362 0.8694616 0.4447432 -0.2150352 0.7754105 0.6313899 -0.009242534 0.8864067 0.4439408 0.1311482 0.6668907 0.7331397 0.1332778 0.8517941 0.3527925 0.3872782 0.8117542 0.367778 0.453646 0.8200355 0.1641668 0.5482619 0.849069 0.1193305 0.5146281 0.7499296 -0.024284 0.6610718 0.8326354 -0.2624382 0.4876931 0.8572515 -0.2258427 0.4627258 0.7768229 -0.4592031 0.4309045 0.8863677 -0.4175624 0.1999852 0.7336793 -0.6647076 0.1409913 0.8766734 -0.4743301 -0.08034259 0.7878831 -0.5772451 -0.2145422 0.8954645 -0.3285474 -0.3003335 0.7243155 -0.3774988 -0.5769417 0.8628033 -0.06696617 -0.501085 0.8198481 -0.02919757 -0.5718361 0.7377241 0.2285568 -0.6352363 0.8552103 0.3090853 -0.4160309 0.8038813 0.4069241 -0.4338064 0.8392972 0.4984114 -0.2171782 0.8478296 0.4831776 -0.2184596 0.789184 0.6096281 0.07444715 0.8452873 0.5258367 0.0947901 0.7580482 0.5423632 0.3622224 0.8163998 0.4206181 0.3956916 0.6992191 0.3944925 0.5962117 0.8196097 0.1663757 0.5482326 0.7116672 0.00311917 0.7025099 0.8200263 -0.0681191 0.5682575 0.7196608 -0.4088349 0.5611973 0.8193275 -0.2858111 0.4970055 0.7432656 -0.5768949 0.3387455 0.8154675 -0.5241429 0.2455341 0.7303554 -0.6822149 0.0341162 0.8169009 -0.5747182 -0.04870468 0.7429793 -0.6235572 -0.2432246 0.8732065 -0.3825936 -0.3018819 0.7964668 -0.4116102 -0.4429646 0.7862491 -0.2100632 -0.5811074 0.8762071 -0.1191044 -0.4669855 0.7887531 0.06934303 -0.6107864 0.8134067 0.09308528 -0.5741993 0.7426741 0.3371098 -0.5786123 0.8565785 0.3491457 -0.3799611 0.7414564 0.5833194 -0.3316338 0.84311 0.5140999 -0.1576921 0.7164685 0.696987 -0.02969676 0.8153294 0.5453195 0.1945883 0.7796839 0.5655649 0.2687553 0.898988 0.3542174 0.2575865 0.7515295 0.3480689 0.5604029 0.7937025 0.06594759 0.6047209 0.8633871 0.1173123 0.4907144 0.858753 -0.1512604 0.4895544 0.7247872 -0.3103852 0.6150972 0.7885782 -0.409654 0.4586154 0.8723371 -0.3819184 0.3052317 0.7644236 -0.5876169 0.2652602 0.7804308 -0.6251825 0.00864166 0.8709653 -0.4867538 -0.0670101 0.7427994 -0.6106149 -0.2745878 0.8569377 -0.3920692 -0.3345738 0.901391 -0.3107252 -0.3015694 0.8228563 -0.1922062 -0.5347565 0.8669328 -0.1166766 -0.4845763 0.7481802 0.05183368 -0.6614679 0.8767021 0.1587092 -0.4540978 0.8090367 0.2840568 -0.5145595 0.8281688 0.4436037 -0.3425671 0.8652448 0.411557 -0.2863082 0.801338 0.5817532 -0.1393581 0.8761649 0.4796966 -0.04718303 0.7806184 0.6073339 0.1475822 0.8581179 0.4692201 0.2084855 0.7582704 0.5195618 0.3938041 0.8152224 0.2825047 0.5055726 0.7491152 0.268719 0.6054887 0.7846169 0.002031981 0.6199776 0.8087297 -0.01474565 0.5879956 0.775022 -0.2746056 0.5691509 0.8538846 -0.2945854 0.4290694 0.8005459 -0.4195197 0.4279364 0.8201821 -0.527159 0.2222722 0.8635272 -0.4478737 0.2317973 0.8173051 -0.5660253 -0.1078323 0.7594683 -0.6426849 -0.1008167 0.7974624 -0.4227808 -0.4304768 0.6965475 -0.5384967 -0.474176 0.8182337 -0.2674919 -0.5088632 0.7346757 -0.1929827 -0.6503918 0.8355072 -0.03257626 -0.5485132 0.7312732 0.1706531 -0.6603916 0.8663772 0.245819 -0.4346994 0.7718067 0.4314528 -0.467079 0.8716211 0.4319271 -0.2317664 0.7927012 0.5108279 -0.3326858 0.7555261 0.6518135 -0.06572276 0.8079041 0.5892789 -0.006454348 0.748151 0.6488265 0.1389042 0.8292306 0.4930586 0.2631917 0.7588075 0.5272921 0.3823275 0.809211 0.3276374 0.4876795 0.7382858 0.3130148 0.5974578 0.8225933 0.03817963 0.5673469 0.7834866 -0.006964802 0.6213699 0.7557244 -0.2661373 0.5983741 0.7977605 -0.2113232 0.5647308 0.776607 -0.4721519 0.4170782 0.8203901 -0.4504345 0.3522342 0.7359203 -0.6382774 0.2258834 0.8655301 -0.5008257 0.005597829 0.8051343 -0.5894818 -0.06534636 0.8571562 -0.4374525 -0.2718802 0.8227645 -0.4671996 -0.3237024 0.7811782 -0.2595862 -0.5677815 0.874962 -0.1525073 -0.4595469 0.7784419 0.03930622 -0.6264849 0.8365187 0.08114689 -0.5418964 0.7327665 0.3731046 -0.569075 0.8123728 0.3694909 -0.4511397 0.736453 0.6046492 -0.3033751 0.8605883 0.4867586 -0.1498466 0.7322151 0.6778646 0.06603598 0.8710013 0.4768248 0.1183002 0.6998111 0.5464468 0.4600657 0.8090083 0.3704907 0.4563356 0.7157878 0.24726 0.6530776 0.8404935 0.1034758 0.5318493 0.7372797 -0.1489161 0.658971 0.8239945 -0.1575733 0.5442462 0.7534485 -0.4928747 0.4351896 0.8767292 -0.4120011 0.2481958 0.7457141 -0.6443879 0.1693364 0.8712775 -0.4876157 -0.0557357 0.7607883 -0.6196851 -0.1928517 0.7756818 -0.4726952 -0.4181827 0.7951399 -0.4467795 -0.4100495 0.8015758 -0.1452262 -0.5799876 0.8325108 -0.1536028 -0.5322894 0.7863967 0.1004232 -0.6095043 0.8999508 0.1482225 -0.4100231 0.7991356 0.3589171 -0.4822457 0.8708718 0.4120997 -0.2678735 0.8445506 0.462387 -0.2700605 0.7806628 0.6206851 -0.07290905 0.8554311 0.5172454 0.02635812 0.7510501 0.6349674 0.1809427 0.8077433 0.4697453 0.3562166 0.7456445 0.480422 0.4617457 0.8065884 0.2924447 0.5137036 0.739537 0.258311 0.6215791 0.8201595 0.025909 0.5715482 0.765777 -0.04347753 0.6416349 0.8130849 -0.245442 0.5278744 0.8090084 -0.2444125 0.5345727 0.7552719 -0.4329588 0.4920479 0.839796 -0.4652473 0.2797991 0.8198766 -0.5008827 0.2773428 0.7960337 -0.5987052 0.08878314 0.8918207 -0.4523431 -0.006455898 0.7915004 -0.5821852 -0.1859778 0.8667281 -0.4075824 -0.2875051 0.7830247 -0.4500935 -0.429288 0.8385539 -0.1878693 -0.5114027 0.8333442 -0.1935691 -0.5177534 0.7436124 0.01582306 -0.6684238 0.8277437 0.2024312 -0.5233182 0.7600309 0.293182 -0.5799976 0.8514331 0.3926843 -0.3476502 0.8794049 0.36901 -0.3007969 0.7670636 0.6187437 -0.1696168 0.8999296 0.4359374 -0.009242355 0.7683095 0.615027 0.1773203 0.8617162 0.3899037 0.3246849 0.8353694 0.4331118 0.3384854 0.8051153 0.3047384 0.5088457 0.8916504 0.1509738 0.4268098 0.7678442 0.04022175 0.6393728 0.8471595 -0.1629136 0.5057471 0.8331863 -0.1604996 0.5291886 0.7388711 -0.4146164 0.53119 0.8417873 -0.4542195 0.291683 0.7736703 -0.5681571 0.2804137 0.8180373 -0.5687888 0.08540773 0.8753389 -0.4825989 0.02966696 0.7982948 -0.5821151 -0.1544917 0.8068763 -0.5688074 -0.1594014 0.7534754 -0.4670621 -0.4627395 0.8663131 -0.2982459 -0.4006881 0.7747718 -0.1747182 -0.6076202 0.889808 -0.03252923 -0.4551742 0.8069109 0.09068316 -0.5836708 0.7890449 0.2517881 -0.5603666 0.8863868 0.2574804 -0.384737 0.7847144 0.4638119 -0.41122 0.8354675 0.5195335 -0.1791062 0.8659666 0.4777649 -0.1477931 0.7953762 0.5940155 0.1205096 0.859583 0.489802 0.1456403 0.7776476 0.4950792 0.387506 0.8549764 0.3687264 0.3647686 0.731131 0.2814582 0.6214731 0.8444949 0.062182 0.5319416 0.7890996 -0.02050912 0.6139228 0.8729038 -0.1716822 0.4566883 0.8330364 -0.2300862 0.5031013 0.7569005 -0.5313285 0.380515 0.9040306 -0.3909014 0.1729885 0.7952926 -0.5994241 0.09055596 0.7961983 -0.5901457 -0.1334032 0.7800382 -0.612168 -0.1295796 0.7744644 -0.4962196 -0.3923914 0.8129841 -0.4351521 -0.3869106 0.7349386 -0.334753 -0.5897505 0.8603451 -0.1190703 -0.4956095 0.7928187 -0.03632318 -0.6083742 0.8444323 0.05045843 -0.5332806 0.7802791 0.1753439 -0.6003493 0.8143752 0.3445903 -0.466959 0.7940558 0.3783816 -0.4757133 0.7522034 0.5726002 -0.3260663 0.7981617 0.5383843 -0.270334 0.7954896 0.6056072 -0.02088981 0.7138701 0.6987505 0.04623198 0.8207513 0.5172323 0.2425656 0.7310523 0.5652824 0.3821237 0.7646705 0.3472867 0.5428361 0.7922555 0.3580808 0.4940744 0.8637853 0.1241647 0.4883217 0.5676997 0.3369481 0.7511212 0.8294858 -0.0384165 0.5572053 0.7834812 -0.009225308 0.6213471 0.7824491 -0.2773261 0.5575515 0.8638412 -0.2823338 0.4172124 0.7878717 -0.5070229 0.3495514 0.8304884 -0.4706763 0.2979146 0.6756578 -0.7329182 -0.07948338 0.8507488 -0.5248399 0.02774006 0.7797891 -0.5706636 -0.2574337 0.8545632 -0.4497429 -0.2597178 0.7042529 -0.3891384 -0.5938007 0.7959078 -0.2689042 -0.5424217 0.7565523 -0.1350142 -0.6398436 0.8495952 0.04244935 -0.5257245 0.7510429 0.1618513 -0.6401085 0.8646107 0.3058595 -0.3986206 0.8804838 0.2959781 -0.3703314 0.7523813 0.6035593 -0.2638916 0.8374179 0.5222675 -0.1611463 0.7317917 0.6801164 0.0438497 0.8188672 0.5523131 0.1562272 0.7371776 0.5985042 0.3136271 0.8767264 0.3563973 0.3230046 0.8536721 0.3602642 0.3761033 0.8020882 0.2134312 0.557765 0.8762637 0.07148295 0.4764999 0.8275141 0.02785229 0.5607538 0.8053634 -0.2601854 0.5326288 0.8277714 -0.2567339 0.4988811 0.7458219 -0.5359827 0.3955659 0.8780733 -0.4437877 0.1789966 0.799272 -0.5907077 0.1105841 0.8402062 -0.5333356 -0.09801459 0.8526022 -0.5158846 -0.08326351 0.7833236 -0.5164816 -0.3459061 0.8783872 -0.3152515 -0.3592387 0.8083677 -0.3219068 -0.4928669 0.839739 -0.08851385 -0.5357273 0.8629127 -0.06962829 -0.5005334 0.8075169 0.2143695 -0.5495108 0.8661181 0.2169008 -0.4503259 0.7147869 0.5397951 -0.444636 0.8368693 0.4985823 -0.2259768 0.6744426 0.7309078 -0.1044085 0.8428301 0.5276054 0.1061604 0.7804987 0.5865784 0.2162122 0.8580715 0.3908476 0.3330938 0.8734738 0.3641762 0.3231397 0.7856082 0.2382743 0.5710036 0.8771345 0.1141535 0.4664809 0.7473368 -0.06705707 0.6610531 0.8902642 -0.184416 0.4164381 0.8396552 -0.2775638 0.4668378 0.7804365 -0.5269001 0.3365939 0.8698349 -0.4453843 0.2121794 0.7652817 -0.6357335 0.1009303 0.7890042 -0.6037076 -0.1140598 0.8091436 -0.5746049 -0.122947 0.7279946 -0.5390252 -0.4236458 0.848146 -0.3557652 -0.3925297 0.7227817 -0.2482889 -0.6449336 0.8916705 -0.06400465 -0.4481374 0.7655213 0.1052781 -0.6347391 0.8683788 0.1918933 -0.4572693 0.7302306 0.4741321 -0.4918963 0.809039 0.4684419 -0.3549903 0.7506716 0.6012938 -0.2737477 0.8408678 0.5319972 -0.0996012 0.7377113 0.6746622 0.02475851 0.8358886 0.4865641 0.2540584 0.8413774 0.4810993 0.2462266 0.7707366 0.3624727 0.5240025 0.8842368 0.2084739 0.4179282 0.7654271 0.05351585 0.6412936 0.842064 -0.03685337 0.5381174 0.7625136 -0.1925131 0.6176664 0.8351413 -0.3688324 0.4080464 0.7866303 -0.4404385 0.4326969 0.8272948 -0.5421053 0.1473265 0.8916985 -0.4457761 0.07846939 0.7716739 -0.6255595 -0.1148689 0.8313979 -0.5218599 -0.1908925 0.72622 -0.569949 -0.3843992 0.8532853 -0.2469239 -0.4592742 0.8733242 -0.2456285 -0.42068 0.7676274 -0.08779102 -0.6348551 0.8670125 0.07235777 -0.4930047 0.7856879 0.1860243 -0.5899913 0.7937015 0.3787513 -0.4760099 0.8691837 0.358204 -0.3408954 0.771419 0.5530221 -0.3147685 0.877175 0.4780946 -0.04460388 0.8697825 0.4919514 -0.03823959 0.7775599 0.6025654 0.1797655 0.8681357 0.4144626 0.2730593 0.85153 0.427458 0.3036057 0.7808851 0.2562583 0.569693 0.8317142 0.1988617 0.5183681 0.7417291 0.02495396 0.6702353 0.8172231 -0.1897867 0.5441759 0.842895 -0.1935368 0.5020673 0.7942079 -0.3556614 0.4926853 0.905237 -0.3776003 0.1948435 0.9092066 -0.3685477 0.1936907 0.6963438 -0.7055208 0.131703 0.7823635 -0.5972571 -0.1766104 0.9094607 -0.3805243 -0.1675784 0.325788 -0.7277095 -0.6035737 -0.1972101 -0.4308664 -0.8806034 0.9360095 -0.2065157 -0.2850219 -0.8953939 -0.07779175 0.438427 0.9239819 -0.3692716 0.0994789 -0.923081 -0.1521094 -0.3532482 -0.8831557 0.1879199 0.4297932 0.8339803 -0.3904555 0.3898994 -0.8496384 -0.4333971 0.3004688 -0.2313061 0.07739895 -0.9697974 0.9785286 0.03885382 0.2024157 0.6838996 0.05291736 0.7276546 -0.005508601 0.08919715 0.9959988 0.5342674 0.2198484 0.8162262 0.4010474 0.2531664 0.8803794 0.8151971 0.292474 0.4999128 0.870891 0.2579651 0.4183337 0.9151507 0.286231 0.2838503 0.1376418 0.4975419 0.8564502 0.3944647 0.5946788 0.700539 0.8082368 0.49925 0.3122543 0.3636037 0.7211639 0.5896736 0.4562994 0.7278569 0.5118743 0.8510896 0.4904987 0.1872368 0.9471749 0.3128271 0.07070338 0.3634267 0.872002 0.3279233 0.6669138 0.7243185 0.1748963 1.30795e-4 0.9754571 0.2201901 0.8963565 0.4420264 -0.03402864 0.5950011 0.8037243 0.001092195 0.3300908 0.9435376 0.02787423 0.9463235 0.3096073 -0.09281831 0.6606571 0.7484388 -0.05806601 0.5985397 0.7820059 -0.1738311 0.8912016 0.4134959 -0.1864969 0.7094255 0.6460247 -0.2817225 0.01138544 0.9662731 -0.2572678 0.005974471 0.96595 -0.2586603 0.5261996 0.715572 -0.4594245 0.9180611 0.274619 -0.2859166 0.3025861 0.8045866 -0.510962 -0.01649826 0.7613924 -0.6480814 0.760394 0.3901753 -0.519196 0.6474868 0.5074459 -0.5685592 0.2670503 0.6205111 -0.7373264 0.7394229 0.2895276 -0.6078056 0.1623498 0.504673 -0.8479079 0.9501456 0.0346527 -0.3098752 0.443935 0.2633654 -0.8564815 0.4527184 0.2737225 -0.8486002 0.9380578 0.02346223 -0.3456839 0.6693292 -0.003168761 -0.7429592 0.580145 -0.1143777 -0.8064426 0.7537161 -0.2324581 -0.6147158 0.3274937 -0.1446102 -0.9337215 0.7502164 -0.2048949 -0.6286443 0.8911479 -0.250045 -0.3785935 0.08465182 -0.4344697 -0.8966996 0.3025856 -0.4872552 -0.8191609 0.3180555 -0.5150753 -0.7959511 0.768797 -0.4557794 -0.4485717 0.6504706 -0.538291 -0.5358459 0.3585065 -0.7422498 -0.5661611 0.1162106 -0.715438 -0.6889438 0.8493585 -0.4798968 -0.2197481 0.9402873 -0.3201775 -0.1155253 0.3377918 -0.8199292 -0.4621828 0.6809906 -0.6889429 -0.2482124 -0.05352181 -0.9260035 -0.3737016 0.5142424 -0.8515417 -0.1021351 0.3400132 -0.9342164 -0.1078467 0.8683783 -0.4883405 0.08627212 0.8503571 -0.5172758 0.09653258 0.7213069 -0.6858661 0.09645843 0.01244664 -0.999573 0.02644097 0.3546121 -0.8914461 0.2820894 0.3938165 -0.8730955 0.2874247 0.8003209 -0.4854285 0.3519173 0.6946619 -0.5718474 0.4363891 0.4364871 -0.7706757 0.4642607 0.9697132 -0.1537109 0.1898136 -0.2238224 -0.7044695 0.6735179 0.4742531 -0.5084201 0.7187442 0.3736298 -0.5309763 0.7605689 0.79966 -0.201183 0.5657469 0.7667288 -0.2174661 0.6040161 0.9025608 -0.005780458 0.4305236 0.4625995 -0.1392206 0.8755681 0.1549438 -0.3011923 0.9408909 0.4587406 -0.1396207 0.8775324 0.999975 -0.004618227 0.005356967 0.9999665 0.001726031 0.008017838 0.9999951 -0.003120243 -4.26469e-4 0.9999838 -0.005336999 -0.001982867 0.9994127 0.009699046 -0.03286808 0.9999305 -0.003719449 -0.01118987 0.9997086 0.02386277 0.003660619 0.9999868 -0.001616656 0.004877269 -0.07156139 0.5001374 -0.8629841 -0.07184672 0.5003379 -0.8628442 -0.0713393 0.9974499 -0.002124071 -0.07097834 0.499646 0.8633168 -0.07193106 0.5003048 0.8628563 -0.07160949 -0.4975216 0.8644908 -0.07199609 -0.4972343 0.864624 -0.07148593 -0.9974359 0.003390967 -0.06950241 -0.9975802 0.001768589 -0.03767699 -0.5009307 -0.8646669 -0.0361247 -0.4998112 -0.8653807 -0.99993 0.009288132 0.007334232 -0.999934 0.01117742 0.002676546 -0.9999326 0.004053652 0.01088219 -0.9999296 -0.00349462 0.01133924 -0.9999477 0.005136489 0.008846223 -0.9999283 0.01162296 -0.002921342 -0.999947 0.01028662 4.47256e-4 -0.9999256 0.009170353 -0.00805366 -0.9999474 -0.004882812 0.009028077 -0.9999267 -0.009344875 0.007713735 -0.9999463 0.00472778 -0.009231448 -0.9999371 0.003899872 -0.01052725 -0.9999308 -0.01147168 0.002609074 -0.9999467 -0.01032865 1.51422e-4 -0.9999307 -8.84365e-4 -0.01173973 -0.9999265 -0.01155847 -0.003665864 -0.9999433 -0.0049299 -0.009450733 -0.9999442 -0.005002319 -0.00930351 -0.9999292 -0.008901476 -0.007903933 -0.9999939 0.002485752 0.002449214 -0.9999706 -0.006885826 -0.003382146 -0.9999998 -6.18671e-4 7.65555e-5 -0.9999995 -1.05477e-4 9.6267e-4 0.03372049 -0.009190857 -0.9993891 -0.03159791 0.2942755 -0.9551982 0.003856301 0.3734324 -0.9276494 -0.004118502 0.7711381 -0.6366546 0.01547271 0.796831 -0.6040042 -0.02235239 0.9748632 -0.2216807 0.02598309 0.9943847 -0.1025869 -0.01740133 0.9530506 0.3023109 0.02313083 0.9155721 0.4014883 -0.02532064 0.7476596 0.6635994 0.0201537 0.5752274 0.8177453 -0.01197242 0.4733029 0.8808184 0.0175817 0.2113038 0.9772623 -0.02064186 0.07510501 0.996962 0.01723086 -0.1982591 0.9799982 -0.02197945 -0.3472977 0.9374973 0.02769458 -0.5637315 0.8254938 -0.03184723 -0.7511687 0.6593416 0.02709394 -0.886886 0.4611932 -0.02599239 -0.9695062 0.2436848 0.03572243 -0.9993408 -0.006488978 -0.03352844 -0.9719331 -0.232856 0.02674973 -0.7846729 -0.6193327 -0.01043814 -0.8222089 -0.5690901 0.01686996 -0.4707661 -0.8820968 -0.03749972 -0.3488283 -0.9364361 0.9992752 -0.03447347 -0.01614952 0.999832 -0.01034098 0.01514291 0.999704 0.0158025 0.01850157 0.9999928 -0.00339055 0.001759469 0.9999566 -0.005497097 -0.007525265 0.9999772 -0.001340687 0.006638705 1 -1.45195e-4 -9.45377e-7 0.9999791 0.001368105 0.006333768 0.9999503 0.009842634 -0.001645803 0.9999992 -6.17778e-4 0.001162886 1 -1.30934e-4 -1.86473e-4 0.9999992 -0.00101912 -7.05789e-4 0.9999991 -6.58184e-4 -0.001233816 1 -3.3038e-4 1.27465e-4 1 -4.71771e-5 -2.30305e-5 0.9999881 -0.004737377 -0.001147627 0.9997465 -0.001785755 0.02244299 0.9999867 -5.20371e-5 -0.005156159 0.9998868 0.01496702 -0.001544296 0.999985 0.002048254 -0.00508368 0.9997237 -0.009688436 -0.0214188 0.9998809 0.01230776 -0.00932604 0.9998273 0.01649212 -0.008568406 -0.01741021 -0.2632631 -0.964567 0.1278021 -0.1904353 -0.9733453 0.02169376 -0.7656361 -0.6429081 0.01992297 -0.7661216 -0.6423869 -0.04882562 -0.9887053 -0.1416963 0.09407347 -0.9942894 -0.05038744 -0.08915472 -0.9630446 0.2541586 0.1192047 -0.8943901 0.431111 -0.1350678 -0.6757145 0.7246839 0.08760881 -0.5789955 0.8106102 -0.0555914 -0.111085 0.9922549 -0.01159846 -0.08893442 0.99597 0.03355354 0.3836507 0.9228686 -0.1044208 0.4496468 0.8870818 0.1301014 0.8000355 0.5856764 -0.1445289 0.8934682 0.4252363 0.1401262 0.9835678 0.1138377 -0.1622583 0.9794024 -0.1201804 0.1433462 0.8682355 -0.4749936 -0.1487094 0.7467973 -0.6482125 0.1814991 0.4810075 -0.8577237 -0.1751683 0.243775 -0.9538816 0.1347074 0.04864066 -0.9896909 0.001293778 0.4489673 -0.8935472 0.003454089 0.4484643 -0.8937941 -0.1115953 0.7288561 -0.6755111 0.1423991 0.7983201 -0.585156 -0.1128731 0.9157673 -0.385526 0.1129024 0.9563865 -0.2694029 -0.1570613 0.9872618 0.02541762 0.05447781 0.9938535 0.09637182 0.1052905 0.8781976 0.4665652 -0.1673274 0.8327415 0.5277719 0.06596434 0.5272268 0.8471603 0.08168333 0.5227432 0.8485679 -0.09078335 0.2129513 0.9728363 0.1092432 0.1240563 0.9862434 -0.1146883 -0.1893505 0.9751887 0.02371853 -0.2357515 0.971524 0.07606315 -0.5934816 0.8012453 -0.1003493 -0.6330683 0.767564 0.0413264 -0.9003717 0.4331546 -0.01185297 -0.894666 0.4465785 0.04358434 -0.9980775 0.0440675 -0.01815629 -0.9995284 0.02476805 -0.04134631 -0.9387324 -0.3421579 0.1075955 -0.9150938 -0.3886212 -0.1057456 -0.7398898 -0.6643652 0.07613521 -0.6863963 -0.7232314 -0.05303907 -0.455174 -0.8888215 0.0838499 -0.4044018 -0.9107296 -0.1765825 -0.04827219 -0.9831015 -1 -1.00325e-5 0 -1 -5.57344e-7 0 -1 4.29952e-6 0 -1 -1.45985e-6 0 -1 4.83608e-6 0 -1 -8.0016e-6 0 -1 4.0348e-6 0 -1 4.611e-6 0 -1 -1.29357e-6 0 -1 1.79752e-6 0 -1 1.26016e-6 0 -1 -3.77948e-6 0 1 4.03093e-6 0 1 1.71815e-6 0 1 -2.32524e-6 0 1 6.09597e-6 0 1 -2.16446e-6 0 1 -9.3109e-6 0 1 2.16675e-6 0 1 2.64388e-6 0 1 3.76682e-6 0 1 -4.00514e-6 0 1 2.16176e-6 0 1 6.03365e-6 0 1 -8.01565e-6 0 -0.01742768 -0.2632676 -0.9645655 0.1278021 -0.1904354 -0.9733453 -0.1102218 -0.7826746 -0.6125942 0.01841676 -0.7494769 -0.6617743 0.1705262 -0.9767594 -0.1298538 -0.1698243 -0.983897 0.05573701 0.09814947 -0.8783115 0.4679057 -0.04525136 -0.8303176 0.5554503 0.04797971 -0.5667508 0.822491 -0.03334683 -0.5235032 0.851371 0.01115548 -0.07738333 0.996939 -0.01159369 -0.088934 0.9959701 0.0335536 0.3836513 0.9228683 -0.1044211 0.4496439 0.8870832 0.1301063 0.8000347 0.5856764 -0.1445204 0.8934718 0.425232 0.1401277 0.9835676 0.1138383 -0.1936357 0.9703713 -0.1445164 0.1886367 0.8615494 -0.471327 -0.1504729 0.6793247 -0.7182451 0.1537504 0.4833155 -0.8618394 -0.1586705 0.2200477 -0.9624983 0.192101 0.2098517 -0.958676 -0.1290437 0.4447172 -0.8863263 0.07331991 0.526959 -0.8467223 -0.1385978 0.7485511 -0.6484304 0.159579 0.8154301 -0.5564244 -0.1055356 0.9694687 -0.2213429 0.1250268 0.9807418 -0.1500463 -0.1906905 0.9570035 0.2185898 0.2827836 0.8687818 0.4065119 -0.1466178 0.8123571 0.5644283 0.06599199 0.5272277 0.8471576 0.08168333 0.5227429 0.8485681 -0.09078294 0.2129539 0.9728357 0.1092565 0.1240575 0.9862418 -0.1146881 -0.1893501 0.9751889 0.02370452 -0.2357523 0.9715241 0.07607501 -0.5934824 0.8012436 -0.1003493 -0.6330685 0.7675639 0.04133242 -0.9003712 0.4331551 -0.01185297 -0.8946646 0.4465814 0.04358685 -0.9980774 0.04406636 -0.04475653 -0.9988632 0.01640957 0.006011605 -0.9337278 -0.3579336 0.1006628 -0.9157595 -0.3889107 -0.1271572 -0.774982 -0.619059 0.2226543 -0.6345858 -0.7400851 -0.2102981 -0.460254 -0.8625202 0.170211 -0.1904755 -0.9668233 -0.1837131 -0.04820621 -0.9817972 -1 -1.00325e-5 0 -1 -2.6476e-6 0 -1 4.961e-7 0 -1 1.02609e-5 0 -1 3.03316e-6 0 -1 -1.45985e-6 0 -1 -5.36628e-6 0 -1 1.82399e-6 0 -1 -4.2602e-6 0 1 8.15797e-6 0 1 -2.97482e-6 0 1 -8.69375e-7 0 1 1.11478e-5 0 1 1.26495e-6 0 1 -5.19472e-6 0 1 2.64387e-6 0 1 -2.00697e-6 0 1 5.50539e-6 0 1 -2.53179e-6 0 1 -7.41609e-6 0 -0.9982593 -0.02310639 0.05426394 -0.9904244 -0.08881944 0.1056914 -0.9995763 -0.02659392 -0.0118395 -0.9989939 -0.04326385 0.01181745 -0.9848139 -0.04340642 0.1680998 -0.9967092 -0.08036601 0.01058441 -0.994558 0.01615923 0.1029236 -0.9919492 0.03971576 0.1202481 -0.994871 0.04913979 0.08841407 -0.9987298 -0.04998755 -0.006327331 -0.9951112 0.04635459 0.08720767 -0.9997043 -0.0242241 -0.002193212 -0.9971225 0.04457867 0.06131547 -0.9932803 0.1017971 0.05505961 -0.9994951 0.02515554 -0.01941299 -0.9096809 0.4152636 -0.006078839 -0.6894839 0.7064292 0.159906 -0.8972478 0.3625562 0.2519912 -0.7668927 0.47824 0.4279745 -0.8391473 0.1952397 0.5076549 -0.8746718 0.1427529 0.4632181 -0.7771874 -0.003599762 0.629259 -0.84429 -0.1145882 0.5234921 -0.7568008 -0.2583789 0.6004108 -0.8071008 -0.3232375 0.4940706 -0.7325011 -0.4790285 0.4837085 -0.8400161 -0.5074497 0.1920102 -0.8253744 -0.5310213 0.1917639 -0.7854878 -0.6183501 0.02553528 -0.8879508 -0.4382838 -0.1394667 -0.8318625 -0.5155561 -0.2054429 -0.7586141 -0.4321295 -0.4876157 -0.8888303 -0.208941 -0.4078292 -0.8124067 -0.1618829 -0.5601692 -0.8713905 0.02497577 -0.4899541 -0.8039447 0.08759891 -0.5882171 -0.7675898 0.3361214 -0.5457367 -0.8617025 0.3465911 -0.3705988 -0.7938467 0.4881269 -0.3626838 -0.8726013 0.4650997 -0.1491619 -0.7757853 0.6214194 -0.1095222 -0.7561833 0.6460169 0.1041592 -0.8589349 0.4713202 0.2002199 -0.7988247 0.4957832 0.3407025 -0.8780384 0.3213306 0.3546763 -0.7699134 0.3306687 0.5457946 -0.8051695 0.2534292 0.5361676 -0.6983442 0.02831733 0.7152017 -0.8559636 -0.134638 0.4991983 -0.7754912 -0.2661836 0.5725032 -0.852272 -0.3513997 0.387493 -0.7429251 -0.3901097 0.5439456 -0.8358403 -0.4988709 0.2291269 -0.8202165 -0.5251074 0.226952 -0.7326294 -0.6797811 0.03393906 -0.8215151 -0.5653825 -0.07386261 -0.7097646 -0.6626297 -0.2390733 -0.7992743 -0.4446347 -0.4043026 -0.8139912 -0.4376851 -0.3819034 -0.797667 -0.2608543 -0.5437671 -0.8988597 -0.1126831 -0.4235017 -0.7773754 0.06401735 -0.625771 -0.8740054 0.1756086 -0.4530742 -0.7903013 0.297667 -0.5355542 -0.7329717 0.5813247 -0.3532906 -0.8763992 0.3833954 -0.2914317 -0.7263283 0.6697319 -0.1546169 -0.9008864 0.4282744 0.07060414 -0.7636396 0.6111211 0.2082918 -0.807669 0.4164987 0.4173723 -0.8485885 0.3480591 0.3984375 -0.7330875 0.2218722 0.6429273 -0.8493793 0.01936829 0.5274276 -0.7891165 -0.04643791 0.6124857 -0.8170339 -0.2255438 0.5306466 -0.8367338 -0.2294862 0.4972049 -0.752835 -0.516697 0.4077547 -0.8770788 -0.4397842 0.1931909 -0.6823896 -0.7284516 0.06085109 -0.9034471 -0.4118682 -0.1189448 -0.7847304 -0.5387996 -0.3064201 -0.8748841 -0.2699218 -0.4021444 -0.8490107 -0.2809806 -0.4474717 -0.8011378 -0.1021338 -0.5897008 -0.8854568 0.05224907 -0.4617753 -0.8095458 0.1251592 -0.5735599 -0.8152666 0.3822725 -0.4349806 -0.8603936 0.3641588 -0.3565267 -0.7664692 0.5822929 -0.2710354 -0.8398106 0.5403404 -0.05244529 -0.7897625 0.6133031 -0.01160544 -0.8743155 0.4613241 0.1508395 -0.764236 0.5677947 0.3058637 -0.8560308 0.3153676 0.4095786 -0.8033277 0.3938495 0.4467072 -0.7491784 0.0661832 0.6590536 -0.8018833 0.08609527 0.5912451 -0.7452588 -0.1570203 0.6480231 -0.8739783 -0.2430184 0.4208374 -0.7751019 -0.4164975 0.4751284 -0.7377084 -0.5753483 0.3532149 -0.8701211 -0.453719 0.1924279 -0.7921167 -0.6102252 -0.01328831 -0.856976 -0.5090269 -0.08052194 -0.7792883 -0.5664291 -0.268082 -0.858161 -0.4195091 -0.2959253 -0.7186902 -0.4324857 -0.5444636 -0.8152679 -0.1689571 -0.553888 -0.7911254 -0.1503747 -0.5928812 -0.8654881 0.05702036 -0.4976739 -0.8088424 0.1077397 -0.5780712 -0.8351069 0.3452451 -0.4282551 -0.8298373 0.3526868 -0.4324145 -0.8413207 0.503422 -0.1968395 -0.8608969 0.4699522 -0.1949397 -0.7546849 0.6548732 0.03989738 -0.8742434 0.4684848 0.1273596 -0.8304511 0.5095599 0.2251659 -0.8604441 0.3284621 0.3895494 -0.8190762 0.4066147 0.4046956 -0.7439886 0.2635484 0.6140221 -0.8457858 0.05570489 0.5306068 -0.8001152 0.02324432 0.599396 -0.7611374 -0.2374773 0.6035515 -0.8287748 -0.2744098 0.48768 -0.7286932 -0.4714673 0.4967141 -0.8267711 -0.5042493 0.2493636 -0.7957206 -0.561201 0.2277761 -0.8560344 -0.5115945 0.07400298 -0.7598184 -0.6501295 0.002780914 -0.7648031 -0.5577815 -0.3224223 -0.8129928 -0.5232576 -0.25543 -0.8696234 -0.3369778 -0.3608341 -0.8372671 -0.3555436 -0.4154187 -0.780857 -0.1940298 -0.5938139 -0.8924753 -0.032175 -0.4499474 -0.7719772 0.1153475 -0.625097 -0.8328712 0.2084929 -0.5126952 -0.7030786 0.4188157 -0.5746946 -0.8636475 0.4409303 -0.2443226 -0.7431089 0.6273075 -0.2329688 -0.8375295 0.5399055 -0.08394342 -0.6982613 0.696339 0.1659616 -0.8020356 0.5525251 0.2268369 -0.7802531 0.4748098 0.4071375 -0.8197815 0.405596 0.4042899 -0.7513505 0.2334539 0.6172292 -0.7696502 0.2131522 0.6018347 -0.818634 -0.03811103 0.5730499 -0.7102593 -0.1572789 0.6861451 -0.8166147 -0.2706454 0.5097956 -0.7309049 -0.4562724 0.5075367 -0.8209105 -0.4472035 0.3551267 -0.7201593 -0.6534792 0.2330997 -0.850293 -0.5255779 0.02774304 -0.7769638 -0.6259822 -0.06688606 -0.8463725 -0.4826405 -0.225193 -0.8875218 -0.3935154 -0.2396892 -0.7622704 -0.450823 -0.4644379 -0.8546985 -0.2176429 -0.4712982 -0.7590076 -0.1932137 -0.6217523 -0.8043888 0.148073 -0.5753548 -0.8275374 0.1295757 -0.5462529 -0.792448 0.3528225 -0.4975366 -0.8831959 0.3706378 -0.2873896 -0.8353726 0.4581851 -0.3036762 -0.8023734 0.5857498 -0.1144294 -0.8392392 0.5391203 -0.07090139 -0.7613384 0.6350761 0.1305466 -0.8361555 0.4559068 0.3049478 -0.8391749 0.4530488 0.3008861 -0.77695 0.3579802 0.5178793 -0.8832236 0.1678138 0.4378979 -0.7989576 0.09350693 0.5940735 -0.8536568 -0.07876831 0.5148455 -0.8110311 -0.1273611 0.5709709 -0.8576873 -0.3228982 0.4001366 -0.8646108 -0.3122892 0.3936035 -0.7592816 -0.5723397 0.3097075 -0.8653579 -0.4809283 0.1409391 -0.7293724 -0.6838701 0.0183736 -0.8326205 -0.5265543 -0.1717086 -0.7392585 -0.5929818 -0.3191699 -0.8092786 -0.4270784 -0.4033263 -0.7403346 -0.4186544 -0.5259594 -0.8089252 -0.252886 -0.5307437 -0.725505 -0.1674 -0.6675477 -0.8141334 0.01466548 -0.5804927 -0.7641185 0.0808131 -0.639994 -0.8440681 0.308874 -0.4383444 -0.815786 0.3104521 -0.487968 -0.8204009 0.514122 -0.2502419 -0.8698065 0.4332281 -0.2361146 -0.7983788 0.5972651 -0.07658898 -0.8638619 0.4960239 0.08776605 -0.8196238 0.5583551 0.1282827 -0.7850493 0.4746379 0.3980161 -0.8990706 0.2508952 0.358781 -0.8116594 0.2621338 0.5220106 -0.8041086 -0.01034706 0.5943925 -0.8777455 -0.08190673 0.4720743 -0.7904087 -0.2199226 0.5717414 -0.8559275 -0.3644775 0.3668029 -0.8648713 -0.3602573 0.3495889 -0.7888148 -0.5747426 0.2178127 -0.9010825 -0.4317269 0.04077154 -0.7922733 -0.6069737 -0.06233841 -0.8377699 -0.4770155 -0.2657029 -0.8058814 -0.5057666 -0.3078235 -0.7381669 -0.3309959 -0.5878363 -0.7845268 -0.3259907 -0.5274919 -0.7506568 -0.08485794 -0.6552202 -0.8412609 0.01504826 -0.5404201 -0.8104695 0.215474 -0.5447111 -0.8420547 0.2262088 -0.4896667 -0.8150253 0.4169681 -0.4023326 -0.8007123 0.4218845 -0.4252922 -0.7693756 0.6057623 -0.202764 -0.8289362 0.5471758 -0.1160326 -0.7836065 0.6211836 -0.009591698 -0.8499106 0.4762114 0.2255543 -0.8722705 0.4468442 0.1986821 -0.7974383 0.4770535 0.3694755 -0.8325503 0.3936944 0.3896984 -0.7507412 0.3614304 0.5529518 -0.8083613 0.107127 0.5788573 -0.7989687 0.1033347 0.5924282 -0.7512242 -0.1487532 0.6430667 -0.8656856 -0.2315473 0.4438179 -0.7918611 -0.3650492 0.4895867 -0.8738018 -0.4180695 0.2483713 -0.8350761 -0.4887916 0.2524498 -0.8204058 -0.5680059 0.06560248 -0.8274108 -0.5586515 0.05744612 -0.7379201 -0.6393176 -0.2162109 -0.8608794 -0.4210062 -0.285728 -0.7932461 -0.4457165 -0.4148464 -0.7602908 -0.3372629 -0.5551682 -0.8401111 -0.236352 -0.4882123 -0.8034304 -0.008196651 -0.5953423 -0.6368238 0.08815681 -0.765953 -0.8669738 0.3052418 -0.3939337 -0.8001574 0.4061851 -0.4413184 -0.8413214 0.5050153 -0.1927126 -0.8791703 0.458774 -0.1287875 -0.7547214 0.6560104 -0.006785929 -0.8763898 0.4242538 0.2279248 -0.6592009 0.7160789 0.2295325 -0.856275 0.2905763 0.4270347 -0.7816454 0.3086519 0.5420004 -0.8227171 0.08992248 0.5612936 -0.865772 0.03527796 0.4991939 -0.7877866 -0.154278 0.5963143 -0.8168743 -0.176061 0.5492896 -0.7488824 -0.4148204 0.5168167 -0.8717454 -0.4047087 0.276172 -0.7671703 -0.5981567 0.2316427 -0.8929589 -0.4490798 0.03085315 -0.6923742 -0.7058873 -0.1494696 -0.8598626 -0.4293003 -0.2762926 -0.8916236 -0.3648065 -0.2681856 -0.8290839 -0.2390413 -0.5054495 -0.6949094 -0.39065 -0.6037331 -0.8313739 -0.03292065 -0.5547375 -0.8203971 -0.04621887 -0.5699233 -0.7920742 0.1808234 -0.5830278 -0.8424056 0.27345 -0.4643037 -0.7741345 0.3642055 -0.5177549 -0.8545048 0.4612316 -0.2389294 -0.864405 0.443453 -0.2369672 -0.7816988 0.6229588 -0.02948546 -0.8552532 0.5145715 0.06130504 -0.734593 0.6367431 0.2343744 -0.8367601 0.3649301 0.4082384 -0.7767029 0.3956766 0.4900742 -0.8656378 0.06426429 0.4965295 -0.7951982 0.0286805 0.6056709 -0.8385561 -0.1699897 0.517617 -0.8671607 -0.1830244 0.4631787 -0.7702843 -0.4385907 0.4629259 -0.8856815 -0.3966906 0.2412566 -0.7948394 -0.5733554 0.1987313 -0.8615993 -0.5074777 0.01062798 -0.8233871 -0.5671145 -0.02036929 -0.7879558 -0.5648711 -0.2450438 -0.8761337 -0.3895994 -0.2839052 -0.8240993 -0.4190996 -0.3810722 -0.8174389 -0.2700701 -0.5087788 -0.9047886 -0.1076129 -0.4120404 -0.7928054 -0.02621263 -0.6089111 -0.7932078 0.1858059 -0.5799117 -0.8570625 0.2078294 -0.4714349 -0.7298257 0.4650722 -0.5010612 -0.8498215 0.4848874 -0.2066101 -0.7944079 0.5728031 -0.202022 -0.802343 0.5966372 0.01642936 -0.8607549 0.5029456 0.07840251 -0.75911 0.6023189 0.2469092 -0.8191139 0.4463977 0.3602523 -0.764356 0.4586877 0.4531729 -0.8017243 0.2228999 0.5545753 -0.7257918 0.2096256 0.6551973 -0.8201147 -0.08249694 0.5662209 -0.7792731 -0.05836278 0.6239609 -0.8419342 -0.2732705 0.4652635 -0.7550387 -0.4029641 0.5172396 -0.8486908 -0.4295756 0.3085272 -0.7684671 -0.5733088 0.2842102 -0.7867335 -0.6137279 0.06624704 -0.7562826 -0.6523377 0.04992312 -0.797402 -0.5570654 -0.2320089 -0.770816 -0.5811665 -0.260937 -0.771165 -0.4187326 -0.4795496 -0.8078694 -0.358268 -0.467965 -0.7165714 -0.2228876 -0.6609436 -0.8345426 -0.03055101 -0.5500957 -0.7600245 0.08945095 -0.6437092 -0.9041396 0.2150248 -0.3691828 -0.7988535 0.3700121 -0.4742618 -0.8202779 0.5291407 -0.2171506 -0.8615477 0.4829123 -0.1566252 -0.7719533 0.6346031 0.03697621 -0.7650721 0.643164 0.03170049 -0.7567512 0.5670846 0.325181 -0.8394812 0.4262709 0.3369933 -0.7596691 0.3416074 0.5533602 -0.7940867 0.287455 0.5355335 -0.8165389 -0.009357213 0.5772146 -0.7301619 0.06982648 0.6796969 -0.8217074 -0.3062183 0.480653 -0.7715283 -0.2871473 0.5677064 -0.7137681 -0.5163754 0.4731718 -0.8187866 -0.5322342 0.2152105 -0.7744429 -0.6020081 0.1944855 -0.8713768 -0.486702 -0.06183648 -0.8517585 -0.5180487 -0.07831424 -0.794308 -0.4999032 -0.3452128 -0.8291708 -0.4338272 -0.352519 -0.6998052 -0.3939325 -0.5958943 -0.8242167 -0.1965494 -0.5310699 -0.7096747 -0.009629428 -0.7044638 -0.8497434 0.1491363 -0.5056627 -0.774055 0.2591216 -0.5776634 -0.8651466 0.390291 -0.3149516 -0.8579474 0.3951542 -0.328298 -0.7996219 0.5732986 -0.1786996 -0.8985025 0.4382618 -0.02489662 -0.7500702 0.6477189 0.1336222 -0.8720781 0.402444 0.2784218 -0.7890362 0.4641792 0.4024421 -0.7555833 0.1996537 0.623885 -0.8361147 0.201806 0.5100849 -0.7959852 -0.02926045 0.6046085 -0.8808665 -0.1037294 0.4618597 -0.7452945 -0.3114297 0.5895318 -0.8932442 -0.364746 0.2628215 -0.7749849 -0.5613011 0.2904128 -0.7783491 -0.625781 -0.05070531 -0.7962241 -0.6035951 -0.04123377 -0.8534862 -0.4359251 -0.2855359 -0.7651245 -0.5075882 -0.3961552 -0.8455841 -0.2051033 -0.4928694 -0.8564743 -0.1886396 -0.4804862 -0.7467446 -0.01634752 -0.6649099 -0.8163178 0.1891775 -0.5457447 -0.7522444 0.282857 -0.59508 -0.8867255 0.3022313 -0.3498201 -0.7688025 0.5427997 -0.3380995 -0.8757064 0.4655622 -0.1280243 -0.7780632 0.6256278 -0.05663716 -0.8806284 0.4563834 0.127311 -0.7649766 0.577806 0.2845191 -0.8648722 0.3415626 0.3678739 -0.803609 0.3658943 0.4693976 -0.7396503 0.1938056 0.6444818 -0.8439598 0.01147067 0.5362838 -0.7808313 -0.07798957 0.6198549 -0.8668602 -0.1738761 0.4672481 -0.7359831 -0.3787632 0.5611304 -0.8204088 -0.4825531 0.3067114 -0.7778285 -0.5503588 0.3034603 -0.8537295 -0.5116775 0.09660279 -0.8023921 -0.5938217 0.05952191 -0.7297443 -0.6644282 -0.1612714 -0.8624101 -0.4286368 -0.2692946 -0.796494 -0.4794518 -0.3684065 -0.800651 -0.2740656 -0.532772 -0.8763558 -0.1599153 -0.4543431 -0.7855696 0.01735562 -0.61853 -0.8873784 0.1003211 -0.4499949 -0.7728914 0.3852609 -0.5041955 -0.8906621 0.3475461 -0.2931429 -0.7766213 0.5737835 -0.2600616 -0.841522 0.5349525 -0.07527649 -0.7802392 0.6248978 -0.02701157 -0.7704058 0.6048437 0.2015917 -0.8667228 0.4297153 0.2532519 -0.7489574 0.46358 0.4734516 -0.8659222 0.2251797 0.4466239 -0.8897162 0.184623 0.4175158 -0.8382552 0.01386439 0.5451018 -0.8674716 -0.04562819 0.4953899 -0.7740105 -0.1651762 0.6112485 -0.8380817 -0.3376206 0.4285225 -0.8438836 -0.3361408 0.4181746 -0.7386489 -0.5809146 0.3419592 -0.8385304 -0.5305168 0.1241724 -0.7242318 -0.6892904 0.01916158 -0.8207615 -0.5578525 -0.1230903 -0.7111613 -0.6343779 -0.3030087 -0.806584 -0.4413233 -0.3932631 -0.7321733 -0.4418099 -0.5183882 -0.8274891 -0.1798098 -0.531912 -0.7692774 -0.1597719 -0.6186156 -0.8308116 0.09490579 -0.5484023 -0.8510669 0.1071877 -0.5139999 -0.6156697 0.5351907 -0.5783787 -0.8170105 0.3344203 -0.4697414 -0.8533537 0.462667 -0.2402639 -0.8528119 0.4636422 -0.2403076 -0.7931038 0.6056484 -0.06462639 -0.8063908 0.5890548 -0.05242508 -0.7626708 0.5808559 0.2844994 -0.7477352 0.5928067 0.2991195 -0.8004977 0.3218902 0.5055593 -0.7914515 0.322649 0.5191361 -0.8576711 0.07677686 0.5084347 -0.8503853 0.08670347 0.5189679 -0.7792954 -0.109382 0.6170367 -0.8847647 -0.2364108 0.4016237 -0.7997283 -0.3535303 0.485233 -0.8414359 -0.5040888 0.1946287 -0.7909393 -0.5799354 0.195167 -0.7887095 -0.5923135 -0.1646276 -0.7699344 -0.6119448 -0.1808995 -0.7752249 -0.4498405 -0.4434748 -0.7657073 -0.4539711 -0.4556343 -0.7646037 -0.202084 -0.6119994 -0.744512 -0.1970515 -0.6378656 -0.8236384 0.1000201 -0.5582256 -0.7259209 0.1907423 -0.6607998 -0.7989858 0.3815432 -0.4648082 -0.8046156 0.3817561 -0.4548145 -0.7461822 0.5654594 -0.3513799 -0.8410252 0.5194959 -0.1509989 -0.7690586 0.6327757 -0.09024327 -0.8707775 0.4871024 0.06691688 -0.7407162 0.6288035 0.2365285 -0.8278702 0.3951777 0.3980773 -0.8083659 0.4029064 0.4291982 -0.8377819 0.1930379 0.5107427 -0.8382191 0.1930922 0.5100041 -0.7450063 0.01751548 0.6668275 -0.8441204 -0.1747773 0.5068667 -0.8109756 -0.2139522 0.5445576 -0.8022056 -0.4170746 0.4272178 -0.8795742 -0.3928971 0.2682928 -0.8132575 -0.5179177 0.2652803 -0.8329802 -0.5532016 -0.01057916 -0.8428617 -0.5377704 -0.01968145 -0.8440374 -0.4742105 -0.2504505 -0.8155021 -0.5230098 -0.2478247 -0.8475649 -0.4064164 -0.3412616 -0.6939093 -0.4108248 -0.5913653 -0.8119953 -0.1201682 -0.5711597 -0.7725272 -0.1632466 -0.6136386 -0.7851833 0.1354572 -0.6042671 -0.8628399 0.1905686 -0.4681784 -0.7919227 0.3661065 -0.4886969 -0.8503077 0.3655329 -0.3786324 -0.6474642 0.7289771 -0.222222 -0.8806475 0.4317923 -0.1949756 -0.7687712 0.6380092 -0.04399085 -0.8487457 0.5061724 0.1530365 -0.8361621 0.5281266 0.1480382 -0.7322564 0.5272375 0.4310699 -0.8314172 0.3435764 0.4366928 -0.7513645 0.2574069 0.6076126 -0.8262748 0.1300648 0.548045 -0.7436106 -0.01866525 0.6683524 -0.8426008 -0.1905674 0.5036945 -0.787173 -0.2574581 0.5604231 -0.7892566 -0.4486041 0.4193192 -0.8881651 -0.393949 0.2365733 -0.8020592 -0.5696958 0.1792979 -0.8695286 -0.4938646 0.004236221 -0.8034175 -0.5926342 -0.05749052 -0.8354578 -0.4690349 -0.2863855 -0.8231474 -0.4893073 -0.2881091 -0.8575803 -0.2526766 -0.4480077 -0.8010435 -0.2610117 -0.5387043 -0.8387185 -0.06950891 -0.5401108 -0.7597438 -0.006806552 -0.6501871 -0.7756301 0.2088778 -0.5956242 -0.762102 0.2004383 -0.6156503 -0.7527235 0.4341681 -0.4948794 -0.8794006 0.3889343 -0.2745629 -0.7888451 0.5879708 -0.1789244 -0.8845029 0.4663284 -0.01387763 -0.7949861 0.6027114 0.06881976 -0.8316189 0.522117 0.1892195 -0.6847731 0.5993182 0.4146125 -0.8132897 0.3188768 0.4867007 -0.7470915 0.3157302 0.584952 -0.7765817 0.0797348 0.6249505 -0.8580904 -0.02757048 0.5127582 -0.7787375 -0.1786467 0.6013761 -0.8670032 -0.2865585 0.4076638 -0.8812103 -0.2831654 0.378531 -0.7752134 -0.544771 0.3197951 -0.8808256 -0.4647914 0.09008485 -0.7535114 -0.6197081 0.2195054 -0.7988814 -0.5848348 -0.1405592 -0.7966276 -0.5883036 -0.1388653 -0.758273 -0.5435532 -0.3599612 -0.8376185 -0.3745614 -0.3976165 -0.7746651 -0.3790379 -0.5061861 -0.848314 -0.1299811 -0.5132918 -0.8304824 -0.1539358 -0.5353528 -0.7304887 0.08535027 -0.6775704 -0.8460618 0.2082726 -0.4907158 -0.787581 0.3476146 -0.5088027 -0.8827775 0.3545457 -0.3082231 -0.7842093 0.5296787 -0.3231972 -0.8380386 0.5427883 -0.05542737 -0.8638669 0.5029697 -0.02748608 -0.7899609 0.5866447 0.1783531 -0.8869764 0.3834401 0.2573843 -0.7747064 0.4639675 0.4296094 -0.8485364 0.1741337 0.4996634 -0.8865199 0.1113808 0.4490844 -0.7466042 -0.04773187 0.663554 -0.8843323 -0.2019174 0.4209344 -0.7263186 -0.4068675 0.5540038 -0.876161 -0.4297876 0.2182306 -0.7869808 -0.5807092 0.2084177 -0.8528745 -0.5206651 -0.03889554 -0.8466315 -0.5311152 -0.03364086 -0.8183808 -0.4968631 -0.2887557 -0.8854469 -0.3647639 -0.2879775 -0.7653572 -0.366469 -0.5290832 -0.8413686 -0.1234133 -0.5261827 -0.8459329 -0.1176708 -0.5201453 -0.7044695 0.1230114 -0.6989929 -0.8454486 0.2512372 -0.4712715 -0.7968428 0.3931437 -0.4587807 -0.8882591 0.3697639 -0.2725265 -0.7837147 0.5598385 -0.2690209 -0.8032059 0.5919316 -0.06691479 -0.8799659 0.4745048 0.0224806 -0.8116561 0.5650912 0.1479408 -0.8389716 0.454024 0.2999815 -0.8661656 0.4004378 0.2990097 -0.776076 0.3359771 0.5336906 -0.8785692 0.1685914 0.4468706 -0.788015 -0.008915841 0.6155915 -0.8754833 -0.08459728 0.4757861 -0.7516708 -0.3295885 0.5712814 -0.8909081 -0.3525115 0.2863888 -0.7925248 -0.5194028 0.3195707 -0.8033577 -0.591422 0.06954622 -0.8579261 -0.5137472 0.005165398 -0.771823 -0.6221739 -0.131107 -0.8184855 -0.4525294 -0.3539757 -0.7897677 -0.4989442 -0.3568217 -0.8583564 -0.2689432 -0.4369141 -0.78593 -0.2692686 -0.5566046 -0.7522468 -0.001112878 -0.6588805 -0.8125074 -0.03269451 -0.5820335 -0.8246971 0.2303808 -0.5165264 -0.8331244 0.2318059 -0.5021651 -0.7073319 0.5212622 -0.4774593 -0.827037 0.5182404 -0.2177995 -0.8058935 0.5673801 -0.1691619 -0.8767175 0.4786851 -0.04719191 -0.7813541 0.6216161 0.05549031 -0.8346624 0.5013691 0.2279643 -0.8459411 0.4808599 0.2305592 -0.7337769 0.4464775 0.5120833 -0.8619145 0.1930461 0.4688674 -0.7924174 0.1387866 0.5939807 -0.850934 0.03678935 0.5239829 -0.7385216 -0.1390377 0.6597381 -0.8315569 -0.2563132 0.4927643 -0.7119357 -0.4537689 0.5359492 -0.8340621 -0.4566446 0.3095421 -0.7372292 -0.6355128 0.2293834 -0.8277223 -0.5597217 0.03984481 -0.7484908 -0.6621327 -0.03663367 -0.8042364 -0.5251467 -0.2782531 -0.8702809 -0.4038856 -0.2819355 -0.7645003 -0.3035553 -0.5686771 -0.8173941 -0.230006 -0.5281708 -0.7371685 -0.1144086 -0.6659529 -0.7837571 0.1030058 -0.6124662 -0.7808582 0.1064321 -0.6155752 -0.8240064 0.2909141 -0.4861918 -0.7838744 0.351889 -0.511581 -0.7999417 0.4751955 -0.3664458 -0.8429833 0.4535817 -0.2892112 -0.8263651 0.5412943 -0.1553104 -0.8908475 0.4510741 -0.05406469 -0.5996505 0.7363654 0.3133454 0.4587131 -0.7541025 0.4700126 -0.4820215 -0.8723821 -0.08127176 0.6592143 -0.7394803 -0.1364021 -0.6675816 -0.4891366 -0.5613201 0.564765 -0.4710738 -0.6775914 -0.6063908 0.0249297 -0.7947759 0.6588347 0.401225 -0.636361 -0.5047699 0.6610879 -0.5551308 0.7196395 0.6578733 -0.2220848 -0.7005157 0.6751996 0.2310483 0.5827864 0.6140946 0.5322104 -0.7702009 0.2649363 0.5801719 0.5721105 0.001641571 0.820175 -0.5063322 -0.5135177 0.6927679 -0.80532 -0.4371679 -0.4004299 0.711229 -0.2799882 -0.6447946 -0.7438391 -0.00146991 -0.6683571 0.8170148 0.1789575 -0.5481433 -0.7078167 0.6012852 -0.3707447 0.5523883 0.8331271 0.02768969 -0.1146402 0.9832395 0.1417666 -0.2110682 0.6406586 0.7382458 0.05174195 0.2063884 0.9771012 -0.1856979 -0.4182318 0.8891561 0.6354364 -0.6112253 0.4718307 -0.6651458 -0.7461629 0.02867072 0.7272452 -0.6810829 -0.08509159 -0.6424216 -0.6187442 -0.4521617 0.6402898 -0.5047188 -0.5790407 -0.661488 -0.2423114 -0.7097315 0.7633075 -0.02008926 -0.6457229 -0.7481747 0.2721037 -0.60514 0.7663042 0.4421579 -0.4661271 -0.4572178 0.8712567 -0.1785049 0.4971389 0.8503736 0.1723882 -0.6260962 0.6812753 0.379299 0.7732344 0.4196255 0.4754187 -0.1181578 -0.361554 0.9248338 -0.3277372 -0.8086639 0.4885194 0.03693479 -0.9991833 0.01638782 0.262082 -0.7777817 -0.5712869 -0.6699458 -0.267251 -0.6926395 0.5505922 0.001217186 -0.8347735 -0.602841 0.2347806 -0.7625359 0.5843335 0.4362677 -0.6842697 -0.4995032 0.7025232 -0.50691 0.4716062 0.7857048 -0.4003195 -0.612313 0.7895568 -0.04090076 0.7007614 0.7069442 0.09572595 -0.7883652 0.4354133 0.4346215 0.898732 0.1280975 0.419371 -0.592701 -0.6809726 0.4300953 0.6320106 -0.7695744 0.09120243 -0.647917 -0.6818755 -0.3394841 0.5132868 -0.6518155 -0.558277 -0.6655606 -0.3531665 -0.6574972 0.733403 -0.1494261 -0.663168 -0.8341588 0.2076982 -0.5109213 0.701513 0.5179656 -0.4894805 -0.6471806 0.7556052 -0.1010851 -0.03818762 -0.9727237 0.2288019 -0.3868576 -0.8797801 -0.2762758 0.6413887 -0.703583 -0.3059272 -0.509718 -0.5803602 -0.635114 0.6671805 -0.3040993 -0.6799954 -0.1613809 0.1254924 -0.978881 -0.3071728 0.6403551 -0.7039817 0.5115197 0.6088867 -0.6063042 -0.4595831 0.8817291 -0.1064763 0.5359572 0.7843671 0.3122793 -0.5610821 0.5111155 0.6511128 0.6067627 0.375065 0.7008319 -0.6141721 -0.003893017 0.7891626 0.1081522 -0.06761109 0.9918327 0.4070745 -0.4975703 0.7659728 -0.6329641 -0.5419966 0.5528076 0.6438757 -0.7345823 0.2140396 -0.0474233 0.4499992 -0.891769 0.3899385 0.7887352 -0.4752314 -0.5416082 0.7858577 -0.2984766 0.5247133 0.849494 0.05509978 -0.4132832 0.8843535 0.2170621 0.2792177 0.6530803 0.7039344 0.4871731 0.5860199 0.6474899 -0.6408802 0.08833831 0.7625411 0.6883318 -0.02795702 0.724857 -0.5340225 -0.4146184 0.7368253 0.5204169 -0.5407578 0.6608687 -0.476777 -0.7399427 0.4745193 0.5474475 -0.816228 0.1845888 -0.3585553 -0.9322423 0.04860675 0.222448 -0.843092 -0.4896048 -0.6321084 -0.04264861 -0.7737055 0.5087419 0.2776524 -0.8149178 -0.713891 0.4959855 -0.4943258 0.727833 0.672775 0.1327895 -0.677908 0.5117694 0.5277622 0.7279983 -0.1621985 0.6661157 -0.652777 -0.4959437 0.572645 0.6004545 -0.6328942 0.4887735 -0.5949032 -0.8003374 0.07450079 -0.06563782 -0.9065131 -0.4170441 -0.3901426 -0.4650872 -0.7946587 0.7006102 0.2828437 -0.6550915 -0.5492708 0.7568509 -0.3542291 0.3917318 0.8544592 -0.3412413 -0.4085204 0.8686051 0.280422 0.678977 0.554567 0.4810881 -0.5671368 0.301755 0.7663549 0.5437679 0.1519045 0.8253736 -0.6933226 -0.2277237 0.6837 0.5815765 -0.5372315 0.6108611 -0.4326996 -0.8556708 0.2838994 0.5825877 -0.7970537 0.159051 -0.7022686 -0.6792414 -0.21319 0.6543077 -0.6655413 -0.3590769 -0.5757995 -0.4354106 -0.6920062 0.5740282 0.2540324 -0.7784338 -0.5173802 0.673215 -0.5282986 0.497564 0.724057 -0.4776732 -0.5753151 0.8123698 0.09522563 0.7691885 0.5288115 0.3587583 -0.5219448 0.4624177 0.7167591 0.3955199 0.211733 0.8937188 -0.4900758 0.01361888 0.8715735 0.6127921 -0.2011744 0.7642087 -0.7247268 -0.4386499 0.5313732 0.6141088 -0.6147416 0.4949375 -0.4819413 -0.8567687 0.1835213 0.3668534 -0.9237226 0.1102502 -0.5114929 -0.7906399 -0.3365468 0.5858929 -0.7085039 -0.3933848 -0.4989455 -0.455607 -0.737208 0.619893 -0.2991194 -0.725438 -0.5848787 -0.0301522 -0.8105602 0.6968535 0.276302 -0.6618553 -0.3111795 0.8213341 -0.478098 0.1671962 0.975677 0.1417743 -0.4172526 -0.1702424 -0.8927026 -0.1635292 0.3008305 -0.9395527 0.677922 0.2766466 -0.6810936 -0.6603224 0.5974109 -0.4550545 0.6407427 0.6950667 -0.3260845 -0.7393324 0.6723568 0.03638786 -0.5939755 -0.7172767 0.3642903 0.5198616 -0.8541817 -0.01084876 -0.05436635 -0.9914058 -0.1189911 -0.4480081 -0.68602 -0.5732935 0.3726661 0.07377254 -0.9250285 -0.41501 0.6002575 -0.6837088 0.3681737 0.651279 -0.6635389 -0.2014251 0.9487052 -0.2436933 0.4877777 0.8584196 -0.15871 -0.6150602 0.7593075 0.2124931 0.7945047 0.5082506 0.332331 -0.6962062 0.2327664 0.6790558 0.6526047 -0.06955152 0.7544996 -0.6561166 -0.2900447 0.6966959 0.5758889 -0.6509898 0.4945343 -0.1905804 -0.9812952 0.02718144 0.4792263 -0.7796327 -0.4031317 -0.6751845 -0.5508238 -0.4906314 0.7631973 -0.2390532 -0.6003196 -0.8062481 0.1895993 -0.5603715 0.6083537 0.43624 -0.6630237 -0.6414459 0.6815 -0.3522853 0.4208377 0.8444297 -0.3314122 -0.1930884 0.9633857 0.1860242 -0.4863353 0.8479116 0.2110071 0.6747329 0.5062563 0.5370662 -0.6002718 0.09071528 0.7946348 0.5567464 -0.3112921 0.7701498 -0.4173224 -0.6973722 0.5826784 -0.06847071 -0.9826135 0.1725763 0.7592054 -0.622679 -0.1894155 -0.674098 -0.5009871 -0.5427743 0.6289932 -0.3462397 -0.6960501 -0.6205238 -0.06784397 -0.7812474 0.5648877 0.07458811 -0.8217898 -0.6708322 0.4514526 -0.5883662 0.5524105 0.5670893 -0.610944 -0.4379796 0.8906298 -0.122281 0.6093098 0.7576423 0.2339226 -0.6587915 0.4949924 0.5665477 0.6124362 0.4124413 0.6743991 -0.5397918 0.01787775 0.8416088 -0.07246005 -0.01232743 0.9972952 0.3764995 -0.5765998 0.7251074 -0.7175176 -0.2546925 -0.6483057 0.61577 0.1444492 -0.774572 -0.7763291 0.4642046 -0.4264121 0.3733186 0.7763529 -0.5078479 0.1458933 0.986878 -0.06918752 -0.5463541 0.5130024 0.6620618 0.4947034 0.2199288 0.8407735 -0.6258894 -0.005315184 0.7798938 0.7036135 -0.2703058 0.6571627 -0.6790027 -0.4878634 0.5485843 0.6968553 -0.6672763 0.2629354 -0.4200105 0.830645 -0.3655407 0.4292616 0.8933606 0.1328213 -0.5652517 0.6337881 0.5280183 0.5352779 0.3023448 0.788711 0.1607825 -0.1653041 0.9730486 -0.4094968 -0.6317771 0.6581566 0.5946257 -0.6033589 0.531393 -0.609839 -0.7866961 0.09594625 0.1597654 -0.9852958 0.06055796 0.4127464 -0.842701 -0.3456814 -0.7905435 -0.458957 -0.4054622 0.2784324 0.178085 -0.9438014 0.2403782 0.6946391 -0.678008 -0.6912003 0.6938678 -0.2019647 0.751284 0.6376906 0.1700677 0.1927484 -0.1918377 0.962313 -0.4404864 -0.6934278 0.5702014 0.2651689 -0.7674233 0.5837355 0.141687 -0.984942 0.09906721 -0.4481764 -0.8939382 -0.003520786 0.3736388 -0.8378013 -0.3980993 -0.5727903 -0.6482944 -0.501623 0.5794247 -0.4800252 -0.6586675 -0.695927 -0.08588463 -0.7129583 0.5530809 0.5347416 -0.6388686 -0.4778879 0.8417162 -0.2512708 0.6136035 0.7798393 -0.1238602 -0.7378898 0.6288274 0.2451423 -0.1112197 0.107854 0.987926 0.4287822 -0.438545 0.7898254 -0.2667098 -0.556571 0.7868257 -0.2714849 -0.9086028 0.317391 0.219084 -0.7922281 -0.5695411 -0.03767675 -0.2668341 -0.9630057 -0.7149596 0.2269757 -0.6612978 0.6827436 0.483243 -0.5480306 -0.7511164 0.6002115 -0.2749009 0.6730785 0.7270581 -0.1354692 -0.6532884 0.7243614 0.2202609 0.6474846 0.6818841 0.3402909 -0.7314202 0.350183 0.5851465 0.725313 0.2598157 0.6375083 -0.6090973 -0.1651413 0.7757119 0.536952 -0.2680854 0.799883 -0.5473256 -0.6060079 0.5772254 0.5568195 -0.690938 0.4610387 -0.4410679 -0.8697317 0.2214183 0.4465499 -0.8941282 0.03358924 -0.5855241 -0.7756645 -0.2355975 0.7139423 -0.6045081 -0.3533503 -0.7156673 -0.3816216 -0.584966 0.7953599 -0.1381593 -0.5901818 -0.7724323 0.2701165 -0.5747916 0.6771312 0.5274808 -0.5130863 -0.6009265 0.7258382 -0.3347331 0.5012437 0.8631932 -0.0604344 -0.4720671 0.8731129 0.121765 0.5664042 0.7121204 0.4148144 -0.6917806 0.4730384 0.5455953 0.5810887 0.3803296 0.7195036 -0.5054331 -0.01380628 0.8627554 0.2777397 -0.07176148 0.9579724 -0.3527335 -0.5699124 0.7421448 0.629693 -0.5328074 0.5653345 -0.590066 -0.7451668 0.3107227 0.698468 -0.7154793 0.01523143 -0.6685065 -0.613171 -0.4208568 0.6496654 -0.3886443 -0.6533686 -0.6503624 -0.02904629 -0.7590686 0.6083509 0.3473511 -0.713622 -0.8339455 0.5102914 -0.2100894 0.57011 0.8022125 -0.1772838 -0.323257 0.8533467 0.4090287 0.2157127 0.5468426 0.8089693 0.2881382 0.04979264 0.9562934 0.7344585 -0.6358829 -0.2371155 -0.5141987 -0.6289153 -0.5831512 0.6501297 -0.3029712 -0.6968069 -0.5616551 0.7647556 0.3157412 0.1011885 0.672846 0.7328296 -0.676145 0.267706 0.686412 0.965421 -0.2581644 0.03624188 -0.007385492 -0.8259195 -0.5637399 0.8907846 -0.344157 -0.2967469 0.8699356 -0.1277328 -0.4763364 0.7160177 -0.07795488 -0.6937158 0.7394617 0.3769179 -0.5577896 0.7779851 0.3205826 -0.5403389 0.8728349 0.3349127 -0.3549548 0.7547956 0.5485754 -0.3596509 0.7827277 0.5968188 -0.1764786 0.7315409 0.6448587 -0.2213712 0.7398211 0.6662641 0.09357857 0.8691757 0.4665579 0.1638818 0.7472169 0.5389216 0.3888837 0.9011103 0.2254179 0.3703875 0.8016002 0.3579474 0.478864 0.7879147 0.05627489 0.6132078 0.8458085 0.001612246 0.5334842 0.793658 -0.1906109 0.5777323 0.8499339 -0.2121187 0.482305 0.7568442 -0.4214628 0.4995559 0.8152176 -0.4861958 0.3146971 0.7701587 -0.5619587 0.3017584 0.7867366 -0.6139305 0.064305 0.8410683 -0.5409289 1.60078e-4 0.7317908 -0.6572843 -0.1801661 0.8567134 -0.3918621 -0.3353899 0.8358429 -0.4048495 -0.370761 0.7818229 -0.208504 -0.5876047 0.8816444 -0.06945401 -0.4667756 0.8273574 -0.011819 -0.5615516 0.7779502 0.2480814 -0.5772773 0.7361369 0.2463694 -0.6304003 0.7756834 0.4989795 -0.3864385 0.8563567 0.447616 -0.2574747 0.7842718 0.5870586 -0.2006987 0.8785399 0.4771447 0.02237504 0.8454342 0.5306581 0.06035655 0.7514894 0.5832074 0.308436 0.8572804 0.4024778 0.3210636 0.7578818 0.401537 0.5141823 0.8396559 0.104897 0.5328928 0.7845067 0.07142519 0.6159933 0.8411085 -0.1505165 0.5195012 0.8253855 -0.1486195 0.5446571 0.7337607 -0.508633 0.4504306 0.8235042 -0.4534043 0.3409772 0.8566203 -0.5068951 0.09622579 0.8713052 -0.4837094 0.08278083 0.7763657 -0.6055229 -0.1749237 0.8770085 -0.4207113 -0.2320738 0.8343313 -0.4494478 -0.3191992 0.8010199 -0.3054878 -0.5148246 0.8674356 -0.2184374 -0.4470355 0.7365974 -0.01554799 -0.6761528 0.8335853 0.2180587 -0.5075295 0.8891254 0.1244242 -0.4404255 0.7989473 0.4170228 -0.4333307 0.783733 0.4227425 -0.4550293 0.7518256 0.6278398 -0.201434 0.859093 0.5036631 -0.09101092 0.7722558 0.6180284 0.1471801 0.8825616 0.43603 0.1759624 0.7829893 0.4734349 0.403469 0.8223032 0.3889027 0.4154182 0.7049536 0.2991855 0.6430619 0.8071049 0.1458897 0.5720997 0.7284941 0.01642107 0.6848553 0.8053559 -0.1917378 0.5609266 0.8503932 -0.200719 0.4863573 0.7877177 -0.4425123 0.4285835 0.8262092 -0.4197893 0.3757067 0.7679274 -0.5931411 0.241808 0.8775792 -0.4793916 0.006197273 0.8477597 -0.5297827 -0.02518069 0.7836468 -0.567652 -0.2523273 0.8497089 -0.4612519 -0.2554245 0.7208852 -0.4222525 -0.5495702 0.8450875 -0.1944614 -0.498008 0.8221735 -0.1786208 -0.5404864 0.8189646 0.05998158 -0.5707008 0.8731041 0.08416986 -0.4802132 0.754906 0.3816669 -0.533336 0.9108101 0.3402154 -0.2338346 0.7882183 0.4654661 -0.4025584 0.8299153 0.5541977 -0.06407433 0.8629235 0.4982322 -0.08442604 0.7841895 0.586896 0.2014946 0.8978013 0.3909711 0.2027183 0.7402525 0.427055 0.5192786 0.8100939 0.1874747 0.5555189 0.7859254 0.1669246 0.5953634 0.8172238 0.1138286 0.5649676 0.7186632 -0.1116744 0.6863324 0.8422253 -0.2123997 0.495523 0.7458357 -0.3951354 0.5362808 0.8280809 -0.4753539 0.2971882 0.8098733 -0.5063945 0.2960913 0.8279946 -0.5572999 0.06198203 0.7746289 -0.6241118 0.1021498 0.7736802 -0.5984172 -0.2081248 0.8640339 -0.4512912 -0.2231185 0.804381 -0.404627 -0.4350267 0.8745279 -0.2826922 -0.3940638 0.7718157 -0.2268925 -0.5939868 0.8305302 0.03479069 -0.5558861 0.8562837 0.04492419 -0.5145486 0.6927956 0.4096529 -0.5934802 0.8203432 0.4230574 -0.3847849 0.7814936 0.5283706 -0.3318018 0.8804259 0.4403803 -0.1758276 0.7287813 0.6843238 -0.02405971 0.8334733 0.5410915 0.1119925 0.7000623 0.5993463 0.388197 0.7974345 0.472388 0.3754301 0.7833245 0.3007555 0.5440117 0.8059133 0.2677342 0.5280362 0.7611852 0.08775913 0.6425694 0.8126886 0.02839267 0.5820063 0.7735155 -0.1721122 0.6099602 0.7995542 -0.1864883 0.5709074 0.7472091 -0.419535 0.5154309 0.8208233 -0.4130997 0.3944588 0.7576141 -0.5687793 0.3201734 0.8535417 -0.5081637 0.1150484 0.7858804 -0.6166332 0.04642701 0.8639776 -0.4934725 -0.100138 0.8157516 -0.5493044 -0.1811472 0.8488039 -0.3932189 -0.3534273 0.8446797 -0.40006 -0.355624 0.818259 -0.2318882 -0.5260041 0.7723925 -0.2817611 -0.5692281 0.7952718 0.02193897 -0.6058561 0.8686197 0.06745243 -0.4908666 0.8154863 0.3157222 -0.4850792 0.8630637 0.3012431 -0.4054303 0.7354924 0.605055 -0.3048925 0.8690289 0.4671374 -0.1630071 0.7110253 0.6938686 0.1139714 0.8553582 0.478142 0.1993557 0.8043954 0.479968 0.3501129 0.8695189 0.3478881 0.3505864 0.717989 0.3087282 0.6238419 0.897967 0.05708426 0.4363446 0.757613 -0.08257251 0.6474601 0.8514326 -0.3115925 0.421868 0.867527 -0.3022713 0.3950051 0.7623026 -0.5903685 0.2652544 0.8197341 -0.537859 0.1968345 0.7468082 -0.6650395 2.17399e-4 0.8432354 -0.5167881 -0.1479334 0.7528033 -0.6472887 -0.1196019 0.8001036 -0.4655468 -0.3782863 0.7466661 -0.5348737 -0.3954743 0.8261287 -0.3006854 -0.4765497 0.7191696 -0.2400037 -0.6520686 0.8134099 -0.08561372 -0.5753562 0.7057363 0.0817309 -0.7037445 0.8432846 0.2474809 -0.4771 0.8408778 0.2515578 -0.4792109 0.7802044 0.4784559 -0.4029406 0.8866143 0.4092559 -0.2154642 0.7986097 0.5784625 -0.1661441 0.8418089 0.5389657 0.02956217 0.8829382 0.4654965 0.06109994 0.7836793 0.5514764 0.2858681 0.8711297 0.3590341 0.3350039 0.8127719 0.3738306 0.4468251 0.8376223 0.1607176 0.5220718 0.8747533 0.1154612 0.4706117 0.7624702 -0.09269052 0.6403498 0.8861726 -0.212453 0.4117791 0.8186191 -0.2307897 0.5259268 0.8569279 -0.4014216 0.3233194 0.8030418 -0.4971777 0.3285394 0.8438701 -0.5321196 0.06878989 0.8312373 -0.5504517 0.07776522 0.8172085 -0.5354492 -0.2132238 0.8345347 -0.5074313 -0.2146288 0.7597278 -0.45947 -0.4601098 0.8238614 -0.3529386 -0.443494 0.7509082 -0.2076284 -0.626919 0.8642592 -0.02824652 -0.5022534 0.8057168 0.03723603 -0.5911294 0.7820386 0.2695001 -0.561948 0.8576537 0.2601962 -0.4435406 0.713478 0.5720565 -0.4045993 0.8127574 0.5452675 -0.2052041 0.7707951 0.6141147 -0.1695232 0.7317976 0.6685401 0.1323873 0.8077535 0.5861259 0.06317359 0.857572 0.4359106 0.2730427 0.823094 0.4620233 0.3302285 0.739389 0.3570519 0.5708047 0.8328276 0.2007509 0.5158461 0.7094738 0.07195091 0.7010492 0.7937911 -0.153868 0.5884051 0.7917367 -0.1574507 0.5902222 0.8861798 -0.2547547 0.3870214 0.8407006 -0.341056 0.4205991 0.7628724 -0.5862023 0.2727499 0.8535479 -0.4954164 0.1613029 0.7425975 -0.6694487 0.01968449 0.8194164 -0.5233493 -0.2338001 0.8411347 -0.4881521 -0.2328094 0.8498383 -0.3588994 -0.3859611 0.7986764 -0.367677 -0.4763714 0.7588626 -0.1456233 -0.6347609 0.8119296 -0.09532213 -0.5759204 0.7108995 0.2790319 -0.645572 0.8612046 0.1299664 -0.4913608 0.7533412 0.4246025 -0.502185 0.8986542 0.3702945 -0.2351654 0.8409303 0.4919253 -0.2254901 0.7808191 0.6227166 0.05045425 0.8254481 0.560666 0.06549185 0.753295 0.5549185 0.3530046 0.8278661 0.4130985 0.379457 0.8054043 0.3728267 0.4607868 0.8774699 0.2274446 0.4222745 0.8065789 0.1808378 0.5627861 0.8613153 -0.02566051 0.5074225 0.8127491 -0.0828163 0.5766979 0.6804485 -0.4878723 0.5467819 0.8415652 -0.2926979 0.4539781 0.7834521 -0.5032721 0.364582 0.8749725 -0.4400086 0.2020288 0.8013835 -0.5821109 0.1375923 0.8682181 -0.4890525 -0.08381557 0.8347637 -0.5363389 -0.1245411 0.7945297 -0.4892449 -0.3596694 0.9068577 -0.236733 -0.3486641 0.7161995 -0.4634787 -0.5217718 0.8329572 -0.1178541 -0.5406411 0.8122178 -0.1385431 -0.566664 0.7718618 0.2069315 -0.6011729 0.8561741 0.1165173 -0.5033785 0.7930189 0.3696789 -0.4842092 0.8795785 0.3370953 -0.3357207 0.7797042 0.5454285 -0.3075213 0.8377704 0.5423349 -0.06335377 0.8466134 0.5291524 -0.05695313 0.5904569 0.6808788 0.4333183 0.8154208 0.5335767 0.2244661 0.8370677 0.3450656 0.4245555 0.8311895 0.3465823 0.4347469 0.8270037 0.1343938 0.5458967 0.878942 0.06327873 0.4727122 0.7744825 -0.0892843 0.6262629 0.8743788 -0.2551785 0.4127296 0.849429 -0.2979345 0.435552 0.7493789 -0.5889118 0.3026782 0.8797352 -0.4505717 0.1518264 0.7576492 -0.6499852 -0.05905073 0.897885 -0.4238336 -0.1190277 0.7625143 -0.4904215 -0.4219704 0.8992963 -0.2737671 -0.3410542 0.8363586 -0.2066287 -0.5077489 0.8605835 -0.07913953 -0.5031232 0.7712653 -0.01009112 -0.636434 0.8628774 0.2300313 -0.4500313 0.7166761 0.2646668 -0.6452341 0.8360738 0.4745712 -0.2752509 0.8456866 0.4579485 -0.2740394 0.7623293 0.6380105 -0.1086127 0.747366 0.6461296 0.1547923 0.8482066 0.5296283 -0.006285011 0.8284549 0.4631344 0.3149111 0.698606 0.4845495 0.5264613 0.8327756 0.2900528 0.4715447 0.7179541 0.1198956 0.6856873 0.8224331 0.009956479 0.5687748 0.766968 -0.1710965 0.6184548 0.8045867 -0.2083995 0.5560665 0.7167551 -0.424798 0.5529998 0.8264829 -0.4203438 0.3744824 0.7450047 -0.6002627 0.2909513 0.8252015 -0.5437993 0.1527249 0.7447705 -0.6659125 0.04332971 0.8065178 -0.567327 -0.1663402 0.7945988 -0.5848339 -0.1630408 0.7689748 -0.5013629 -0.396627 0.8310495 -0.3851991 -0.4012213 0.7426766 -0.3464356 -0.5730742 0.8062443 -0.1380658 -0.575246 0.8485986 -0.09336119 -0.5207344 0.8290479 0.1050673 -0.5492182 0.8560409 0.1145741 -0.5040505 0.8089809 0.3708359 -0.456104 0.874845 0.3444052 -0.3406339 0.771573 0.5723537 -0.2776442 0.8650854 0.492095 -0.09731334 0.818883 0.571667 -0.05126178 0.7354582 0.6422885 0.2157937 0.8658472 0.4040926 0.2949879 0.6947032 0.6293801 0.3482358 0.8124334 0.3174136 0.4890816 0.8285579 0.3242204 0.4564788 0.8103654 0.1122776 0.5750667 0.8258797 0.08428931 0.5575107 0.6833488 -0.1136711 0.7211889 0.8766503 -0.2020146 0.4366627 0.69331 -0.5398954 0.4773198 0.8738287 -0.4322142 0.2227426 0.7713231 -0.6277641 0.1047522 0.8721194 -0.4890452 -0.01557809 0.7917847 -0.5837762 -0.1796736 0.8677371 -0.4454898 -0.2203887 0.7472846 -0.4734182 -0.4663057 0.7995501 -0.2699859 -0.5364954 0.7708657 -0.2588509 -0.5820331 0.811888 0.04708445 -0.5819115 0.8214733 0.0386992 -0.5689324 0.7958977 0.3096655 -0.5202446 0.8661906 0.288512 -0.4080132 0.7829359 0.5243039 -0.3348387 0.9024106 0.402926 -0.1526628 0.8105779 0.5855814 0.007618248 0.8731355 0.482278 0.07100927 0.7715414 0.5728068 0.2767966 0.8193604 0.4847817 0.3059987 0.7019392 0.4417333 0.5587067 0.8567087 0.1632983 0.4892688 0.7682368 0.1142349 0.629891 0.8708832 -0.1304125 0.4738726 0.8424333 -0.1720188 0.5106034 0.7957096 -0.402171 0.4528849 0.856567 -0.3771889 0.3521671 0.7294754 -0.6334764 0.2580178 0.8371105 -0.546943 0.009974122 0.7773697 -0.6275916 -0.04272109 0.8015425 -0.5430355 -0.2502843 0.8962461 -0.3690327 -0.2460849 0.7506862 -0.4002708 -0.5255983 0.8477787 -0.2177945 -0.4835668 0.7132244 -0.08757549 -0.6954435 0.8688289 0.1465489 -0.4729267 0.8388622 0.1890653 -0.5104551 0.793224 0.4226962 -0.438319 0.8876162 0.376454 -0.2653675 0.7767603 0.5850079 -0.2332581 0.8222417 0.5679116 0.03735071 0.8836538 0.4641114 0.0612927 0.7434339 0.5413109 0.392796 0.7339554 0.3416617 0.5870066 0.8330084 0.4045739 0.3773818 0.8602431 0.05530917 0.5068755 0.818639 0.02111035 0.5739203 0.7504596 -0.2818542 0.5978033 0.8389067 -0.1545094 0.5218837 0.815503 -0.4510973 0.362583 0.7801032 -0.5089158 0.3639281 0.8628579 -0.4712778 0.1826841 0.7030373 -0.7105 0.03047007 0.8655749 -0.4768379 -0.1529895 0.7846472 -0.5179513 -0.3406689 0.874863 -0.371748 -0.3105129 0.7891182 -0.3007466 -0.5355783 0.8924986 -0.1005733 -0.4396947 0.842833 -0.05610084 -0.5352433 0.7541872 0.2162591 -0.6200273 0.9036856 0.2096008 -0.3733897 0.7350819 0.5461811 -0.4016725 0.8710287 0.4787541 -0.1100164 0.7476921 0.6345744 -0.1956318 0.8073247 0.559877 0.1864525 0.7752765 0.5895275 0.2267236 0.8626462 0.3783364 0.3357129 0.8428117 0.3881067 0.3728832 0.7904958 0.215415 0.5733347 0.885918 0.06615281 0.4591006 0.7981185 -0.01550734 0.6023009 0.7768259 -0.2933155 0.5572323 0.8482793 -0.2799805 0.449481 0.7343627 -0.5614147 0.3814774 0.8586158 -0.4948121 0.1339402 0.7783877 -0.5888719 0.2175834 0.8134573 -0.5790203 -0.05498158 0.7806994 -0.6182714 -0.09082365 0.7839427 -0.521202 -0.3373165 0.7796137 -0.5275095 -0.3375446 0.744085 -0.3696098 -0.5565305 0.8803535 -0.1725614 -0.4418149 0.7482762 -0.02427154 -0.6629433 0.8454892 0.05589544 -0.5310593 0.7035247 0.3718384 -0.6056313 0.8707861 0.3512086 -0.34407 0.786578 0.5201917 -0.3327099 0.8498243 0.5215821 -0.07583475 0.7967265 0.5924738 -0.1191709 0.7547233 0.637642 0.1542902 0.8264434 0.5291065 0.1924515 0.751403 0.5072201 0.4220445 0.8697601 0.2992697 0.3923712 0.7490545 0.2193281 0.6251501 0.8939028 0.05711883 0.4446067 0.7777618 -0.1114544 0.6185989 0.8414691 -0.2782502 0.4631487 0.8813616 -0.264229 0.3916439 0.7813119 -0.5193353 0.3461828 0.8403972 -0.490387 0.2307666 0.7014527 -0.7068151 0.09152317 0.8253153 -0.5599319 -0.07301336 0.722265 -0.6459696 -0.2470965 0.8300864 -0.4056689 -0.3826087 0.7444548 -0.5179999 -0.4212638 0.815863 -0.202039 -0.5418006 0.6927927 -0.3164865 -0.6479774 0.8014959 0.03435748 -0.5970127 0.8029735 0.03520381 -0.5949743 0.756675 0.3442039 -0.5558478 0.7925531 0.3411243 -0.5054641 0.775903 0.4995307 -0.3852841 0.8673759 0.45415 -0.2034871 0.7632285 0.6318228 -0.1352121 0.8643766 0.5028059 0.006269931 0.7002572 0.6592718 0.2738625 0.8653377 0.3827075 0.3236134 0.7731691 0.3868831 0.5025247 0.8587586 0.1650786 0.4850597 0.7407702 0.2766225 0.6121599 0.7899108 -0.1139432 0.602543 0.852615 -0.05123573 0.5200219 0.770091 -0.3141997 0.5551922 0.8797167 -0.2893175 0.3773512 0.7299482 -0.6277734 0.270326 0.8844118 -0.4525759 0.1139772 0.7389885 -0.6653349 -0.1059503 0.8893781 -0.4106972 -0.2008346 0.7630051 -0.4909682 -0.4204447 0.7788125 -0.2461338 -0.5769484 0.7910243 -0.24931 -0.5586815 0.7946154 0.1173905 -0.5956558 0.800572 0.112142 -0.58865 0.7996197 0.3348211 -0.4985011 0.8352184 0.3358252 -0.4354672 0.7550979 0.5235494 -0.3946179 0.8381311 0.5243086 -0.1504549 0.8079466 0.5730196 -0.1373714 0.7903605 0.5902033 0.1642876 0.7678284 0.6201229 0.1608946 0.7541268 0.5111239 0.4123653 0.8062772 0.4316889 0.404428 0.7574634 0.2980569 0.5808713 0.8159599 0.2046467 0.5406749 0.7443508 0.07473999 0.6635931 0.8437235 -0.1104964 0.525282 0.8096489 -0.1565188 0.5656593 0.8173493 -0.3395867 0.4654256 0.8901352 -0.3145346 0.3297381 0.769281 -0.555947 0.314849 0.8203909 -0.5632094 0.09876334 0.8832274 -0.4662241 0.05044341 0.7962468 -0.55598 -0.2384899 0.8742645 -0.4168499 -0.2487922 0.7601729 -0.4449429 -0.4734586 0.8809623 -0.1845387 -0.4357188 0.8017508 -0.1395418 -0.5811401 0.651946 0.1954416 -0.7326452 0.8008348 0.06405997 -0.5954493 0.7419573 0.3447241 -0.5750345 0.8506319 0.3401064 -0.4009404 0.7915056 0.5135994 -0.3312622 0.8778495 0.4402766 -0.1885125 0.8100273 0.5761258 -0.1092472 0.8325093 0.5450327 0.09933638 0.8551671 0.5134853 0.07086753 0.7332992 0.5496119 0.4002488 0.83485 0.3794035 0.3988468 0.7263263 0.3326374 0.6015003 0.8294094 0.07717674 0.5532845 0.8565019 0.05452346 0.513256 0.804206 -0.212153 0.5551971 0.8841794 -0.2282787 0.4075731 0.8066219 -0.3965865 0.4382696 0.8555905 -0.4456834 0.2633081 0.7922863 -0.559092 0.244333 0.7356474 -0.6772888 0.0101425 0.8204678 -0.5675914 -0.06835728 0.7338696 -0.6110809 -0.2966744 0.8546689 -0.4198012 -0.3054639 0.755043 -0.3555293 -0.5509166 0.8625698 -0.2130491 -0.4588939 0.750339 -0.07085198 -0.6572453 0.8389357 0.1669059 -0.5180054 0.8807301 0.1097938 -0.4607167 0.7289829 0.4206433 -0.54004 0.8827418 0.3949775 -0.2544794 0.8211953 0.5148561 -0.2460929 0.7936978 0.6082617 0.007851421 0.8931666 0.4438838 0.07225596 0.7657799 0.5613703 0.3137592 0.8849599 0.294773 0.3604925 0.8563826 0.302699 0.4183087 0.7701635 0.1203402 0.6263915 0.8517794 -0.07426851 0.5186097 0.8754155 -0.04285293 0.4814682 0.8214843 -0.3056686 0.4813836 0.8727404 -0.3108451 0.37643 0.8009597 -0.4738417 0.3659752 0.8591578 -0.4805137 0.175939 0.8117192 -0.5652794 0.1468717 0.8140274 -0.5792736 -0.04244524 0.8746643 -0.477525 -0.08326005 0.7946177 -0.550431 -0.2561419 0.8647497 -0.3282504 -0.3800787 0.8667413 -0.3249357 -0.3783864 0.7969938 -0.216614 -0.5638079 0.8372327 -0.138306 -0.5290679 0.7288383 0.02736216 -0.6841389 0.8557386 0.2129424 -0.4715582 0.8133811 0.2771235 -0.5114819 0.7983152 0.4716405 -0.3744972 0.8785949 0.4059737 -0.2515082 0.7860921 0.6055604 -0.1239199 0.8758277 0.4824783 0.01185506 0.8037236 0.5848328 0.1095405 0.8187223 0.4526998 0.3532091 0.8727095 0.3648867 0.324401 0.7725489 0.3025105 0.5582613 0.8836759 0.02252811 0.4675568 0.8371481 0.0488227 0.5447931 0.7960589 -0.3064372 0.5219066 0.8417877 -0.289437 0.4556531 0.858529 -0.447018 0.2512031 0.8094311 -0.5324256 0.2476779 0.8202799 -0.5717955 0.01381891 0.7904442 -0.6114769 0.03597211 0.7378197 -0.618536 -0.2702508 0.8671854 -0.4086028 -0.2846636 0.7921633 -0.4056606 -0.4559791 0.865209 -0.1879439 -0.4648554 0.6169289 -0.3951813 -0.6806105 0.8530344 -0.002746939 -0.5218476 0.7815357 0.0768541 -0.6191087 0.8497598 0.1916896 -0.491084 0.7389799 0.3767411 -0.5585471 0.8017005 0.488813 -0.3440032 0.8980411 0.3958989 -0.1917975 0.783748 0.6115679 -0.1082773 0.8129761 0.5747251 0.09359979 0.8628216 0.4895876 0.1258685 0.7687566 0.5692504 0.2914915 0.7463098 0.3670102 0.5552706 0.828857 0.348545 0.4376214 0.7990155 0.05363696 0.5989135 0.7129746 0.09846329 0.6942422 0.7919067 -0.2422602 0.5605301 0.758394 -0.2416865 0.6053316 0.8132185 -0.4279071 0.3944252 0.7502859 -0.5279837 0.3978748 0.7954247 -0.5906278 0.1358619 0.8142605 -0.5614992 0.1473043 0.6822076 -0.6873596 -0.2492581 0.8587428 -0.5071118 -0.0734747 0.7949011 -0.5286844 -0.2976996 0.8713786 -0.3960757 -0.2895227 0.778899 -0.3255856 -0.5360133 0.8182107 -0.2644137 -0.5105063 0.7286532 -0.1182242 -0.6746019 0.8241224 0.01701718 -0.5661561 0.7426285 0.2052715 -0.6374688 0.8203079 0.2453998 -0.5165986 0.7651306 0.4484481 -0.4620277 0.7872027 0.4447588 -0.4272019 0.7389303 0.6179276 -0.268603 0.8270141 0.5442126 -0.1409982 0.7464062 0.6650671 -0.02374321 0.8439257 0.4969875 0.2019723 0.862698 0.4747107 0.1743618 0.7679259 0.4647637 0.4407771 0.8620784 0.309307 0.401435 0.7028085 0.2256937 0.6746279 0.7726454 -0.02604001 0.6343036 0.7385469 -0.07116585 0.6704357 0.8572276 -0.215644 0.4676095 0.7411162 -0.3977069 0.5409029 0.8766344 -0.4298529 0.2161915 0.909242 -0.3590688 0.2105912 0.6332919 -0.7739131 -3.20735e-4 0.8452363 -0.4997962 -0.1891553 0.9249808 -0.3444654 -0.160481 -0.5942045 -0.3996293 -0.6980097 0.8991966 -0.3178001 0.3007468 -0.933121 -0.3595425 0.003807425 0.8950594 0.382234 0.2297081 0.9026687 0.4299044 0.01927834 -0.9594855 0.06162595 -0.2749364 0.8253076 -0.4337677 -0.3615425 -0.82273 -0.2442594 -0.5132765 0.8837289 -0.0223245 -0.4674667 -0.8970466 0.1186631 0.4257071 0.794784 -0.07834714 0.6018142 -0.7604491 -0.3995434 0.5119397 0.8703761 -0.3642809 0.3312776 0.8817565 0.1704878 0.4398175 -0.04426729 0.1866536 -0.9814279 -0.01062804 0.5178265 -0.8554197 0.9567065 0.03714406 0.2886745 0.7683734 -0.03768002 0.6388916 0.07400232 0.185925 0.9797733 0.7782427 0.2629277 0.5702696 0.5889374 0.2713599 0.7612599 0.4632125 0.3078432 0.8310638 0.8222885 0.3859722 0.4181713 0.2118588 0.5522362 0.8063195 0.8606796 0.3582546 0.3617794 0.6542435 0.5416014 0.5278573 0.3710513 0.6116436 0.6987226 0.8583816 0.4739009 0.1964668 0.435103 0.7788106 0.451818 0.2046529 0.8432348 0.4970639 0.9641074 0.262403 0.04051667 0.645839 0.7226741 0.2462399 -0.0315451 0.8897298 0.4553963 0.5974756 0.7745599 0.2075568 0.9999036 0.01381498 -0.001482427 0.3075495 0.9286358 0.207482 0.8567296 0.5148442 -0.03082245 0.7357175 0.6768727 -0.023732 0.1064918 0.9924359 0.06107783 0.584491 0.80526 -0.09963291 0.3051304 0.9490634 -0.0785768 0.561644 0.7809196 -0.2733512 0.8852057 0.4378973 -0.1570256 0.7302377 0.5984581 -0.3295465 0.01992624 0.9564069 -0.2913569 0.2149556 0.9124649 -0.3481408 0.7166658 0.5873762 -0.3760045 0.7781525 0.4592193 -0.4284815 0.2710275 0.7774584 -0.5675408 0.2030745 0.7661217 -0.6097692 0.9535343 0.1633585 -0.2531532 0.5100557 0.5331065 -0.6750116 0.3437953 0.5974171 -0.7244982 0.5860497 0.2539943 -0.7694366 0.7207001 0.1513184 -0.676531 0.716452 0.05744892 -0.695267 0.2010647 0.3126181 -0.928355 0.7865289 -0.02577269 -0.6170156 0.2764064 0.01136624 -0.9609737 0.6529526 -0.2642842 -0.7097936 0.6292597 -0.2755366 -0.7267131 0.1379495 -0.1875413 -0.9725216 0.2809538 -0.2831089 -0.9170138 0.8791222 -0.2741173 -0.3898769 0.0372647 -0.4723243 -0.8806368 0.3434076 -0.5608509 -0.7533378 0.3012654 -0.5703557 -0.7641555 0.7793162 -0.4612947 -0.4241152 0.6923916 -0.5439699 -0.4740154 -0.05162072 -0.7197194 -0.6923434 0.9530389 -0.2858629 -0.09999668 0.5877228 -0.6788766 -0.4401232 0.9073532 -0.4066997 -0.1063277 0.2702485 -0.815511 -0.511769 0.6646256 -0.707516 -0.2401956 0.4405671 -0.8750652 -0.2004032 0.05316919 -0.9216969 -0.3842499 0.3876935 -0.9171711 -0.09214609 0.7920822 -0.5989335 0.117833 0.6617055 -0.737277 0.1362659 -0.202323 -0.9740644 0.1013116 0.8954077 -0.4139477 0.163989 0.4108874 -0.8703312 0.2714684 0.8560507 -0.4454351 0.2622303 0.5721449 -0.6765093 0.4636651 0.3871627 -0.7961392 0.4650456 0.2932548 -0.8130519 0.5029397 0.9370504 -0.2060999 0.2818858 0.5494304 -0.5075529 0.6637141 0.8411065 -0.2674388 0.4701237 0.6710603 -0.3912293 0.6297759 -0.06234854 -0.5841614 0.8092393 -0.1159197 -0.5888911 0.7998561 0.4060501 -0.3101147 0.8596234 0.7652333 -0.04100996 0.6424456 0.3935465 -0.1532922 0.9064341 0.2712596 -0.1219921 0.9547441 0.9988674 -0.01872253 -0.04374253 0.9999571 0.006747305 0.006356 0.9999957 -0.002587974 -0.001428365 0.9999867 -0.004763901 -0.001982629 0.9999871 -5.40696e-4 -0.005068659 0.9999907 -0.001183629 0.004164695 0.9999929 -9.73708e-5 -0.003783404 -0.07156139 0.5001373 -0.8629842 -0.07184797 0.5003387 -0.8628436 -0.07241058 0.9973703 -0.003032028 -0.07133859 0.9974499 -0.002124428 -0.07097828 0.4996458 0.8633169 -0.07193011 0.5003067 0.8628553 -0.07161581 -0.4975228 0.8644897 -0.07199913 -0.4972331 0.8646245 -0.07148516 -0.9974359 0.003390371 -0.06950169 -0.9975804 0.001768052 -0.03767973 -0.5009312 -0.8646667 -0.03611838 -0.4998114 -0.8653808 -0.9999391 0.006191134 0.009143888 -0.999929 0.0104317 0.005754411 -0.9999411 0.01081854 8.71578e-4 -0.9999234 -2.0566e-4 0.01238155 -0.9999459 0.005213797 0.009005725 -0.9999291 0.01144677 -0.003289997 -0.999944 0.01057261 4.46647e-4 -0.9999256 0.009170413 -0.00805366 -0.9999344 -0.006761431 0.009248852 -0.999947 -0.004902482 0.009064257 -0.9999273 -0.01069957 0.005559265 -0.9999463 0.00472778 -0.009231448 -0.999937 0.003899872 -0.01052719 -0.9999371 -0.01114183 0.001268029 -0.9999449 -0.01050472 1.51725e-4 -0.9999307 -8.84368e-4 -0.01173979 -0.9999272 -0.01142394 -0.003874242 -0.9999432 -0.0049299 -0.009450733 -0.9999442 -0.005002319 -0.00930345 -0.9999293 -0.008901357 -0.007903814 -0.9999707 -0.006873488 -0.003384351 -0.9999998 -6.18671e-4 7.54267e-5 -0.9999995 -1.05477e-4 9.63798e-4 -0.01418161 0.01674133 -0.9997593 0.004790544 0.05009657 -0.998733 -0.004528939 0.5900573 -0.8073487 0.01274108 0.6164836 -0.7872646 -0.01492142 0.8871981 -0.4611474 0.02529215 0.9392721 -0.3422402 -0.02270233 0.9933313 -0.1130387 0.02975404 0.985787 0.1653448 -0.02263092 0.9468038 0.3210151 0.01923096 0.7513161 0.6596624 0.01670664 0.7477976 0.6637166 -0.02646601 0.4731706 0.8805732 0.03159916 0.2604887 0.9649598 -0.0206418 0.07510495 0.996962 0.02530682 -0.2558034 0.9663975 -0.01545393 -0.3473395 0.9376122 7.53292e-4 -0.7515515 0.6596741 0.01747256 -0.7725493 0.6347145 -0.01560163 -0.9609737 0.2761995 0.01841855 -0.9864494 0.1630282 -0.0173006 -0.9966201 -0.08030754 0.02056139 -0.9695286 -0.244114 -0.02141821 -0.8754424 -0.4828479 0.01874947 -0.7937711 -0.6079277 -0.0230599 -0.5602111 -0.8280288 0.01875925 -0.470751 -0.8820668 0.9998807 -0.01193487 0.009808778 0.9996908 -0.01485854 -0.01994264 0.9999025 -0.004284024 0.01329654 0.9999432 -0.007957756 -0.007102429 0.9998983 -0.003647446 0.01379394 1 -1.33399e-4 2.22532e-5 0.9996284 0.02692419 0.004264891 0.9999938 9.25764e-4 0.003427922 1 -1.4367e-4 -3.54373e-5 0.9999763 0.006213605 -0.002952933 0.9999992 -9.07023e-4 9.6571e-4 0.9999992 -9.86291e-4 -7.55118e-4 1 -1.74671e-4 -1.52915e-4 0.9999991 -6.53354e-4 -0.001233816 1 -2.06881e-4 2.07352e-4 0.9999933 -0.003466129 -0.00117439 1 -5.83341e-5 -9.59567e-6 0.9994828 0.01152926 0.03002363 0.9999908 2.14489e-4 -0.00430721 0.9998007 0.01875895 -0.006833493 0.9997709 -0.01764625 -0.01211607 0.9998486 0.009927511 -0.01429122 0.9998576 0.01041346 -0.0132898 -6.31074e-5 -0.9526074 -0.3042027 -0.00220561 -0.9463894 -0.3230208 0.001464247 -0.9967995 0.07992941 -0.002943336 -0.9927265 0.1203562 0.002130031 -0.8192404 0.5734463 -0.001011192 -0.8048003 0.5935449 9.10885e-4 -0.4450377 0.8955115 -0.003577768 -0.4075273 0.913186 0.005535423 -0.02013778 0.999782 -0.006345868 0.1031782 0.9946427 0.004542529 0.4597591 0.8880321 -0.00720191 0.5718779 0.8203072 0.009456038 0.799973 0.5999616 -0.01018208 0.9389551 0.3438891 0.005403578 0.9872622 0.15901 -2.60737e-4 0.9685253 -0.248915 -0.00473994 0.9768127 -0.2140437 0.002053678 0.6959988 -0.7180401 -0.005716979 0.6508029 -0.7592252 0.006801486 0.276735 -0.9609223 -0.005221307 0.166988 -0.9859452 -6.50212e-4 -0.2617961 -0.965123 0.004479229 -0.3031473 -0.9529332 -0.003469645 -0.6690404 -0.743218 0.002539098 -0.7092723 -0.7049301 1 2.59511e-5 0 1 1.18211e-5 0 1 -6.66758e-6 0 1 -2.56075e-5 0 1 -3.40253e-6 0 1 1.25402e-5 0 1 -1.20206e-6 0 1 4.3838e-7 0 1 -3.15635e-7 0 1 8.16259e-7 0 1 3.18121e-6 0 1 -1.08218e-6 0 1 -1.10102e-5 0 1 -6.6826e-7 0 1 5.25984e-6 0 1 -4.44837e-7 0 1 -2.72372e-7 0 1 1.14329e-6 0 1 -2.22775e-6 0 1 -6.36614e-6 0 1 5.22756e-6 0 1 -2.98363e-6 0 1 -8.701e-6 0 1 1.88866e-6 0 1 3.33489e-6 0 1 -5.17143e-6 0 1 5.23593e-7 0 1 1.35123e-6 0 1 -5.74587e-6 0 1 -1.81954e-6 0 1 8.87679e-6 0 1 -8.59975e-6 0 1 3.71521e-6 0 1 3.86551e-6 0 1 -7.03584e-6 0 1 -6.16114e-6 0 1 5.03213e-6 0 1 6.55833e-6 0 1 -2.10019e-6 0 1 1.46879e-6 0 1 -1.48748e-6 0 1 -6.44527e-6 0 1 3.77115e-6 0 1 -7.19907e-7 0 1 -6.21129e-7 0 1 -3.41673e-7 0 1 3.21244e-6 0 1 3.45151e-6 0 1 -3.16599e-6 0 1 -1.0761e-6 0 1 6.70024e-7 0 1 7.456e-7 0 1 -1.06161e-6 0 1 5.19745e-6 0 1 -2.17341e-6 0 1 5.66685e-6 0 1 -6.98784e-6 0 1 9.93469e-6 0 1 3.36734e-6 0 1 -9.29814e-6 0 1 4.217e-7 0 0.02304643 -0.8152866 0.5785989 -0.01615667 -0.8939989 0.4477779 0.01585274 -0.9868378 0.1609349 -0.02306199 -0.999513 -0.02102112 0.02524441 -0.9587672 -0.2830692 -0.0242955 -0.8423913 -0.5383184 0.01948523 -0.7185416 -0.695211 -0.01599943 -0.5182903 -0.8550551 0.02326869 -0.2975608 -0.9544193 -0.01456308 -0.1615169 -0.9867626 -0.00138837 0.2558566 -0.9667139 0.03503924 0.3564963 -0.9336395 -0.03110855 0.6311227 -0.775059 0.02605617 0.8725627 -0.4878069 -0.0200231 0.9370624 -0.3485876 0.02447295 0.9995233 0.01882612 -0.02676957 0.9811981 0.1911376 0.02073621 0.8177938 0.5751377 -0.009415268 0.7599205 0.6499479 0.008055984 0.3859736 0.9224748 0.020536 0.4124726 0.9107386 -0.03135889 -0.03242212 0.9989822 0.0443378 -0.3005911 0.952722 -0.03199797 -0.5548407 0.8313411 0.01904636 -0.7206541 0.6930331 -0.03321975 -0.8313996 0.5546812 0.03748774 -0.9716221 0.2335489 -0.03748625 -0.9974166 -0.06127941 0.03266739 -0.9162139 -0.3993558 -0.01520109 -0.8379452 -0.5455427 0.007621228 -0.5102557 -0.8599891 -9.65032e-6 -0.5250101 -0.851096 0.006478846 -0.02928233 -0.9995502 -0.01770639 0.04497545 -0.9988312 0.01877945 0.3800824 -0.924762 -0.01728397 0.5150483 -0.856987 0.01194226 0.8015215 -0.5978468 -0.00673902 0.7717562 -0.6358829 0.01106566 0.9590706 -0.2829511 -0.01027083 0.9792904 -0.2022002 -0.01192772 0.9881501 0.1530262 0.007606565 0.9801092 0.1983136 0.02264064 0.7944389 0.606922 -0.03599357 0.6728958 0.7388612 0.03660434 0.3451989 0.9378155 -0.03050136 0.1154748 0.992842 0.01960253 -0.279203 0.9600321 -0.0126003 -0.374853 0.9269987 -0.01751518 -0.9157188 0.4014381 -0.00906521 -0.9240897 0.3820682 0.02732175 -0.9993911 -0.02170348 -0.0351774 -0.9677599 -0.2494063 0.02827644 -0.8419563 -0.5388042 -0.01787841 -0.7190834 -0.6946939 0.01043444 -0.4600461 -0.8878338 -0.01256012 -0.3765385 -0.9263159 0.02365535 -0.04454267 -0.9987275 -0.02912265 0.1498759 -0.9882759 0.02437812 0.5127463 -0.858194 -0.008343756 0.5981406 -0.8013478 5.96328e-4 0.8983616 -0.4392565 -0.008472263 0.8890264 -0.4577775 0.02253234 0.9995688 0.01882684 -0.02162903 0.9893925 0.1436483 0.008046567 0.8142566 0.5804494 -5.56271e-4 0.826045 0.5636041 0.008418023 0.4767242 0.8790127 -0.008793175 0.4330126 0.9013451 0.01477003 -0.0681886 0.9975632 2.36409e-4 -0.03244268 0.9994736 -0.01777172 -0.5550183 0.8316484 0.01765227 -0.634693 0.7725628 -1.59993e-4 -0.8990817 0.437781 0.001810431 -0.9015369 0.4326987 0.005014598 -0.9997947 0.01963484 -0.009750664 -0.999731 -0.02104675 0.006599485 -0.8542967 -0.5197438 0.005606472 -0.852967 -0.5219348 -0.01021569 -0.5637982 -0.8258494 0.02628558 -0.4636964 -0.8856042 -0.03065919 -0.07083868 -0.9970166 0.03059363 0.1657912 -0.9856863 -0.02743762 0.4257783 -0.9044116 0.03679394 0.6812278 -0.7311463 -0.02909344 0.8473073 -0.5303056 0.003115117 0.9807636 -0.1951751 0.02227371 0.9884334 -0.1500112 0.003478825 0.9464278 0.3228969 -0.003013968 0.9515511 0.3074761 0.005418956 0.6076782 0.794165 -0.003510713 0.6250218 0.7805995 -0.006273865 0.1806469 0.983528 0.02315545 0.08899021 0.9957634 -0.02851551 -0.263881 0.9641337 0.02890157 -0.5405065 0.8408433 -0.008749842 -0.6438146 0.7651315 -0.005760014 0.7514026 -0.659819 -0.001891732 0.8672576 -0.4978563 0.005262017 0.8506738 -0.5256675 -1.81537e-4 0.9487128 -0.3161392 0.001944363 0.9514971 -0.3076519 -0.001792252 0.9925425 -0.1218864 0.001785695 0.9944766 -0.1049435 -0.001792311 0.9970142 0.07719892 0.005364179 0.9937884 0.1111574 -0.006243467 0.9662594 0.2574955 0.006448388 0.9235602 0.3833995 -2.08902e-4 0.9328703 0.3602124 0.001617848 0.8519585 0.5236068 -0.003147482 0.8386805 0.5446147 0.003463447 0.7308893 0.6824874 0.001710236 0.725455 0.6882675 -0.004667162 0.6277331 0.7784147 0.008741676 0.5395808 0.8418885 -0.002529025 0.489452 0.8720266 -0.004554927 0.3641358 0.9313348 0.007471203 0.2917032 0.9564798 -0.005469381 0.1947953 0.9808288 0.005339205 0.08235245 0.9965891 -0.003456354 0.01279813 0.9999122 0.003301084 -0.1176376 0.9930512 0.001640498 -0.1256221 0.9920769 -0.0045951 -0.2980169 0.9545496 0.007066071 -0.356177 0.9343919 -0.007474839 -0.4909611 0.8711494 0.009888887 -0.5761461 0.817287 -0.009554445 -0.6877228 0.7259106 0.006620526 -0.7694182 0.6387112 -0.004851579 -0.8248333 0.5653553 0.004722774 -0.872996 0.4877046 -0.003941714 -0.9137251 0.4063139 0.004884481 -0.9546176 0.2977944 0.001311063 -0.9595556 0.2815163 -0.005470573 -0.9947668 0.1020257 0.008741855 -0.9995577 0.02842867 -0.006648659 -0.9953435 -0.09616237 -0.004627287 -0.9584963 -0.2850677 0.005200088 -0.9773313 -0.2116516 0.005082786 -0.9256068 -0.3784525 -0.004554867 -0.8857427 -0.4641544 0.006043016 -0.8280147 -0.560674 -0.004460334 -0.79613 -0.6051092 8.82077e-4 -0.6355867 -0.7720291 0.003877341 -0.6436117 -0.7653424 -0.003649652 -0.4651909 -0.885203 0.006668984 -0.4202046 -0.9074049 -0.006344735 -0.2702692 -0.9627639 0.005265533 -0.20481 -0.9787876 -0.003320217 -0.05664753 -0.9983888 0.001870214 -0.02650582 -0.9996469 -0.002659857 0.1310988 -0.9913657 0.002960324 0.1587871 -0.9873085 -0.002284765 0.3356115 -0.9419978 0.002107262 0.3561412 -0.9344298 -0.002179324 0.4913247 -0.8709739 0.004242777 0.5298194 -0.8480999 -0.004741728 0.6152952 -0.7882826 0.006732285 0.6988843 -0.7152031 1 -1.95039e-5 0 1 -5.52605e-6 0 1 9.27457e-6 0 1 1.17251e-6 0 1 -1.32355e-5 0 1 1.33535e-5 0 1 -1.24332e-5 0 1 -2.76655e-5 0 1 4.62106e-6 0 1 1.59139e-5 0 1 -1.19586e-5 0 1 -2.13366e-6 0 1 -2.02164e-5 0 1 2.35361e-5 0 1 3.32029e-6 0 1 -7.5698e-6 0 1 -8.57111e-6 0 1 1.93989e-6 0 -0.006300389 0.7570505 -0.6533262 0.005113363 0.943023 -0.3326883 -0.00466752 0.9953984 -0.09571015 0.005472719 0.9587665 0.2841425 -0.004360735 0.9055589 0.4241982 0.004219949 0.4903421 0.8715198 -0.003250837 0.4082002 0.9128867 0.002720952 -0.1442242 0.9895414 -0.006718754 -0.2924938 0.9562438 0.008006811 -0.6464427 0.7629206 -0.007731556 -0.8870165 0.4616731 0.005255818 -0.9737989 0.2273502 -0.005720853 -0.9852631 -0.1709508 0.007370471 -0.9224563 -0.3860312 -0.008473813 -0.6141027 -0.7891808 0.005439221 -0.4320394 -0.9018384 -0.003987133 0.07997322 -0.9967891 -0.002261519 0.1014494 -0.9948381 0.004545509 0.6307035 -0.7760108 -1 -7.52346e-7 0 -1 5.16924e-6 0 -1 -3.26771e-6 0 -1 3.55038e-6 0 -1 -1.02365e-5 0 -0.002487599 0.8611017 -0.5084268 0.001984894 0.8869208 -0.4619174 0.004233717 0.999558 0.02942645 -0.008026957 0.9724247 0.2330792 0.005687534 0.8333775 0.5526751 -0.006712317 0.5795477 0.8149107 0.005862951 0.391768 0.9200454 -0.005568802 -0.1361804 0.9906684 0.003027319 -0.2502092 0.9681871 -0.001882493 -0.7430924 0.6691863 -0.001494705 -0.74656 0.6653164 0.002738654 -0.9740488 0.2263215 -0.002684116 -0.9909024 0.1345553 -6.72979e-4 -0.9440042 -0.3299326 0.001543045 -0.9340846 -0.3570485 0.001690924 -0.6290244 -0.7773839 -0.00184518 -0.5853348 -0.8107897 0.001109421 -0.1560801 -0.9877439 -0.002560138 -0.09189027 -0.9957659 0.004995942 0.376083 -0.9265725 -0.00311166 0.4836045 -0.8752811 -1 -3.13806e-6 0 -1 1.33257e-5 0 -1 -2.40166e-5 0 -1 -7.09494e-7 0 0.007370114 0.7985354 -0.6019027 -0.005670368 0.9963772 -0.08485478 0.004170596 0.9985252 0.05413198 -0.003681123 0.8336281 0.5523141 0.004043459 0.753053 0.6579477 -0.004555702 0.4288755 0.9033522 0.007832705 0.2165099 0.976249 -0.007283568 -0.1847322 0.982762 0.004881918 -0.5803079 0.8143826 0.008171737 -0.6080066 0.79389 -0.006819903 -0.9545133 0.2980904 0.007218599 -0.99437 0.1057177 -0.00492078 -0.9233883 -0.3838357 0.002321839 -0.868438 -0.4957926 -0.001389205 -0.5714296 -0.82065 0.002197682 -0.5174562 -0.8557069 -0.004378795 -0.06316238 -0.9979937 0.008008658 0.1135652 -0.9934983 -0.009059309 0.6497603 -0.7600852 -1 1.06459e-5 0 -1 -2.00965e-5 0 -1 1.82435e-6 0 0.007095694 0.7778234 -0.6284429 -0.006240487 0.9488834 -0.3155652 0.006501913 0.9999694 0.004353523 -0.004512965 0.9774316 0.2112039 0.003929853 0.7586842 0.6514468 -0.002637684 0.6894403 0.7243377 0.003082692 0.2165158 0.9762743 -0.002277255 0.1517305 0.9884193 7.40615e-4 -0.5445306 0.8387408 8.36995e-4 -0.5453792 0.8381891 -6.37503e-4 -0.9465685 0.3225023 -0.001335859 -0.9435942 0.3311018 0.002785682 -0.9759771 -0.2178555 -4.61599e-4 -0.9659657 -0.2586698 -0.004717588 -0.6694989 -0.7427981 0.009719848 -0.5227931 -0.8524042 -0.007667303 -0.005856037 -0.9999535 0.006437301 0.2519404 -0.9677214 -0.005766868 0.5609167 -0.8278522 -1 4.31868e-6 0 -1 -4.62027e-5 0 -1 1.0001e-6 0 -1 4.7975e-6 0 -0.9525958 0.2380373 -0.1894722 -0.9484533 0.2381363 -0.2091112 -0.9453742 0.2827154 -0.1622948 -0.9499238 0.2964556 -0.09878706 -0.9503666 0.2956288 -0.09699058 -0.9459896 0.3217798 -0.03951525 -0.9519727 0.3061826 -3.29643e-4 -0.946689 0.3211876 0.0248695 -0.9524106 0.2871825 0.1021783 -0.9478101 0.3080846 0.08209627 -0.9488222 0.2916739 0.1210899 -0.9450481 0.2741925 0.1780527 -0.9522624 0.2306711 0.1999682 -0.9490538 0.2286051 0.2168793 -0.9465081 0.2025551 0.2511855 -0.9513475 0.1559572 0.2657358 -0.9497077 0.1531046 0.2731565 -0.9459359 0.1188259 0.3018043 -0.9501495 0.06030476 0.3059073 -0.9494294 0.063021 0.3075911 -0.9473246 0.003913938 0.3202512 -0.9513814 -0.02593636 0.3069216 -0.9486401 -0.03897547 0.3139476 -0.9451958 -0.09772193 0.3115372 -0.9519734 -0.1284718 0.2779238 -0.9465939 -0.1578603 0.2811406 -0.9506268 -0.2067138 0.2314699 -0.9477009 -0.219873 0.2313418 -0.9466888 -0.2657228 0.1821315 -0.9538374 -0.2651089 0.1411085 -0.9482545 -0.2901177 0.1290166 -0.9440428 -0.3164857 0.0928446 -0.9482629 -0.3158296 0.03239208 -0.9529973 -0.3025894 0.01535588 -0.9461269 -0.3223374 -0.03070098 -0.950377 -0.2963777 -0.09457176 -0.9522724 -0.2923579 -0.08777499 -0.9444098 -0.2912372 -0.1525486 -0.9473903 -0.2553715 -0.1929691 -0.9557611 -0.2157825 -0.1998969 -0.9450515 -0.2076727 -0.252487 -0.9452199 -0.1511586 -0.2893277 -0.9533795 -0.1078814 -0.2818317 -0.9468254 -0.08679902 -0.3098188 -0.9484567 -0.01883918 -0.3163464 -0.9535434 0.002321958 -0.3012472 -0.944623 0.04389876 -0.3252083 -0.9446232 0.1093001 -0.3094195 -0.9544602 0.138469 -0.2642577 -0.9515498 0.1518354 -0.2673934 -0.9455358 0.2000066 -0.2568259 -1 -4.68205e-5 2.68312e-5 -1 -1.10445e-5 4.86485e-5 -1 1.16812e-5 4.55229e-6 -1 -4.32936e-5 3.5291e-5 -1 3.7311e-5 -7.07294e-6 -1 2.37337e-5 1.70311e-5 -1 4.73049e-6 5.25782e-5 -1 -1.4283e-5 2.93974e-6 -1 3.78764e-5 1.04966e-6 -1 1.91974e-6 1.18301e-5 -1 7.5822e-6 2.21884e-5 -1 -1.00295e-5 1.00085e-5 -1 2.16771e-5 2.14109e-5 -1 8.75833e-6 2.45341e-5 -1 -3.80824e-6 0 -1 -4.23445e-6 0 -1 -7.65275e-6 6.74213e-6 -1 -3.67078e-6 7.64707e-6 -1 -1.54718e-6 2.79892e-5 -1 1.80984e-6 0 -1 5.05112e-6 3.75273e-6 -1 6.46215e-6 0 -1 -6.71731e-6 1.65788e-6 -1 -4.0045e-6 0 -1 -8.43971e-6 0 -1 5.67617e-6 2.80979e-7 -1 6.42619e-7 0 -1 -5.57179e-6 -5.38654e-6 -1 2.00039e-5 -3.46866e-5 -1 -1.10699e-5 -2.00215e-6 -1 2.67252e-5 -2.11214e-5 -1 -5.72708e-6 -1.29652e-5 -1 -7.37688e-6 -1.20265e-5 -1 -3.14948e-7 0 -1 2.30896e-6 0 -1 2.63932e-6 0 -1 1.04948e-6 0 -1 -4.33274e-6 0 -1 -5.38752e-7 0 -1 4.15562e-5 6.94787e-6 -1 -2.00614e-6 -8.22857e-6 -1 -2.78608e-6 -3.4755e-6 -1 -2.15037e-5 -6.71128e-7 -1 6.3046e-6 -5.69238e-6 -1 6.90987e-6 9.58734e-6 -1 -7.71545e-7 -8.39386e-6 -1 3.75326e-6 -6.29633e-7 -1 -9.29903e-6 -3.57073e-6 -1 -9.39999e-6 -2.05113e-5 -1 1.38755e-5 -1.18085e-5 -1 -8.1404e-6 -3.26313e-6 -1 -7.76443e-7 -3.29476e-6 -1 1.80178e-5 -7.41893e-6 -1 -8.40027e-6 -3.53915e-6 + + + + + + + + + + + + + + +

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

+
+ + + +

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

+
+ + + +

2026 3961 2024 3961 2025 3961 2024 3962 2026 3962 2027 3962 2023 3963 2024 3963 2027 3963 2023 3964 2027 3964 2028 3964 2031 3965 2029 3965 2030 3965 2031 3966 2030 3966 2032 3966 2030 3967 2028 3967 2027 3967 2032 3968 2030 3968 2027 3968 2036 3969 2034 3969 2035 3969 2039 3970 2037 3970 2038 3970 2040 3971 2039 3971 2038 3971 2037 3972 2039 3972 2026 3972 2037 3973 2026 3973 2025 3973 2043 3974 2042 3974 2041 3974 2045 3975 2042 3975 2043 3975 2045 3976 2044 3976 2042 3976 2049 3977 2046 3977 2047 3977 2048 3978 2049 3978 2047 3978 2049 3979 2044 3979 2045 3979 2049 3980 2048 3980 2044 3980 2030 3981 2029 3981 2046 3981 2030 3982 2046 3982 2049 3982 2053 3983 2051 3983 2052 3983 2041 3984 2052 3984 2051 3984 2043 3985 2041 3985 2051 3985 2043 3986 2051 3986 2050 3986 2056 3987 2055 3987 2054 3987 2058 3988 2059 3988 2060 3988 2046 3989 2057 3989 2058 3989 2047 3990 2046 3990 2058 3990 2047 3991 2058 3991 2060 3991 2048 3992 2047 3992 2060 3992 2064 3993 2061 3993 2062 3993 2064 3994 2063 3994 2061 3994 2065 3995 2064 3995 2062 3995 2057 3996 2065 3996 2062 3996 2058 3997 2057 3997 2062 3997 2059 3998 2058 3998 2062 3998 2059 3999 2062 3999 2061 3999 2064 4000 2065 4000 2056 4000 2064 4001 2056 4001 2054 4001 2063 4002 2064 4002 2054 4002 2061 4003 2053 4003 2052 4003 2061 4004 2063 4004 2053 4004 2059 4005 2041 4005 2042 4005 2060 4006 2059 4006 2042 4006 2056 4007 2040 4007 2038 4007 2055 4008 2056 4008 2038 4008 2055 4009 2038 4009 2037 4009 2054 4010 2036 4010 2035 4010 2054 4011 2055 4011 2036 4011 2053 4012 2035 4012 2034 4012 2051 4013 2053 4013 2034 4013 2051 4014 2034 4014 2033 4014 2050 4015 2051 4015 2033 4015 2040 4016 2029 4016 2031 4016 2039 4017 2040 4017 2031 4017 2039 4018 2031 4018 2032 4018 2034 4019 2036 4019 2025 4019 2034 4020 2025 4020 2024 4020 2033 4021 2034 4021 2024 4021 2033 4022 2024 4022 2023 4022 2030 4023 2045 4023 2028 4023 2030 4024 2049 4024 2045 4024 2026 4025 2032 4025 2027 4025 2039 4026 2032 4026 2026 4026 2055 4027 2037 4027 2025 4027 2055 4028 2025 4028 2036 4028 2048 4029 2042 4029 2044 4029 2048 4030 2060 4030 2042 4030 2040 4031 2067 4031 2066 4031 2040 4032 2066 4032 2029 4032 2066 4033 2068 4033 2029 4033 2040 4034 2070 4034 2067 4034 2068 4035 2069 4035 2029 4035 2040 4036 2056 4036 2070 4036 2056 4037 2071 4037 2070 4037 2056 4038 2076 4038 2071 4038 2359 4039 2046 4039 2072 4039 2073 4040 2046 4040 2359 4040 2072 4041 2046 4041 2069 4041 2069 4042 2046 4042 2029 4042 2056 4043 2065 4043 2076 4043 2075 4044 2065 4044 2074 4044 2076 4045 2065 4045 2075 4045 2065 4046 2057 4046 2074 4046 2077 4047 2057 4047 2073 4047 2074 4048 2057 4048 2077 4048 2073 4049 2057 4049 2046 4049 2059 4050 2061 4050 2052 4050 2059 4051 2052 4051 2041 4051 2063 4052 2054 4052 2035 4052 2063 4053 2035 4053 2053 4053 2079 4054 2081 4054 2080 4054 2081 4055 2082 4055 2080 4055 2081 4056 2083 4056 2082 4056 2083 4057 2084 4057 2082 4057 2083 4058 2085 4058 2084 4058 2085 4059 2086 4059 2084 4059 2085 4060 2087 4060 2086 4060 2087 4061 2088 4061 2086 4061 2087 4062 2089 4062 2088 4062 2089 4063 2090 4063 2088 4063 2089 4064 2091 4064 2090 4064 2091 4065 2092 4065 2090 4065 2091 4066 2093 4066 2092 4066 2093 4067 2094 4067 2092 4067 2093 4068 2095 4068 2094 4068 2095 4069 2096 4069 2094 4069 2095 4070 2097 4070 2096 4070 2097 4071 2098 4071 2099 4071 2098 4072 2100 4072 2099 4072 2100 4073 2101 4073 2099 4073 2101 4074 2103 4074 2102 4074 2103 4075 2104 4075 2102 4075 2104 4076 2105 4076 2102 4076 2104 4077 2106 4077 2105 4077 2106 4078 2107 4078 2105 4078 2106 4079 2108 4079 2107 4079 2106 4080 2109 4080 2108 4080 2109 4081 2110 4081 2108 4081 2111 4082 2112 4082 2110 4082 2111 4083 2113 4083 2112 4083 2112 4084 2113 4084 2114 4084 2113 4085 2115 4085 2114 4085 2113 4086 2116 4086 2115 4086 2116 4087 2117 4087 2115 4087 2116 4088 2118 4088 2117 4088 2118 4089 2119 4089 2117 4089 2118 4090 2120 4090 2119 4090 2120 4091 2121 4091 2119 4091 2120 4092 2122 4092 2121 4092 2122 4093 2123 4093 2121 4093 2122 4094 2124 4094 2123 4094 2124 4095 2125 4095 2123 4095 2124 4096 2126 4096 2125 4096 2126 4097 2127 4097 2125 4097 2126 4098 2128 4098 2127 4098 2127 4099 2128 4099 2129 4099 2129 4100 2131 4100 2130 4100 2131 4101 2132 4101 2130 4101 2132 4102 2134 4102 2133 4102 2134 4103 2135 4103 2133 4103 2135 4104 2136 4104 2133 4104 2135 4105 2137 4105 2136 4105 2138 4106 2139 4106 2137 4106 2138 4107 2140 4107 2139 4107 2138 4108 2141 4108 2140 4108 2141 4109 2142 4109 2140 4109 2142 4110 2144 4110 2143 4110 2144 4111 2145 4111 2143 4111 2147 4112 2149 4112 2148 4112 2149 4113 2150 4113 2148 4113 2150 4114 2151 4114 2148 4114 2150 4115 2152 4115 2151 4115 2152 4116 2153 4116 2151 4116 2152 4117 2154 4117 2153 4117 2152 4118 2155 4118 2154 4118 2155 4119 2156 4119 2154 4119 2155 4120 2157 4120 2156 4120 2157 4121 2158 4121 2156 4121 2157 4122 2159 4122 2158 4122 2158 4123 2159 4123 2160 4123 2159 4124 2161 4124 2160 4124 2161 4125 2162 4125 2160 4125 2161 4126 2163 4126 2162 4126 2164 4127 2165 4127 2163 4127 2164 4128 2166 4128 2165 4128 2166 4129 2167 4129 2165 4129 2166 4130 2168 4130 2167 4130 2166 4131 2169 4131 2168 4131 2169 4132 2170 4132 2168 4132 2169 4133 2171 4133 2170 4133 2171 4134 2172 4134 2170 4134 2172 4135 2173 4135 2170 4135 2172 4136 2174 4136 2173 4136 2173 4137 2174 4137 2175 4137 2176 4138 2178 4138 2177 4138 2178 4139 2179 4139 2177 4139 2178 4140 2180 4140 2179 4140 2180 4141 2181 4141 2179 4141 2180 4142 2182 4142 2181 4142 2182 4143 2183 4143 2181 4143 2183 4144 2184 4144 2181 4144 2183 4145 2185 4145 2184 4145 2187 4146 2188 4146 2186 4146 2187 4147 2189 4147 2188 4147 2189 4148 2190 4148 2188 4148 2189 4149 2191 4149 2190 4149 2190 4150 2191 4150 2192 4150 2191 4151 2193 4151 2192 4151 2193 4152 2195 4152 2194 4152 2195 4153 2196 4153 2194 4153 2195 4154 2197 4154 2196 4154 2197 4155 2198 4155 2196 4155 2197 4156 2199 4156 2198 4156 2199 4157 2200 4157 2198 4157 2199 4158 2201 4158 2200 4158 2203 4159 2204 4159 2202 4159 2203 4160 2205 4160 2204 4160 2204 4161 2205 4161 2206 4161 2205 4162 2207 4162 2206 4162 2207 4163 2208 4163 2206 4163 2207 4164 2209 4164 2208 4164 2209 4165 2210 4165 2208 4165 2211 4166 2213 4166 2212 4166 2213 4167 2214 4167 2212 4167 2213 4168 2215 4168 2214 4168 2215 4169 2216 4169 2214 4169 2216 4170 2217 4170 2214 4170 2216 4171 2218 4171 2217 4171 2218 4172 2220 4172 2219 4172 2219 4173 2221 4173 2222 4173 2220 4174 2221 4174 2219 4174 2221 4175 2223 4175 2222 4175 2223 4176 2224 4176 2222 4176 2223 4177 2225 4177 2224 4177 2225 4178 2226 4178 2224 4178 2225 4179 2227 4179 2226 4179 2227 4180 2228 4180 2226 4180 2230 4181 2231 4181 2229 4181 2230 4182 2232 4182 2231 4182 2230 4183 2233 4183 2232 4183 2233 4184 2234 4184 2232 4184 2233 4185 2235 4185 2234 4185 2233 4186 2236 4186 2235 4186 2236 4187 2237 4187 2235 4187 2237 4188 2238 4188 2235 4188 2237 4189 2239 4189 2238 4189 2237 4190 2067 4190 2239 4190 2067 4191 2240 4191 2239 4191 2067 4192 2070 4192 2240 4192 2070 4193 2241 4193 2240 4193 2070 4194 2071 4194 2241 4194 2071 4195 2242 4195 2241 4195 2071 4196 2243 4196 2242 4196 2071 4197 2076 4197 2243 4197 2076 4198 2075 4198 2243 4198 2247 4199 2248 4199 2246 4199 2249 4200 2248 4200 2247 4200 2249 4201 2250 4201 2248 4201 2251 4202 2250 4202 2249 4202 2252 4203 2078 4203 2251 4203 2251 4204 2078 4204 2250 4204 2252 4205 2079 4205 2078 4205 2253 4206 2079 4206 2252 4206 2253 4207 2081 4207 2079 4207 2254 4208 2081 4208 2253 4208 2255 4209 2081 4209 2254 4209 2255 4210 2083 4210 2081 4210 2255 4211 2085 4211 2083 4211 2256 4212 2085 4212 2255 4212 2256 4213 2087 4213 2085 4213 2257 4214 2087 4214 2256 4214 2258 4215 2087 4215 2257 4215 2258 4216 2089 4216 2087 4216 2259 4217 2089 4217 2258 4217 2259 4218 2091 4218 2089 4218 2260 4219 2091 4219 2259 4219 2261 4220 2091 4220 2260 4220 2261 4221 2093 4221 2091 4221 2262 4222 2093 4222 2261 4222 2262 4223 2095 4223 2093 4223 2263 4224 2095 4224 2262 4224 2264 4225 2095 4225 2263 4225 2264 4226 2097 4226 2095 4226 2265 4227 2097 4227 2264 4227 2265 4228 2098 4228 2097 4228 2266 4229 2098 4229 2265 4229 2266 4230 2100 4230 2098 4230 2267 4231 2100 4231 2266 4231 2267 4232 2101 4232 2100 4232 2268 4233 2101 4233 2267 4233 2268 4234 2103 4234 2101 4234 2269 4235 2103 4235 2268 4235 2269 4236 2104 4236 2103 4236 2270 4237 2104 4237 2269 4237 2271 4238 2104 4238 2270 4238 2271 4239 2106 4239 2104 4239 2272 4240 2106 4240 2271 4240 2273 4241 2106 4241 2272 4241 2273 4242 2109 4242 2106 4242 2273 4243 2110 4243 2109 4243 2274 4244 2110 4244 2273 4244 2274 4245 2111 4245 2110 4245 2275 4246 2111 4246 2274 4246 2275 4247 2113 4247 2111 4247 2276 4248 2113 4248 2275 4248 2277 4249 2113 4249 2276 4249 2277 4250 2116 4250 2113 4250 2278 4251 2116 4251 2277 4251 2279 4252 2116 4252 2278 4252 2279 4253 2118 4253 2116 4253 2280 4254 2118 4254 2279 4254 2280 4255 2120 4255 2118 4255 2281 4256 2120 4256 2280 4256 2281 4257 2122 4257 2120 4257 2282 4258 2122 4258 2281 4258 2283 4259 2122 4259 2282 4259 2283 4260 2124 4260 2122 4260 2284 4261 2124 4261 2283 4261 2285 4262 2124 4262 2284 4262 2285 4263 2126 4263 2124 4263 2286 4264 2126 4264 2285 4264 2286 4265 2128 4265 2126 4265 2287 4266 2128 4266 2286 4266 2287 4267 2129 4267 2128 4267 2288 4268 2129 4268 2287 4268 2288 4269 2131 4269 2129 4269 2289 4270 2131 4270 2288 4270 2289 4271 2132 4271 2131 4271 2290 4272 2132 4272 2289 4272 2290 4273 2134 4273 2132 4273 2291 4274 2134 4274 2290 4274 2291 4275 2135 4275 2134 4275 2292 4276 2135 4276 2291 4276 2293 4277 2137 4277 2292 4277 2292 4278 2137 4278 2135 4278 2294 4279 2138 4279 2293 4279 2293 4280 2138 4280 2137 4280 2295 4281 2138 4281 2294 4281 2295 4282 2141 4282 2138 4282 2296 4283 2141 4283 2295 4283 2296 4284 2142 4284 2141 4284 2297 4285 2142 4285 2296 4285 2297 4286 2144 4286 2142 4286 2298 4287 2144 4287 2297 4287 2298 4288 2145 4288 2144 4288 2299 4289 2145 4289 2298 4289 2299 4290 2146 4290 2145 4290 2300 4291 2146 4291 2299 4291 2300 4292 2147 4292 2146 4292 2301 4293 2147 4293 2300 4293 2301 4294 2149 4294 2147 4294 2302 4295 2149 4295 2301 4295 2302 4296 2150 4296 2149 4296 2303 4297 2150 4297 2302 4297 2303 4298 2152 4298 2150 4298 2304 4299 2152 4299 2303 4299 2305 4300 2152 4300 2304 4300 2305 4301 2155 4301 2152 4301 2306 4302 2155 4302 2305 4302 2306 4303 2157 4303 2155 4303 2307 4304 2157 4304 2306 4304 2308 4305 2157 4305 2307 4305 2308 4306 2159 4306 2157 4306 2309 4307 2159 4307 2308 4307 2309 4308 2161 4308 2159 4308 2310 4309 2161 4309 2309 4309 2311 4310 2161 4310 2310 4310 2311 4311 2163 4311 2161 4311 2312 4312 2163 4312 2311 4312 2312 4313 2164 4313 2163 4313 2313 4314 2164 4314 2312 4314 2313 4315 2166 4315 2164 4315 2314 4316 2166 4316 2313 4316 2315 4317 2166 4317 2314 4317 2315 4318 2169 4318 2166 4318 2316 4319 2169 4319 2315 4319 2317 4320 2171 4320 2316 4320 2316 4321 2171 4321 2169 4321 2318 4322 2171 4322 2317 4322 2318 4323 2172 4323 2171 4323 2319 4324 2174 4324 2318 4324 2318 4325 2174 4325 2172 4325 2320 4326 2174 4326 2319 4326 2320 4327 2175 4327 2174 4327 2320 4328 2176 4328 2175 4328 2321 4329 2176 4329 2320 4329 2321 4330 2178 4330 2176 4330 2322 4331 2178 4331 2321 4331 2323 4332 2178 4332 2322 4332 2323 4333 2180 4333 2178 4333 2324 4334 2180 4334 2323 4334 2324 4335 2182 4335 2180 4335 2325 4336 2182 4336 2324 4336 2325 4337 2183 4337 2182 4337 2326 4338 2183 4338 2325 4338 2327 4339 2183 4339 2326 4339 2327 4340 2185 4340 2183 4340 2328 4341 2185 4341 2327 4341 2328 4342 2186 4342 2185 4342 2329 4343 2186 4343 2328 4343 2329 4344 2187 4344 2186 4344 2329 4345 2189 4345 2187 4345 2330 4346 2189 4346 2329 4346 2331 4347 2189 4347 2330 4347 2331 4348 2191 4348 2189 4348 2332 4349 2191 4349 2331 4349 2332 4350 2193 4350 2191 4350 2333 4351 2193 4351 2332 4351 2333 4352 2195 4352 2193 4352 2334 4353 2195 4353 2333 4353 2335 4354 2197 4354 2334 4354 2334 4355 2197 4355 2195 4355 2336 4356 2197 4356 2335 4356 2336 4357 2199 4357 2197 4357 2337 4358 2199 4358 2336 4358 2338 4359 2199 4359 2337 4359 2338 4360 2201 4360 2199 4360 2338 4361 2202 4361 2201 4361 2339 4362 2202 4362 2338 4362 2339 4363 2203 4363 2202 4363 2340 4364 2203 4364 2339 4364 2340 4365 2205 4365 2203 4365 2341 4366 2205 4366 2340 4366 2341 4367 2207 4367 2205 4367 2342 4368 2207 4368 2341 4368 2342 4369 2209 4369 2207 4369 2343 4370 2209 4370 2342 4370 2344 4371 2209 4371 2343 4371 2344 4372 2210 4372 2209 4372 2345 4373 2210 4373 2344 4373 2345 4374 2211 4374 2210 4374 2346 4375 2211 4375 2345 4375 2346 4376 2213 4376 2211 4376 2347 4377 2213 4377 2346 4377 2347 4378 2215 4378 2213 4378 2348 4379 2215 4379 2347 4379 2348 4380 2216 4380 2215 4380 2349 4381 2216 4381 2348 4381 2350 4382 2216 4382 2349 4382 2350 4383 2218 4383 2216 4383 2351 4384 2218 4384 2350 4384 2351 4385 2220 4385 2218 4385 2352 4386 2220 4386 2351 4386 2352 4387 2221 4387 2220 4387 2353 4388 2221 4388 2352 4388 2353 4389 2223 4389 2221 4389 2354 4390 2223 4390 2353 4390 2355 4391 2223 4391 2354 4391 2355 4392 2225 4392 2223 4392 2356 4393 2225 4393 2355 4393 2356 4394 2227 4394 2225 4394 2357 4395 2227 4395 2356 4395 2357 4396 2228 4396 2227 4396 2357 4397 2229 4397 2228 4397 2358 4398 2229 4398 2357 4398 2358 4399 2230 4399 2229 4399 2359 4400 2230 4400 2358 4400 2072 4401 2230 4401 2359 4401 2072 4402 2233 4402 2230 4402 2069 4403 2233 4403 2072 4403 2069 4404 2236 4404 2233 4404 2068 4405 2236 4405 2069 4405 2066 4406 2237 4406 2068 4406 2068 4407 2237 4407 2236 4407 2066 4408 2067 4408 2237 4408 2088 4409 2360 4409 2086 4409 2090 4410 2360 4410 2088 4410 2090 4411 2361 4411 2360 4411 2092 4412 2361 4412 2090 4412 2094 4413 2244 4413 2092 4413 2092 4414 2244 4414 2361 4414 2094 4415 2245 4415 2244 4415 2096 4416 2245 4416 2094 4416 2096 4417 2247 4417 2245 4417 2097 4418 2247 4418 2096 4418 2097 4419 2249 4419 2247 4419 2099 4420 2249 4420 2097 4420 2099 4421 2251 4421 2249 4421 2101 4422 2251 4422 2099 4422 2101 4423 2252 4423 2251 4423 2102 4424 2252 4424 2101 4424 2102 4425 2362 4425 2252 4425 2102 4426 2253 4426 2362 4426 2105 4427 2253 4427 2102 4427 2105 4428 2254 4428 2253 4428 2105 4429 2255 4429 2254 4429 2107 4430 2255 4430 2105 4430 2107 4431 2256 4431 2255 4431 2108 4432 2256 4432 2107 4432 2108 4433 2257 4433 2256 4433 2110 4434 2257 4434 2108 4434 2110 4435 2258 4435 2257 4435 2110 4436 2259 4436 2258 4436 2112 4437 2259 4437 2110 4437 2112 4438 2260 4438 2259 4438 2114 4439 2260 4439 2112 4439 2114 4440 2363 4440 2260 4440 2115 4441 2363 4441 2114 4441 2115 4442 2261 4442 2363 4442 2117 4443 2261 4443 2115 4443 2117 4444 2262 4444 2261 4444 2117 4445 2263 4445 2262 4445 2119 4446 2263 4446 2117 4446 2119 4447 2264 4447 2263 4447 2119 4448 2265 4448 2264 4448 2121 4449 2265 4449 2119 4449 2121 4450 2266 4450 2265 4450 2123 4451 2266 4451 2121 4451 2123 4452 2267 4452 2266 4452 2123 4453 2364 4453 2267 4453 2125 4454 2364 4454 2123 4454 2127 4455 2269 4455 2125 4455 2125 4456 2269 4456 2364 4456 2127 4457 2270 4457 2269 4457 2129 4458 2270 4458 2127 4458 2129 4459 2271 4459 2270 4459 2130 4460 2271 4460 2129 4460 2130 4461 2272 4461 2271 4461 2132 4462 2273 4462 2130 4462 2130 4463 2273 4463 2272 4463 2133 4464 2273 4464 2132 4464 2133 4465 2274 4465 2273 4465 2133 4466 2275 4466 2274 4466 2136 4467 2275 4467 2133 4467 2137 4468 2275 4468 2136 4468 2137 4469 2277 4469 2275 4469 2139 4470 2277 4470 2137 4470 2139 4471 2278 4471 2277 4471 2140 4472 2278 4472 2139 4472 2140 4473 2279 4473 2278 4473 2140 4474 2280 4474 2279 4474 2142 4475 2280 4475 2140 4475 2142 4476 2365 4476 2280 4476 2143 4477 2365 4477 2142 4477 2143 4478 2281 4478 2365 4478 2145 4479 2281 4479 2143 4479 2145 4480 2283 4480 2281 4480 2146 4481 2283 4481 2145 4481 2146 4482 2284 4482 2283 4482 2147 4483 2284 4483 2146 4483 2147 4484 2285 4484 2284 4484 2148 4485 2285 4485 2147 4485 2148 4486 2286 4486 2285 4486 2151 4487 2287 4487 2148 4487 2148 4488 2287 4488 2286 4488 2151 4489 2288 4489 2287 4489 2153 4490 2288 4490 2151 4490 2154 4491 2288 4491 2153 4491 2154 4492 2289 4492 2288 4492 2156 4493 2289 4493 2154 4493 2156 4494 2290 4494 2289 4494 2156 4495 2291 4495 2290 4495 2158 4496 2291 4496 2156 4496 2158 4497 2293 4497 2291 4497 2160 4498 2293 4498 2158 4498 2160 4499 2294 4499 2293 4499 2162 4500 2294 4500 2160 4500 2162 4501 2295 4501 2294 4501 2163 4502 2295 4502 2162 4502 2163 4503 2296 4503 2295 4503 2165 4504 2296 4504 2163 4504 2165 4505 2297 4505 2296 4505 2167 4506 2297 4506 2165 4506 2167 4507 2299 4507 2297 4507 2168 4508 2299 4508 2167 4508 2168 4509 2366 4509 2299 4509 2170 4510 2366 4510 2168 4510 2170 4511 2300 4511 2366 4511 2170 4512 2301 4512 2300 4512 2173 4513 2301 4513 2170 4513 2173 4514 2302 4514 2301 4514 2173 4515 2303 4515 2302 4515 2175 4516 2303 4516 2173 4516 2175 4517 2304 4517 2303 4517 2176 4518 2304 4518 2175 4518 2176 4519 2305 4519 2304 4519 2177 4520 2305 4520 2176 4520 2177 4521 2306 4521 2305 4521 2179 4522 2306 4522 2177 4522 2179 4523 2307 4523 2306 4523 2181 4524 2307 4524 2179 4524 2181 4525 2308 4525 2307 4525 2181 4526 2309 4526 2308 4526 2184 4527 2309 4527 2181 4527 2184 4528 2310 4528 2309 4528 2185 4529 2310 4529 2184 4529 2185 4530 2311 4530 2310 4530 2186 4531 2311 4531 2185 4531 2186 4532 2312 4532 2311 4532 2188 4533 2312 4533 2186 4533 2188 4534 2313 4534 2312 4534 2190 4535 2313 4535 2188 4535 2190 4536 2314 4536 2313 4536 2192 4537 2314 4537 2190 4537 2192 4538 2315 4538 2314 4538 2193 4539 2315 4539 2192 4539 2193 4540 2316 4540 2315 4540 2193 4541 2317 4541 2316 4541 2194 4542 2317 4542 2193 4542 2194 4543 2318 4543 2317 4543 2196 4544 2318 4544 2194 4544 2196 4545 2319 4545 2318 4545 2198 4546 2319 4546 2196 4546 2198 4547 2367 4547 2319 4547 2198 4548 2320 4548 2367 4548 2200 4549 2320 4549 2198 4549 2200 4550 2321 4550 2320 4550 2201 4551 2321 4551 2200 4551 2201 4552 2322 4552 2321 4552 2202 4553 2322 4553 2201 4553 2204 4554 2322 4554 2202 4554 2204 4555 2324 4555 2322 4555 2204 4556 2325 4556 2324 4556 2206 4557 2325 4557 2204 4557 2206 4558 2326 4558 2325 4558 2208 4559 2326 4559 2206 4559 2208 4560 2327 4560 2326 4560 2208 4561 2328 4561 2327 4561 2210 4562 2328 4562 2208 4562 2210 4563 2368 4563 2328 4563 2211 4564 2368 4564 2210 4564 2211 4565 2329 4565 2368 4565 2212 4566 2329 4566 2211 4566 2212 4567 2330 4567 2329 4567 2212 4568 2331 4568 2330 4568 2214 4569 2331 4569 2212 4569 2214 4570 2332 4570 2331 4570 2217 4571 2333 4571 2214 4571 2214 4572 2333 4572 2332 4572 2218 4573 2333 4573 2217 4573 2218 4574 2334 4574 2333 4574 2219 4575 2334 4575 2218 4575 2219 4576 2335 4576 2334 4576 2219 4577 2336 4577 2335 4577 2222 4578 2336 4578 2219 4578 2222 4579 2337 4579 2336 4579 2222 4580 2369 4580 2337 4580 2224 4581 2369 4581 2222 4581 2226 4582 2369 4582 2224 4582 2226 4583 2340 4583 2369 4583 2226 4584 2341 4584 2340 4584 2228 4585 2341 4585 2226 4585 2229 4586 2341 4586 2228 4586 2229 4587 2342 4587 2341 4587 2231 4588 2342 4588 2229 4588 2231 4589 2343 4589 2342 4589 2232 4590 2343 4590 2231 4590 2232 4591 2344 4591 2343 4591 2234 4592 2344 4592 2232 4592 2234 4593 2345 4593 2344 4593 2235 4594 2345 4594 2234 4594 2235 4595 2346 4595 2345 4595 2238 4596 2346 4596 2235 4596 2238 4597 2348 4597 2346 4597 2239 4598 2348 4598 2238 4598 2239 4599 2349 4599 2348 4599 2240 4600 2349 4600 2239 4600 2240 4601 2350 4601 2349 4601 2241 4602 2350 4602 2240 4602 2241 4603 2351 4603 2350 4603 2242 4604 2351 4604 2241 4604 2242 4605 2352 4605 2351 4605 2243 4606 2352 4606 2242 4606 2243 4607 2353 4607 2352 4607 2075 4608 2353 4608 2243 4608 2075 4609 2354 4609 2353 4609 2074 4610 2354 4610 2075 4610 2074 4611 2355 4611 2354 4611 2074 4612 2356 4612 2355 4612 2077 4613 2356 4613 2074 4613 2077 4614 2357 4614 2356 4614 2073 4615 2357 4615 2077 4615 2073 4616 2358 4616 2357 4616 2073 4617 2359 4617 2358 4617 2244 4618 2245 4618 2045 4618 2045 4619 2361 4619 2244 4619 2045 4620 2245 4620 2028 4620 2245 4621 2246 4621 2028 4621 2045 4622 2360 4622 2361 4622 2246 4623 2248 4623 2028 4623 2045 4624 2043 4624 2360 4624 2043 4625 2086 4625 2360 4625 2043 4626 2084 4626 2086 4626 2248 4627 2023 4627 2028 4627 2250 4628 2023 4628 2248 4628 2250 4629 2078 4629 2023 4629 2043 4630 2050 4630 2084 4630 2084 4631 2050 4631 2082 4631 2050 4632 2033 4632 2082 4632 2079 4633 2033 4633 2078 4633 2080 4634 2033 4634 2079 4634 2082 4635 2033 4635 2080 4635 2078 4636 2033 4636 2023 4636 2245 4637 2247 4637 2246 4637 2362 4638 2253 4638 2252 4638 2363 4639 2261 4639 2260 4639 2364 4640 2268 4640 2267 4640 2364 4641 2269 4641 2268 4641 2275 4642 2277 4642 2276 4642 2365 4643 2281 4643 2280 4643 2281 4644 2283 4644 2282 4644 2291 4645 2293 4645 2292 4645 2297 4646 2299 4646 2298 4646 2366 4647 2300 4647 2299 4647 2367 4648 2320 4648 2319 4648 2322 4649 2324 4649 2323 4649 2368 4650 2329 4650 2328 4650 2337 4651 2369 4651 2338 4651 2369 4652 2339 4652 2338 4652 2369 4653 2340 4653 2339 4653 2346 4654 2348 4654 2347 4654

+
+ + + +

2389 4655 2371 4655 2370 4655 2371 4656 2372 4656 2370 4656 2370 4657 2372 4657 2373 4657 2372 4658 2374 4658 2373 4658 2373 4659 2374 4659 2375 4659 2374 4660 2376 4660 2375 4660 2375 4661 2376 4661 2377 4661 2376 4662 2378 4662 2377 4662 2377 4663 2378 4663 2379 4663 2379 4664 2378 4664 2380 4664 2378 4665 2381 4665 2380 4665 2381 4666 2382 4666 2380 4666 2380 4667 2382 4667 2383 4667 2383 4668 2382 4668 2384 4668 2382 4669 2385 4669 2384 4669 2384 4670 2385 4670 2386 4670 2385 4671 2387 4671 2386 4671 2386 4672 2387 4672 2388 4672 2387 4673 2389 4673 2388 4673 2388 4674 2389 4674 2370 4674 2392 4675 2390 4675 2391 4675 2392 4676 2391 4676 2393 4676 2394 4677 2392 4677 2393 4677 2394 4678 2393 4678 2395 4678 2396 4679 2394 4679 2395 4679 2396 4680 2395 4680 2397 4680 2398 4681 2396 4681 2397 4681 2398 4682 2397 4682 2399 4682 2400 4683 2398 4683 2399 4683 2400 4684 2399 4684 2401 4684 2402 4685 2400 4685 2401 4685 2403 4686 2402 4686 2401 4686 2403 4687 2401 4687 2404 4687 2405 4688 2403 4688 2404 4688 2405 4689 2404 4689 2406 4689 2407 4690 2405 4690 2406 4690 2407 4691 2406 4691 2408 4691 2409 4692 2407 4692 2408 4692 2409 4693 2408 4693 2410 4693 2411 4694 2409 4694 2410 4694 2411 4695 2410 4695 2412 4695 2413 4696 2411 4696 2412 4696 2414 4697 2412 4697 2415 4697 2414 4698 2413 4698 2412 4698 2416 4699 2414 4699 2415 4699 2416 4700 2415 4700 2417 4700 2418 4701 2416 4701 2417 4701 2418 4702 2417 4702 2419 4702 2390 4703 2419 4703 2391 4703 2390 4704 2418 4704 2419 4704 2382 77 2417 77 2415 77 2385 4705 2382 4705 2415 4705 2381 77 2417 77 2382 77 2385 4706 2415 4706 2412 4706 2381 4707 2419 4707 2417 4707 2381 4708 2391 4708 2419 4708 2385 4709 2412 4709 2410 4709 2378 77 2391 77 2381 77 2378 4710 2393 4710 2391 4710 2387 4711 2410 4711 2408 4711 2387 77 2385 77 2410 77 2393 4712 2378 4712 2376 4712 2408 77 2389 77 2387 77 2395 4713 2393 4713 2376 4713 2406 4714 2389 4714 2408 4714 2397 77 2376 77 2374 77 2397 4715 2395 4715 2376 4715 2404 77 2389 77 2406 77 2404 4716 2371 4716 2389 4716 2401 4717 2371 4717 2404 4717 2399 4718 2397 4718 2374 4718 2399 4719 2374 4719 2372 4719 2401 4720 2372 4720 2371 4720 2401 77 2399 77 2372 77 2386 12 2388 12 2409 12 2388 12 2407 12 2409 12 2386 12 2409 12 2411 12 2388 4721 2405 4721 2407 4721 2384 4722 2386 4722 2411 4722 2370 12 2405 12 2388 12 2384 12 2411 12 2413 12 2370 4723 2403 4723 2405 4723 2384 12 2413 12 2414 12 2370 12 2402 12 2403 12 2383 12 2414 12 2416 12 2383 12 2384 12 2414 12 2373 12 2402 12 2370 12 2400 12 2402 12 2373 12 2418 12 2383 12 2416 12 2418 4724 2380 4724 2383 4724 2400 4725 2373 4725 2375 4725 2398 12 2400 12 2375 12 2396 4726 2398 4726 2375 4726 2390 12 2380 12 2418 12 2392 12 2380 12 2390 12 2396 12 2375 12 2377 12 2392 4727 2379 4727 2380 4727 2394 4728 2396 4728 2377 4728 2394 4729 2379 4729 2392 4729 2394 12 2377 12 2379 12

+
+ + + +

2437 4730 2420 4730 2438 4730 2438 4731 2420 4731 2421 4731 2420 4732 2422 4732 2421 4732 2421 4733 2422 4733 2423 4733 2422 4734 2424 4734 2423 4734 2423 4735 2424 4735 2425 4735 2424 4736 2426 4736 2425 4736 2426 4737 2427 4737 2425 4737 2425 4738 2427 4738 2428 4738 2427 4739 2429 4739 2428 4739 2428 4740 2429 4740 2430 4740 2429 4741 2431 4741 2430 4741 2430 4742 2431 4742 2432 4742 2432 4743 2433 4743 2434 4743 2431 4744 2433 4744 2432 4744 2434 4745 2435 4745 2436 4745 2433 4746 2435 4746 2434 4746 2435 4747 2437 4747 2436 4747 2436 4748 2437 4748 2438 4748 2439 4749 2467 4749 2440 4749 2441 4750 2439 4750 2440 4750 2441 4751 2440 4751 2442 4751 2443 4752 2441 4752 2442 4752 2443 4753 2442 4753 2444 4753 2445 4754 2443 4754 2444 4754 2445 4755 2444 4755 2446 4755 2447 4756 2445 4756 2446 4756 2447 4757 2446 4757 2448 4757 2449 4758 2447 4758 2448 4758 2449 4759 2448 4759 2450 4759 2451 4760 2449 4760 2450 4760 2451 4761 2450 4761 2452 4761 2453 4762 2451 4762 2452 4762 2453 4763 2452 4763 2454 4763 2455 4764 2453 4764 2454 4764 2455 4765 2454 4765 2456 4765 2457 4766 2455 4766 2456 4766 2457 4767 2456 4767 2458 4767 2459 4768 2457 4768 2458 4768 2459 4769 2458 4769 2460 4769 2461 4770 2459 4770 2460 4770 2462 4771 2460 4771 2463 4771 2462 4772 2461 4772 2460 4772 2464 4773 2462 4773 2463 4773 2464 4774 2463 4774 2465 4774 2466 4775 2464 4775 2465 4775 2466 4776 2465 4776 2467 4776 2439 4777 2466 4777 2467 4777 2431 77 2465 77 2463 77 2433 4778 2431 4778 2463 4778 2429 77 2465 77 2431 77 2433 77 2463 77 2460 77 2429 77 2467 77 2465 77 2433 77 2460 77 2458 77 2429 77 2440 77 2467 77 2427 77 2440 77 2429 77 2435 77 2458 77 2456 77 2435 77 2433 77 2458 77 2427 77 2442 77 2440 77 2442 4779 2427 4779 2426 4779 2456 77 2437 77 2435 77 2444 77 2442 77 2426 77 2454 4714 2437 4714 2456 4714 2444 77 2426 77 2424 77 2452 77 2437 77 2454 77 2446 77 2444 77 2424 77 2452 4780 2420 4780 2437 4780 2446 77 2424 77 2422 77 2450 77 2420 77 2452 77 2448 4781 2446 4781 2422 4781 2450 4782 2422 4782 2420 4782 2450 4783 2448 4783 2422 4783 2436 4784 2455 4784 2457 4784 2434 4785 2436 4785 2457 4785 2434 12 2457 12 2459 12 2438 12 2455 12 2436 12 2438 4786 2453 4786 2455 4786 2434 12 2459 12 2461 12 2438 4787 2451 4787 2453 4787 2434 4788 2461 4788 2462 4788 2421 12 2451 12 2438 12 2432 12 2434 12 2462 12 2421 4789 2449 4789 2451 4789 2432 12 2462 12 2464 12 2449 12 2421 12 2423 12 2447 4790 2449 4790 2423 4790 2466 12 2432 12 2464 12 2466 4791 2430 4791 2432 4791 2445 4792 2447 4792 2423 4792 2439 12 2430 12 2466 12 2445 12 2423 12 2425 12 2439 4793 2428 4793 2430 4793 2441 4794 2428 4794 2439 4794 2443 12 2445 12 2425 12 2441 12 2425 12 2428 12 2441 4795 2443 4795 2425 4795

+
+ + + +

2468 4796 2470 4796 2469 4796 2468 4797 2469 4797 3240 4797 2471 4798 2470 4798 2468 4798 2471 4799 2472 4799 2470 4799 3240 4800 2469 4800 2473 4800 2469 4801 2474 4801 2473 4801 2471 4802 2475 4802 2472 4802 3208 4803 2475 4803 2471 4803 2473 4804 2474 4804 3237 4804 3237 4805 2474 4805 2477 4805 2476 4806 2475 4806 3208 4806 2476 4807 2478 4807 2475 4807 2480 4808 2479 4808 2477 4808 2476 4809 2481 4809 2478 4809 2481 4810 2482 4810 2483 4810 2488 4811 2485 4811 2484 4811 2488 4812 2487 4812 2485 4812 2488 4813 2489 4813 2487 4813 2490 4814 2489 4814 2488 4814 2490 4815 2491 4815 2489 4815 2486 4816 2491 4816 2490 4816 2486 4817 2492 4817 2491 4817 2493 4818 2492 4818 2486 4818 2493 4819 2494 4819 2492 4819 2495 4820 2494 4820 2493 4820 2495 4821 2496 4821 2494 4821 2497 4822 2496 4822 2495 4822 2497 4823 2498 4823 2496 4823 2499 4824 2500 4824 2497 4824 2497 4825 2500 4825 2498 4825 2499 4826 2501 4826 2500 4826 2502 4827 2501 4827 2499 4827 2503 4828 2501 4828 2502 4828 2503 4829 2504 4829 2501 4829 2503 4830 2505 4830 2504 4830 2506 4831 2505 4831 2503 4831 2506 4832 2507 4832 2505 4832 2506 4833 2508 4833 2507 4833 2509 4834 2508 4834 2506 4834 2509 4835 2510 4835 2508 4835 2511 4836 2510 4836 2509 4836 2511 4837 2512 4837 2510 4837 2511 4838 2513 4838 2512 4838 2514 4839 2513 4839 2511 4839 2514 4840 2515 4840 2513 4840 2516 4841 2515 4841 2514 4841 2516 4842 2517 4842 2515 4842 2518 4843 2517 4843 2516 4843 2518 4844 2519 4844 2517 4844 2520 4845 2519 4845 2518 4845 2521 4846 2519 4846 2520 4846 2521 4847 2522 4847 2519 4847 2521 4848 2523 4848 2522 4848 2524 4849 2523 4849 2521 4849 2525 4850 2523 4850 2524 4850 2525 4851 2526 4851 2523 4851 2527 4852 2526 4852 2525 4852 2527 4853 2528 4853 2526 4853 2527 4854 2529 4854 2528 4854 2530 4855 2529 4855 2527 4855 2530 4856 2531 4856 2529 4856 2532 4857 2531 4857 2530 4857 2532 4858 2533 4858 2531 4858 2534 4859 2533 4859 2532 4859 2534 4860 2535 4860 2533 4860 2536 4861 2535 4861 2534 4861 2536 4862 2537 4862 2535 4862 2536 4863 2538 4863 2537 4863 2539 4864 2538 4864 2536 4864 2540 4865 2538 4865 2539 4865 2540 4866 2541 4866 2538 4866 2540 4867 2542 4867 2541 4867 2543 4868 2542 4868 2540 4868 2543 4869 2544 4869 2542 4869 2543 4870 2545 4870 2544 4870 2546 4871 2545 4871 2543 4871 2546 4872 2547 4872 2545 4872 2548 4873 2547 4873 2546 4873 2548 4874 2549 4874 2547 4874 2550 4875 2549 4875 2548 4875 2550 4876 2551 4876 2549 4876 2550 4877 2552 4877 2551 4877 2553 4878 2552 4878 2550 4878 2553 4879 2554 4879 2552 4879 2555 4880 2554 4880 2553 4880 2555 4881 2556 4881 2554 4881 2557 4882 2556 4882 2555 4882 2557 4883 2558 4883 2556 4883 2557 4884 2559 4884 2558 4884 2560 4885 2559 4885 2557 4885 2560 4886 2561 4886 2559 4886 2562 4887 2561 4887 2560 4887 2562 4888 2563 4888 2561 4888 2564 4889 2563 4889 2562 4889 2564 4890 2565 4890 2563 4890 2564 4891 2566 4891 2565 4891 2567 4892 2566 4892 2564 4892 2567 4893 2568 4893 2566 4893 2569 4894 2568 4894 2567 4894 2569 4895 2570 4895 2568 4895 2571 4896 2570 4896 2569 4896 2571 4897 2572 4897 2570 4897 2573 4898 2572 4898 2571 4898 2573 4899 2574 4899 2572 4899 2573 4900 2575 4900 2574 4900 2576 4901 2575 4901 2573 4901 2576 4902 2577 4902 2575 4902 2576 4903 2578 4903 2577 4903 2579 4904 2578 4904 2576 4904 2579 4905 2580 4905 2578 4905 2581 4906 2580 4906 2579 4906 2581 4907 2582 4907 2580 4907 2583 4908 2582 4908 2581 4908 2583 4909 2584 4909 2582 4909 2585 4910 2586 4910 2583 4910 2583 4911 2586 4911 2584 4911 2585 4912 2587 4912 2586 4912 2588 4913 2587 4913 2585 4913 2588 4914 2589 4914 2587 4914 2590 4915 2589 4915 2588 4915 2590 4916 2591 4916 2589 4916 2590 4917 2592 4917 2591 4917 2593 4918 2592 4918 2590 4918 2593 4919 2594 4919 2592 4919 2595 4920 2594 4920 2593 4920 2595 4921 2596 4921 2594 4921 2597 4922 2596 4922 2595 4922 2597 4923 2598 4923 2596 4923 2599 4924 2598 4924 2597 4924 2599 4925 2600 4925 2598 4925 2601 4926 2600 4926 2599 4926 2601 4927 2602 4927 2600 4927 2601 4928 2603 4928 2602 4928 2604 4929 2603 4929 2601 4929 2604 4930 2605 4930 2603 4930 2606 4931 2605 4931 2604 4931 2607 4932 2605 4932 2606 4932 2607 4933 2608 4933 2605 4933 2609 4934 2608 4934 2607 4934 2609 4935 2610 4935 2608 4935 2609 4936 2611 4936 2610 4936 2612 4937 2611 4937 2609 4937 2612 4938 2613 4938 2611 4938 2614 4939 2613 4939 2612 4939 2614 4940 2615 4940 2613 4940 2614 4941 2616 4941 2615 4941 2617 4942 2616 4942 2614 4942 2617 4943 2618 4943 2616 4943 2617 4944 2619 4944 2618 4944 2620 4945 2619 4945 2617 4945 2620 4946 2621 4946 2619 4946 2622 4947 2621 4947 2620 4947 2622 4948 2623 4948 2621 4948 2624 4949 2623 4949 2622 4949 2624 4950 2625 4950 2623 4950 2626 4951 2625 4951 2624 4951 2626 4952 2627 4952 2625 4952 2628 4953 2627 4953 2626 4953 2628 4954 2629 4954 2627 4954 2630 4955 2629 4955 2628 4955 2630 4956 2631 4956 2629 4956 2630 4957 2632 4957 2631 4957 2633 4958 2632 4958 2630 4958 2634 4959 2632 4959 2633 4959 2634 4960 2635 4960 2632 4960 2634 4961 2636 4961 2635 4961 2637 4962 2636 4962 2634 4962 2637 4963 2638 4963 2636 4963 2637 4964 2639 4964 2638 4964 2640 4965 2639 4965 2637 4965 2640 4966 2641 4966 2639 4966 2642 4967 2641 4967 2640 4967 2642 4968 2643 4968 2641 4968 2644 4969 2643 4969 2642 4969 2644 4970 2645 4970 2643 4970 2646 4971 2645 4971 2644 4971 2646 4972 2647 4972 2645 4972 2648 4973 2647 4973 2646 4973 2648 4974 2649 4974 2647 4974 2648 4975 2650 4975 2649 4975 2651 4976 2650 4976 2648 4976 2651 4977 2652 4977 2650 4977 2653 4978 2652 4978 2651 4978 2653 4979 2654 4979 2652 4979 2655 4980 2654 4980 2653 4980 2655 4981 2656 4981 2654 4981 2655 4982 2657 4982 2656 4982 2658 4983 2657 4983 2655 4983 2659 4984 2660 4984 2658 4984 2658 4985 2660 4985 2657 4985 2659 4986 2661 4986 2660 4986 2659 4987 2662 4987 2661 4987 2663 4988 2662 4988 2659 4988 2664 4989 2662 4989 2663 4989 2664 4990 2665 4990 2662 4990 2664 4991 2666 4991 2665 4991 2667 4992 2666 4992 2664 4992 2667 4993 2668 4993 2666 4993 2669 4994 2668 4994 2667 4994 2669 4995 2670 4995 2668 4995 2669 4996 2671 4996 2670 4996 2669 4997 2672 4997 2671 4997 2673 4998 2672 4998 2669 4998 2673 4999 2674 4999 2672 4999 2675 5000 2674 5000 2673 5000 2675 5001 2676 5001 2674 5001 2677 5002 2676 5002 2675 5002 2677 5003 2678 5003 2676 5003 2679 5004 2678 5004 2677 5004 2679 5005 2680 5005 2678 5005 2681 5006 2680 5006 2679 5006 2681 5007 2682 5007 2680 5007 2681 5008 2683 5008 2682 5008 2684 5009 2683 5009 2681 5009 2684 5010 2685 5010 2683 5010 2686 5011 2685 5011 2684 5011 2686 5012 2687 5012 2685 5012 2688 5013 2687 5013 2686 5013 2688 5014 2689 5014 2687 5014 2688 5015 2690 5015 2689 5015 2691 5016 2690 5016 2688 5016 2691 5017 2692 5017 2690 5017 2691 5018 2693 5018 2692 5018 2694 5019 2693 5019 2691 5019 2695 5020 2696 5020 2694 5020 2694 5021 2696 5021 2693 5021 2695 5022 2697 5022 2696 5022 2698 5023 2697 5023 2695 5023 2698 5024 2699 5024 2697 5024 2698 5025 2700 5025 2699 5025 2701 5026 2700 5026 2698 5026 2701 5027 2702 5027 2700 5027 2703 5028 2702 5028 2701 5028 2703 5029 2704 5029 2702 5029 2703 5030 2705 5030 2704 5030 2706 5031 2705 5031 2703 5031 2707 5032 2705 5032 2706 5032 2707 5033 2708 5033 2705 5033 2707 5034 2709 5034 2708 5034 2710 5035 2709 5035 2707 5035 2710 5036 2711 5036 2709 5036 2712 5037 2711 5037 2710 5037 2712 5038 2713 5038 2711 5038 2714 5039 2713 5039 2712 5039 2714 5040 2715 5040 2713 5040 2714 5041 2716 5041 2715 5041 2717 5042 2716 5042 2714 5042 2717 5043 2718 5043 2716 5043 2719 5044 2718 5044 2717 5044 2719 5045 2720 5045 2718 5045 2719 5046 2721 5046 2720 5046 2722 5047 2721 5047 2719 5047 2722 5048 2723 5048 2721 5048 2724 5049 2723 5049 2722 5049 2724 5050 2725 5050 2723 5050 2724 5051 2726 5051 2725 5051 2727 5052 2726 5052 2724 5052 2727 5053 2728 5053 2726 5053 2727 5054 2729 5054 2728 5054 2730 5055 2729 5055 2727 5055 2730 5056 2731 5056 2729 5056 2732 5057 2731 5057 2730 5057 2732 5058 2733 5058 2731 5058 2734 5059 2733 5059 2732 5059 2735 5060 2733 5060 2734 5060 2735 5061 2736 5061 2733 5061 2735 5062 2737 5062 2736 5062 2738 5063 2737 5063 2735 5063 2739 5064 2737 5064 2738 5064 2739 5065 2740 5065 2737 5065 2739 5066 2741 5066 2740 5066 2742 5067 2741 5067 2739 5067 2742 5068 2743 5068 2741 5068 2744 5069 2743 5069 2742 5069 2744 5070 2745 5070 2743 5070 2746 5071 2745 5071 2744 5071 2746 5072 2747 5072 2745 5072 2748 5073 2747 5073 2746 5073 2748 5074 2749 5074 2747 5074 2748 5075 2750 5075 2749 5075 2751 5076 2750 5076 2748 5076 2751 5077 2752 5077 2750 5077 2753 5078 2752 5078 2751 5078 2753 5079 2754 5079 2752 5079 2755 5080 2754 5080 2753 5080 2755 5081 2756 5081 2754 5081 2757 5082 2756 5082 2755 5082 2757 5083 2758 5083 2756 5083 2757 5084 2759 5084 2758 5084 2760 5085 2759 5085 2757 5085 2760 5086 2761 5086 2759 5086 2762 5087 2761 5087 2760 5087 2762 5088 2763 5088 2761 5088 2764 5089 2765 5089 2762 5089 2762 5090 2765 5090 2763 5090 2766 5091 2765 5091 2764 5091 2766 5092 2767 5092 2765 5092 2766 5093 2768 5093 2767 5093 2769 5094 2768 5094 2766 5094 2769 5095 2770 5095 2768 5095 2769 5096 2771 5096 2770 5096 2772 5097 2771 5097 2769 5097 2772 5098 2773 5098 2771 5098 2772 5099 2774 5099 2773 5099 2775 5100 2774 5100 2772 5100 2776 5101 2774 5101 2775 5101 2776 5102 2777 5102 2774 5102 2776 5103 2778 5103 2777 5103 2779 5104 2780 5104 2776 5104 2776 5105 2780 5105 2778 5105 2779 5106 2781 5106 2780 5106 2782 5107 2781 5107 2779 5107 2782 5108 2783 5108 2781 5108 2784 5109 2783 5109 2782 5109 2784 5110 2785 5110 2783 5110 2786 5111 2785 5111 2784 5111 2786 5112 2787 5112 2785 5112 2786 5113 2788 5113 2787 5113 2789 5114 2788 5114 2786 5114 2790 5115 2788 5115 2789 5115 2790 5116 2791 5116 2788 5116 2790 5117 2792 5117 2791 5117 2793 5118 2792 5118 2790 5118 2793 5119 2794 5119 2792 5119 2795 5120 2794 5120 2793 5120 2795 5121 2796 5121 2794 5121 2795 5122 2797 5122 2796 5122 2798 5123 2797 5123 2795 5123 2798 5124 2799 5124 2797 5124 2800 5125 2799 5125 2798 5125 2800 5126 2801 5126 2799 5126 2802 5127 2801 5127 2800 5127 2802 5128 2803 5128 2801 5128 2804 5129 2803 5129 2802 5129 2804 5130 2805 5130 2803 5130 2806 5131 2805 5131 2804 5131 2806 5132 2807 5132 2805 5132 2808 5133 2807 5133 2806 5133 2808 5134 2809 5134 2807 5134 2808 5135 2810 5135 2809 5135 2811 5136 2810 5136 2808 5136 2811 5137 2812 5137 2810 5137 2813 5138 2812 5138 2811 5138 2813 5139 2814 5139 2812 5139 2815 5140 2814 5140 2813 5140 2815 5141 2816 5141 2814 5141 2817 5142 2816 5142 2815 5142 2818 5143 2816 5143 2817 5143 2818 5144 2819 5144 2816 5144 2818 5145 2820 5145 2819 5145 2821 5146 2820 5146 2818 5146 2822 5147 2820 5147 2821 5147 2822 5148 2823 5148 2820 5148 2824 5149 2823 5149 2822 5149 2824 5150 2825 5150 2823 5150 2826 5151 2825 5151 2824 5151 2826 5152 2827 5152 2825 5152 2826 5153 2828 5153 2827 5153 2829 5154 2828 5154 2826 5154 2829 5155 2830 5155 2828 5155 2831 5156 2830 5156 2829 5156 2831 5157 2832 5157 2830 5157 2831 5158 2833 5158 2832 5158 2834 5159 2833 5159 2831 5159 2834 5160 2835 5160 2833 5160 2836 5161 2835 5161 2834 5161 2837 5162 2835 5162 2836 5162 2837 5163 2838 5163 2835 5163 2839 5164 2838 5164 2837 5164 2839 5165 2840 5165 2838 5165 2841 5166 2840 5166 2839 5166 2841 5167 2842 5167 2840 5167 2841 5168 2843 5168 2842 5168 2844 5169 2843 5169 2841 5169 2844 5170 2845 5170 2843 5170 2846 5171 2845 5171 2844 5171 2846 5172 2847 5172 2845 5172 2846 5173 2848 5173 2847 5173 2849 5174 2848 5174 2846 5174 2849 5175 2850 5175 2848 5175 2851 5176 2850 5176 2849 5176 2851 5177 2852 5177 2850 5177 2851 5178 2853 5178 2852 5178 2854 5179 2853 5179 2851 5179 2854 5180 2855 5180 2853 5180 2856 5181 2855 5181 2854 5181 2856 5182 2857 5182 2855 5182 2856 5183 2858 5183 2857 5183 2856 5184 2859 5184 2858 5184 2860 5185 2859 5185 2856 5185 2860 5186 2861 5186 2859 5186 2860 5187 2862 5187 2861 5187 2863 5188 2862 5188 2860 5188 2864 5189 2862 5189 2863 5189 2864 5190 2865 5190 2862 5190 2864 5191 2866 5191 2865 5191 2867 5192 2866 5192 2864 5192 2868 5193 2866 5193 2867 5193 2868 5194 2869 5194 2866 5194 2870 5195 2869 5195 2868 5195 2870 5196 2871 5196 2869 5196 2872 5197 2871 5197 2870 5197 2872 5198 2873 5198 2871 5198 2872 5199 2874 5199 2873 5199 2875 5200 2874 5200 2872 5200 2875 5201 2876 5201 2874 5201 2877 5202 2876 5202 2875 5202 2877 5203 2878 5203 2876 5203 2879 5204 2878 5204 2877 5204 2879 5205 2880 5205 2878 5205 2881 5206 2880 5206 2879 5206 2881 5207 2882 5207 2880 5207 2883 5208 2884 5208 2881 5208 2881 5209 2884 5209 2882 5209 2883 5210 2885 5210 2884 5210 2886 5211 2885 5211 2883 5211 2887 5212 2885 5212 2886 5212 2887 5213 2888 5213 2885 5213 2887 5214 2889 5214 2888 5214 2890 5215 2889 5215 2887 5215 2890 5216 2891 5216 2889 5216 2890 5217 2892 5217 2891 5217 2893 5218 2892 5218 2890 5218 2893 5219 2894 5219 2892 5219 2895 5220 2894 5220 2893 5220 2895 5221 2896 5221 2894 5221 2897 5222 2896 5222 2895 5222 2897 5223 2898 5223 2896 5223 2897 5224 2899 5224 2898 5224 2900 5225 2899 5225 2897 5225 2900 5226 2901 5226 2899 5226 2902 5227 2901 5227 2900 5227 2902 5228 2903 5228 2901 5228 2904 5229 2903 5229 2902 5229 2904 5230 2905 5230 2903 5230 2906 5231 2907 5231 2904 5231 2904 5232 2907 5232 2905 5232 2906 5233 2908 5233 2907 5233 2909 5234 2908 5234 2906 5234 2909 5235 2910 5235 2908 5235 2909 5236 2911 5236 2910 5236 2912 5237 2911 5237 2909 5237 2912 5238 2913 5238 2911 5238 2914 5239 2913 5239 2912 5239 2915 5240 2913 5240 2914 5240 2915 5241 2916 5241 2913 5241 2917 5242 2916 5242 2915 5242 2918 5243 2919 5243 2917 5243 2917 5244 2919 5244 2916 5244 2918 5245 2920 5245 2919 5245 2921 5246 2920 5246 2918 5246 2921 5247 2922 5247 2920 5247 2923 5248 2924 5248 2921 5248 2921 5249 2924 5249 2922 5249 2925 5250 2924 5250 2923 5250 2925 5251 2926 5251 2924 5251 2925 5252 2927 5252 2926 5252 2928 5253 2927 5253 2925 5253 2928 5254 2929 5254 2927 5254 2930 5255 2929 5255 2928 5255 2930 5256 2931 5256 2929 5256 2932 5257 2931 5257 2930 5257 2932 5258 2933 5258 2931 5258 2934 5259 2933 5259 2932 5259 2934 5260 2935 5260 2933 5260 2936 5261 2935 5261 2934 5261 2936 5262 2937 5262 2935 5262 2938 5263 2937 5263 2936 5263 2938 5264 2939 5264 2937 5264 2938 5265 2940 5265 2939 5265 2941 5266 2940 5266 2938 5266 2941 5267 2942 5267 2940 5267 2943 5268 2942 5268 2941 5268 2943 5269 2944 5269 2942 5269 2945 5270 2944 5270 2943 5270 2946 5271 2944 5271 2945 5271 2946 5272 2947 5272 2944 5272 2946 5273 2948 5273 2947 5273 2949 5274 2948 5274 2946 5274 2949 5275 2950 5275 2948 5275 2951 5276 2950 5276 2949 5276 2951 5277 2952 5277 2950 5277 2953 5278 2952 5278 2951 5278 2953 5279 2954 5279 2952 5279 2955 5280 2954 5280 2953 5280 2955 5281 2956 5281 2954 5281 2957 5282 2956 5282 2955 5282 2957 5283 2958 5283 2956 5283 2957 5284 2959 5284 2958 5284 2960 5285 2959 5285 2957 5285 2961 5286 2959 5286 2960 5286 2961 5287 2962 5287 2959 5287 2963 5288 2962 5288 2961 5288 2963 5289 2964 5289 2962 5289 2963 5290 2965 5290 2964 5290 2966 5291 2965 5291 2963 5291 2966 5292 2967 5292 2965 5292 2968 5293 2967 5293 2966 5293 2968 5294 2969 5294 2967 5294 2970 5295 2971 5295 2968 5295 2968 5296 2971 5296 2969 5296 2972 5297 2971 5297 2970 5297 2972 5298 2973 5298 2971 5298 2972 5299 2974 5299 2973 5299 2975 5300 2974 5300 2972 5300 2975 5301 2976 5301 2974 5301 2977 5302 2976 5302 2975 5302 2977 5303 2978 5303 2976 5303 2979 5304 2978 5304 2977 5304 2979 5305 2980 5305 2978 5305 2981 5306 2980 5306 2979 5306 2981 5307 2982 5307 2980 5307 2983 5308 2982 5308 2981 5308 2983 5309 2984 5309 2982 5309 2983 5310 2985 5310 2984 5310 2986 5311 2985 5311 2983 5311 2986 5312 2987 5312 2985 5312 2986 5313 2988 5313 2987 5313 2989 5314 2988 5314 2986 5314 2989 5315 2990 5315 2988 5315 2991 5316 2990 5316 2989 5316 2991 5317 2992 5317 2990 5317 2993 5318 2992 5318 2991 5318 2993 5319 2994 5319 2992 5319 2995 5320 2994 5320 2993 5320 2995 5321 2996 5321 2994 5321 2997 5322 2996 5322 2995 5322 2997 5323 2998 5323 2996 5323 2997 5324 2999 5324 2998 5324 3000 5325 2999 5325 2997 5325 3000 5326 3001 5326 2999 5326 3002 5327 3001 5327 3000 5327 3002 5328 3003 5328 3001 5328 3004 5329 3005 5329 3002 5329 3002 5330 3005 5330 3003 5330 3004 5331 3006 5331 3005 5331 3007 5332 3006 5332 3004 5332 3007 5333 3008 5333 3006 5333 3009 5334 3008 5334 3007 5334 3009 5335 3010 5335 3008 5335 3011 5336 3010 5336 3009 5336 3011 5337 3012 5337 3010 5337 3013 5338 3012 5338 3011 5338 3013 5339 3014 5339 3012 5339 3013 5340 3015 5340 3014 5340 3016 5341 3015 5341 3013 5341 3016 5342 3017 5342 3015 5342 3018 5343 3017 5343 3016 5343 3018 5344 3019 5344 3017 5344 3020 5345 3019 5345 3018 5345 3020 5346 3021 5346 3019 5346 3022 5347 3023 5347 3020 5347 3020 5348 3023 5348 3021 5348 3024 5349 3023 5349 3022 5349 3024 5350 3025 5350 3023 5350 3024 5351 3026 5351 3025 5351 3027 5352 3026 5352 3024 5352 3027 5353 3028 5353 3026 5353 3029 5354 3028 5354 3027 5354 3029 5355 3030 5355 3028 5355 3031 5356 3030 5356 3029 5356 3031 5357 3032 5357 3030 5357 3033 5358 3032 5358 3031 5358 3033 5359 3034 5359 3032 5359 3035 5360 3034 5360 3033 5360 3035 5361 3036 5361 3034 5361 3035 5362 3037 5362 3036 5362 3038 5363 3037 5363 3035 5363 3038 5364 3039 5364 3037 5364 3040 5365 3039 5365 3038 5365 3040 5366 3041 5366 3039 5366 3042 5367 3041 5367 3040 5367 3042 5368 3043 5368 3041 5368 3044 5369 3043 5369 3042 5369 3044 5370 3045 5370 3043 5370 3044 5371 3046 5371 3045 5371 3047 5372 3046 5372 3044 5372 3047 5373 3048 5373 3046 5373 3049 5374 3048 5374 3047 5374 3049 5375 3050 5375 3048 5375 3051 5376 3050 5376 3049 5376 3051 5377 3052 5377 3050 5377 3051 5378 3053 5378 3052 5378 3054 5379 3053 5379 3051 5379 3054 5380 3055 5380 3053 5380 3056 5381 3055 5381 3054 5381 3056 5382 3057 5382 3055 5382 3058 5383 3057 5383 3056 5383 3058 5384 3059 5384 3057 5384 3060 5385 3059 5385 3058 5385 3060 5386 3061 5386 3059 5386 3060 5387 3062 5387 3061 5387 3063 5388 3062 5388 3060 5388 3063 5389 3064 5389 3062 5389 3065 5390 3064 5390 3063 5390 3065 5391 3066 5391 3064 5391 3065 5392 3067 5392 3066 5392 3068 5393 3067 5393 3065 5393 3068 5394 3069 5394 3067 5394 3070 5395 3069 5395 3068 5395 3070 5396 3224 5396 3069 5396 3071 5397 3224 5397 3070 5397 3071 5398 2483 5398 3224 5398 3072 5399 2483 5399 3071 5399 3073 5400 2483 5400 3072 5400 3073 5401 2481 5401 2483 5401 3073 5402 2478 5402 2481 5402 2495 5403 2493 5403 3074 5403 3075 5404 2495 5404 3074 5404 2497 5405 2495 5405 3075 5405 3076 5406 2497 5406 3075 5406 2499 5407 2497 5407 3076 5407 3077 5408 2506 5408 2503 5408 3078 5409 2506 5409 3077 5409 2509 5410 2506 5410 3078 5410 3079 5411 2509 5411 3078 5411 2511 5412 2509 5412 3079 5412 2514 5413 2511 5413 3079 5413 2520 5414 2518 5414 3080 5414 3081 5415 2520 5415 3080 5415 2521 5416 2520 5416 3081 5416 2524 5417 2521 5417 3081 5417 2527 5418 2525 5418 3082 5418 3083 5419 2532 5419 2530 5419 2534 5420 2532 5420 3083 5420 2540 5421 2539 5421 3084 5421 2543 5422 2540 5422 3084 5422 3085 5423 2550 5423 2548 5423 3086 5424 2550 5424 3085 5424 2553 5425 2550 5425 3086 5425 3087 5426 2553 5426 3086 5426 2555 5427 2553 5427 3087 5427 2557 5428 2555 5428 3087 5428 2560 5429 2557 5429 3088 5429 2562 5430 2560 5430 3088 5430 3089 5431 2562 5431 3088 5431 2564 5432 2562 5432 3089 5432 3090 5433 2564 5433 3089 5433 2567 5434 2564 5434 3090 5434 2569 5435 2567 5435 3090 5435 2571 5436 2569 5436 3091 5436 3092 5437 2573 5437 2571 5437 2576 5438 2573 5438 3092 5438 3093 5439 2576 5439 3092 5439 2579 5440 2576 5440 3093 5440 2581 5441 2579 5441 3093 5441 2585 5442 2583 5442 3094 5442 3095 5443 2585 5443 3094 5443 2588 5444 2585 5444 3095 5444 2590 5445 2588 5445 3096 5445 3097 5446 2590 5446 3096 5446 2593 5447 2590 5447 3097 5447 3098 5448 2593 5448 3097 5448 2595 5449 2593 5449 3098 5449 2595 5450 3098 5450 3099 5450 2597 5451 2595 5451 3099 5451 3100 5452 2601 5452 2599 5452 2604 5453 2601 5453 3100 5453 2614 5454 2612 5454 3101 5454 2617 5455 2614 5455 3101 5455 3102 5456 2617 5456 3101 5456 2620 5457 2617 5457 3102 5457 2624 5458 2622 5458 3103 5458 2626 5459 2624 5459 3103 5459 2634 5460 2633 5460 3104 5460 2637 5461 2634 5461 3104 5461 3105 5462 2637 5462 3104 5462 3106 5463 2637 5463 3105 5463 2640 5464 2637 5464 3106 5464 2642 5465 2640 5465 3106 5465 2646 5466 2644 5466 2642 5466 2648 5467 2646 5467 3107 5467 3108 5468 2648 5468 3107 5468 2651 5469 2648 5469 3108 5469 2653 5470 2651 5470 3108 5470 3109 5471 2655 5471 2653 5471 2658 5472 2655 5472 3109 5472 2659 5473 2658 5473 3110 5473 3111 5474 2659 5474 3110 5474 2663 5475 2659 5475 3111 5475 3112 5476 2663 5476 3111 5476 2664 5477 2663 5477 3112 5477 3113 5478 2667 5478 2664 5478 2669 5479 2667 5479 3113 5479 3114 5480 2669 5480 3113 5480 3115 5481 2669 5481 3114 5481 2673 5482 2669 5482 3115 5482 3116 5483 2675 5483 2673 5483 2677 5484 2675 5484 3116 5484 3117 5485 2684 5485 2681 5485 2686 5486 2684 5486 3117 5486 3118 5487 2688 5487 2686 5487 2691 5488 2688 5488 3118 5488 3119 5489 2695 5489 2694 5489 2698 5490 2695 5490 3119 5490 3120 5491 2698 5491 3119 5491 2701 5492 2698 5492 3120 5492 3121 5493 2703 5493 2701 5493 2706 5494 2703 5494 3121 5494 3122 5495 2714 5495 2712 5495 2717 5496 2714 5496 3122 5496 3123 5497 2717 5497 3122 5497 2719 5498 3123 5498 3124 5498 2719 5499 2717 5499 3123 5499 2722 5500 2719 5500 3124 5500 3125 5501 2724 5501 2722 5501 3126 5502 2724 5502 3125 5502 2727 5503 2724 5503 3126 5503 2730 5504 2727 5504 3126 5504 2739 5505 2738 5505 3127 5505 3128 5506 2739 5506 3127 5506 2742 5507 2739 5507 3128 5507 2744 5508 2742 5508 3128 5508 2746 5509 2744 5509 3129 5509 2748 5510 2746 5510 3129 5510 3130 5511 2748 5511 3129 5511 2751 5512 2748 5512 3130 5512 3131 5513 2755 5513 2753 5513 2757 5514 2755 5514 3131 5514 2760 5515 2757 5515 3131 5515 3132 5516 2762 5516 2760 5516 2764 5517 2762 5517 3132 5517 3133 5518 2766 5518 2764 5518 2769 5519 2766 5519 3133 5519 3134 5520 2769 5520 3133 5520 2772 5521 2769 5521 3134 5521 3135 5522 2772 5522 3134 5522 2775 5523 2772 5523 3135 5523 2776 5524 2775 5524 3135 5524 3136 5525 2776 5525 3135 5525 2779 5526 2776 5526 3136 5526 2784 5527 2782 5527 3137 5527 2786 5528 2784 5528 3137 5528 3138 5529 2790 5529 2789 5529 2793 5530 2790 5530 3138 5530 3139 5531 2793 5531 3138 5531 2795 5532 2793 5532 3139 5532 2802 5533 2800 5533 3140 5533 3141 5534 2802 5534 3140 5534 2804 5535 2802 5535 3141 5535 3142 5536 2806 5536 2804 5536 2808 5537 2806 5537 3142 5537 3143 5538 2808 5538 3142 5538 2811 5539 2808 5539 3143 5539 3144 5540 2811 5540 3143 5540 2813 5541 2811 5541 3144 5541 2817 5542 2815 5542 2813 5542 2818 5543 2817 5543 3145 5543 2821 5544 2818 5544 3145 5544 3146 5545 2826 5545 2824 5545 2829 5546 2826 5546 3146 5546 3147 5547 2831 5547 2829 5547 2834 5548 2831 5548 3147 5548 2836 5549 2834 5549 3147 5549 3148 5550 2839 5550 2837 5550 2841 5551 2839 5551 3148 5551 2841 5552 3148 5552 3149 5552 2844 5553 2841 5553 3149 5553 3150 5554 2844 5554 3149 5554 2846 5555 2844 5555 3150 5555 3151 5556 2846 5556 3150 5556 2849 5557 2846 5557 3151 5557 3152 5558 2849 5558 3151 5558 2851 5559 2849 5559 3152 5559 3153 5560 2851 5560 3152 5560 2854 5561 2851 5561 3153 5561 3154 5562 2854 5562 3153 5562 2856 5563 2854 5563 3154 5563 3155 5564 2856 5564 3154 5564 3156 5565 2856 5565 3155 5565 2860 5566 2856 5566 3156 5566 2863 5567 2860 5567 3156 5567 2864 5568 2863 5568 3157 5568 3158 5569 2872 5569 2870 5569 2875 5570 2872 5570 3158 5570 2883 5571 2881 5571 3159 5571 2886 5572 2883 5572 3159 5572 2890 5573 2887 5573 3160 5573 3161 5574 2890 5574 3160 5574 2893 5575 2890 5575 3161 5575 2895 5576 2893 5576 3161 5576 3162 5577 2895 5577 3161 5577 2897 5578 2895 5578 3162 5578 2900 5579 2897 5579 3163 5579 3164 5580 2900 5580 3163 5580 2902 5581 2900 5581 3164 5581 2904 5582 2902 5582 3164 5582 2918 5583 2917 5583 3165 5583 2921 5584 2918 5584 3165 5584 3166 5585 2921 5585 3165 5585 2923 5586 2921 5586 3166 5586 3167 5587 2925 5587 2923 5587 2928 5588 2925 5588 3167 5588 2930 5589 2928 5589 3167 5589 3168 5590 2932 5590 2930 5590 2934 5591 2932 5591 3168 5591 2936 5592 2934 5592 3168 5592 2941 5593 2938 5593 3169 5593 3170 5594 2941 5594 3169 5594 2943 5595 2941 5595 3170 5595 2945 5596 2943 5596 3170 5596 3171 5597 2955 5597 2953 5597 2957 5598 2955 5598 3171 5598 3172 5599 2957 5599 3171 5599 2960 5600 2957 5600 3172 5600 2966 5601 2963 5601 3173 5601 2968 5602 2966 5602 3173 5602 3174 5603 2975 5603 2972 5603 2977 5604 2975 5604 3174 5604 3175 5605 2977 5605 3174 5605 2979 5606 2977 5606 3175 5606 3176 5607 2981 5607 2979 5607 2983 5608 2981 5608 3176 5608 3177 5609 2983 5609 3176 5609 2986 5610 2983 5610 3177 5610 2986 5611 3177 5611 3178 5611 2989 5612 2986 5612 3178 5612 2991 5613 2989 5613 3178 5613 2997 5614 2995 5614 3179 5614 2997 5615 3179 5615 3000 5615 3002 5616 3000 5616 3180 5616 3004 5617 3002 5617 3180 5617 3181 5618 3013 5618 3011 5618 3016 5619 3013 5619 3181 5619 3182 5620 3018 5620 3016 5620 3020 5621 3018 5621 3182 5621 3183 5622 3027 5622 3024 5622 3029 5623 3027 5623 3183 5623 3184 5624 3029 5624 3183 5624 3031 5625 3029 5625 3184 5625 3033 5626 3031 5626 3184 5626 3040 5627 3038 5627 3185 5627 3042 5628 3040 5628 3185 5628 3044 5629 3042 5629 3186 5629 3047 5630 3044 5630 3186 5630 3049 5631 3047 5631 3187 5631 3051 5632 3049 5632 3187 5632 3188 5633 3058 5633 3056 5633 3060 5634 3058 5634 3188 5634 3189 5635 3060 5635 3188 5635 3063 5636 3060 5636 3189 5636 3190 5637 3065 5637 3063 5637 3068 5638 3065 5638 3190 5638 3191 5639 3072 5639 3071 5639 3073 5640 3072 5640 3191 5640 3192 5641 3073 5641 3191 5641 2478 5642 3073 5642 3192 5642 2478 5643 3192 5643 3193 5643 2475 5644 2478 5644 3193 5644 2472 5645 2475 5645 3193 5645 3195 5646 2499 5646 3076 5646 3195 5647 2502 5647 2499 5647 3195 5648 2503 5648 2502 5648 3196 5649 2503 5649 3195 5649 3194 5650 2503 5650 3196 5650 3194 5651 3077 5651 2503 5651 3197 5652 3077 5652 3194 5652 3197 5653 3078 5653 3077 5653 2485 5654 3078 5654 3197 5654 2485 5655 3079 5655 3078 5655 2487 5656 3079 5656 2485 5656 2489 5657 3079 5657 2487 5657 2489 5658 2514 5658 3079 5658 2489 5659 2516 5659 2514 5659 2491 5660 2516 5660 2489 5660 2491 5661 2518 5661 2516 5661 2492 5662 2518 5662 2491 5662 2494 5663 2518 5663 2492 5663 2494 5664 3080 5664 2518 5664 2494 5665 3081 5665 3080 5665 2496 5666 3081 5666 2494 5666 2498 5667 3081 5667 2496 5667 2498 5668 2524 5668 3081 5668 2500 5669 2524 5669 2498 5669 2500 5670 2525 5670 2524 5670 2501 5671 2525 5671 2500 5671 2501 5672 3082 5672 2525 5672 2504 5673 3082 5673 2501 5673 2504 5674 2527 5674 3082 5674 2505 5675 2527 5675 2504 5675 2505 5676 2530 5676 2527 5676 2507 5677 2530 5677 2505 5677 2507 5678 3083 5678 2530 5678 2510 5679 3083 5679 2507 5679 2510 5680 2534 5680 3083 5680 2512 5681 2534 5681 2510 5681 2512 5682 2536 5682 2534 5682 2513 5683 2536 5683 2512 5683 2513 5684 2539 5684 2536 5684 3198 5685 2539 5685 2513 5685 3198 5686 3084 5686 2539 5686 2515 5687 3084 5687 3198 5687 2517 5688 3084 5688 2515 5688 2517 5689 2543 5689 3084 5689 2517 5690 2546 5690 2543 5690 2519 5691 2546 5691 2517 5691 2519 5692 2548 5692 2546 5692 2522 5693 2548 5693 2519 5693 2523 5694 2548 5694 2522 5694 2523 5695 3085 5695 2548 5695 2526 5696 3085 5696 2523 5696 2526 5697 3086 5697 3085 5697 2526 5698 3087 5698 3086 5698 2529 5699 3087 5699 2526 5699 2531 5700 3087 5700 2529 5700 2531 5701 2557 5701 3087 5701 2533 5702 2557 5702 2531 5702 2533 5703 3088 5703 2557 5703 2535 5704 3088 5704 2533 5704 2537 5705 3088 5705 2535 5705 2537 5706 3089 5706 3088 5706 2538 5707 3089 5707 2537 5707 2538 5708 3090 5708 3089 5708 2541 5709 3090 5709 2538 5709 2541 5710 2569 5710 3090 5710 2542 5711 2569 5711 2541 5711 2542 5712 3091 5712 2569 5712 2544 5713 3091 5713 2542 5713 2545 5714 3091 5714 2544 5714 2545 5715 2571 5715 3091 5715 2547 5716 2571 5716 2545 5716 2547 5717 3092 5717 2571 5717 2549 5718 3092 5718 2547 5718 2551 5719 3092 5719 2549 5719 2551 5720 3093 5720 3092 5720 2552 5721 3093 5721 2551 5721 2552 5722 2581 5722 3093 5722 2554 5723 2581 5723 2552 5723 2554 5724 2583 5724 2581 5724 2556 5725 2583 5725 2554 5725 2558 5726 2583 5726 2556 5726 2558 5727 3094 5727 2583 5727 2559 5728 3094 5728 2558 5728 2559 5729 3095 5729 3094 5729 2561 5730 3095 5730 2559 5730 2561 5731 2588 5731 3095 5731 2563 5732 2588 5732 2561 5732 2565 5733 2588 5733 2563 5733 2565 5734 3096 5734 2588 5734 2566 5735 3096 5735 2565 5735 2566 5736 3097 5736 3096 5736 2568 5737 3097 5737 2566 5737 2570 5738 3097 5738 2568 5738 2570 5739 3098 5739 3097 5739 2572 5740 3098 5740 2570 5740 2572 5741 3099 5741 3098 5741 2574 5742 3099 5742 2572 5742 2574 5743 2597 5743 3099 5743 2575 5744 2597 5744 2574 5744 2577 5745 2597 5745 2575 5745 2577 5746 2599 5746 2597 5746 2577 5747 3100 5747 2599 5747 2578 5748 3100 5748 2577 5748 2580 5749 3100 5749 2578 5749 2580 5750 2604 5750 3100 5750 2582 5751 2604 5751 2580 5751 2582 5752 2606 5752 2604 5752 2584 5753 2606 5753 2582 5753 2584 5754 2607 5754 2606 5754 2586 5755 2607 5755 2584 5755 2586 5756 2609 5756 2607 5756 2587 5757 2609 5757 2586 5757 2587 5758 2612 5758 2609 5758 2587 5759 3101 5759 2612 5759 2589 5760 3101 5760 2587 5760 2591 5761 3101 5761 2589 5761 2591 5762 3102 5762 3101 5762 2592 5763 3102 5763 2591 5763 2592 5764 2620 5764 3102 5764 2594 5765 2620 5765 2592 5765 2594 5766 2622 5766 2620 5766 2596 5767 2622 5767 2594 5767 2596 5768 3103 5768 2622 5768 2598 5769 3103 5769 2596 5769 2600 5770 3103 5770 2598 5770 2600 5771 2626 5771 3103 5771 3199 5772 2626 5772 2600 5772 3199 5773 2628 5773 2626 5773 2602 5774 2628 5774 3199 5774 2603 5775 2628 5775 2602 5775 2603 5776 2630 5776 2628 5776 2603 5777 2633 5777 2630 5777 2605 5778 2633 5778 2603 5778 2605 5779 3104 5779 2633 5779 2608 5780 3104 5780 2605 5780 2610 5781 3104 5781 2608 5781 2610 5782 3105 5782 3104 5782 2611 5783 3105 5783 2610 5783 2613 5784 3105 5784 2611 5784 2613 5785 3106 5785 3105 5785 2615 5786 3106 5786 2613 5786 2616 5787 3106 5787 2615 5787 2616 5788 2642 5788 3106 5788 2618 5789 2642 5789 2616 5789 2618 5790 2646 5790 2642 5790 2619 5791 2646 5791 2618 5791 2619 5792 3107 5792 2646 5792 2621 5793 3107 5793 2619 5793 2621 5794 3108 5794 3107 5794 2623 5795 3108 5795 2621 5795 2625 5796 3108 5796 2623 5796 2625 5797 2653 5797 3108 5797 2627 5798 2653 5798 2625 5798 2627 5799 3109 5799 2653 5799 2629 5800 3109 5800 2627 5800 2629 5801 2658 5801 3109 5801 2631 5802 2658 5802 2629 5802 2632 5803 2658 5803 2631 5803 2632 5804 3110 5804 2658 5804 2635 5805 3110 5805 2632 5805 2635 5806 3111 5806 3110 5806 2636 5807 3111 5807 2635 5807 2636 5808 3112 5808 3111 5808 2638 5809 3112 5809 2636 5809 2638 5810 2664 5810 3112 5810 2639 5811 2664 5811 2638 5811 2639 5812 3113 5812 2664 5812 2643 5813 3113 5813 2639 5813 2643 5814 3114 5814 3113 5814 2645 5815 3114 5815 2643 5815 2645 5816 3115 5816 3114 5816 2647 5817 3115 5817 2645 5817 2647 5818 2673 5818 3115 5818 2649 5819 2673 5819 2647 5819 2649 5820 3116 5820 2673 5820 2650 5821 3116 5821 2649 5821 2652 5822 3116 5822 2650 5822 2652 5823 2677 5823 3116 5823 2654 5824 2677 5824 2652 5824 2656 5825 2677 5825 2654 5825 2656 5826 2679 5826 2677 5826 2656 5827 2681 5827 2679 5827 2657 5828 2681 5828 2656 5828 2657 5829 3117 5829 2681 5829 2660 5830 3117 5830 2657 5830 2661 5831 3117 5831 2660 5831 2662 5832 2686 5832 2661 5832 2661 5833 2686 5833 3117 5833 2662 5834 3118 5834 2686 5834 2665 5835 3118 5835 2662 5835 2666 5836 3118 5836 2665 5836 2666 5837 2691 5837 3118 5837 2668 5838 2691 5838 2666 5838 2668 5839 2694 5839 2691 5839 2670 5840 2694 5840 2668 5840 2671 5841 2694 5841 2670 5841 2671 5842 3119 5842 2694 5842 2672 5843 3119 5843 2671 5843 2672 5844 3120 5844 3119 5844 2674 5845 3120 5845 2672 5845 2674 5846 2701 5846 3120 5846 2676 5847 2701 5847 2674 5847 2676 5848 3121 5848 2701 5848 2678 5849 3121 5849 2676 5849 2680 5850 3121 5850 2678 5850 2680 5851 2706 5851 3121 5851 2682 5852 2706 5852 2680 5852 2682 5853 2707 5853 2706 5853 2683 5854 2707 5854 2682 5854 2683 5855 2710 5855 2707 5855 2685 5856 2710 5856 2683 5856 2685 5857 2712 5857 2710 5857 2687 5858 2712 5858 2685 5858 2687 5859 3122 5859 2712 5859 2689 5860 3122 5860 2687 5860 2690 5861 3122 5861 2689 5861 2690 5862 3123 5862 3122 5862 2692 5863 3123 5863 2690 5863 2692 5864 3124 5864 3123 5864 2693 5865 3124 5865 2692 5865 2696 5866 3124 5866 2693 5866 2696 5867 2722 5867 3124 5867 2697 5868 2722 5868 2696 5868 2697 5869 3125 5869 2722 5869 2699 5870 3125 5870 2697 5870 2700 5871 3125 5871 2699 5871 2700 5872 3126 5872 3125 5872 2702 5873 3126 5873 2700 5873 2702 5874 2730 5874 3126 5874 2704 5875 2730 5875 2702 5875 2705 5876 2732 5876 2704 5876 2704 5877 2732 5877 2730 5877 2708 5878 2732 5878 2705 5878 2708 5879 2734 5879 2732 5879 2709 5880 2734 5880 2708 5880 2709 5881 2735 5881 2734 5881 2711 5882 2735 5882 2709 5882 2711 5883 2738 5883 2735 5883 2711 5884 3127 5884 2738 5884 2713 5885 3127 5885 2711 5885 2715 5886 3127 5886 2713 5886 2715 5887 3128 5887 3127 5887 2716 5888 3128 5888 2715 5888 2718 5889 3128 5889 2716 5889 2718 5890 2744 5890 3128 5890 2718 5891 3129 5891 2744 5891 2720 5892 3129 5892 2718 5892 2721 5893 3129 5893 2720 5893 2723 5894 3130 5894 2721 5894 2721 5895 3130 5895 3129 5895 2725 5896 3130 5896 2723 5896 2725 5897 2751 5897 3130 5897 2726 5898 2751 5898 2725 5898 2726 5899 2753 5899 2751 5899 2728 5900 2753 5900 2726 5900 2728 5901 3131 5901 2753 5901 2729 5902 3131 5902 2728 5902 2731 5903 3131 5903 2729 5903 2731 5904 2760 5904 3131 5904 2733 5905 2760 5905 2731 5905 2733 5906 3132 5906 2760 5906 2736 5907 3132 5907 2733 5907 2736 5908 2764 5908 3132 5908 2737 5909 2764 5909 2736 5909 2740 5910 2764 5910 2737 5910 2740 5911 3133 5911 2764 5911 2741 5912 3133 5912 2740 5912 3200 5913 3133 5913 2741 5913 3200 5914 3134 5914 3133 5914 2743 5915 3134 5915 3200 5915 2743 5916 3135 5916 3134 5916 2745 5917 3135 5917 2743 5917 2747 5918 3135 5918 2745 5918 2749 5919 3135 5919 2747 5919 2749 5920 3136 5920 3135 5920 2750 5921 3136 5921 2749 5921 2750 5922 2779 5922 3136 5922 2752 5923 2779 5923 2750 5923 2754 5924 2779 5924 2752 5924 2754 5925 2782 5925 2779 5925 2756 5926 2782 5926 2754 5926 2756 5927 3137 5927 2782 5927 2758 5928 3137 5928 2756 5928 2759 5929 2786 5929 2758 5929 2758 5930 2786 5930 3137 5930 2763 5931 2789 5931 2759 5931 2759 5932 2789 5932 2786 5932 2765 5933 2789 5933 2763 5933 2765 5934 3138 5934 2789 5934 2767 5935 3138 5935 2765 5935 2768 5936 3138 5936 2767 5936 2768 5937 3139 5937 3138 5937 2770 5938 3139 5938 2768 5938 2770 5939 2795 5939 3139 5939 2771 5940 2795 5940 2770 5940 2771 5941 2798 5941 2795 5941 2773 5942 2798 5942 2771 5942 2773 5943 2800 5943 2798 5943 2774 5944 2800 5944 2773 5944 2774 5945 3140 5945 2800 5945 2777 5946 3140 5946 2774 5946 2777 5947 3141 5947 3140 5947 2778 5948 3141 5948 2777 5948 2780 5949 3141 5949 2778 5949 2780 5950 2804 5950 3141 5950 2781 5951 2804 5951 2780 5951 2781 5952 3142 5952 2804 5952 2783 5953 3142 5953 2781 5953 2785 5954 3142 5954 2783 5954 2785 5955 3143 5955 3142 5955 2787 5956 3143 5956 2785 5956 2787 5957 3144 5957 3143 5957 2788 5958 3144 5958 2787 5958 2788 5959 2813 5959 3144 5959 2791 5960 2813 5960 2788 5960 2791 5961 2817 5961 2813 5961 2792 5962 2817 5962 2791 5962 2794 5963 2817 5963 2792 5963 2794 5964 3145 5964 2817 5964 2796 5965 3145 5965 2794 5965 2797 5966 3145 5966 2796 5966 2797 5967 2821 5967 3145 5967 2799 5968 2821 5968 2797 5968 2799 5969 2822 5969 2821 5969 2799 5970 2824 5970 2822 5970 2801 5971 2824 5971 2799 5971 2801 5972 3146 5972 2824 5972 2803 5973 3146 5973 2801 5973 2805 5974 3146 5974 2803 5974 2805 5975 2829 5975 3146 5975 2807 5976 2829 5976 2805 5976 2807 5977 3147 5977 2829 5977 2809 5978 3147 5978 2807 5978 3201 5979 3147 5979 2809 5979 3201 5980 2836 5980 3147 5980 2810 5981 2836 5981 3201 5981 2810 5982 2837 5982 2836 5982 2812 5983 2837 5983 2810 5983 2812 5984 3148 5984 2837 5984 2814 5985 3148 5985 2812 5985 2816 5986 3148 5986 2814 5986 2816 5987 3149 5987 3148 5987 2819 5988 3149 5988 2816 5988 2819 5989 3150 5989 3149 5989 2820 5990 3150 5990 2819 5990 2820 5991 3151 5991 3150 5991 2823 5992 3151 5992 2820 5992 2825 5993 3151 5993 2823 5993 2825 5994 3152 5994 3151 5994 2827 5995 3152 5995 2825 5995 2828 5996 3152 5996 2827 5996 2828 5997 3153 5997 3152 5997 2828 5998 3154 5998 3153 5998 2830 5999 3154 5999 2828 5999 2830 6000 3155 6000 3154 6000 2832 6001 3155 6001 2830 6001 2833 6002 3155 6002 2832 6002 2833 6003 3156 6003 3155 6003 2835 6004 3156 6004 2833 6004 2835 6005 2863 6005 3156 6005 2838 6006 2863 6006 2835 6006 2838 6007 3157 6007 2863 6007 2840 6008 3157 6008 2838 6008 2840 6009 2864 6009 3157 6009 2842 6010 2864 6010 2840 6010 2842 6011 2867 6011 2864 6011 2843 6012 2867 6012 2842 6012 2843 6013 2868 6013 2867 6013 2845 6014 2870 6014 2843 6014 2843 6015 2870 6015 2868 6015 2847 6016 2870 6016 2845 6016 2847 6017 3158 6017 2870 6017 2850 6018 3158 6018 2847 6018 2850 6019 2875 6019 3158 6019 2852 6020 2875 6020 2850 6020 2852 6021 2877 6021 2875 6021 2853 6022 2877 6022 2852 6022 2853 6023 2879 6023 2877 6023 2855 6024 2879 6024 2853 6024 2855 6025 2881 6025 2879 6025 2857 6026 2881 6026 2855 6026 2857 6027 3159 6027 2881 6027 2858 6028 3159 6028 2857 6028 2859 6029 3159 6029 2858 6029 2859 6030 2886 6030 3159 6030 2861 6031 2886 6031 2859 6031 2861 6032 2887 6032 2886 6032 2862 6033 2887 6033 2861 6033 2862 6034 3160 6034 2887 6034 2865 6035 3160 6035 2862 6035 2865 6036 3161 6036 3160 6036 2866 6037 3161 6037 2865 6037 2869 6038 3161 6038 2866 6038 2869 6039 3162 6039 3161 6039 2871 6040 3162 6040 2869 6040 2871 6041 2897 6041 3162 6041 2873 6042 2897 6042 2871 6042 2873 6043 3163 6043 2897 6043 2874 6044 3163 6044 2873 6044 2874 6045 3164 6045 3163 6045 2876 6046 3164 6046 2874 6046 2878 6047 3164 6047 2876 6047 2878 6048 2904 6048 3164 6048 2880 6049 2904 6049 2878 6049 2882 6050 2904 6050 2880 6050 2882 6051 2906 6051 2904 6051 2884 6052 2906 6052 2882 6052 2884 6053 2909 6053 2906 6053 2885 6054 2909 6054 2884 6054 2885 6055 2912 6055 2909 6055 2888 6056 2912 6056 2885 6056 2888 6057 2914 6057 2912 6057 2889 6058 2914 6058 2888 6058 2889 6059 2915 6059 2914 6059 2889 6060 2917 6060 2915 6060 2891 6061 2917 6061 2889 6061 2892 6062 2917 6062 2891 6062 2892 6063 3165 6063 2917 6063 2894 6064 3165 6064 2892 6064 2896 6065 3165 6065 2894 6065 2896 6066 3166 6066 3165 6066 2898 6067 3166 6067 2896 6067 2898 6068 2923 6068 3166 6068 2899 6069 2923 6069 2898 6069 2899 6070 3167 6070 2923 6070 2901 6071 3167 6071 2899 6071 2903 6072 3167 6072 2901 6072 2903 6073 2930 6073 3167 6073 2905 6074 2930 6074 2903 6074 2905 6075 3168 6075 2930 6075 2907 6076 3168 6076 2905 6076 2908 6077 3168 6077 2907 6077 2908 6078 2936 6078 3168 6078 2910 6079 2936 6079 2908 6079 2910 6080 2938 6080 2936 6080 2911 6081 2938 6081 2910 6081 2911 6082 3169 6082 2938 6082 2913 6083 3169 6083 2911 6083 2913 6084 3170 6084 3169 6084 2916 6085 3170 6085 2913 6085 2916 6086 2945 6086 3170 6086 2919 6087 2945 6087 2916 6087 2920 6088 2945 6088 2919 6088 2920 6089 2946 6089 2945 6089 2922 6090 2946 6090 2920 6090 2922 6091 2949 6091 2946 6091 2924 6092 2949 6092 2922 6092 2924 6093 2951 6093 2949 6093 2926 6094 2951 6094 2924 6094 2926 6095 2953 6095 2951 6095 2927 6096 2953 6096 2926 6096 2927 6097 3171 6097 2953 6097 2929 6098 3171 6098 2927 6098 2931 6099 3171 6099 2929 6099 2931 6100 3172 6100 3171 6100 2935 6101 3172 6101 2931 6101 2935 6102 2960 6102 3172 6102 2935 6103 2961 6103 2960 6103 2937 6104 2961 6104 2935 6104 2937 6105 2963 6105 2961 6105 2939 6106 2963 6106 2937 6106 2939 6107 3173 6107 2963 6107 2940 6108 3173 6108 2939 6108 2942 6109 3173 6109 2940 6109 2942 6110 2968 6110 3173 6110 2942 6111 2970 6111 2968 6111 2944 6112 2970 6112 2942 6112 2944 6113 2972 6113 2970 6113 2947 6114 2972 6114 2944 6114 2947 6115 3174 6115 2972 6115 2948 6116 3174 6116 2947 6116 2950 6117 3174 6117 2948 6117 2950 6118 3175 6118 3174 6118 2952 6119 3175 6119 2950 6119 2952 6120 2979 6120 3175 6120 2954 6121 2979 6121 2952 6121 2954 6122 3176 6122 2979 6122 2956 6123 3176 6123 2954 6123 2958 6124 3176 6124 2956 6124 2958 6125 3177 6125 3176 6125 2959 6126 3177 6126 2958 6126 2959 6127 3178 6127 3177 6127 2962 6128 3178 6128 2959 6128 2962 6129 2991 6129 3178 6129 2964 6130 2991 6130 2962 6130 2965 6131 2991 6131 2964 6131 2965 6132 2993 6132 2991 6132 2967 6133 2993 6133 2965 6133 2967 6134 2995 6134 2993 6134 2969 6135 2995 6135 2967 6135 2969 6136 3179 6136 2995 6136 2971 6137 3179 6137 2969 6137 2973 6138 3179 6138 2971 6138 2973 6139 3000 6139 3179 6139 2974 6140 3000 6140 2973 6140 2976 6141 3000 6141 2974 6141 2976 6142 3180 6142 3000 6142 2978 6143 3180 6143 2976 6143 2978 6144 3004 6144 3180 6144 2980 6145 3004 6145 2978 6145 2980 6146 3007 6146 3004 6146 2982 6147 3007 6147 2980 6147 2982 6148 3009 6148 3007 6148 2984 6149 3009 6149 2982 6149 2984 6150 3011 6150 3009 6150 2985 6151 3011 6151 2984 6151 2987 6152 3011 6152 2985 6152 2987 6153 3181 6153 3011 6153 2990 6154 3181 6154 2987 6154 2992 6155 3016 6155 2990 6155 2990 6156 3016 6156 3181 6156 2992 6157 3182 6157 3016 6157 2994 6158 3182 6158 2992 6158 2996 6159 3182 6159 2994 6159 2996 6160 3020 6160 3182 6160 2996 6161 3022 6161 3020 6161 2998 6162 3022 6162 2996 6162 2998 6163 3024 6163 3022 6163 2999 6164 3024 6164 2998 6164 2999 6165 3183 6165 3024 6165 3001 6166 3183 6166 2999 6166 3003 6167 3183 6167 3001 6167 3003 6168 3184 6168 3183 6168 3005 6169 3184 6169 3003 6169 3006 6170 3184 6170 3005 6170 3006 6171 3033 6171 3184 6171 3008 6172 3033 6172 3006 6172 3008 6173 3035 6173 3033 6173 3010 6174 3035 6174 3008 6174 3010 6175 3038 6175 3035 6175 3012 6176 3038 6176 3010 6176 3012 6177 3185 6177 3038 6177 3014 6178 3185 6178 3012 6178 3014 6179 3042 6179 3185 6179 3015 6180 3042 6180 3014 6180 3015 6181 3186 6181 3042 6181 3017 6182 3186 6182 3015 6182 3019 6183 3186 6183 3017 6183 3019 6184 3047 6184 3186 6184 3021 6185 3047 6185 3019 6185 3021 6186 3187 6186 3047 6186 3023 6187 3187 6187 3021 6187 3025 6188 3187 6188 3023 6188 3025 6189 3051 6189 3187 6189 3026 6190 3051 6190 3025 6190 3026 6191 3054 6191 3051 6191 3202 6192 3054 6192 3026 6192 3030 6193 3056 6193 3202 6193 3202 6194 3056 6194 3054 6194 3030 6195 3188 6195 3056 6195 3032 6196 3188 6196 3030 6196 3034 6197 3189 6197 3032 6197 3032 6198 3189 6198 3188 6198 3036 6199 3189 6199 3034 6199 3036 6200 3063 6200 3189 6200 3037 6201 3063 6201 3036 6201 3037 6202 3190 6202 3063 6202 3039 6203 3190 6203 3037 6203 3039 6204 3068 6204 3190 6204 3041 6205 3068 6205 3039 6205 3043 6206 3068 6206 3041 6206 3043 6207 3070 6207 3068 6207 3045 6208 3070 6208 3043 6208 3045 6209 3071 6209 3070 6209 3046 6210 3071 6210 3045 6210 3046 6211 3191 6211 3071 6211 3048 6212 3191 6212 3046 6212 3050 6213 3191 6213 3048 6213 3050 6214 3192 6214 3191 6214 3052 6215 3192 6215 3050 6215 3052 6216 3193 6216 3192 6216 3053 6217 3193 6217 3052 6217 3055 6218 3193 6218 3053 6218 3055 6219 2472 6219 3193 6219 3057 6220 2472 6220 3055 6220 3057 6221 2470 6221 2472 6221 3059 6222 2470 6222 3057 6222 3061 6223 2470 6223 3059 6223 3061 6224 2469 6224 2470 6224 3062 6225 2469 6225 3061 6225 3062 6226 2474 6226 2469 6226 3064 6227 2474 6227 3062 6227 3066 6228 2474 6228 3064 6228 3066 6229 2477 6229 2474 6229 3066 6230 2480 6230 2477 6230 3067 6231 2480 6231 3066 6231 2484 6232 3197 6232 3194 6232 2485 6233 3197 6233 2484 6233 2510 6234 2507 6234 2508 6234 2515 6235 3198 6235 2513 6235 2529 6236 2526 6236 2528 6236 2602 6237 3199 6237 2600 6237 2643 6238 2639 6238 2641 6238 2743 6239 3200 6239 2741 6239 2763 6240 2759 6240 2761 6240 2810 6241 3201 6241 2809 6241 2850 6242 2847 6242 2848 6242 2935 6243 2931 6243 2933 6243 2990 6244 2987 6244 2988 6244 3028 6245 3202 6245 3026 6245 3030 6246 3202 6246 3028 6246 2480 6247 3067 6247 3069 6247 3225 6248 2480 6248 3069 6248 3224 6249 3225 6249 3069 6249 3206 6250 3203 6250 3244 6250 3207 6251 3205 6251 3203 6251 3207 6252 3203 6252 3206 6252 3208 6253 2471 6253 3205 6253 3208 6254 3205 6254 3207 6254 3206 6255 3244 6255 3204 6255 3209 6256 3207 6256 3206 6256 3208 6257 3207 6257 3209 6257 3210 6258 3209 6258 3206 6258 3209 6259 2476 6259 3208 6259 3210 6260 3206 6260 3204 6260 2476 6261 3209 6261 3210 6261 3212 6262 3210 6262 3204 6262 3213 6263 3211 6263 3204 6263 3211 6264 3212 6264 3204 6264 2476 6265 3210 6265 3212 6265 3212 6266 3211 6266 3214 6266 2481 6267 2476 6267 3212 6267 3213 6268 3214 6268 3211 6268 3215 6269 3212 6269 3214 6269 2481 6270 3212 6270 3215 6270 3216 6271 3215 6271 3214 6271 2482 6272 2481 6272 3215 6272 3218 6273 3216 6273 3214 6273 3217 6274 3214 6274 3213 6274 2482 6275 3215 6275 3216 6275 3218 6276 3214 6276 3217 6276 2483 6277 2482 6277 3216 6277 3219 6278 3216 6278 3218 6278 3219 6279 2483 6279 3216 6279 3221 6280 3218 6280 3217 6280 3220 6281 3217 6281 3213 6281 3221 6282 3219 6282 3218 6282 3222 6283 3221 6283 3217 6283 3222 6284 3217 6284 3220 6284 3221 6285 2483 6285 3219 6285 3221 6286 3224 6286 2483 6286 3223 6287 3222 6287 3220 6287 3224 6288 3221 6288 3222 6288 3225 6289 3222 6289 3223 6289 3225 6290 3224 6290 3222 6290 3226 6291 3225 6291 3223 6291 3228 6292 3223 6292 3220 6292 3226 6293 3223 6293 3228 6293 3227 6294 3225 6294 3226 6294 3227 6295 3226 6295 3228 6295 3229 6296 3227 6296 3228 6296 2480 6297 3225 6297 3227 6297 3229 6298 3228 6298 3230 6298 2479 6299 3227 6299 3229 6299 2480 6300 3227 6300 2479 6300 3230 6301 2479 6301 3229 6301 3231 6302 3230 6302 3228 6302 3232 6303 2479 6303 3230 6303 3233 6304 3230 6304 3231 6304 2477 6305 2479 6305 3232 6305 3233 6306 3232 6306 3230 6306 3235 6307 3231 6307 3234 6307 3235 6308 3233 6308 3231 6308 3233 6309 2477 6309 3232 6309 3237 6310 3233 6310 3235 6310 3233 6311 3237 6311 2477 6311 2473 6312 3237 6312 3235 6312 3238 6313 3235 6313 3234 6313 3238 6314 3234 6314 3236 6314 3238 6315 2473 6315 3235 6315 3240 6316 2473 6316 3238 6316 3241 6317 3238 6317 3236 6317 3241 6318 3240 6318 3238 6318 3241 6319 3236 6319 3239 6319 3242 6320 3241 6320 3239 6320 2468 6321 3240 6321 3241 6321 3242 6322 3243 6322 3241 6322 2468 6323 3241 6323 3243 6323 3243 6324 2471 6324 2468 6324 3242 6325 3239 6325 3203 6325 3203 6326 3239 6326 3244 6326 2471 6327 3243 6327 3242 6327 3242 6328 3203 6328 3205 6328 3205 6329 2471 6329 3242 6329 3213 6330 3228 6330 3220 6330 3213 6331 3204 6331 3244 6331 3213 6332 3239 6332 3236 6332 3213 6333 3244 6333 3239 6333 3213 6334 3231 6334 3228 6334 3213 6335 3234 6335 3231 6335 3213 6336 3236 6336 3234 6336 3246 6337 3251 6337 3254 6337 3246 6338 3245 6338 3251 6338 3245 6339 3247 6339 3251 6339 3251 6340 3247 6340 3252 6340 3247 6341 3248 6341 3252 6341 3252 6342 3248 6342 3256 6342 3248 6343 3249 6343 3256 6343 3256 6344 3249 6344 3255 6344 3249 6345 3250 6345 3255 6345 3255 6346 3250 6346 3253 6346 3253 6347 3246 6347 3254 6347 3250 6348 3246 6348 3253 6348 3252 6349 3257 6349 3258 6349 3252 6350 3258 6350 3259 6350 3256 6351 3262 6351 3260 6351 3256 6352 3260 6352 3257 6352 3256 6353 3261 6353 3262 6353 3256 6354 3257 6354 3252 6354 3251 6355 3259 6355 3263 6355 3251 6356 3252 6356 3259 6356 3264 6357 3251 6357 3263 6357 3255 6358 3265 6358 3261 6358 3255 6359 3261 6359 3256 6359 3254 6360 3264 6360 3266 6360 3254 6361 3251 6361 3264 6361 3267 6362 3265 6362 3255 6362 3267 6363 3255 6363 3253 6363 3268 6364 3254 6364 3266 6364 3269 6365 3254 6365 3268 6365 3270 6366 3267 6366 3253 6366 3269 6367 3253 6367 3254 6367 3269 6368 3270 6368 3253 6368 3245 6369 3248 6369 3247 6369 3250 6370 3249 6370 3246 6370 3246 6371 3249 6371 3245 6371 3245 6372 3249 6372 3248 6372 3271 6373 3283 6373 3262 6373 3271 6374 3262 6374 3261 6374 3272 6375 3271 6375 3261 6375 3272 6376 3261 6376 3265 6376 3272 6377 3265 6377 3267 6377 3273 6378 3272 6378 3267 6378 3274 6379 3273 6379 3267 6379 3274 6380 3267 6380 3270 6380 3275 6381 3274 6381 3270 6381 3275 6382 3270 6382 3269 6382 3275 6383 3269 6383 3268 6383 3276 6384 3275 6384 3268 6384 3276 6385 3268 6385 3266 6385 3277 6386 3276 6386 3266 6386 3277 6387 3266 6387 3264 6387 3278 6388 3277 6388 3264 6388 3278 6389 3264 6389 3263 6389 3279 6390 3278 6390 3263 6390 3279 6391 3263 6391 3259 6391 3280 6392 3279 6392 3259 6392 3280 6393 3259 6393 3258 6393 3281 6394 3280 6394 3258 6394 3281 6395 3258 6395 3257 6395 3282 6396 3281 6396 3257 6396 3282 6397 3257 6397 3260 6397 3283 6398 3282 6398 3260 6398 3283 6399 3260 6399 3262 6399 3075 6400 3074 6400 3278 6400 3074 6401 3277 6401 3278 6401 2493 6402 3277 6402 3074 6402 3075 6403 3278 6403 3279 6403 3076 6404 3075 6404 3279 6404 2493 6405 3276 6405 3277 6405 2486 6406 3276 6406 2493 6406 3076 6407 3279 6407 3280 6407 2486 6408 3275 6408 3276 6408 3195 6409 3076 6409 3280 6409 2490 6410 3275 6410 2486 6410 3195 6411 3280 6411 3281 6411 2488 6412 3275 6412 2490 6412 3274 6413 3275 6413 2488 6413 3282 6414 3195 6414 3281 6414 3282 6415 3196 6415 3195 6415 3283 6416 3196 6416 3282 6416 3283 6417 3194 6417 3196 6417 3273 6418 3274 6418 2488 6418 3271 6419 3194 6419 3283 6419 3273 6420 2488 6420 2484 6420 3272 6421 3273 6421 2484 6421 3272 6422 3194 6422 3271 6422 3272 6423 2484 6423 3194 6423

+
+ + + +

3284 6424 3285 6424 3286 6424 3287 6425 3285 6425 3284 6425 3285 6426 3288 6426 3286 6426 3287 6427 3289 6427 3285 6427 3286 6428 3288 6428 3290 6428 3287 6429 3291 6429 3289 6429 3292 6430 3291 6430 3287 6430 3290 6431 3288 6431 3293 6431 3294 6432 3291 6432 3292 6432 3288 6433 3295 6433 3293 6433 3294 6434 3296 6434 3291 6434 3296 6435 3297 6435 3291 6435 3297 6436 3296 6436 3298 6436 3306 6437 3303 6437 3302 6437 3306 6438 3305 6438 3303 6438 3306 6439 3307 6439 3305 6439 3309 6440 3307 6440 3306 6440 3309 6441 3308 6441 3307 6441 3309 6442 3310 6442 3308 6442 3304 6443 3310 6443 3309 6443 3304 6444 3311 6444 3310 6444 3312 6445 3311 6445 3304 6445 3312 6446 3313 6446 3311 6446 3314 6447 3313 6447 3312 6447 3314 6448 3315 6448 3313 6448 3316 6449 3315 6449 3314 6449 3316 6450 3317 6450 3315 6450 3316 6451 3318 6451 3317 6451 3319 6452 3318 6452 3316 6452 3319 6453 3320 6453 3318 6453 3321 6454 3320 6454 3319 6454 3321 6455 3322 6455 3320 6455 3323 6456 3322 6456 3321 6456 3323 6457 3324 6457 3322 6457 3325 6458 3324 6458 3323 6458 3325 6459 3326 6459 3324 6459 3327 6460 3326 6460 3325 6460 3327 6461 3328 6461 3326 6461 3329 6462 3328 6462 3327 6462 3329 6463 3330 6463 3328 6463 3331 6464 3330 6464 3329 6464 3331 6465 3332 6465 3330 6465 3331 6466 3333 6466 3332 6466 3334 6467 3333 6467 3331 6467 3334 6468 3335 6468 3333 6468 3336 6469 3335 6469 3334 6469 3336 6470 3337 6470 3335 6470 3336 6471 3338 6471 3337 6471 3339 6472 3338 6472 3336 6472 3339 6473 3340 6473 3338 6473 3341 6474 3340 6474 3339 6474 3341 6475 3342 6475 3340 6475 3343 6476 3342 6476 3341 6476 3343 6477 3344 6477 3342 6477 3345 6478 3346 6478 3343 6478 3343 6479 3346 6479 3344 6479 3347 6480 3346 6480 3345 6480 3347 6481 3348 6481 3346 6481 3347 6482 3349 6482 3348 6482 3350 6483 3349 6483 3347 6483 3350 6484 3351 6484 3349 6484 3352 6485 3351 6485 3350 6485 3352 6486 3353 6486 3351 6486 3354 6487 3353 6487 3352 6487 3354 6488 3355 6488 3353 6488 3354 6489 3356 6489 3355 6489 3357 6490 3356 6490 3354 6490 3357 6491 3358 6491 3356 6491 3357 6492 3359 6492 3358 6492 3360 6493 3359 6493 3357 6493 3360 6494 3361 6494 3359 6494 3362 6495 3361 6495 3360 6495 3362 6496 3363 6496 3361 6496 3364 6497 3363 6497 3362 6497 3364 6498 3365 6498 3363 6498 3366 6499 3365 6499 3364 6499 3366 6500 3367 6500 3365 6500 3366 6501 3368 6501 3367 6501 3369 6502 3368 6502 3366 6502 3369 6503 3370 6503 3368 6503 3371 6504 3370 6504 3369 6504 3371 6505 3372 6505 3370 6505 3371 6506 3373 6506 3372 6506 3374 6507 3373 6507 3371 6507 3374 6508 3375 6508 3373 6508 3376 6509 3375 6509 3374 6509 3376 6510 3377 6510 3375 6510 3376 6511 3378 6511 3377 6511 3379 6512 3378 6512 3376 6512 3379 6513 3380 6513 3378 6513 3381 6514 3380 6514 3379 6514 3381 6515 3382 6515 3380 6515 3383 6516 3382 6516 3381 6516 3383 6517 3384 6517 3382 6517 3385 6518 3384 6518 3383 6518 3385 6519 3386 6519 3384 6519 3387 6520 3386 6520 3385 6520 3387 6521 3388 6521 3386 6521 3389 6522 3388 6522 3387 6522 3389 6523 3390 6523 3388 6523 3391 6524 3390 6524 3389 6524 3391 6525 3392 6525 3390 6525 3391 6526 3393 6526 3392 6526 3394 6527 3393 6527 3391 6527 3394 6528 3395 6528 3393 6528 3394 6529 3396 6529 3395 6529 3397 6530 3396 6530 3394 6530 3397 6531 3398 6531 3396 6531 3397 6532 3399 6532 3398 6532 3400 6533 3399 6533 3397 6533 3400 6534 3401 6534 3399 6534 3402 6535 3401 6535 3400 6535 3402 6536 3403 6536 3401 6536 3404 6537 3403 6537 3402 6537 3404 6538 3405 6538 3403 6538 3406 6539 3405 6539 3404 6539 3406 6540 3407 6540 3405 6540 3406 6541 3408 6541 3407 6541 3409 6542 3408 6542 3406 6542 3409 6543 3410 6543 3408 6543 3411 6544 3410 6544 3409 6544 3411 6545 3412 6545 3410 6545 3413 6546 3412 6546 3411 6546 3413 6547 3414 6547 3412 6547 3415 6548 3414 6548 3413 6548 3415 6549 3416 6549 3414 6549 3417 6550 3418 6550 3415 6550 3415 6551 3418 6551 3416 6551 3417 6552 3419 6552 3418 6552 3420 6553 3419 6553 3417 6553 3420 6554 3421 6554 3419 6554 3422 6555 3421 6555 3420 6555 3422 6556 3423 6556 3421 6556 3422 6557 3424 6557 3423 6557 3425 6558 3424 6558 3422 6558 3425 6559 3426 6559 3424 6559 3425 6560 3427 6560 3426 6560 3428 6561 3427 6561 3425 6561 3428 6562 3429 6562 3427 6562 3430 6563 3429 6563 3428 6563 3430 6564 3431 6564 3429 6564 3432 6565 3431 6565 3430 6565 3432 6566 3433 6566 3431 6566 3434 6567 3433 6567 3432 6567 3434 6568 3435 6568 3433 6568 3436 6569 3435 6569 3434 6569 3436 6570 3437 6570 3435 6570 3438 6571 3437 6571 3436 6571 3438 6572 3439 6572 3437 6572 3440 6573 3439 6573 3438 6573 3440 6574 3441 6574 3439 6574 3440 6575 3442 6575 3441 6575 3443 6576 3442 6576 3440 6576 3443 6577 3444 6577 3442 6577 3445 6578 3444 6578 3443 6578 3445 6579 3446 6579 3444 6579 3445 6580 3447 6580 3446 6580 3448 6581 3447 6581 3445 6581 3448 6582 3449 6582 3447 6582 3450 6583 3449 6583 3448 6583 3450 6584 3451 6584 3449 6584 3452 6585 3451 6585 3450 6585 3452 6586 3453 6586 3451 6586 3452 6587 3454 6587 3453 6587 3455 6588 3454 6588 3452 6588 3455 6589 3456 6589 3454 6589 3457 6590 3456 6590 3455 6590 3457 6591 3458 6591 3456 6591 3457 6592 3459 6592 3458 6592 3460 6593 3459 6593 3457 6593 3460 6594 3461 6594 3459 6594 3462 6595 3461 6595 3460 6595 3462 6596 3463 6596 3461 6596 3464 6597 3463 6597 3462 6597 3464 6598 3465 6598 3463 6598 3466 6599 3465 6599 3464 6599 3466 6600 3467 6600 3465 6600 3468 6601 3467 6601 3466 6601 3468 6602 3469 6602 3467 6602 3470 6603 3469 6603 3468 6603 3470 6604 3471 6604 3469 6604 3472 6605 3471 6605 3470 6605 3472 6606 3473 6606 3471 6606 3474 6607 3473 6607 3472 6607 3474 6608 3475 6608 3473 6608 3474 6609 3476 6609 3475 6609 3477 6610 3476 6610 3474 6610 3477 6611 3478 6611 3476 6611 3479 6612 3478 6612 3477 6612 3479 6613 3480 6613 3478 6613 3481 6614 3480 6614 3479 6614 3481 6615 3482 6615 3480 6615 3483 6616 3482 6616 3481 6616 3483 6617 3484 6617 3482 6617 3485 6618 3484 6618 3483 6618 3485 6619 3486 6619 3484 6619 3487 6620 3486 6620 3485 6620 3487 6621 3488 6621 3486 6621 3487 6622 3489 6622 3488 6622 3490 6623 3489 6623 3487 6623 3490 6624 3491 6624 3489 6624 3490 6625 3492 6625 3491 6625 3490 6626 3493 6626 3492 6626 3494 6627 3493 6627 3490 6627 3494 6628 3495 6628 3493 6628 3496 6629 3495 6629 3494 6629 3496 6630 3497 6630 3495 6630 3496 6631 3498 6631 3497 6631 3499 6632 3498 6632 3496 6632 3500 6633 3498 6633 3499 6633 3500 6634 3501 6634 3498 6634 3500 6635 3502 6635 3501 6635 3503 6636 3502 6636 3500 6636 3503 6637 3504 6637 3502 6637 3505 6638 3504 6638 3503 6638 3505 6639 3506 6639 3504 6639 3505 6640 3507 6640 3506 6640 3508 6641 3507 6641 3505 6641 3508 6642 3509 6642 3507 6642 3510 6643 3509 6643 3508 6643 3510 6644 3511 6644 3509 6644 3510 6645 3512 6645 3511 6645 3513 6646 3512 6646 3510 6646 3514 6647 3512 6647 3513 6647 3514 6648 3515 6648 3512 6648 3514 6649 3516 6649 3515 6649 3517 6650 3516 6650 3514 6650 3517 6651 3518 6651 3516 6651 3519 6652 3518 6652 3517 6652 3519 6653 3520 6653 3518 6653 3521 6654 3520 6654 3519 6654 3521 6655 3522 6655 3520 6655 3523 6656 3522 6656 3521 6656 3523 6657 3524 6657 3522 6657 3525 6658 3524 6658 3523 6658 3525 6659 3526 6659 3524 6659 3527 6660 3526 6660 3525 6660 3527 6661 3528 6661 3526 6661 3527 6662 3529 6662 3528 6662 3530 6663 3529 6663 3527 6663 3530 6664 3531 6664 3529 6664 3532 6665 3531 6665 3530 6665 3532 6666 3533 6666 3531 6666 3534 6667 3533 6667 3532 6667 3534 6668 3535 6668 3533 6668 3536 6669 3535 6669 3534 6669 3536 6670 3537 6670 3535 6670 3538 6671 3537 6671 3536 6671 3538 6672 3539 6672 3537 6672 3540 6673 3539 6673 3538 6673 3540 6674 3541 6674 3539 6674 3542 6675 3541 6675 3540 6675 3542 6676 3543 6676 3541 6676 3542 6677 3544 6677 3543 6677 3545 6678 3544 6678 3542 6678 3545 6679 3546 6679 3544 6679 3545 6680 3547 6680 3546 6680 3548 6681 3547 6681 3545 6681 3548 6682 3549 6682 3547 6682 3550 6683 3549 6683 3548 6683 3550 6684 3551 6684 3549 6684 3552 6685 3551 6685 3550 6685 3552 6686 3553 6686 3551 6686 3552 6687 3554 6687 3553 6687 3555 6688 3554 6688 3552 6688 3555 6689 3556 6689 3554 6689 3555 6690 3557 6690 3556 6690 3558 6691 3557 6691 3555 6691 3558 6692 3559 6692 3557 6692 3560 6693 3559 6693 3558 6693 3560 6694 3561 6694 3559 6694 3562 6695 3561 6695 3560 6695 3562 6696 3563 6696 3561 6696 3564 6697 3563 6697 3562 6697 3564 6698 3565 6698 3563 6698 3566 6699 3565 6699 3564 6699 3566 6700 3567 6700 3565 6700 3568 6701 3567 6701 3566 6701 3568 6702 3569 6702 3567 6702 3570 6703 3569 6703 3568 6703 3570 6704 3571 6704 3569 6704 3572 6705 3571 6705 3570 6705 3573 6706 3571 6706 3572 6706 3573 6707 3574 6707 3571 6707 3575 6708 3576 6708 3573 6708 3573 6709 3576 6709 3574 6709 3577 6710 3578 6710 3575 6710 3575 6711 3578 6711 3576 6711 3577 6712 3579 6712 3578 6712 3580 6713 3579 6713 3577 6713 3580 6714 3581 6714 3579 6714 3582 6715 3581 6715 3580 6715 3582 6716 3583 6716 3581 6716 3584 6717 3583 6717 3582 6717 3584 6718 3585 6718 3583 6718 3584 6719 3586 6719 3585 6719 3587 6720 3586 6720 3584 6720 3587 6721 3588 6721 3586 6721 3589 6722 3588 6722 3587 6722 3589 6723 3590 6723 3588 6723 3589 6724 3591 6724 3590 6724 3592 6725 3591 6725 3589 6725 3592 6726 3593 6726 3591 6726 3594 6727 3593 6727 3592 6727 3594 6728 3595 6728 3593 6728 3594 6729 3596 6729 3595 6729 3597 6730 3596 6730 3594 6730 3597 6731 3598 6731 3596 6731 3599 6732 3598 6732 3597 6732 3599 6733 3600 6733 3598 6733 3601 6734 3600 6734 3599 6734 3601 6735 3602 6735 3600 6735 3603 6736 3602 6736 3601 6736 3603 6737 3604 6737 3602 6737 3605 6738 3604 6738 3603 6738 3605 6739 3606 6739 3604 6739 3605 6740 3607 6740 3606 6740 3608 6741 3607 6741 3605 6741 3609 6742 3607 6742 3608 6742 3609 6743 3610 6743 3607 6743 3609 6744 3611 6744 3610 6744 3612 6745 3611 6745 3609 6745 3612 6746 3613 6746 3611 6746 3614 6747 3613 6747 3612 6747 3615 6748 3613 6748 3614 6748 3615 6749 3616 6749 3613 6749 3617 6750 3616 6750 3615 6750 3617 6751 3618 6751 3616 6751 3617 6752 3619 6752 3618 6752 3620 6753 3619 6753 3617 6753 3621 6754 3619 6754 3620 6754 3621 6755 3622 6755 3619 6755 3621 6756 3623 6756 3622 6756 3621 6757 3624 6757 3623 6757 3625 6758 3624 6758 3621 6758 3625 6759 3626 6759 3624 6759 3627 6760 3626 6760 3625 6760 3627 6761 3628 6761 3626 6761 3627 6762 3629 6762 3628 6762 3630 6763 3629 6763 3627 6763 3630 6764 3631 6764 3629 6764 3632 6765 3631 6765 3630 6765 3632 6766 3633 6766 3631 6766 3634 6767 3635 6767 3632 6767 3632 6768 3635 6768 3633 6768 3636 6769 3635 6769 3634 6769 3636 6770 3637 6770 3635 6770 3638 6771 3639 6771 3636 6771 3636 6772 3639 6772 3637 6772 3638 6773 3640 6773 3639 6773 3641 6774 3640 6774 3638 6774 3641 6775 3642 6775 3640 6775 3643 6776 3642 6776 3641 6776 3643 6777 3644 6777 3642 6777 3645 6778 3644 6778 3643 6778 3645 6779 3646 6779 3644 6779 3647 6780 3646 6780 3645 6780 3647 6781 3648 6781 3646 6781 3647 6782 3649 6782 3648 6782 3650 6783 3649 6783 3647 6783 3650 6784 3651 6784 3649 6784 3652 6785 3651 6785 3650 6785 3652 6786 3653 6786 3651 6786 3652 6787 3654 6787 3653 6787 3655 6788 3654 6788 3652 6788 3655 6789 3656 6789 3654 6789 3655 6790 3657 6790 3656 6790 3658 6791 3657 6791 3655 6791 3658 6792 3659 6792 3657 6792 3660 6793 3659 6793 3658 6793 3660 6794 3661 6794 3659 6794 3660 6795 3662 6795 3661 6795 3663 6796 3662 6796 3660 6796 3663 6797 3664 6797 3662 6797 3665 6798 3664 6798 3663 6798 3665 6799 3666 6799 3664 6799 3667 6800 3666 6800 3665 6800 3667 6801 3668 6801 3666 6801 3669 6802 3668 6802 3667 6802 3669 6803 3670 6803 3668 6803 3669 6804 3671 6804 3670 6804 3672 6805 3671 6805 3669 6805 3672 6806 3673 6806 3671 6806 3674 6807 3673 6807 3672 6807 3674 6808 3675 6808 3673 6808 3676 6809 3675 6809 3674 6809 3676 6810 3677 6810 3675 6810 3676 6811 3678 6811 3677 6811 3679 6812 3678 6812 3676 6812 3679 6813 3680 6813 3678 6813 3681 6814 3680 6814 3679 6814 3681 6815 3682 6815 3680 6815 3683 6816 3682 6816 3681 6816 3683 6817 3684 6817 3682 6817 3685 6818 3684 6818 3683 6818 3685 6819 3686 6819 3684 6819 3685 6820 3687 6820 3686 6820 3685 6821 3688 6821 3687 6821 3689 6822 3688 6822 3685 6822 3690 6823 3688 6823 3689 6823 3690 6824 3691 6824 3688 6824 3690 6825 3692 6825 3691 6825 3693 6826 3692 6826 3690 6826 3693 6827 3694 6827 3692 6827 3695 6828 3694 6828 3693 6828 3695 6829 3696 6829 3694 6829 3697 6830 3696 6830 3695 6830 3697 6831 3698 6831 3696 6831 3699 6832 3698 6832 3697 6832 3700 6833 3701 6833 3699 6833 3699 6834 3701 6834 3698 6834 3700 6835 3702 6835 3701 6835 3703 6836 3702 6836 3700 6836 3704 6837 3705 6837 3703 6837 3703 6838 3705 6838 3702 6838 3706 6839 3707 6839 3704 6839 3704 6840 3707 6840 3705 6840 3706 6841 3708 6841 3707 6841 3709 6842 3708 6842 3706 6842 3709 6843 3710 6843 3708 6843 3711 6844 3710 6844 3709 6844 3711 6845 3712 6845 3710 6845 3713 6846 3712 6846 3711 6846 3713 6847 3714 6847 3712 6847 3715 6848 3714 6848 3713 6848 3715 6849 3716 6849 3714 6849 3717 6850 3716 6850 3715 6850 3717 6851 3718 6851 3716 6851 3719 6852 3718 6852 3717 6852 3719 6853 3720 6853 3718 6853 3721 6854 3720 6854 3719 6854 3721 6855 3722 6855 3720 6855 3721 6856 3723 6856 3722 6856 3724 6857 3723 6857 3721 6857 3724 6858 3725 6858 3723 6858 3726 6859 3725 6859 3724 6859 3726 6860 3727 6860 3725 6860 3726 6861 3728 6861 3727 6861 3729 6862 3728 6862 3726 6862 3729 6863 3730 6863 3728 6863 3731 6864 3730 6864 3729 6864 3731 6865 3732 6865 3730 6865 3733 6866 3732 6866 3731 6866 3734 6867 3732 6867 3733 6867 3734 6868 3735 6868 3732 6868 3734 6869 3736 6869 3735 6869 3737 6870 3736 6870 3734 6870 3737 6871 3738 6871 3736 6871 3739 6872 3738 6872 3737 6872 3739 6873 3740 6873 3738 6873 3741 6874 3740 6874 3739 6874 3741 6875 3742 6875 3740 6875 3743 6876 3742 6876 3741 6876 3743 6877 3744 6877 3742 6877 3745 6878 3744 6878 3743 6878 3745 6879 3746 6879 3744 6879 3747 6880 3746 6880 3745 6880 3747 6881 3748 6881 3746 6881 3749 6882 3748 6882 3747 6882 3749 6883 3750 6883 3748 6883 3751 6884 3750 6884 3749 6884 3751 6885 3752 6885 3750 6885 3751 6886 3753 6886 3752 6886 3754 6887 3753 6887 3751 6887 3754 6888 3755 6888 3753 6888 3754 6889 3756 6889 3755 6889 3757 6890 3756 6890 3754 6890 3757 6891 3758 6891 3756 6891 3759 6892 3758 6892 3757 6892 3759 6893 3760 6893 3758 6893 3761 6894 3760 6894 3759 6894 3761 6895 3762 6895 3760 6895 3763 6896 3762 6896 3761 6896 3763 6897 3764 6897 3762 6897 3765 6898 3764 6898 3763 6898 3765 6899 3766 6899 3764 6899 3767 6900 3766 6900 3765 6900 3767 6901 3768 6901 3766 6901 3769 6902 3768 6902 3767 6902 3769 6903 3770 6903 3768 6903 3769 6904 3771 6904 3770 6904 3772 6905 3771 6905 3769 6905 3772 6906 3773 6906 3771 6906 3774 6907 3773 6907 3772 6907 3774 6908 3775 6908 3773 6908 3776 6909 3775 6909 3774 6909 3776 6910 3777 6910 3775 6910 3778 6911 3777 6911 3776 6911 3778 6912 3779 6912 3777 6912 3778 6913 3780 6913 3779 6913 3781 6914 3780 6914 3778 6914 3782 6915 3780 6915 3781 6915 3782 6916 3783 6916 3780 6916 3782 6917 3784 6917 3783 6917 3785 6918 3784 6918 3782 6918 3785 6919 3786 6919 3784 6919 3787 6920 3786 6920 3785 6920 3787 6921 3788 6921 3786 6921 3789 6922 3788 6922 3787 6922 3789 6923 3790 6923 3788 6923 3789 6924 3791 6924 3790 6924 3792 6925 3791 6925 3789 6925 3793 6926 3791 6926 3792 6926 3793 6927 3794 6927 3791 6927 3793 6928 3795 6928 3794 6928 3796 6929 3795 6929 3793 6929 3796 6930 3797 6930 3795 6930 3798 6931 3797 6931 3796 6931 3798 6932 3799 6932 3797 6932 3798 6933 3800 6933 3799 6933 3801 6934 3800 6934 3798 6934 3801 6935 3802 6935 3800 6935 3803 6936 3802 6936 3801 6936 3803 6937 3804 6937 3802 6937 3805 6938 3806 6938 3803 6938 3803 6939 3806 6939 3804 6939 3807 6940 3806 6940 3805 6940 3807 6941 3808 6941 3806 6941 3807 6942 3809 6942 3808 6942 3810 6943 3809 6943 3807 6943 3810 6944 3811 6944 3809 6944 3810 6945 3812 6945 3811 6945 3813 6946 3812 6946 3810 6946 3813 6947 3814 6947 3812 6947 3815 6948 3814 6948 3813 6948 3815 6949 3816 6949 3814 6949 3815 6950 3817 6950 3816 6950 3818 6951 3817 6951 3815 6951 3818 6952 3819 6952 3817 6952 3820 6953 3819 6953 3818 6953 3820 6954 3821 6954 3819 6954 3822 6955 3821 6955 3820 6955 3822 6956 3823 6956 3821 6956 3824 6957 3823 6957 3822 6957 3824 6958 3825 6958 3823 6958 3824 6959 3826 6959 3825 6959 3827 6960 3826 6960 3824 6960 3827 6961 3828 6961 3826 6961 3829 6962 3828 6962 3827 6962 3829 6963 3830 6963 3828 6963 3829 6964 3831 6964 3830 6964 3832 6965 3831 6965 3829 6965 3832 6966 3833 6966 3831 6966 3832 6967 3834 6967 3833 6967 3835 6968 3834 6968 3832 6968 3835 6969 3836 6969 3834 6969 3837 6970 3836 6970 3835 6970 3837 6971 3838 6971 3836 6971 3839 6972 3838 6972 3837 6972 3839 6973 3840 6973 3838 6973 3841 6974 3840 6974 3839 6974 3841 6975 3842 6975 3840 6975 3841 6976 3843 6976 3842 6976 3844 6977 3843 6977 3841 6977 3844 6978 3845 6978 3843 6978 3846 6979 3845 6979 3844 6979 3846 6980 3847 6980 3845 6980 3846 6981 3848 6981 3847 6981 3849 6982 3848 6982 3846 6982 3849 6983 3850 6983 3848 6983 3851 6984 3850 6984 3849 6984 3851 6985 3852 6985 3850 6985 3853 6986 3852 6986 3851 6986 3853 6987 3854 6987 3852 6987 3855 6988 3854 6988 3853 6988 3855 6989 3856 6989 3854 6989 3855 6990 3857 6990 3856 6990 3858 6991 3857 6991 3855 6991 3858 6992 3859 6992 3857 6992 3860 6993 3859 6993 3858 6993 3860 6994 3861 6994 3859 6994 3862 6995 3861 6995 3860 6995 3862 6996 3863 6996 3861 6996 3864 6997 3863 6997 3862 6997 3864 6998 3865 6998 3863 6998 3866 6999 3865 6999 3864 6999 3866 7000 3867 7000 3865 7000 3866 7001 3868 7001 3867 7001 3869 7002 3868 7002 3866 7002 3869 7003 3870 7003 3868 7003 3871 7004 3870 7004 3869 7004 3871 7005 3872 7005 3870 7005 3871 7006 3873 7006 3872 7006 3874 7007 3873 7007 3871 7007 3874 7008 3875 7008 3873 7008 3874 7009 3876 7009 3875 7009 3877 7010 3876 7010 3874 7010 3877 7011 3878 7011 3876 7011 3879 7012 3878 7012 3877 7012 3879 7013 3880 7013 3878 7013 3881 7014 3880 7014 3879 7014 3881 7015 3882 7015 3880 7015 3883 7016 3882 7016 3881 7016 3883 7017 3884 7017 3882 7017 3883 7018 3885 7018 3884 7018 3886 7019 3885 7019 3883 7019 3886 7020 3299 7020 3885 7020 3887 7021 3299 7021 3886 7021 3887 7022 4051 7022 3299 7022 3888 7023 4051 7023 3887 7023 3888 7024 3889 7024 4051 7024 3888 7025 3301 7025 3889 7025 3888 7026 3300 7026 3301 7026 3890 7027 3300 7027 3888 7027 3890 7028 3298 7028 3300 7028 3891 7029 3298 7029 3890 7029 3891 7030 3297 7030 3298 7030 3316 7031 3314 7031 3892 7031 3893 7032 3316 7032 3892 7032 3319 7033 3316 7033 3893 7033 3321 7034 3319 7034 3893 7034 3327 7035 3325 7035 3894 7035 3329 7036 3327 7036 3894 7036 3331 7037 3329 7037 3895 7037 3896 7038 3331 7038 3895 7038 3334 7039 3331 7039 3896 7039 3897 7040 3334 7040 3896 7040 3336 7041 3334 7041 3897 7041 3898 7042 3336 7042 3897 7042 3339 7043 3336 7043 3898 7043 3341 7044 3339 7044 3898 7044 3899 7045 3352 7045 3350 7045 3354 7046 3352 7046 3899 7046 3900 7047 3354 7047 3899 7047 3357 7048 3354 7048 3900 7048 3366 7049 3364 7049 3901 7049 3902 7050 3366 7050 3901 7050 3369 7051 3366 7051 3902 7051 3371 7052 3369 7052 3902 7052 3903 7053 3371 7053 3902 7053 3374 7054 3371 7054 3903 7054 3904 7055 3376 7055 3374 7055 3379 7056 3376 7056 3904 7056 3905 7057 3379 7057 3904 7057 3381 7058 3379 7058 3905 7058 3383 7059 3381 7059 3905 7059 3906 7060 3385 7060 3383 7060 3387 7061 3385 7061 3906 7061 3907 7062 3387 7062 3906 7062 3389 7063 3387 7063 3907 7063 3908 7064 3389 7064 3907 7064 3391 7065 3389 7065 3908 7065 3909 7066 3391 7066 3908 7066 3394 7067 3391 7067 3909 7067 3394 7068 3909 7068 3910 7068 3397 7069 3394 7069 3910 7069 3911 7070 3397 7070 3910 7070 3400 7071 3397 7071 3911 7071 3912 7072 3400 7072 3911 7072 3402 7073 3400 7073 3912 7073 3404 7074 3402 7074 3912 7074 3406 7075 3404 7075 3913 7075 3409 7076 3406 7076 3913 7076 3415 7077 3413 7077 3914 7077 3417 7078 3415 7078 3914 7078 3420 7079 3417 7079 3915 7079 3916 7080 3420 7080 3915 7080 3422 7081 3420 7081 3916 7081 3917 7082 3425 7082 3422 7082 3428 7083 3425 7083 3917 7083 3434 7084 3432 7084 3918 7084 3919 7085 3434 7085 3918 7085 3436 7086 3434 7086 3919 7086 3920 7087 3436 7087 3919 7087 3438 7088 3436 7088 3920 7088 3440 7089 3438 7089 3921 7089 3922 7090 3440 7090 3921 7090 3443 7091 3440 7091 3922 7091 3923 7092 3443 7092 3922 7092 3445 7093 3443 7093 3923 7093 3924 7094 3445 7094 3923 7094 3448 7095 3445 7095 3924 7095 3450 7096 3448 7096 3924 7096 3452 7097 3450 7097 3925 7097 3926 7098 3452 7098 3925 7098 3455 7099 3452 7099 3926 7099 3927 7100 3455 7100 3926 7100 3457 7101 3455 7101 3927 7101 3928 7102 3457 7102 3927 7102 3460 7103 3457 7103 3928 7103 3929 7104 3460 7104 3928 7104 3462 7105 3460 7105 3929 7105 3930 7106 3470 7106 3468 7106 3472 7107 3470 7107 3930 7107 3931 7108 3472 7108 3930 7108 3474 7109 3472 7109 3931 7109 3932 7110 3474 7110 3931 7110 3477 7111 3474 7111 3932 7111 3479 7112 3477 7112 3932 7112 3933 7113 3483 7113 3481 7113 3934 7114 3483 7114 3933 7114 3485 7115 3483 7115 3934 7115 3935 7116 3485 7116 3934 7116 3487 7117 3485 7117 3935 7117 3936 7118 3487 7118 3935 7118 3490 7119 3487 7119 3936 7119 3490 7120 3936 7120 3937 7120 3494 7121 3490 7121 3937 7121 3500 7122 3499 7122 3938 7122 3503 7123 3500 7123 3938 7123 3503 7124 3938 7124 3939 7124 3505 7125 3503 7125 3939 7125 3940 7126 3505 7126 3939 7126 3508 7127 3505 7127 3940 7127 3941 7128 3508 7128 3940 7128 3510 7129 3508 7129 3941 7129 3942 7130 3517 7130 3514 7130 3519 7131 3517 7131 3942 7131 3521 7132 3519 7132 3943 7132 3523 7133 3521 7133 3943 7133 3944 7134 3536 7134 3534 7134 3538 7135 3536 7135 3944 7135 3945 7136 3538 7136 3944 7136 3540 7137 3538 7137 3945 7137 3946 7138 3542 7138 3540 7138 3545 7139 3542 7139 3946 7139 3947 7140 3545 7140 3946 7140 3548 7141 3545 7141 3947 7141 3548 7142 3947 7142 3948 7142 3550 7143 3548 7143 3948 7143 3949 7144 3550 7144 3948 7144 3552 7145 3550 7145 3949 7145 3950 7146 3552 7146 3949 7146 3555 7147 3552 7147 3950 7147 3558 7148 3555 7148 3950 7148 3572 7149 3570 7149 3568 7149 3573 7150 3572 7150 3951 7150 3575 7151 3573 7151 3951 7151 3582 7152 3580 7152 3952 7152 3584 7153 3582 7153 3952 7153 3953 7154 3584 7154 3952 7154 3954 7155 3584 7155 3953 7155 3587 7156 3584 7156 3954 7156 3589 7157 3587 7157 3954 7157 3955 7158 3589 7158 3954 7158 3592 7159 3589 7159 3955 7159 3956 7160 3592 7160 3955 7160 3594 7161 3592 7161 3956 7161 3957 7162 3594 7162 3956 7162 3597 7163 3594 7163 3957 7163 3599 7164 3597 7164 3957 7164 3958 7165 3599 7165 3957 7165 3601 7166 3599 7166 3958 7166 3959 7167 3601 7167 3958 7167 3603 7168 3601 7168 3959 7168 3960 7169 3605 7169 3603 7169 3961 7170 3605 7170 3960 7170 3608 7171 3605 7171 3961 7171 3609 7172 3608 7172 3961 7172 3962 7173 3609 7173 3961 7173 3612 7174 3609 7174 3962 7174 3614 7175 3612 7175 3962 7175 3963 7176 3617 7176 3615 7176 3620 7177 3617 7177 3963 7177 3964 7178 3621 7178 3620 7178 3965 7179 3621 7179 3964 7179 3625 7180 3621 7180 3965 7180 3966 7181 3625 7181 3965 7181 3627 7182 3625 7182 3966 7182 3967 7183 3627 7183 3966 7183 3630 7184 3627 7184 3967 7184 3632 7185 3630 7185 3967 7185 3968 7186 3632 7186 3967 7186 3634 7187 3632 7187 3968 7187 3969 7188 3638 7188 3636 7188 3641 7189 3638 7189 3969 7189 3970 7190 3643 7190 3641 7190 3645 7191 3643 7191 3970 7191 3645 7192 3970 7192 3971 7192 3647 7193 3645 7193 3971 7193 3650 7194 3647 7194 3971 7194 3652 7195 3650 7195 3972 7195 3655 7196 3652 7196 3972 7196 3658 7197 3655 7197 3973 7197 3974 7198 3658 7198 3973 7198 3660 7199 3658 7199 3974 7199 3975 7200 3667 7200 3665 7200 3976 7201 3667 7201 3975 7201 3669 7202 3667 7202 3976 7202 3977 7203 3669 7203 3976 7203 3672 7204 3669 7204 3977 7204 3674 7205 3672 7205 3977 7205 3679 7206 3676 7206 3978 7206 3681 7207 3679 7207 3978 7207 3685 7208 3683 7208 3979 7208 3980 7209 3685 7209 3979 7209 3689 7210 3685 7210 3980 7210 3690 7211 3689 7211 3980 7211 3981 7212 3695 7212 3693 7212 3697 7213 3695 7213 3981 7213 3699 7214 3697 7214 3981 7214 3982 7215 3711 7215 3709 7215 3713 7216 3711 7216 3982 7216 3983 7217 3713 7217 3982 7217 3715 7218 3713 7218 3983 7218 3717 7219 3715 7219 3983 7219 3721 7220 3719 7220 3984 7220 3985 7221 3721 7221 3984 7221 3724 7222 3721 7222 3985 7222 3986 7223 3724 7223 3985 7223 3726 7224 3724 7224 3986 7224 3729 7225 3726 7225 3987 7225 3731 7226 3729 7226 3987 7226 3988 7227 3734 7227 3733 7227 3737 7228 3734 7228 3988 7228 3989 7229 3743 7229 3741 7229 3745 7230 3743 7230 3989 7230 3747 7231 3745 7231 3989 7231 3990 7232 3754 7232 3751 7232 3991 7233 3754 7233 3990 7233 3757 7234 3754 7234 3991 7234 3992 7235 3757 7235 3991 7235 3759 7236 3757 7236 3992 7236 3761 7237 3759 7237 3992 7237 3763 7238 3761 7238 3993 7238 3765 7239 3763 7239 3993 7239 3994 7240 3767 7240 3765 7240 3769 7241 3767 7241 3994 7241 3995 7242 3769 7242 3994 7242 3772 7243 3769 7243 3995 7243 3996 7244 3772 7244 3995 7244 3774 7245 3772 7245 3996 7245 3997 7246 3774 7246 3996 7246 3776 7247 3774 7247 3997 7247 3998 7248 3776 7248 3997 7248 3778 7249 3776 7249 3998 7249 3999 7250 3778 7250 3998 7250 3781 7251 3778 7251 3999 7251 4000 7252 3782 7252 3781 7252 3785 7253 3782 7253 4000 7253 3787 7254 3785 7254 4000 7254 4001 7255 3798 7255 3796 7255 3801 7256 3798 7256 4001 7256 3803 7257 3801 7257 4002 7257 3805 7258 3803 7258 4002 7258 4003 7259 3810 7259 3807 7259 3813 7260 3810 7260 4003 7260 4004 7261 3813 7261 4003 7261 3815 7262 3813 7262 4004 7262 4005 7263 3815 7263 4004 7263 3818 7264 3815 7264 4005 7264 3820 7265 3818 7265 4005 7265 3822 7266 3820 7266 4006 7266 4007 7267 3822 7267 4006 7267 3824 7268 3822 7268 4007 7268 3827 7269 3824 7269 4007 7269 3829 7270 3827 7270 4008 7270 3832 7271 3829 7271 4008 7271 4009 7272 3832 7272 4008 7272 3835 7273 3832 7273 4009 7273 3837 7274 3835 7274 4010 7274 3839 7275 3837 7275 4010 7275 3841 7276 3839 7276 4011 7276 4012 7277 3841 7277 4011 7277 3844 7278 3841 7278 4012 7278 3849 7279 3846 7279 4013 7279 4014 7280 3849 7280 4013 7280 3851 7281 3849 7281 4014 7281 3853 7282 3851 7282 4014 7282 4015 7283 3855 7283 3853 7283 3858 7284 3855 7284 4015 7284 3864 7285 3862 7285 4016 7285 4017 7286 3864 7286 4016 7286 3866 7287 3864 7287 4017 7287 3869 7288 3866 7288 4017 7288 4018 7289 3871 7289 3869 7289 3874 7290 3871 7290 4018 7290 3883 7291 3881 7291 4019 7291 3883 7292 4019 7292 3886 7292 3887 7293 3886 7293 4020 7293 3888 7294 3887 7294 4020 7294 4021 7295 3890 7295 3888 7295 3891 7296 3890 7296 4021 7296 4022 7297 3891 7297 4021 7297 3297 7298 3891 7298 4022 7298 3297 7299 4022 7299 4023 7299 3291 7300 3297 7300 4023 7300 3289 7301 3291 7301 4023 7301 4025 7302 3893 7302 3892 7302 4026 7303 3893 7303 4025 7303 4026 7304 3321 7304 3893 7304 4026 7305 3323 7305 3321 7305 4024 7306 3323 7306 4026 7306 4024 7307 3325 7307 3323 7307 4027 7308 3325 7308 4024 7308 4027 7309 3894 7309 3325 7309 3302 7310 3894 7310 4027 7310 3303 7311 3894 7311 3302 7311 3303 7312 3329 7312 3894 7312 3305 7313 3329 7313 3303 7313 3305 7314 3895 7314 3329 7314 3307 7315 3895 7315 3305 7315 3308 7316 3895 7316 3307 7316 3308 7317 3896 7317 3895 7317 3310 7318 3896 7318 3308 7318 3311 7319 3896 7319 3310 7319 3311 7320 3897 7320 3896 7320 3313 7321 3897 7321 3311 7321 3313 7322 3898 7322 3897 7322 3315 7323 3898 7323 3313 7323 3315 7324 3341 7324 3898 7324 3317 7325 3341 7325 3315 7325 3318 7326 3341 7326 3317 7326 3318 7327 3343 7327 3341 7327 3320 7328 3343 7328 3318 7328 3320 7329 3345 7329 3343 7329 3320 7330 3347 7330 3345 7330 3322 7331 3347 7331 3320 7331 3322 7332 3350 7332 3347 7332 3324 7333 3350 7333 3322 7333 3324 7334 3899 7334 3350 7334 3326 7335 3899 7335 3324 7335 3328 7336 3899 7336 3326 7336 3328 7337 3900 7337 3899 7337 3330 7338 3900 7338 3328 7338 3330 7339 3357 7339 3900 7339 3332 7340 3357 7340 3330 7340 3332 7341 3360 7341 3357 7341 3333 7342 3360 7342 3332 7342 3333 7343 3362 7343 3360 7343 3335 7344 3364 7344 3333 7344 3333 7345 3364 7345 3362 7345 3337 7346 3364 7346 3335 7346 3337 7347 3901 7347 3364 7347 3338 7348 3901 7348 3337 7348 3340 7349 3901 7349 3338 7349 3340 7350 3902 7350 3901 7350 3342 7351 3902 7351 3340 7351 3344 7352 3902 7352 3342 7352 3344 7353 3903 7353 3902 7353 3346 7354 3903 7354 3344 7354 3348 7355 3903 7355 3346 7355 3348 7356 3374 7356 3903 7356 3349 7357 3374 7357 3348 7357 3349 7358 3904 7358 3374 7358 3351 7359 3904 7359 3349 7359 3353 7360 3904 7360 3351 7360 3353 7361 3905 7361 3904 7361 3355 7362 3905 7362 3353 7362 3356 7363 3905 7363 3355 7363 3356 7364 3383 7364 3905 7364 3358 7365 3383 7365 3356 7365 3358 7366 3906 7366 3383 7366 3359 7367 3906 7367 3358 7367 3361 7368 3906 7368 3359 7368 3361 7369 3907 7369 3906 7369 3363 7370 3907 7370 3361 7370 3363 7371 3908 7371 3907 7371 3365 7372 3908 7372 3363 7372 3367 7373 3908 7373 3365 7373 3367 7374 3909 7374 3908 7374 3368 7375 3909 7375 3367 7375 3368 7376 3910 7376 3909 7376 3370 7377 3910 7377 3368 7377 3372 7378 3910 7378 3370 7378 3372 7379 3911 7379 3910 7379 4028 7380 3911 7380 3372 7380 3375 7381 3912 7381 4028 7381 4028 7382 3912 7382 3911 7382 3377 7383 3912 7383 3375 7383 3377 7384 3404 7384 3912 7384 3378 7385 3404 7385 3377 7385 3378 7386 3913 7386 3404 7386 3380 7387 3913 7387 3378 7387 3382 7388 3913 7388 3380 7388 3382 7389 3409 7389 3913 7389 3384 7390 3409 7390 3382 7390 3384 7391 3411 7391 3409 7391 3386 7392 3411 7392 3384 7392 3388 7393 3411 7393 3386 7393 3388 7394 3413 7394 3411 7394 3390 7395 3413 7395 3388 7395 3390 7396 3914 7396 3413 7396 3392 7397 3914 7397 3390 7397 3392 7398 3417 7398 3914 7398 3393 7399 3417 7399 3392 7399 3393 7400 3915 7400 3417 7400 3395 7401 3915 7401 3393 7401 3395 7402 3916 7402 3915 7402 3396 7403 3916 7403 3395 7403 3396 7404 3422 7404 3916 7404 3398 7405 3422 7405 3396 7405 3399 7406 3422 7406 3398 7406 3399 7407 3917 7407 3422 7407 3401 7408 3917 7408 3399 7408 3401 7409 3428 7409 3917 7409 3403 7410 3428 7410 3401 7410 3403 7411 3430 7411 3428 7411 3405 7412 3430 7412 3403 7412 3405 7413 3432 7413 3430 7413 3405 7414 3918 7414 3432 7414 3407 7415 3918 7415 3405 7415 3408 7416 3918 7416 3407 7416 3408 7417 3919 7417 3918 7417 3410 7418 3919 7418 3408 7418 3412 7419 3919 7419 3410 7419 3412 7420 3920 7420 3919 7420 3414 7421 3920 7421 3412 7421 3414 7422 3438 7422 3920 7422 3416 7423 3438 7423 3414 7423 3416 7424 3921 7424 3438 7424 3418 7425 3921 7425 3416 7425 3418 7426 3922 7426 3921 7426 4029 7427 3922 7427 3418 7427 4029 7428 3923 7428 3922 7428 3423 7429 3923 7429 4029 7429 3423 7430 3924 7430 3923 7430 3424 7431 3924 7431 3423 7431 3424 7432 3450 7432 3924 7432 3426 7433 3450 7433 3424 7433 3426 7434 3925 7434 3450 7434 3427 7435 3925 7435 3426 7435 3429 7436 3925 7436 3427 7436 3429 7437 3926 7437 3925 7437 3431 7438 3926 7438 3429 7438 3431 7439 3927 7439 3926 7439 3433 7440 3927 7440 3431 7440 3433 7441 3928 7441 3927 7441 3435 7442 3928 7442 3433 7442 3435 7443 3929 7443 3928 7443 3437 7444 3929 7444 3435 7444 3437 7445 3462 7445 3929 7445 3439 7446 3462 7446 3437 7446 3439 7447 3464 7447 3462 7447 3441 7448 3464 7448 3439 7448 3441 7449 3466 7449 3464 7449 3441 7450 3468 7450 3466 7450 3442 7451 3468 7451 3441 7451 3444 7452 3468 7452 3442 7452 3444 7453 3930 7453 3468 7453 3446 7454 3930 7454 3444 7454 3447 7455 3930 7455 3446 7455 3447 7456 3931 7456 3930 7456 3449 7457 3931 7457 3447 7457 3449 7458 3932 7458 3931 7458 3451 7459 3932 7459 3449 7459 3453 7460 3932 7460 3451 7460 3453 7461 3479 7461 3932 7461 3454 7462 3479 7462 3453 7462 3456 7463 3479 7463 3454 7463 3456 7464 3481 7464 3479 7464 3458 7465 3481 7465 3456 7465 3458 7466 3933 7466 3481 7466 3459 7467 3933 7467 3458 7467 3459 7468 3934 7468 3933 7468 3461 7469 3934 7469 3459 7469 3461 7470 3935 7470 3934 7470 3463 7471 3935 7471 3461 7471 3463 7472 3936 7472 3935 7472 3465 7473 3936 7473 3463 7473 3465 7474 3937 7474 3936 7474 3467 7475 3937 7475 3465 7475 3469 7476 3937 7476 3467 7476 3469 7477 3494 7477 3937 7477 3471 7478 3494 7478 3469 7478 3471 7479 3496 7479 3494 7479 3473 7480 3496 7480 3471 7480 3473 7481 3499 7481 3496 7481 3475 7482 3499 7482 3473 7482 3475 7483 3938 7483 3499 7483 3476 7484 3938 7484 3475 7484 3478 7485 3938 7485 3476 7485 3478 7486 3939 7486 3938 7486 3480 7487 3939 7487 3478 7487 3480 7488 3940 7488 3939 7488 3482 7489 3940 7489 3480 7489 3482 7490 3941 7490 3940 7490 3484 7491 3941 7491 3482 7491 3484 7492 3510 7492 3941 7492 3486 7493 3510 7493 3484 7493 3486 7494 3513 7494 3510 7494 3488 7495 3513 7495 3486 7495 3488 7496 3514 7496 3513 7496 3489 7497 3514 7497 3488 7497 3491 7498 3514 7498 3489 7498 3491 7499 3942 7499 3514 7499 3492 7500 3942 7500 3491 7500 3492 7501 3519 7501 3942 7501 3495 7502 3519 7502 3492 7502 3495 7503 3943 7503 3519 7503 3497 7504 3943 7504 3495 7504 3497 7505 3523 7505 3943 7505 3498 7506 3523 7506 3497 7506 3498 7507 3525 7507 3523 7507 3501 7508 3525 7508 3498 7508 3501 7509 3527 7509 3525 7509 3502 7510 3527 7510 3501 7510 3504 7511 3527 7511 3502 7511 3504 7512 3530 7512 3527 7512 3504 7513 3532 7513 3530 7513 3506 7514 3532 7514 3504 7514 3507 7515 3532 7515 3506 7515 3507 7516 3534 7516 3532 7516 3507 7517 3944 7517 3534 7517 3509 7518 3944 7518 3507 7518 3511 7519 3944 7519 3509 7519 3511 7520 3945 7520 3944 7520 3512 7521 3945 7521 3511 7521 3515 7522 3945 7522 3512 7522 3515 7523 3540 7523 3945 7523 3516 7524 3540 7524 3515 7524 3516 7525 3946 7525 3540 7525 3518 7526 3946 7526 3516 7526 3518 7527 3947 7527 3946 7527 3520 7528 3947 7528 3518 7528 4030 7529 3947 7529 3520 7529 4030 7530 3948 7530 3947 7530 3522 7531 3948 7531 4030 7531 3524 7532 3948 7532 3522 7532 3524 7533 3949 7533 3948 7533 3526 7534 3949 7534 3524 7534 3528 7535 3949 7535 3526 7535 3528 7536 3950 7536 3949 7536 3529 7537 3950 7537 3528 7537 3531 7538 3950 7538 3529 7538 3531 7539 3558 7539 3950 7539 3533 7540 3558 7540 3531 7540 3535 7541 3558 7541 3533 7541 3535 7542 3560 7542 3558 7542 3535 7543 3562 7543 3560 7543 3537 7544 3562 7544 3535 7544 3537 7545 3564 7545 3562 7545 3539 7546 3564 7546 3537 7546 3541 7547 3566 7547 3539 7547 3539 7548 3566 7548 3564 7548 3543 7549 3566 7549 3541 7549 3543 7550 3568 7550 3566 7550 3544 7551 3568 7551 3543 7551 3546 7552 3568 7552 3544 7552 3546 7553 3572 7553 3568 7553 3547 7554 3572 7554 3546 7554 3547 7555 3951 7555 3572 7555 4031 7556 3951 7556 3547 7556 4031 7557 3575 7557 3951 7557 3549 7558 3575 7558 4031 7558 3551 7559 3575 7559 3549 7559 3551 7560 3577 7560 3575 7560 3553 7561 3577 7561 3551 7561 3553 7562 3580 7562 3577 7562 3554 7563 3580 7563 3553 7563 3556 7564 3580 7564 3554 7564 3556 7565 3952 7565 3580 7565 3557 7566 3952 7566 3556 7566 3559 7567 3952 7567 3557 7567 3559 7568 3953 7568 3952 7568 3561 7569 3953 7569 3559 7569 3561 7570 3954 7570 3953 7570 3563 7571 3954 7571 3561 7571 4032 7572 3954 7572 3563 7572 4032 7573 3955 7573 3954 7573 3565 7574 3955 7574 4032 7574 3567 7575 3955 7575 3565 7575 3567 7576 3956 7576 3955 7576 3569 7577 3956 7577 3567 7577 3569 7578 3957 7578 3956 7578 3571 7579 3957 7579 3569 7579 3574 7580 3957 7580 3571 7580 3574 7581 3958 7581 3957 7581 4033 7582 3958 7582 3574 7582 4033 7583 3959 7583 3958 7583 3576 7584 3959 7584 4033 7584 3578 7585 3959 7585 3576 7585 3578 7586 3603 7586 3959 7586 3579 7587 3603 7587 3578 7587 3579 7588 3960 7588 3603 7588 3581 7589 3960 7589 3579 7589 3581 7590 3961 7590 3960 7590 3583 7591 3961 7591 3581 7591 3585 7592 3962 7592 3583 7592 3583 7593 3962 7593 3961 7593 3586 7594 3962 7594 3585 7594 3588 7595 3962 7595 3586 7595 3588 7596 3614 7596 3962 7596 3588 7597 3615 7597 3614 7597 3590 7598 3615 7598 3588 7598 3590 7599 3963 7599 3615 7599 3591 7600 3963 7600 3590 7600 3593 7601 3963 7601 3591 7601 3593 7602 3620 7602 3963 7602 3595 7603 3620 7603 3593 7603 3596 7604 3620 7604 3595 7604 3596 7605 3964 7605 3620 7605 3598 7606 3964 7606 3596 7606 3598 7607 3965 7607 3964 7607 3600 7608 3965 7608 3598 7608 3600 7609 3966 7609 3965 7609 3602 7610 3966 7610 3600 7610 3604 7611 3966 7611 3602 7611 3604 7612 3967 7612 3966 7612 3606 7613 3967 7613 3604 7613 3606 7614 3968 7614 3967 7614 3607 7615 3968 7615 3606 7615 3607 7616 3634 7616 3968 7616 3610 7617 3634 7617 3607 7617 3610 7618 3636 7618 3634 7618 3611 7619 3636 7619 3610 7619 3611 7620 3969 7620 3636 7620 3613 7621 3969 7621 3611 7621 3616 7622 3969 7622 3613 7622 3616 7623 3641 7623 3969 7623 3618 7624 3641 7624 3616 7624 3618 7625 3970 7625 3641 7625 3619 7626 3970 7626 3618 7626 3619 7627 3971 7627 3970 7627 3622 7628 3971 7628 3619 7628 3622 7629 3650 7629 3971 7629 3623 7630 3650 7630 3622 7630 3623 7631 3972 7631 3650 7631 3624 7632 3972 7632 3623 7632 3626 7633 3972 7633 3624 7633 3628 7634 3972 7634 3626 7634 3628 7635 3655 7635 3972 7635 3629 7636 3655 7636 3628 7636 3629 7637 3973 7637 3655 7637 3631 7638 3973 7638 3629 7638 3631 7639 3974 7639 3973 7639 3633 7640 3974 7640 3631 7640 3635 7641 3974 7641 3633 7641 3635 7642 3660 7642 3974 7642 3637 7643 3660 7643 3635 7643 3637 7644 3663 7644 3660 7644 3639 7645 3663 7645 3637 7645 3639 7646 3665 7646 3663 7646 3640 7647 3665 7647 3639 7647 3640 7648 3975 7648 3665 7648 3642 7649 3975 7649 3640 7649 3642 7650 3976 7650 3975 7650 3646 7651 3976 7651 3642 7651 3646 7652 3977 7652 3976 7652 3648 7653 3977 7653 3646 7653 3649 7654 3977 7654 3648 7654 3649 7655 3674 7655 3977 7655 3651 7656 3674 7656 3649 7656 3651 7657 3676 7657 3674 7657 3653 7658 3676 7658 3651 7658 3653 7659 3978 7659 3676 7659 3654 7660 3978 7660 3653 7660 3656 7661 3978 7661 3654 7661 3656 7662 3681 7662 3978 7662 3657 7663 3681 7663 3656 7663 3657 7664 3683 7664 3681 7664 3659 7665 3683 7665 3657 7665 3659 7666 3979 7666 3683 7666 3661 7667 3979 7667 3659 7667 3662 7668 3979 7668 3661 7668 3662 7669 3980 7669 3979 7669 3664 7670 3980 7670 3662 7670 3664 7671 3690 7671 3980 7671 3666 7672 3690 7672 3664 7672 3666 7673 3693 7673 3690 7673 3668 7674 3693 7674 3666 7674 3668 7675 3981 7675 3693 7675 3670 7676 3981 7676 3668 7676 3670 7677 3699 7677 3981 7677 3671 7678 3699 7678 3670 7678 3671 7679 3700 7679 3699 7679 3673 7680 3700 7680 3671 7680 3675 7681 3700 7681 3673 7681 3675 7682 3703 7682 3700 7682 3677 7683 3703 7683 3675 7683 3677 7684 3704 7684 3703 7684 3678 7685 3704 7685 3677 7685 3678 7686 3706 7686 3704 7686 3680 7687 3706 7687 3678 7687 3680 7688 3709 7688 3706 7688 3682 7689 3709 7689 3680 7689 3684 7690 3709 7690 3682 7690 3684 7691 3982 7691 3709 7691 3686 7692 3982 7692 3684 7692 3686 7693 3983 7693 3982 7693 3687 7694 3983 7694 3686 7694 3688 7695 3983 7695 3687 7695 3688 7696 3717 7696 3983 7696 3691 7697 3717 7697 3688 7697 3691 7698 3719 7698 3717 7698 3692 7699 3719 7699 3691 7699 3692 7700 3984 7700 3719 7700 3694 7701 3984 7701 3692 7701 3694 7702 3985 7702 3984 7702 3696 7703 3985 7703 3694 7703 3696 7704 3986 7704 3985 7704 3698 7705 3986 7705 3696 7705 3701 7706 3726 7706 3698 7706 3698 7707 3726 7707 3986 7707 3702 7708 3726 7708 3701 7708 3702 7709 3987 7709 3726 7709 3705 7710 3987 7710 3702 7710 3705 7711 3731 7711 3987 7711 3707 7712 3731 7712 3705 7712 3707 7713 3733 7713 3731 7713 3708 7714 3733 7714 3707 7714 3708 7715 3988 7715 3733 7715 3710 7716 3988 7716 3708 7716 3712 7717 3988 7717 3710 7717 3712 7718 3737 7718 3988 7718 3712 7719 3739 7719 3737 7719 3714 7720 3739 7720 3712 7720 3714 7721 3741 7721 3739 7721 3716 7722 3741 7722 3714 7722 3718 7723 3741 7723 3716 7723 3718 7724 3989 7724 3741 7724 3720 7725 3989 7725 3718 7725 3720 7726 3747 7726 3989 7726 3722 7727 3747 7727 3720 7727 3722 7728 3749 7728 3747 7728 3723 7729 3749 7729 3722 7729 3725 7730 3749 7730 3723 7730 3725 7731 3751 7731 3749 7731 3727 7732 3751 7732 3725 7732 3727 7733 3990 7733 3751 7733 3728 7734 3990 7734 3727 7734 3728 7735 3991 7735 3990 7735 3730 7736 3991 7736 3728 7736 3730 7737 3992 7737 3991 7737 3732 7738 3992 7738 3730 7738 3732 7739 3761 7739 3992 7739 3735 7740 3761 7740 3732 7740 3735 7741 3993 7741 3761 7741 3736 7742 3993 7742 3735 7742 3738 7743 3993 7743 3736 7743 3738 7744 3765 7744 3993 7744 3740 7745 3765 7745 3738 7745 3742 7746 3765 7746 3740 7746 3742 7747 3994 7747 3765 7747 3744 7748 3994 7748 3742 7748 3744 7749 3995 7749 3994 7749 3746 7750 3995 7750 3744 7750 3748 7751 3995 7751 3746 7751 3748 7752 3996 7752 3995 7752 3750 7753 3996 7753 3748 7753 3750 7754 3997 7754 3996 7754 3753 7755 3997 7755 3750 7755 3753 7756 3998 7756 3997 7756 3755 7757 3998 7757 3753 7757 3755 7758 3999 7758 3998 7758 3756 7759 3999 7759 3755 7759 3756 7760 3781 7760 3999 7760 3758 7761 3781 7761 3756 7761 3758 7762 4000 7762 3781 7762 3760 7763 4000 7763 3758 7763 3762 7764 4000 7764 3760 7764 3762 7765 3787 7765 4000 7765 3764 7766 3787 7766 3762 7766 3764 7767 3789 7767 3787 7767 3766 7768 3789 7768 3764 7768 3766 7769 3792 7769 3789 7769 3768 7770 3792 7770 3766 7770 3768 7771 3793 7771 3792 7771 3770 7772 3793 7772 3768 7772 3770 7773 3796 7773 3793 7773 3771 7774 3796 7774 3770 7774 3771 7775 4001 7775 3796 7775 3773 7776 4001 7776 3771 7776 3775 7777 4001 7777 3773 7777 3775 7778 3801 7778 4001 7778 3777 7779 3801 7779 3775 7779 3777 7780 4002 7780 3801 7780 3779 7781 4002 7781 3777 7781 3779 7782 3805 7782 4002 7782 3780 7783 3805 7783 3779 7783 3780 7784 3807 7784 3805 7784 3783 7785 3807 7785 3780 7785 3784 7786 3807 7786 3783 7786 3784 7787 4003 7787 3807 7787 3786 7788 4003 7788 3784 7788 3786 7789 4004 7789 4003 7789 3788 7790 4004 7790 3786 7790 3788 7791 4005 7791 4004 7791 3790 7792 4005 7792 3788 7792 3791 7793 4005 7793 3790 7793 3791 7794 3820 7794 4005 7794 3794 7795 3820 7795 3791 7795 3794 7796 4006 7796 3820 7796 3795 7797 4006 7797 3794 7797 3795 7798 4007 7798 4006 7798 3797 7799 4007 7799 3795 7799 3797 7800 3827 7800 4007 7800 3799 7801 3827 7801 3797 7801 3800 7802 4008 7802 3799 7802 3799 7803 4008 7803 3827 7803 3802 7804 4008 7804 3800 7804 3802 7805 4009 7805 4008 7805 3804 7806 4009 7806 3802 7806 3804 7807 3835 7807 4009 7807 3806 7808 3835 7808 3804 7808 3808 7809 3835 7809 3806 7809 3808 7810 4010 7810 3835 7810 3809 7811 4010 7811 3808 7811 3809 7812 3839 7812 4010 7812 3811 7813 3839 7813 3809 7813 3811 7814 4011 7814 3839 7814 3812 7815 4011 7815 3811 7815 3814 7816 4011 7816 3812 7816 3814 7817 4012 7817 4011 7817 3816 7818 4012 7818 3814 7818 3816 7819 3844 7819 4012 7819 3817 7820 3844 7820 3816 7820 3817 7821 3846 7821 3844 7821 3819 7822 3846 7822 3817 7822 3821 7823 3846 7823 3819 7823 3821 7824 4013 7824 3846 7824 3823 7825 4013 7825 3821 7825 3823 7826 4014 7826 4013 7826 3825 7827 4014 7827 3823 7827 3826 7828 4014 7828 3825 7828 3826 7829 3853 7829 4014 7829 3828 7830 3853 7830 3826 7830 3830 7831 3853 7831 3828 7831 3830 7832 4015 7832 3853 7832 3831 7833 4015 7833 3830 7833 3831 7834 3858 7834 4015 7834 3833 7835 3858 7835 3831 7835 3833 7836 3860 7836 3858 7836 3834 7837 3860 7837 3833 7837 3836 7838 3862 7838 3834 7838 3834 7839 3862 7839 3860 7839 3836 7840 4016 7840 3862 7840 3838 7841 4016 7841 3836 7841 3840 7842 4016 7842 3838 7842 3840 7843 4017 7843 4016 7843 3842 7844 4017 7844 3840 7844 3842 7845 3869 7845 4017 7845 3843 7846 3869 7846 3842 7846 3845 7847 3869 7847 3843 7847 3845 7848 4018 7848 3869 7848 3847 7849 4018 7849 3845 7849 3847 7850 3874 7850 4018 7850 3848 7851 3874 7851 3847 7851 3848 7852 3877 7852 3874 7852 3852 7853 3877 7853 3848 7853 3852 7854 3879 7854 3877 7854 3854 7855 3879 7855 3852 7855 3854 7856 3881 7856 3879 7856 3856 7857 3881 7857 3854 7857 3857 7858 3881 7858 3856 7858 3857 7859 4019 7859 3881 7859 3859 7860 4019 7860 3857 7860 3859 7861 3886 7861 4019 7861 3861 7862 3886 7862 3859 7862 3861 7863 4020 7863 3886 7863 3863 7864 4020 7864 3861 7864 3865 7865 4020 7865 3863 7865 3865 7866 3888 7866 4020 7866 3867 7867 3888 7867 3865 7867 3867 7868 4021 7868 3888 7868 3868 7869 4021 7869 3867 7869 3870 7870 4021 7870 3868 7870 3870 7871 4022 7871 4021 7871 3872 7872 4022 7872 3870 7872 3872 7873 4023 7873 4022 7873 3873 7874 4023 7874 3872 7874 3875 7875 4023 7875 3873 7875 3875 7876 3289 7876 4023 7876 3876 7877 3289 7877 3875 7877 3876 7878 3285 7878 3289 7878 3878 7879 3285 7879 3876 7879 3878 7880 3288 7880 3285 7880 3880 7881 3288 7881 3878 7881 3882 7882 3288 7882 3880 7882 3884 7883 3288 7883 3882 7883 3884 7884 3295 7884 3288 7884 3884 7885 3885 7885 3295 7885 3373 7886 4028 7886 3372 7886 3375 7887 4028 7887 3373 7887 4029 7888 3418 7888 3419 7888 3421 7889 4029 7889 3419 7889 3423 7890 4029 7890 3421 7890 3495 7891 3492 7891 3493 7891 3522 7892 4030 7892 3520 7892 3549 7893 4031 7893 3547 7893 3565 7894 4032 7894 3563 7894 3576 7895 4033 7895 3574 7895 3646 7896 3642 7896 3644 7896 3753 7897 3750 7897 3752 7897 3852 7898 3848 7898 3850 7898 4051 7899 4054 7899 3299 7899 4035 7900 4068 7900 4034 7900 4034 7901 4066 7901 4039 7901 4036 7902 4034 7902 4037 7902 4036 7903 4035 7903 4034 7903 3292 7904 4035 7904 4036 7904 4039 7905 4037 7905 4034 7905 4036 7906 3294 7906 3292 7906 4038 7907 4037 7907 4039 7907 4036 7908 4037 7908 4038 7908 4038 7909 3294 7909 4036 7909 4040 7910 4038 7910 4039 7910 3296 7911 3294 7911 4038 7911 4040 7912 4039 7912 4042 7912 3296 7913 4038 7913 4040 7913 4042 7914 4039 7914 4041 7914 4043 7915 3296 7915 4040 7915 4043 7916 4040 7916 4042 7916 4044 7917 4043 7917 4042 7917 3298 7918 3296 7918 4043 7918 4044 7919 4042 7919 4041 7919 4046 7920 4043 7920 4044 7920 4046 7921 3298 7921 4043 7921 3300 7922 3298 7922 4046 7922 4047 7923 4044 7923 4041 7923 4046 7924 4044 7924 4047 7924 4047 7925 4041 7925 4045 7925 4046 7926 3301 7926 3300 7926 4048 7927 4046 7927 4047 7927 4048 7928 3301 7928 4046 7928 4045 7929 4048 7929 4047 7929 4050 7930 4048 7930 4045 7930 3889 7931 3301 7931 4048 7931 4049 7932 4050 7932 4045 7932 4050 7933 3889 7933 4048 7933 4051 7934 3889 7934 4050 7934 4053 7935 4050 7935 4049 7935 4053 7936 4049 7936 4052 7936 4054 7937 4050 7937 4053 7937 4054 7938 4051 7938 4050 7938 4055 7939 4054 7939 4053 7939 4055 7940 4053 7940 4052 7940 3299 7941 4054 7941 4055 7941 4057 7942 4055 7942 4052 7942 4057 7943 4052 7943 4056 7943 4055 7944 3885 7944 3299 7944 3885 7945 4055 7945 4057 7945 3295 7946 3885 7946 4057 7946 4058 7947 4057 7947 4056 7947 4059 7948 3295 7948 4057 7948 4059 7949 4057 7949 4058 7949 4059 7950 3293 7950 3295 7950 4059 7951 4058 7951 4060 7951 4061 7952 4058 7952 4056 7952 3293 7953 4059 7953 4060 7953 4062 7954 4060 7954 4058 7954 4062 7955 4058 7955 4061 7955 3293 7956 4060 7956 4062 7956 4062 7957 3290 7957 3293 7957 4063 7958 4062 7958 4061 7958 4063 7959 3290 7959 4062 7959 4064 7960 4063 7960 4061 7960 4064 7961 4061 7961 4065 7961 4063 7962 3286 7962 3290 7962 3286 7963 4063 7963 4064 7963 3284 7964 3286 7964 4064 7964 4067 7965 4064 7965 4065 7965 4068 7966 4065 7966 4066 7966 4067 7967 3284 7967 4064 7967 4067 7968 4065 7968 4068 7968 4067 7969 3287 7969 3284 7969 4069 7970 4067 7970 4068 7970 4069 7971 3287 7971 4067 7971 4068 7972 4066 7972 4034 7972 4035 7973 4069 7973 4068 7973 4069 7974 3292 7974 3287 7974 4069 7975 4035 7975 3292 7975 4045 7976 4065 7976 4061 7976 4045 7977 4041 7977 4039 7977 4045 7978 4066 7978 4065 7978 4045 7979 4039 7979 4066 7979 4045 7980 4052 7980 4049 7980 4045 7981 4056 7981 4052 7981 4045 7982 4061 7982 4056 7982 4071 7983 4076 7983 4079 7983 4071 7984 4070 7984 4076 7984 4070 7985 4072 7985 4076 7985 4076 7986 4072 7986 4077 7986 4072 7987 4073 7987 4077 7987 4077 7988 4073 7988 4081 7988 4073 7989 4074 7989 4081 7989 4081 7990 4074 7990 4080 7990 4074 7991 4075 7991 4080 7991 4080 7992 4075 7992 4078 7992 4078 7993 4071 7993 4079 7993 4075 7994 4071 7994 4078 7994 4077 7995 4082 7995 4083 7995 4077 7996 4083 7996 4084 7996 4081 7997 4086 7997 4082 7997 4081 7998 4085 7998 4086 7998 4081 7999 4082 7999 4077 7999 4076 8000 4084 8000 4087 8000 4076 8001 4077 8001 4084 8001 4088 8002 4076 8002 4087 8002 4080 8003 4089 8003 4085 8003 4080 8004 4085 8004 4081 8004 4079 8005 4088 8005 4090 8005 4079 8006 4076 8006 4088 8006 4091 8007 4089 8007 4080 8007 4091 8008 4080 8008 4078 8008 4092 8009 4079 8009 4090 8009 4093 8010 4079 8010 4092 8010 4094 8011 4091 8011 4078 8011 4093 8012 4078 8012 4079 8012 4093 8013 4094 8013 4078 8013 4070 8014 4073 8014 4072 8014 4075 8015 4074 8015 4071 8015 4071 8016 4074 8016 4070 8016 4070 8017 4074 8017 4073 8017 4106 8018 4086 8018 4085 8018 4095 8019 4106 8019 4085 8019 4095 8020 4085 8020 4089 8020 4096 8021 4095 8021 4089 8021 4096 8022 4089 8022 4091 8022 4097 8023 4096 8023 4091 8023 4097 8024 4091 8024 4094 8024 4098 8025 4097 8025 4094 8025 4098 8026 4094 8026 4093 8026 4098 8027 4093 8027 4092 8027 4099 8028 4098 8028 4092 8028 4099 8029 4092 8029 4090 8029 4100 8030 4099 8030 4090 8030 4100 8031 4090 8031 4088 8031 4101 8032 4100 8032 4088 8032 4101 8033 4088 8033 4087 8033 4102 8034 4101 8034 4087 8034 4102 8035 4087 8035 4084 8035 4102 8036 4084 8036 4083 8036 4103 8037 4102 8037 4083 8037 4104 8038 4083 8038 4082 8038 4104 8039 4103 8039 4083 8039 4105 8040 4104 8040 4082 8040 4105 8041 4082 8041 4086 8041 4106 8042 4105 8042 4086 8042 3892 8043 3314 8043 4101 8043 3314 8044 4100 8044 4101 8044 3312 8045 4100 8045 3314 8045 3892 8046 4101 8046 4102 8046 4025 8047 3892 8047 4102 8047 3312 8048 4099 8048 4100 8048 3304 8049 4099 8049 3312 8049 4025 8050 4102 8050 4103 8050 3304 8051 4098 8051 4099 8051 3309 8052 4098 8052 3304 8052 4025 8053 4103 8053 4104 8053 4026 8054 4025 8054 4104 8054 4097 8055 4098 8055 3309 8055 4105 8056 4026 8056 4104 8056 4097 8057 3309 8057 3306 8057 4105 8058 4024 8058 4026 8058 4106 8059 4024 8059 4105 8059 4096 8060 4097 8060 3306 8060 4096 8061 3306 8061 3302 8061 4095 8062 4096 8062 3302 8062 4095 8063 4024 8063 4106 8063 4095 8064 4027 8064 4024 8064 4095 8065 3302 8065 4027 8065

+
+ + + +

4107 8066 4108 8066 4109 8066 4107 8067 4110 8067 4108 8067 4109 8068 4108 8068 4111 8068 4108 8069 4112 8069 4111 8069 4873 8070 4110 8070 4107 8070 4873 8071 4113 8071 4110 8071 4111 8072 4112 8072 4114 8072 4115 8073 4113 8073 4873 8073 4115 8074 4116 8074 4113 8074 4114 8075 4112 8075 4862 8075 4837 8076 4116 8076 4115 8076 4112 8077 4117 8077 4862 8077 4837 8078 4118 8078 4116 8078 4837 8079 4840 8079 4118 8079 4118 8080 4840 8080 4120 8080 4127 8081 4124 8081 4123 8081 4127 8082 4126 8082 4124 8082 4129 8083 4126 8083 4127 8083 4129 8084 4128 8084 4126 8084 4129 8085 4130 8085 4128 8085 4125 8086 4130 8086 4129 8086 4125 8087 4131 8087 4130 8087 4132 8088 4131 8088 4125 8088 4132 8089 4133 8089 4131 8089 4132 8090 4134 8090 4133 8090 4135 8091 4134 8091 4132 8091 4135 8092 4136 8092 4134 8092 4135 8093 4137 8093 4136 8093 4138 8094 4137 8094 4135 8094 4138 8095 4139 8095 4137 8095 4140 8096 4139 8096 4138 8096 4141 8097 4139 8097 4140 8097 4141 8098 4142 8098 4139 8098 4143 8099 4144 8099 4141 8099 4141 8100 4144 8100 4142 8100 4143 8101 4145 8101 4144 8101 4146 8102 4145 8102 4143 8102 4146 8103 4147 8103 4145 8103 4148 8104 4147 8104 4146 8104 4148 8105 4149 8105 4147 8105 4150 8106 4149 8106 4148 8106 4150 8107 4151 8107 4149 8107 4152 8108 4153 8108 4150 8108 4150 8109 4153 8109 4151 8109 4152 8110 4154 8110 4153 8110 4155 8111 4154 8111 4152 8111 4156 8112 4157 8112 4155 8112 4155 8113 4157 8113 4154 8113 4156 8114 4158 8114 4157 8114 4159 8115 4158 8115 4156 8115 4159 8116 4160 8116 4158 8116 4159 8117 4161 8117 4160 8117 4162 8118 4161 8118 4159 8118 4162 8119 4163 8119 4161 8119 4162 8120 4164 8120 4163 8120 4165 8121 4164 8121 4162 8121 4166 8122 4164 8122 4165 8122 4166 8123 4167 8123 4164 8123 4166 8124 4168 8124 4167 8124 4169 8125 4168 8125 4166 8125 4169 8126 4170 8126 4168 8126 4169 8127 4171 8127 4170 8127 4172 8128 4171 8128 4169 8128 4172 8129 4173 8129 4171 8129 4174 8130 4173 8130 4172 8130 4174 8131 4175 8131 4173 8131 4174 8132 4176 8132 4175 8132 4177 8133 4176 8133 4174 8133 4177 8134 4178 8134 4176 8134 4179 8135 4178 8135 4177 8135 4179 8136 4180 8136 4178 8136 4179 8137 4181 8137 4180 8137 4182 8138 4181 8138 4179 8138 4182 8139 4183 8139 4181 8139 4184 8140 4183 8140 4182 8140 4184 8141 4185 8141 4183 8141 4186 8142 4185 8142 4184 8142 4186 8143 4187 8143 4185 8143 4188 8144 4187 8144 4186 8144 4188 8145 4189 8145 4187 8145 4190 8146 4191 8146 4188 8146 4188 8147 4191 8147 4189 8147 4192 8148 4191 8148 4190 8148 4192 8149 4193 8149 4191 8149 4194 8150 4193 8150 4192 8150 4194 8151 4195 8151 4193 8151 4194 8152 4196 8152 4195 8152 4197 8153 4196 8153 4194 8153 4197 8154 4198 8154 4196 8154 4199 8155 4198 8155 4197 8155 4199 8156 4200 8156 4198 8156 4199 8157 4201 8157 4200 8157 4202 8158 4201 8158 4199 8158 4203 8159 4201 8159 4202 8159 4203 8160 4204 8160 4201 8160 4205 8161 4204 8161 4203 8161 4205 8162 4206 8162 4204 8162 4205 8163 4207 8163 4206 8163 4208 8164 4207 8164 4205 8164 4208 8165 4209 8165 4207 8165 4210 8166 4209 8166 4208 8166 4210 8167 4211 8167 4209 8167 4212 8168 4211 8168 4210 8168 4212 8169 4213 8169 4211 8169 4212 8170 4214 8170 4213 8170 4215 8171 4214 8171 4212 8171 4215 8172 4216 8172 4214 8172 4217 8173 4216 8173 4215 8173 4217 8174 4218 8174 4216 8174 4217 8175 4219 8175 4218 8175 4220 8176 4219 8176 4217 8176 4220 8177 4221 8177 4219 8177 4222 8178 4221 8178 4220 8178 4222 8179 4223 8179 4221 8179 4224 8180 4223 8180 4222 8180 4224 8181 4225 8181 4223 8181 4226 8182 4225 8182 4224 8182 4226 8183 4227 8183 4225 8183 4228 8184 4227 8184 4226 8184 4228 8185 4229 8185 4227 8185 4230 8186 4229 8186 4228 8186 4230 8187 4231 8187 4229 8187 4232 8188 4231 8188 4230 8188 4232 8189 4233 8189 4231 8189 4234 8190 4233 8190 4232 8190 4234 8191 4235 8191 4233 8191 4234 8192 4236 8192 4235 8192 4237 8193 4236 8193 4234 8193 4237 8194 4238 8194 4236 8194 4239 8195 4238 8195 4237 8195 4239 8196 4240 8196 4238 8196 4241 8197 4240 8197 4239 8197 4241 8198 4242 8198 4240 8198 4243 8199 4242 8199 4241 8199 4243 8200 4244 8200 4242 8200 4245 8201 4244 8201 4243 8201 4245 8202 4246 8202 4244 8202 4247 8203 4246 8203 4245 8203 4247 8204 4248 8204 4246 8204 4247 8205 4249 8205 4248 8205 4250 8206 4249 8206 4247 8206 4251 8207 4249 8207 4250 8207 4251 8208 4252 8208 4249 8208 4251 8209 4253 8209 4252 8209 4251 8210 4254 8210 4253 8210 4255 8211 4254 8211 4251 8211 4255 8212 4256 8212 4254 8212 4257 8213 4258 8213 4255 8213 4255 8214 4258 8214 4256 8214 4257 8215 4259 8215 4258 8215 4260 8216 4259 8216 4257 8216 4260 8217 4261 8217 4259 8217 4262 8218 4261 8218 4260 8218 4262 8219 4263 8219 4261 8219 4262 8220 4264 8220 4263 8220 4265 8221 4264 8221 4262 8221 4265 8222 4266 8222 4264 8222 4267 8223 4266 8223 4265 8223 4268 8224 4266 8224 4267 8224 4268 8225 4269 8225 4266 8225 4270 8226 4269 8226 4268 8226 4270 8227 4271 8227 4269 8227 4270 8228 4272 8228 4271 8228 4273 8229 4272 8229 4270 8229 4273 8230 4274 8230 4272 8230 4275 8231 4274 8231 4273 8231 4275 8232 4276 8232 4274 8232 4275 8233 4277 8233 4276 8233 4278 8234 4277 8234 4275 8234 4279 8235 4277 8235 4278 8235 4279 8236 4280 8236 4277 8236 4279 8237 4281 8237 4280 8237 4282 8238 4281 8238 4279 8238 4282 8239 4283 8239 4281 8239 4284 8240 4283 8240 4282 8240 4284 8241 4285 8241 4283 8241 4286 8242 4285 8242 4284 8242 4286 8243 4287 8243 4285 8243 4288 8244 4287 8244 4286 8244 4288 8245 4289 8245 4287 8245 4290 8246 4289 8246 4288 8246 4290 8247 4291 8247 4289 8247 4292 8248 4291 8248 4290 8248 4292 8249 4293 8249 4291 8249 4294 8250 4293 8250 4292 8250 4294 8251 4295 8251 4293 8251 4296 8252 4295 8252 4294 8252 4296 8253 4297 8253 4295 8253 4298 8254 4297 8254 4296 8254 4298 8255 4299 8255 4297 8255 4300 8256 4299 8256 4298 8256 4300 8257 4301 8257 4299 8257 4302 8258 4301 8258 4300 8258 4302 8259 4303 8259 4301 8259 4302 8260 4304 8260 4303 8260 4305 8261 4304 8261 4302 8261 4305 8262 4306 8262 4304 8262 4307 8263 4306 8263 4305 8263 4307 8264 4308 8264 4306 8264 4309 8265 4308 8265 4307 8265 4309 8266 4310 8266 4308 8266 4311 8267 4310 8267 4309 8267 4311 8268 4312 8268 4310 8268 4313 8269 4312 8269 4311 8269 4313 8270 4314 8270 4312 8270 4315 8271 4314 8271 4313 8271 4315 8272 4316 8272 4314 8272 4317 8273 4316 8273 4315 8273 4317 8274 4318 8274 4316 8274 4319 8275 4318 8275 4317 8275 4319 8276 4320 8276 4318 8276 4321 8277 4320 8277 4319 8277 4321 8278 4322 8278 4320 8278 4321 8279 4323 8279 4322 8279 4324 8280 4323 8280 4321 8280 4324 8281 4325 8281 4323 8281 4326 8282 4325 8282 4324 8282 4326 8283 4327 8283 4325 8283 4326 8284 4328 8284 4327 8284 4329 8285 4328 8285 4326 8285 4329 8286 4330 8286 4328 8286 4331 8287 4332 8287 4329 8287 4329 8288 4332 8288 4330 8288 4333 8289 4332 8289 4331 8289 4333 8290 4334 8290 4332 8290 4333 8291 4335 8291 4334 8291 4336 8292 4335 8292 4333 8292 4336 8293 4337 8293 4335 8293 4338 8294 4337 8294 4336 8294 4338 8295 4339 8295 4337 8295 4340 8296 4341 8296 4338 8296 4338 8297 4341 8297 4339 8297 4340 8298 4342 8298 4341 8298 4343 8299 4342 8299 4340 8299 4343 8300 4344 8300 4342 8300 4343 8301 4345 8301 4344 8301 4346 8302 4345 8302 4343 8302 4346 8303 4347 8303 4345 8303 4348 8304 4347 8304 4346 8304 4348 8305 4349 8305 4347 8305 4350 8306 4349 8306 4348 8306 4351 8307 4349 8307 4350 8307 4351 8308 4352 8308 4349 8308 4351 8309 4353 8309 4352 8309 4354 8310 4353 8310 4351 8310 4354 8311 4355 8311 4353 8311 4354 8312 4356 8312 4355 8312 4357 8313 4356 8313 4354 8313 4357 8314 4358 8314 4356 8314 4357 8315 4359 8315 4358 8315 4360 8316 4359 8316 4357 8316 4360 8317 4361 8317 4359 8317 4360 8318 4362 8318 4361 8318 4363 8319 4362 8319 4360 8319 4363 8320 4364 8320 4362 8320 4365 8321 4364 8321 4363 8321 4365 8322 4366 8322 4364 8322 4365 8323 4367 8323 4366 8323 4368 8324 4367 8324 4365 8324 4368 8325 4369 8325 4367 8325 4370 8326 4369 8326 4368 8326 4370 8327 4371 8327 4369 8327 4372 8328 4371 8328 4370 8328 4372 8329 4373 8329 4371 8329 4372 8330 4374 8330 4373 8330 4375 8331 4374 8331 4372 8331 4375 8332 4376 8332 4374 8332 4377 8333 4378 8333 4375 8333 4375 8334 4378 8334 4376 8334 4377 8335 4379 8335 4378 8335 4380 8336 4379 8336 4377 8336 4380 8337 4381 8337 4379 8337 4382 8338 4381 8338 4380 8338 4382 8339 4383 8339 4381 8339 4384 8340 4383 8340 4382 8340 4384 8341 4385 8341 4383 8341 4384 8342 4386 8342 4385 8342 4387 8343 4386 8343 4384 8343 4388 8344 4386 8344 4387 8344 4388 8345 4389 8345 4386 8345 4388 8346 4390 8346 4389 8346 4391 8347 4390 8347 4388 8347 4391 8348 4392 8348 4390 8348 4393 8349 4392 8349 4391 8349 4393 8350 4394 8350 4392 8350 4395 8351 4394 8351 4393 8351 4395 8352 4396 8352 4394 8352 4395 8353 4397 8353 4396 8353 4398 8354 4397 8354 4395 8354 4398 8355 4399 8355 4397 8355 4400 8356 4399 8356 4398 8356 4400 8357 4401 8357 4399 8357 4402 8358 4401 8358 4400 8358 4402 8359 4403 8359 4401 8359 4404 8360 4403 8360 4402 8360 4404 8361 4405 8361 4403 8361 4406 8362 4405 8362 4404 8362 4406 8363 4407 8363 4405 8363 4408 8364 4407 8364 4406 8364 4408 8365 4409 8365 4407 8365 4410 8366 4409 8366 4408 8366 4410 8367 4411 8367 4409 8367 4412 8368 4411 8368 4410 8368 4412 8369 4413 8369 4411 8369 4412 8370 4414 8370 4413 8370 4415 8371 4414 8371 4412 8371 4416 8372 4414 8372 4415 8372 4416 8373 4417 8373 4414 8373 4416 8374 4418 8374 4417 8374 4419 8375 4418 8375 4416 8375 4419 8376 4420 8376 4418 8376 4421 8377 4420 8377 4419 8377 4421 8378 4422 8378 4420 8378 4423 8379 4422 8379 4421 8379 4423 8380 4424 8380 4422 8380 4425 8381 4424 8381 4423 8381 4425 8382 4426 8382 4424 8382 4427 8383 4426 8383 4425 8383 4427 8384 4428 8384 4426 8384 4429 8385 4428 8385 4427 8385 4429 8386 4430 8386 4428 8386 4431 8387 4430 8387 4429 8387 4431 8388 4432 8388 4430 8388 4433 8389 4434 8389 4431 8389 4431 8390 4434 8390 4432 8390 4435 8391 4436 8391 4433 8391 4433 8392 4436 8392 4434 8392 4435 8393 4437 8393 4436 8393 4438 8394 4437 8394 4435 8394 4438 8395 4439 8395 4437 8395 4440 8396 4439 8396 4438 8396 4440 8397 4441 8397 4439 8397 4442 8398 4441 8398 4440 8398 4442 8399 4443 8399 4441 8399 4444 8400 4443 8400 4442 8400 4444 8401 4445 8401 4443 8401 4446 8402 4445 8402 4444 8402 4446 8403 4447 8403 4445 8403 4448 8404 4447 8404 4446 8404 4448 8405 4449 8405 4447 8405 4448 8406 4450 8406 4449 8406 4448 8407 4451 8407 4450 8407 4452 8408 4451 8408 4448 8408 4452 8409 4453 8409 4451 8409 4452 8410 4454 8410 4453 8410 4455 8411 4454 8411 4452 8411 4456 8412 4457 8412 4455 8412 4455 8413 4457 8413 4454 8413 4456 8414 4458 8414 4457 8414 4459 8415 4458 8415 4456 8415 4459 8416 4460 8416 4458 8416 4461 8417 4460 8417 4459 8417 4462 8418 4463 8418 4461 8418 4461 8419 4463 8419 4460 8419 4462 8420 4464 8420 4463 8420 4462 8421 4465 8421 4464 8421 4466 8422 4465 8422 4462 8422 4466 8423 4467 8423 4465 8423 4468 8424 4467 8424 4466 8424 4469 8425 4467 8425 4468 8425 4469 8426 4470 8426 4467 8426 4471 8427 4470 8427 4469 8427 4471 8428 4472 8428 4470 8428 4473 8429 4472 8429 4471 8429 4473 8430 4474 8430 4472 8430 4475 8431 4474 8431 4473 8431 4475 8432 4476 8432 4474 8432 4477 8433 4476 8433 4475 8433 4477 8434 4478 8434 4476 8434 4479 8435 4478 8435 4477 8435 4479 8436 4480 8436 4478 8436 4481 8437 4480 8437 4479 8437 4481 8438 4482 8438 4480 8438 4483 8439 4482 8439 4481 8439 4483 8440 4484 8440 4482 8440 4485 8441 4484 8441 4483 8441 4485 8442 4486 8442 4484 8442 4487 8443 4486 8443 4485 8443 4487 8444 4488 8444 4486 8444 4489 8445 4488 8445 4487 8445 4489 8446 4490 8446 4488 8446 4491 8447 4490 8447 4489 8447 4491 8448 4492 8448 4490 8448 4493 8449 4492 8449 4491 8449 4493 8450 4494 8450 4492 8450 4493 8451 4495 8451 4494 8451 4496 8452 4495 8452 4493 8452 4496 8453 4497 8453 4495 8453 4498 8454 4497 8454 4496 8454 4498 8455 4499 8455 4497 8455 4500 8456 4499 8456 4498 8456 4500 8457 4501 8457 4499 8457 4500 8458 4502 8458 4501 8458 4503 8459 4502 8459 4500 8459 4503 8460 4504 8460 4502 8460 4505 8461 4504 8461 4503 8461 4505 8462 4506 8462 4504 8462 4507 8463 4506 8463 4505 8463 4507 8464 4508 8464 4506 8464 4509 8465 4508 8465 4507 8465 4509 8466 4510 8466 4508 8466 4511 8467 4510 8467 4509 8467 4511 8468 4512 8468 4510 8468 4511 8469 4513 8469 4512 8469 4514 8470 4513 8470 4511 8470 4514 8471 4515 8471 4513 8471 4514 8472 4516 8472 4515 8472 4517 8473 4516 8473 4514 8473 4517 8474 4518 8474 4516 8474 4519 8475 4518 8475 4517 8475 4520 8476 4521 8476 4519 8476 4519 8477 4521 8477 4518 8477 4520 8478 4522 8478 4521 8478 4523 8479 4522 8479 4520 8479 4523 8480 4524 8480 4522 8480 4523 8481 4525 8481 4524 8481 4526 8482 4525 8482 4523 8482 4526 8483 4527 8483 4525 8483 4528 8484 4527 8484 4526 8484 4528 8485 4529 8485 4527 8485 4528 8486 4530 8486 4529 8486 4531 8487 4530 8487 4528 8487 4532 8488 4530 8488 4531 8488 4532 8489 4533 8489 4530 8489 4532 8490 4534 8490 4533 8490 4535 8491 4534 8491 4532 8491 4536 8492 4537 8492 4535 8492 4535 8493 4537 8493 4534 8493 4536 8494 4538 8494 4537 8494 4539 8495 4538 8495 4536 8495 4539 8496 4540 8496 4538 8496 4541 8497 4540 8497 4539 8497 4541 8498 4542 8498 4540 8498 4541 8499 4543 8499 4542 8499 4544 8500 4543 8500 4541 8500 4544 8501 4545 8501 4543 8501 4544 8502 4546 8502 4545 8502 4547 8503 4546 8503 4544 8503 4547 8504 4548 8504 4546 8504 4549 8505 4548 8505 4547 8505 4549 8506 4550 8506 4548 8506 4549 8507 4551 8507 4550 8507 4552 8508 4551 8508 4549 8508 4552 8509 4553 8509 4551 8509 4554 8510 4555 8510 4552 8510 4552 8511 4555 8511 4553 8511 4554 8512 4556 8512 4555 8512 4557 8513 4556 8513 4554 8513 4557 8514 4558 8514 4556 8514 4559 8515 4560 8515 4557 8515 4557 8516 4560 8516 4558 8516 4561 8517 4560 8517 4559 8517 4561 8518 4562 8518 4560 8518 4561 8519 4563 8519 4562 8519 4564 8520 4563 8520 4561 8520 4564 8521 4565 8521 4563 8521 4566 8522 4565 8522 4564 8522 4566 8523 4567 8523 4565 8523 4568 8524 4569 8524 4566 8524 4566 8525 4569 8525 4567 8525 4568 8526 4570 8526 4569 8526 4571 8527 4570 8527 4568 8527 4571 8528 4572 8528 4570 8528 4571 8529 4573 8529 4572 8529 4574 8530 4573 8530 4571 8530 4574 8531 4575 8531 4573 8531 4574 8532 4576 8532 4575 8532 4577 8533 4576 8533 4574 8533 4577 8534 4578 8534 4576 8534 4579 8535 4578 8535 4577 8535 4579 8536 4580 8536 4578 8536 4581 8537 4582 8537 4579 8537 4579 8538 4582 8538 4580 8538 4581 8539 4583 8539 4582 8539 4584 8540 4583 8540 4581 8540 4584 8541 4585 8541 4583 8541 4586 8542 4587 8542 4584 8542 4584 8543 4587 8543 4585 8543 4586 8544 4588 8544 4587 8544 4589 8545 4588 8545 4586 8545 4589 8546 4590 8546 4588 8546 4591 8547 4590 8547 4589 8547 4591 8548 4592 8548 4590 8548 4593 8549 4592 8549 4591 8549 4593 8550 4594 8550 4592 8550 4595 8551 4594 8551 4593 8551 4595 8552 4596 8552 4594 8552 4595 8553 4597 8553 4596 8553 4598 8554 4597 8554 4595 8554 4599 8555 4597 8555 4598 8555 4599 8556 4600 8556 4597 8556 4601 8557 4600 8557 4599 8557 4601 8558 4602 8558 4600 8558 4603 8559 4602 8559 4601 8559 4603 8560 4604 8560 4602 8560 4603 8561 4605 8561 4604 8561 4606 8562 4605 8562 4603 8562 4607 8563 4605 8563 4606 8563 4607 8564 4608 8564 4605 8564 4607 8565 4609 8565 4608 8565 4610 8566 4609 8566 4607 8566 4611 8567 4612 8567 4610 8567 4610 8568 4612 8568 4609 8568 4611 8569 4613 8569 4612 8569 4611 8570 4614 8570 4613 8570 4615 8571 4614 8571 4611 8571 4616 8572 4614 8572 4615 8572 4616 8573 4617 8573 4614 8573 4616 8574 4618 8574 4617 8574 4619 8575 4618 8575 4616 8575 4619 8576 4620 8576 4618 8576 4621 8577 4620 8577 4619 8577 4621 8578 4622 8578 4620 8578 4623 8579 4622 8579 4621 8579 4623 8580 4624 8580 4622 8580 4625 8581 4624 8581 4623 8581 4625 8582 4626 8582 4624 8582 4627 8583 4626 8583 4625 8583 4627 8584 4628 8584 4626 8584 4629 8585 4628 8585 4627 8585 4629 8586 4630 8586 4628 8586 4631 8587 4630 8587 4629 8587 4631 8588 4632 8588 4630 8588 4631 8589 4633 8589 4632 8589 4634 8590 4633 8590 4631 8590 4634 8591 4635 8591 4633 8591 4636 8592 4635 8592 4634 8592 4636 8593 4637 8593 4635 8593 4638 8594 4637 8594 4636 8594 4638 8595 4639 8595 4637 8595 4640 8596 4641 8596 4638 8596 4638 8597 4641 8597 4639 8597 4640 8598 4642 8598 4641 8598 4643 8599 4642 8599 4640 8599 4643 8600 4644 8600 4642 8600 4643 8601 4645 8601 4644 8601 4646 8602 4645 8602 4643 8602 4647 8603 4645 8603 4646 8603 4647 8604 4648 8604 4645 8604 4647 8605 4649 8605 4648 8605 4650 8606 4649 8606 4647 8606 4651 8607 4649 8607 4650 8607 4651 8608 4652 8608 4649 8608 4651 8609 4653 8609 4652 8609 4654 8610 4653 8610 4651 8610 4654 8611 4655 8611 4653 8611 4656 8612 4655 8612 4654 8612 4656 8613 4657 8613 4655 8613 4658 8614 4657 8614 4656 8614 4658 8615 4659 8615 4657 8615 4660 8616 4659 8616 4658 8616 4660 8617 4661 8617 4659 8617 4660 8618 4662 8618 4661 8618 4663 8619 4662 8619 4660 8619 4663 8620 4664 8620 4662 8620 4663 8621 4665 8621 4664 8621 4666 8622 4665 8622 4663 8622 4666 8623 4667 8623 4665 8623 4668 8624 4667 8624 4666 8624 4668 8625 4669 8625 4667 8625 4670 8626 4669 8626 4668 8626 4670 8627 4671 8627 4669 8627 4672 8628 4673 8628 4670 8628 4670 8629 4673 8629 4671 8629 4672 8630 4674 8630 4673 8630 4675 8631 4674 8631 4672 8631 4675 8632 4676 8632 4674 8632 4677 8633 4676 8633 4675 8633 4677 8634 4678 8634 4676 8634 4679 8635 4678 8635 4677 8635 4679 8636 4680 8636 4678 8636 4679 8637 4681 8637 4680 8637 4682 8638 4681 8638 4679 8638 4682 8639 4683 8639 4681 8639 4684 8640 4683 8640 4682 8640 4684 8641 4685 8641 4683 8641 4684 8642 4686 8642 4685 8642 4687 8643 4686 8643 4684 8643 4687 8644 4688 8644 4686 8644 4689 8645 4688 8645 4687 8645 4689 8646 4690 8646 4688 8646 4691 8647 4690 8647 4689 8647 4691 8648 4692 8648 4690 8648 4693 8649 4694 8649 4691 8649 4691 8650 4694 8650 4692 8650 4693 8651 4695 8651 4694 8651 4696 8652 4695 8652 4693 8652 4696 8653 4119 8653 4695 8653 4697 8654 4119 8654 4696 8654 4697 8655 4851 8655 4119 8655 4697 8656 4122 8656 4851 8656 4697 8657 4121 8657 4122 8657 4698 8658 4121 8658 4697 8658 4699 8659 4121 8659 4698 8659 4699 8660 4120 8660 4121 8660 4700 8661 4120 8661 4699 8661 4700 8662 4118 8662 4120 8662 4135 8663 4132 8663 4701 8663 4702 8664 4135 8664 4701 8664 4138 8665 4135 8665 4702 8665 4140 8666 4138 8666 4702 8666 4143 8667 4141 8667 4703 8667 4146 8668 4143 8668 4703 8668 4704 8669 4156 8669 4155 8669 4705 8670 4156 8670 4704 8670 4159 8671 4156 8671 4705 8671 4706 8672 4159 8672 4705 8672 4162 8673 4159 8673 4706 8673 4707 8674 4162 8674 4706 8674 4165 8675 4162 8675 4707 8675 4166 8676 4165 8676 4708 8676 4169 8677 4166 8677 4708 8677 4709 8678 4172 8678 4169 8678 4174 8679 4172 8679 4709 8679 4182 8680 4179 8680 4710 8680 4184 8681 4182 8681 4710 8681 4186 8682 4184 8682 4711 8682 4188 8683 4186 8683 4711 8683 4712 8684 4192 8684 4190 8684 4194 8685 4192 8685 4712 8685 4713 8686 4194 8686 4712 8686 4197 8687 4194 8687 4713 8687 4714 8688 4197 8688 4713 8688 4199 8689 4197 8689 4714 8689 4205 8690 4203 8690 4715 8690 4208 8691 4205 8691 4715 8691 4716 8692 4208 8692 4715 8692 4210 8693 4208 8693 4716 8693 4215 8694 4212 8694 4717 8694 4718 8695 4215 8695 4717 8695 4217 8696 4215 8696 4718 8696 4220 8697 4217 8697 4718 8697 4719 8698 4230 8698 4228 8698 4232 8699 4230 8699 4719 8699 4720 8700 4232 8700 4719 8700 4234 8701 4232 8701 4720 8701 4721 8702 4237 8702 4234 8702 4239 8703 4237 8703 4721 8703 4722 8704 4243 8704 4241 8704 4245 8705 4243 8705 4722 8705 4723 8706 4245 8706 4722 8706 4247 8707 4245 8707 4723 8707 4250 8708 4247 8708 4723 8708 4251 8709 4250 8709 4724 8709 4725 8710 4251 8710 4724 8710 4255 8711 4251 8711 4725 8711 4255 8712 4725 8712 4726 8712 4257 8713 4255 8713 4726 8713 4270 8714 4268 8714 4727 8714 4728 8715 4270 8715 4727 8715 4273 8716 4270 8716 4728 8716 4729 8717 4282 8717 4279 8717 4284 8718 4282 8718 4729 8718 4730 8719 4286 8719 4284 8719 4288 8720 4286 8720 4730 8720 4731 8721 4288 8721 4730 8721 4290 8722 4288 8722 4731 8722 4294 8723 4292 8723 4290 8723 4300 8724 4298 8724 4732 8724 4733 8725 4300 8725 4732 8725 4302 8726 4300 8726 4733 8726 4734 8727 4305 8727 4302 8727 4307 8728 4305 8728 4734 8728 4311 8729 4309 8729 4735 8729 4736 8730 4311 8730 4735 8730 4313 8731 4311 8731 4736 8731 4315 8732 4313 8732 4736 8732 4321 8733 4319 8733 4737 8733 4738 8734 4321 8734 4737 8734 4324 8735 4321 8735 4738 8735 4739 8736 4326 8736 4324 8736 4329 8737 4326 8737 4739 8737 4336 8738 4333 8738 4740 8738 4741 8739 4336 8739 4740 8739 4338 8740 4336 8740 4741 8740 4340 8741 4338 8741 4741 8741 4354 8742 4351 8742 4742 8742 4357 8743 4354 8743 4742 8743 4360 8744 4357 8744 4743 8744 4744 8745 4360 8745 4743 8745 4363 8746 4360 8746 4744 8746 4365 8747 4363 8747 4744 8747 4745 8748 4368 8748 4365 8748 4370 8749 4368 8749 4745 8749 4372 8750 4370 8750 4746 8750 4747 8751 4372 8751 4746 8751 4375 8752 4372 8752 4747 8752 4748 8753 4375 8753 4747 8753 4377 8754 4375 8754 4748 8754 4749 8755 4380 8755 4377 8755 4382 8756 4380 8756 4749 8756 4750 8757 4384 8757 4382 8757 4387 8758 4384 8758 4750 8758 4387 8759 4750 8759 4751 8759 4388 8760 4387 8760 4751 8760 4752 8761 4388 8761 4751 8761 4391 8762 4388 8762 4752 8762 4753 8763 4391 8763 4752 8763 4393 8764 4391 8764 4753 8764 4395 8765 4393 8765 4753 8765 4754 8766 4398 8766 4395 8766 4755 8767 4398 8767 4754 8767 4400 8768 4398 8768 4755 8768 4402 8769 4400 8769 4755 8769 4756 8770 4416 8770 4415 8770 4419 8771 4416 8771 4756 8771 4757 8772 4419 8772 4756 8772 4421 8773 4419 8773 4757 8773 4427 8774 4425 8774 4423 8774 4429 8775 4427 8775 4758 8775 4759 8776 4429 8776 4758 8776 4431 8777 4429 8777 4759 8777 4433 8778 4431 8778 4759 8778 4435 8779 4433 8779 4760 8779 4438 8780 4435 8780 4760 8780 4761 8781 4440 8781 4438 8781 4442 8782 4440 8782 4761 8782 4762 8783 4442 8783 4761 8783 4444 8784 4442 8784 4762 8784 4763 8785 4444 8785 4762 8785 4446 8786 4444 8786 4763 8786 4764 8787 4446 8787 4763 8787 4448 8788 4446 8788 4764 8788 4765 8789 4448 8789 4764 8789 4766 8790 4448 8790 4765 8790 4452 8791 4448 8791 4766 8791 4455 8792 4452 8792 4766 8792 4767 8793 4461 8793 4459 8793 4462 8794 4461 8794 4767 8794 4768 8795 4462 8795 4767 8795 4466 8796 4462 8796 4768 8796 4769 8797 4473 8797 4471 8797 4475 8798 4473 8798 4769 8798 4770 8799 4489 8799 4487 8799 4771 8800 4489 8800 4770 8800 4491 8801 4489 8801 4771 8801 4493 8802 4491 8802 4771 8802 4772 8803 4493 8803 4771 8803 4496 8804 4493 8804 4772 8804 4500 8805 4498 8805 4773 8805 4503 8806 4500 8806 4773 8806 4507 8807 4505 8807 4774 8807 4509 8808 4507 8808 4774 8808 4775 8809 4511 8809 4509 8809 4514 8810 4511 8810 4775 8810 4517 8811 4514 8811 4775 8811 4520 8812 4519 8812 4776 8812 4523 8813 4520 8813 4776 8813 4777 8814 4523 8814 4776 8814 4778 8815 4523 8815 4777 8815 4526 8816 4523 8816 4778 8816 4528 8817 4526 8817 4778 8817 4539 8818 4536 8818 4779 8818 4541 8819 4539 8819 4779 8819 4780 8820 4541 8820 4779 8820 4544 8821 4541 8821 4780 8821 4781 8822 4544 8822 4780 8822 4547 8823 4544 8823 4781 8823 4549 8824 4547 8824 4782 8824 4783 8825 4549 8825 4782 8825 4552 8826 4549 8826 4783 8826 4784 8827 4552 8827 4783 8827 4554 8828 4552 8828 4784 8828 4785 8829 4554 8829 4784 8829 4557 8830 4554 8830 4785 8830 4786 8831 4557 8831 4785 8831 4559 8832 4557 8832 4786 8832 4561 8833 4559 8833 4786 8833 4564 8834 4561 8834 4787 8834 4788 8835 4564 8835 4787 8835 4566 8836 4564 8836 4788 8836 4789 8837 4568 8837 4566 8837 4571 8838 4568 8838 4789 8838 4790 8839 4571 8839 4789 8839 4574 8840 4571 8840 4790 8840 4791 8841 4574 8841 4790 8841 4577 8842 4574 8842 4791 8842 4792 8843 4577 8843 4791 8843 4579 8844 4577 8844 4792 8844 4793 8845 4579 8845 4792 8845 4581 8846 4579 8846 4793 8846 4584 8847 4581 8847 4794 8847 4795 8848 4584 8848 4794 8848 4586 8849 4584 8849 4795 8849 4589 8850 4586 8850 4795 8850 4796 8851 4589 8851 4795 8851 4591 8852 4589 8852 4796 8852 4797 8853 4595 8853 4593 8853 4598 8854 4595 8854 4797 8854 4607 8855 4606 8855 4798 8855 4799 8856 4611 8856 4610 8856 4615 8857 4611 8857 4799 8857 4616 8858 4615 8858 4800 8858 4619 8859 4616 8859 4800 8859 4623 8860 4621 8860 4801 8860 4625 8861 4623 8861 4801 8861 4802 8862 4625 8862 4801 8862 4627 8863 4625 8863 4802 8863 4631 8864 4629 8864 4803 8864 4634 8865 4631 8865 4803 8865 4804 8866 4634 8866 4803 8866 4636 8867 4634 8867 4804 8867 4638 8868 4636 8868 4805 8868 4640 8869 4638 8869 4805 8869 4806 8870 4640 8870 4805 8870 4643 8871 4640 8871 4806 8871 4807 8872 4643 8872 4806 8872 4646 8873 4643 8873 4807 8873 4808 8874 4646 8874 4807 8874 4647 8875 4646 8875 4808 8875 4650 8876 4647 8876 4808 8876 4654 8877 4651 8877 4809 8877 4656 8878 4654 8878 4809 8878 4810 8879 4656 8879 4809 8879 4658 8880 4656 8880 4810 8880 4811 8881 4658 8881 4810 8881 4660 8882 4658 8882 4811 8882 4812 8883 4660 8883 4811 8883 4663 8884 4660 8884 4812 8884 4666 8885 4663 8885 4812 8885 4670 8886 4668 8886 4813 8886 4672 8887 4670 8887 4813 8887 4814 8888 4672 8888 4813 8888 4675 8889 4672 8889 4814 8889 4815 8890 4682 8890 4679 8890 4684 8891 4682 8891 4815 8891 4684 8892 4815 8892 4816 8892 4687 8893 4684 8893 4816 8893 4817 8894 4689 8894 4687 8894 4691 8895 4689 8895 4817 8895 4818 8896 4691 8896 4817 8896 4693 8897 4691 8897 4818 8897 4819 8898 4696 8898 4693 8898 4697 8899 4696 8899 4819 8899 4698 8900 4697 8900 4819 8900 4699 8901 4698 8901 4820 8901 4700 8902 4699 8902 4820 8902 4821 8903 4700 8903 4820 8903 4118 8904 4700 8904 4821 8904 4822 8905 4118 8905 4821 8905 4116 8906 4118 8906 4822 8906 4113 8907 4116 8907 4822 8907 4108 8908 4110 8908 4113 8908 4824 8909 4702 8909 4701 8909 4825 8910 4702 8910 4824 8910 4825 8911 4140 8911 4702 8911 4825 8912 4141 8912 4140 8912 4823 8913 4141 8913 4825 8913 4823 8914 4703 8914 4141 8914 4826 8915 4703 8915 4823 8915 4123 8916 4146 8916 4826 8916 4826 8917 4146 8917 4703 8917 4124 8918 4146 8918 4123 8918 4124 8919 4148 8919 4146 8919 4126 8920 4148 8920 4124 8920 4126 8921 4150 8921 4148 8921 4126 8922 4152 8922 4150 8922 4128 8923 4152 8923 4126 8923 4130 8924 4152 8924 4128 8924 4130 8925 4155 8925 4152 8925 4131 8926 4155 8926 4130 8926 4131 8927 4704 8927 4155 8927 4133 8928 4704 8928 4131 8928 4134 8929 4704 8929 4133 8929 4134 8930 4705 8930 4704 8930 4136 8931 4705 8931 4134 8931 4136 8932 4706 8932 4705 8932 4137 8933 4706 8933 4136 8933 4137 8934 4707 8934 4706 8934 4139 8935 4707 8935 4137 8935 4139 8936 4165 8936 4707 8936 4139 8937 4708 8937 4165 8937 4142 8938 4708 8938 4139 8938 4144 8939 4708 8939 4142 8939 4144 8940 4169 8940 4708 8940 4145 8941 4169 8941 4144 8941 4145 8942 4709 8942 4169 8942 4147 8943 4709 8943 4145 8943 4149 8944 4709 8944 4147 8944 4149 8945 4174 8945 4709 8945 4151 8946 4174 8946 4149 8946 4151 8947 4177 8947 4174 8947 4153 8948 4177 8948 4151 8948 4154 8949 4177 8949 4153 8949 4154 8950 4179 8950 4177 8950 4154 8951 4710 8951 4179 8951 4157 8952 4710 8952 4154 8952 4157 8953 4184 8953 4710 8953 4158 8954 4184 8954 4157 8954 4158 8955 4711 8955 4184 8955 4160 8956 4711 8956 4158 8956 4161 8957 4711 8957 4160 8957 4163 8958 4711 8958 4161 8958 4163 8959 4188 8959 4711 8959 4163 8960 4190 8960 4188 8960 4167 8961 4190 8961 4163 8961 4167 8962 4712 8962 4190 8962 4168 8963 4712 8963 4167 8963 4170 8964 4712 8964 4168 8964 4170 8965 4713 8965 4712 8965 4171 8966 4713 8966 4170 8966 4173 8967 4713 8967 4171 8967 4173 8968 4714 8968 4713 8968 4175 8969 4714 8969 4173 8969 4175 8970 4199 8970 4714 8970 4176 8971 4199 8971 4175 8971 4176 8972 4202 8972 4199 8972 4178 8973 4202 8973 4176 8973 4178 8974 4203 8974 4202 8974 4180 8975 4203 8975 4178 8975 4180 8976 4715 8976 4203 8976 4181 8977 4715 8977 4180 8977 4183 8978 4715 8978 4181 8978 4183 8979 4716 8979 4715 8979 4185 8980 4716 8980 4183 8980 4185 8981 4210 8981 4716 8981 4187 8982 4210 8982 4185 8982 4187 8983 4212 8983 4210 8983 4189 8984 4212 8984 4187 8984 4189 8985 4717 8985 4212 8985 4191 8986 4717 8986 4189 8986 4193 8987 4717 8987 4191 8987 4193 8988 4718 8988 4717 8988 4195 8989 4718 8989 4193 8989 4195 8990 4220 8990 4718 8990 4196 8991 4220 8991 4195 8991 4196 8992 4222 8992 4220 8992 4196 8993 4224 8993 4222 8993 4198 8994 4224 8994 4196 8994 4200 8995 4224 8995 4198 8995 4200 8996 4226 8996 4224 8996 4201 8997 4226 8997 4200 8997 4201 8998 4228 8998 4226 8998 4204 8999 4228 8999 4201 8999 4204 9000 4719 9000 4228 9000 4206 9001 4719 9001 4204 9001 4206 9002 4720 9002 4719 9002 4207 9003 4720 9003 4206 9003 4207 9004 4234 9004 4720 9004 4209 9005 4234 9005 4207 9005 4209 9006 4721 9006 4234 9006 4211 9007 4721 9007 4209 9007 4211 9008 4239 9008 4721 9008 4213 9009 4239 9009 4211 9009 4214 9010 4239 9010 4213 9010 4214 9011 4241 9011 4239 9011 4216 9012 4241 9012 4214 9012 4216 9013 4722 9013 4241 9013 4218 9014 4722 9014 4216 9014 4219 9015 4722 9015 4218 9015 4219 9016 4723 9016 4722 9016 4221 9017 4723 9017 4219 9017 4221 9018 4250 9018 4723 9018 4223 9019 4250 9019 4221 9019 4223 9020 4724 9020 4250 9020 4225 9021 4724 9021 4223 9021 4227 9022 4724 9022 4225 9022 4227 9023 4725 9023 4724 9023 4229 9024 4725 9024 4227 9024 4229 9025 4726 9025 4725 9025 4827 9026 4726 9026 4229 9026 4231 9027 4726 9027 4827 9027 4231 9028 4257 9028 4726 9028 4233 9029 4257 9029 4231 9029 4233 9030 4260 9030 4257 9030 4235 9031 4260 9031 4233 9031 4235 9032 4262 9032 4260 9032 4236 9033 4262 9033 4235 9033 4238 9034 4262 9034 4236 9034 4238 9035 4265 9035 4262 9035 4240 9036 4265 9036 4238 9036 4240 9037 4267 9037 4265 9037 4240 9038 4268 9038 4267 9038 4242 9039 4268 9039 4240 9039 4244 9040 4727 9040 4242 9040 4242 9041 4727 9041 4268 9041 4246 9042 4727 9042 4244 9042 4246 9043 4728 9043 4727 9043 4248 9044 4728 9044 4246 9044 4248 9045 4273 9045 4728 9045 4249 9046 4273 9046 4248 9046 4249 9047 4275 9047 4273 9047 4252 9048 4275 9048 4249 9048 4252 9049 4278 9049 4275 9049 4253 9050 4278 9050 4252 9050 4253 9051 4279 9051 4278 9051 4254 9052 4279 9052 4253 9052 4254 9053 4729 9053 4279 9053 4256 9054 4729 9054 4254 9054 4258 9055 4729 9055 4256 9055 4258 9056 4284 9056 4729 9056 4259 9057 4284 9057 4258 9057 4259 9058 4730 9058 4284 9058 4261 9059 4730 9059 4259 9059 4263 9060 4730 9060 4261 9060 4263 9061 4731 9061 4730 9061 4264 9062 4731 9062 4263 9062 4264 9063 4290 9063 4731 9063 4266 9064 4290 9064 4264 9064 4266 9065 4294 9065 4290 9065 4269 9066 4294 9066 4266 9066 4269 9067 4296 9067 4294 9067 4271 9068 4296 9068 4269 9068 4272 9069 4296 9069 4271 9069 4272 9070 4298 9070 4296 9070 4272 9071 4732 9071 4298 9071 4274 9072 4732 9072 4272 9072 4274 9073 4733 9073 4732 9073 4276 9074 4733 9074 4274 9074 4276 9075 4302 9075 4733 9075 4277 9076 4302 9076 4276 9076 4277 9077 4734 9077 4302 9077 4280 9078 4734 9078 4277 9078 4281 9079 4734 9079 4280 9079 4281 9080 4307 9080 4734 9080 4283 9081 4307 9081 4281 9081 4283 9082 4309 9082 4307 9082 4285 9083 4309 9083 4283 9083 4285 9084 4735 9084 4309 9084 4285 9085 4736 9085 4735 9085 4287 9086 4736 9086 4285 9086 4289 9087 4736 9087 4287 9087 4289 9088 4315 9088 4736 9088 4291 9089 4315 9089 4289 9089 4291 9090 4317 9090 4315 9090 4293 9091 4317 9091 4291 9091 4293 9092 4319 9092 4317 9092 4295 9093 4319 9093 4293 9093 4295 9094 4737 9094 4319 9094 4297 9095 4737 9095 4295 9095 4297 9096 4738 9096 4737 9096 4299 9097 4738 9097 4297 9097 4299 9098 4324 9098 4738 9098 4301 9099 4324 9099 4299 9099 4301 9100 4739 9100 4324 9100 4303 9101 4739 9101 4301 9101 4304 9102 4739 9102 4303 9102 4304 9103 4329 9103 4739 9103 4304 9104 4331 9104 4329 9104 4306 9105 4331 9105 4304 9105 4306 9106 4333 9106 4331 9106 4308 9107 4333 9107 4306 9107 4308 9108 4740 9108 4333 9108 4310 9109 4740 9109 4308 9109 4310 9110 4741 9110 4740 9110 4312 9111 4741 9111 4310 9111 4314 9112 4741 9112 4312 9112 4314 9113 4340 9113 4741 9113 4316 9114 4340 9114 4314 9114 4316 9115 4343 9115 4340 9115 4318 9116 4343 9116 4316 9116 4318 9117 4346 9117 4343 9117 4320 9118 4346 9118 4318 9118 4320 9119 4348 9119 4346 9119 4322 9120 4348 9120 4320 9120 4322 9121 4350 9121 4348 9121 4323 9122 4350 9122 4322 9122 4323 9123 4351 9123 4350 9123 4325 9124 4351 9124 4323 9124 4327 9125 4351 9125 4325 9125 4327 9126 4742 9126 4351 9126 4328 9127 4742 9127 4327 9127 4330 9128 4742 9128 4328 9128 4330 9129 4357 9129 4742 9129 4332 9130 4357 9130 4330 9130 4332 9131 4743 9131 4357 9131 4334 9132 4743 9132 4332 9132 4335 9133 4743 9133 4334 9133 4335 9134 4744 9134 4743 9134 4337 9135 4744 9135 4335 9135 4339 9136 4744 9136 4337 9136 4339 9137 4365 9137 4744 9137 4341 9138 4365 9138 4339 9138 4342 9139 4745 9139 4341 9139 4341 9140 4745 9140 4365 9140 4344 9141 4745 9141 4342 9141 4344 9142 4370 9142 4745 9142 4345 9143 4370 9143 4344 9143 4345 9144 4746 9144 4370 9144 4347 9145 4746 9145 4345 9145 4347 9146 4747 9146 4746 9146 4349 9147 4747 9147 4347 9147 4352 9148 4747 9148 4349 9148 4352 9149 4748 9149 4747 9149 4353 9150 4748 9150 4352 9150 4355 9151 4748 9151 4353 9151 4355 9152 4377 9152 4748 9152 4355 9153 4749 9153 4377 9153 4356 9154 4749 9154 4355 9154 4358 9155 4749 9155 4356 9155 4358 9156 4382 9156 4749 9156 4359 9157 4382 9157 4358 9157 4359 9158 4750 9158 4382 9158 4361 9159 4750 9159 4359 9159 4362 9160 4750 9160 4361 9160 4362 9161 4751 9161 4750 9161 4366 9162 4751 9162 4362 9162 4366 9163 4752 9163 4751 9163 4367 9164 4752 9164 4366 9164 4367 9165 4753 9165 4752 9165 4369 9166 4753 9166 4367 9166 4369 9167 4395 9167 4753 9167 4371 9168 4395 9168 4369 9168 4373 9169 4395 9169 4371 9169 4373 9170 4754 9170 4395 9170 4374 9171 4754 9171 4373 9171 4376 9172 4755 9172 4374 9172 4374 9173 4755 9173 4754 9173 4378 9174 4755 9174 4376 9174 4378 9175 4402 9175 4755 9175 4379 9176 4402 9176 4378 9176 4379 9177 4404 9177 4402 9177 4381 9178 4404 9178 4379 9178 4381 9179 4406 9179 4404 9179 4383 9180 4406 9180 4381 9180 4383 9181 4408 9181 4406 9181 4383 9182 4410 9182 4408 9182 4385 9183 4410 9183 4383 9183 4386 9184 4410 9184 4385 9184 4386 9185 4412 9185 4410 9185 4389 9186 4412 9186 4386 9186 4389 9187 4415 9187 4412 9187 4390 9188 4415 9188 4389 9188 4390 9189 4756 9189 4415 9189 4392 9190 4756 9190 4390 9190 4394 9191 4756 9191 4392 9191 4394 9192 4757 9192 4756 9192 4396 9193 4757 9193 4394 9193 4396 9194 4421 9194 4757 9194 4397 9195 4421 9195 4396 9195 4397 9196 4423 9196 4421 9196 4399 9197 4423 9197 4397 9197 4399 9198 4427 9198 4423 9198 4401 9199 4427 9199 4399 9199 4401 9200 4758 9200 4427 9200 4403 9201 4758 9201 4401 9201 4403 9202 4759 9202 4758 9202 4405 9203 4759 9203 4403 9203 4407 9204 4433 9204 4405 9204 4405 9205 4433 9205 4759 9205 4409 9206 4760 9206 4407 9206 4407 9207 4760 9207 4433 9207 4411 9208 4760 9208 4409 9208 4411 9209 4438 9209 4760 9209 4413 9210 4438 9210 4411 9210 4414 9211 4438 9211 4413 9211 4414 9212 4761 9212 4438 9212 4417 9213 4761 9213 4414 9213 4828 9214 4761 9214 4417 9214 4828 9215 4762 9215 4761 9215 4418 9216 4762 9216 4828 9216 4418 9217 4763 9217 4762 9217 4420 9218 4763 9218 4418 9218 4420 9219 4764 9219 4763 9219 4422 9220 4764 9220 4420 9220 4424 9221 4764 9221 4422 9221 4424 9222 4765 9222 4764 9222 4426 9223 4765 9223 4424 9223 4426 9224 4766 9224 4765 9224 4428 9225 4766 9225 4426 9225 4428 9226 4455 9226 4766 9226 4430 9227 4455 9227 4428 9227 4430 9228 4456 9228 4455 9228 4432 9229 4456 9229 4430 9229 4434 9230 4456 9230 4432 9230 4434 9231 4459 9231 4456 9231 4436 9232 4459 9232 4434 9232 4436 9233 4767 9233 4459 9233 4437 9234 4767 9234 4436 9234 4439 9235 4768 9235 4437 9235 4437 9236 4768 9236 4767 9236 4441 9237 4768 9237 4439 9237 4441 9238 4466 9238 4768 9238 4443 9239 4466 9239 4441 9239 4443 9240 4468 9240 4466 9240 4443 9241 4469 9241 4468 9241 4445 9242 4469 9242 4443 9242 4445 9243 4471 9243 4469 9243 4447 9244 4471 9244 4445 9244 4447 9245 4769 9245 4471 9245 4449 9246 4769 9246 4447 9246 4450 9247 4769 9247 4449 9247 4450 9248 4475 9248 4769 9248 4451 9249 4475 9249 4450 9249 4451 9250 4477 9250 4475 9250 4453 9251 4477 9251 4451 9251 4453 9252 4479 9252 4477 9252 4454 9253 4479 9253 4453 9253 4454 9254 4481 9254 4479 9254 4457 9255 4481 9255 4454 9255 4457 9256 4483 9256 4481 9256 4458 9257 4483 9257 4457 9257 4460 9258 4485 9258 4458 9258 4458 9259 4485 9259 4483 9259 4463 9260 4485 9260 4460 9260 4463 9261 4487 9261 4485 9261 4464 9262 4487 9262 4463 9262 4464 9263 4770 9263 4487 9263 4465 9264 4770 9264 4464 9264 4465 9265 4771 9265 4770 9265 4467 9266 4771 9266 4465 9266 4470 9267 4771 9267 4467 9267 4470 9268 4772 9268 4771 9268 4472 9269 4772 9269 4470 9269 4472 9270 4496 9270 4772 9270 4474 9271 4496 9271 4472 9271 4474 9272 4498 9272 4496 9272 4476 9273 4498 9273 4474 9273 4476 9274 4773 9274 4498 9274 4478 9275 4773 9275 4476 9275 4478 9276 4503 9276 4773 9276 4480 9277 4503 9277 4478 9277 4480 9278 4505 9278 4503 9278 4482 9279 4505 9279 4480 9279 4482 9280 4774 9280 4505 9280 4484 9281 4774 9281 4482 9281 4484 9282 4509 9282 4774 9282 4486 9283 4509 9283 4484 9283 4486 9284 4775 9284 4509 9284 4488 9285 4775 9285 4486 9285 4488 9286 4517 9286 4775 9286 4490 9287 4517 9287 4488 9287 4492 9288 4517 9288 4490 9288 4492 9289 4519 9289 4517 9289 4492 9290 4776 9290 4519 9290 4494 9291 4776 9291 4492 9291 4495 9292 4776 9292 4494 9292 4495 9293 4777 9293 4776 9293 4497 9294 4777 9294 4495 9294 4499 9295 4778 9295 4497 9295 4497 9296 4778 9296 4777 9296 4501 9297 4778 9297 4499 9297 4501 9298 4528 9298 4778 9298 4502 9299 4528 9299 4501 9299 4502 9300 4531 9300 4528 9300 4504 9301 4531 9301 4502 9301 4504 9302 4532 9302 4531 9302 4506 9303 4532 9303 4504 9303 4506 9304 4535 9304 4532 9304 4508 9305 4535 9305 4506 9305 4510 9306 4535 9306 4508 9306 4510 9307 4536 9307 4535 9307 4512 9308 4536 9308 4510 9308 4512 9309 4779 9309 4536 9309 4513 9310 4779 9310 4512 9310 4515 9311 4779 9311 4513 9311 4515 9312 4780 9312 4779 9312 4516 9313 4780 9313 4515 9313 4516 9314 4781 9314 4780 9314 4518 9315 4781 9315 4516 9315 4521 9316 4781 9316 4518 9316 4521 9317 4547 9317 4781 9317 4522 9318 4547 9318 4521 9318 4522 9319 4782 9319 4547 9319 4524 9320 4782 9320 4522 9320 4525 9321 4782 9321 4524 9321 4525 9322 4783 9322 4782 9322 4527 9323 4783 9323 4525 9323 4527 9324 4784 9324 4783 9324 4529 9325 4784 9325 4527 9325 4530 9326 4784 9326 4529 9326 4530 9327 4785 9327 4784 9327 4533 9328 4785 9328 4530 9328 4533 9329 4786 9329 4785 9329 4534 9330 4786 9330 4533 9330 4537 9331 4786 9331 4534 9331 4537 9332 4561 9332 4786 9332 4538 9333 4561 9333 4537 9333 4538 9334 4787 9334 4561 9334 4540 9335 4787 9335 4538 9335 4542 9336 4787 9336 4540 9336 4542 9337 4788 9337 4787 9337 4543 9338 4788 9338 4542 9338 4543 9339 4566 9339 4788 9339 4545 9340 4566 9340 4543 9340 4545 9341 4789 9341 4566 9341 4546 9342 4789 9342 4545 9342 4546 9343 4790 9343 4789 9343 4548 9344 4790 9344 4546 9344 4550 9345 4790 9345 4548 9345 4550 9346 4791 9346 4790 9346 4551 9347 4791 9347 4550 9347 4553 9348 4791 9348 4551 9348 4553 9349 4792 9349 4791 9349 4555 9350 4792 9350 4553 9350 4555 9351 4793 9351 4792 9351 4556 9352 4793 9352 4555 9352 4556 9353 4581 9353 4793 9353 4558 9354 4581 9354 4556 9354 4558 9355 4794 9355 4581 9355 4560 9356 4794 9356 4558 9356 4560 9357 4795 9357 4794 9357 4562 9358 4795 9358 4560 9358 4563 9359 4795 9359 4562 9359 4563 9360 4796 9360 4795 9360 4565 9361 4796 9361 4563 9361 4567 9362 4796 9362 4565 9362 4567 9363 4591 9363 4796 9363 4569 9364 4591 9364 4567 9364 4569 9365 4593 9365 4591 9365 4570 9366 4593 9366 4569 9366 4570 9367 4797 9367 4593 9367 4572 9368 4797 9368 4570 9368 4572 9369 4598 9369 4797 9369 4573 9370 4598 9370 4572 9370 4573 9371 4599 9371 4598 9371 4575 9372 4599 9372 4573 9372 4576 9373 4599 9373 4575 9373 4576 9374 4601 9374 4599 9374 4576 9375 4603 9375 4601 9375 4578 9376 4603 9376 4576 9376 4578 9377 4606 9377 4603 9377 4580 9378 4606 9378 4578 9378 4580 9379 4798 9379 4606 9379 4582 9380 4798 9380 4580 9380 4583 9381 4798 9381 4582 9381 4583 9382 4607 9382 4798 9382 4585 9383 4607 9383 4583 9383 4585 9384 4610 9384 4607 9384 4587 9385 4610 9385 4585 9385 4587 9386 4799 9386 4610 9386 4588 9387 4799 9387 4587 9387 4588 9388 4615 9388 4799 9388 4588 9389 4800 9389 4615 9389 4590 9390 4800 9390 4588 9390 4592 9391 4800 9391 4590 9391 4592 9392 4619 9392 4800 9392 4594 9393 4619 9393 4592 9393 4594 9394 4621 9394 4619 9394 4596 9395 4621 9395 4594 9395 4596 9396 4801 9396 4621 9396 4597 9397 4801 9397 4596 9397 4600 9398 4801 9398 4597 9398 4600 9399 4802 9399 4801 9399 4602 9400 4802 9400 4600 9400 4602 9401 4627 9401 4802 9401 4604 9402 4627 9402 4602 9402 4604 9403 4629 9403 4627 9403 4605 9404 4629 9404 4604 9404 4829 9405 4803 9405 4605 9405 4605 9406 4803 9406 4629 9406 4608 9407 4803 9407 4829 9407 4608 9408 4804 9408 4803 9408 4609 9409 4804 9409 4608 9409 4612 9410 4804 9410 4609 9410 4612 9411 4636 9411 4804 9411 4613 9412 4636 9412 4612 9412 4613 9413 4805 9413 4636 9413 4614 9414 4805 9414 4613 9414 4614 9415 4806 9415 4805 9415 4617 9416 4806 9416 4614 9416 4618 9417 4806 9417 4617 9417 4618 9418 4807 9418 4806 9418 4620 9419 4807 9419 4618 9419 4622 9420 4807 9420 4620 9420 4622 9421 4808 9421 4807 9421 4624 9422 4808 9422 4622 9422 4624 9423 4650 9423 4808 9423 4626 9424 4650 9424 4624 9424 4626 9425 4651 9425 4650 9425 4628 9426 4651 9426 4626 9426 4628 9427 4809 9427 4651 9427 4630 9428 4809 9428 4628 9428 4632 9429 4809 9429 4630 9429 4632 9430 4810 9430 4809 9430 4633 9431 4810 9431 4632 9431 4633 9432 4811 9432 4810 9432 4635 9433 4811 9433 4633 9433 4635 9434 4812 9434 4811 9434 4637 9435 4812 9435 4635 9435 4639 9436 4812 9436 4637 9436 4639 9437 4666 9437 4812 9437 4641 9438 4666 9438 4639 9438 4642 9439 4666 9439 4641 9439 4642 9440 4668 9440 4666 9440 4644 9441 4668 9441 4642 9441 4644 9442 4813 9442 4668 9442 4645 9443 4813 9443 4644 9443 4645 9444 4814 9444 4813 9444 4648 9445 4814 9445 4645 9445 4648 9446 4675 9446 4814 9446 4649 9447 4675 9447 4648 9447 4649 9448 4677 9448 4675 9448 4652 9449 4677 9449 4649 9449 4652 9450 4679 9450 4677 9450 4653 9451 4679 9451 4652 9451 4653 9452 4815 9452 4679 9452 4655 9453 4815 9453 4653 9453 4657 9454 4815 9454 4655 9454 4657 9455 4816 9455 4815 9455 4659 9456 4816 9456 4657 9456 4659 9457 4687 9457 4816 9457 4661 9458 4687 9458 4659 9458 4661 9459 4817 9459 4687 9459 4664 9460 4817 9460 4661 9460 4665 9461 4817 9461 4664 9461 4665 9462 4818 9462 4817 9462 4667 9463 4818 9463 4665 9463 4667 9464 4693 9464 4818 9464 4669 9465 4693 9465 4667 9465 4669 9466 4819 9466 4693 9466 4671 9467 4819 9467 4669 9467 4673 9468 4819 9468 4671 9468 4673 9469 4698 9469 4819 9469 4674 9470 4698 9470 4673 9470 4676 9471 4698 9471 4674 9471 4676 9472 4820 9472 4698 9472 4678 9473 4820 9473 4676 9473 4678 9474 4821 9474 4820 9474 4680 9475 4821 9475 4678 9475 4681 9476 4821 9476 4680 9476 4681 9477 4822 9477 4821 9477 4683 9478 4822 9478 4681 9478 4685 9479 4822 9479 4683 9479 4685 9480 4113 9480 4822 9480 4686 9481 4113 9481 4685 9481 4688 9482 4113 9482 4686 9482 4688 9483 4108 9483 4113 9483 4830 9484 4108 9484 4688 9484 4830 9485 4112 9485 4108 9485 4690 9486 4112 9486 4830 9486 4692 9487 4112 9487 4690 9487 4694 9488 4112 9488 4692 9488 4694 9489 4117 9489 4112 9489 4695 9490 4117 9490 4694 9490 4695 9491 4119 9491 4117 9491 4167 9492 4163 9492 4164 9492 4231 9493 4827 9493 4229 9493 4366 9494 4362 9494 4364 9494 4418 9495 4828 9495 4417 9495 4608 9496 4829 9496 4605 9496 4664 9497 4661 9497 4662 9497 4690 9498 4830 9498 4688 9498 4851 9499 4854 9499 4119 9499 4831 9500 4832 9500 4869 9500 4833 9501 4872 9501 4832 9501 4115 9502 4873 9502 4833 9502 4834 9503 4833 9503 4832 9503 4834 9504 4115 9504 4833 9504 4834 9505 4832 9505 4835 9505 4835 9506 4832 9506 4831 9506 4836 9507 4835 9507 4831 9507 4837 9508 4115 9508 4834 9508 4835 9509 4837 9509 4834 9509 4836 9510 4838 9510 4835 9510 4840 9511 4837 9511 4835 9511 4840 9512 4835 9512 4838 9512 4838 9513 4836 9513 4841 9513 4839 9514 4841 9514 4836 9514 4842 9515 4840 9515 4838 9515 4842 9516 4838 9516 4841 9516 4120 9517 4840 9517 4842 9517 4844 9518 4841 9518 4839 9518 4845 9519 4842 9519 4841 9519 4845 9520 4120 9520 4842 9520 4844 9521 4839 9521 4843 9521 4844 9522 4845 9522 4841 9522 4845 9523 4844 9523 4847 9523 4846 9524 4844 9524 4843 9524 4846 9525 4847 9525 4844 9525 4847 9526 4120 9526 4845 9526 4847 9527 4121 9527 4120 9527 4848 9528 4847 9528 4846 9528 4846 9529 4843 9529 4849 9529 4848 9530 4121 9530 4847 9530 4848 9531 4122 9531 4121 9531 4850 9532 4846 9532 4849 9532 4850 9533 4848 9533 4846 9533 4850 9534 4122 9534 4848 9534 4853 9535 4850 9535 4849 9535 4851 9536 4122 9536 4850 9536 4853 9537 4849 9537 4852 9537 4851 9538 4850 9538 4853 9538 4854 9539 4851 9539 4853 9539 4855 9540 4853 9540 4852 9540 4854 9541 4853 9541 4855 9541 4856 9542 4854 9542 4855 9542 4856 9543 4855 9543 4852 9543 4856 9544 4119 9544 4854 9544 4857 9545 4856 9545 4852 9545 4857 9546 4852 9546 4858 9546 4856 9547 4117 9547 4119 9547 4117 9548 4856 9548 4857 9548 4859 9549 4117 9549 4857 9549 4860 9550 4857 9550 4858 9550 4860 9551 4859 9551 4857 9551 4862 9552 4859 9552 4860 9552 4117 9553 4859 9553 4862 9553 4863 9554 4860 9554 4858 9554 4863 9555 4858 9555 4861 9555 4864 9556 4862 9556 4860 9556 4864 9557 4860 9557 4863 9557 4864 9558 4114 9558 4862 9558 4865 9559 4864 9559 4863 9559 4114 9560 4864 9560 4865 9560 4863 9561 4861 9561 4867 9561 4866 9562 4863 9562 4867 9562 4865 9563 4863 9563 4866 9563 4865 9564 4111 9564 4114 9564 4109 9565 4865 9565 4866 9565 4111 9566 4865 9566 4109 9566 4870 9567 4866 9567 4867 9567 4868 9568 4866 9568 4870 9568 4868 9569 4109 9569 4866 9569 4870 9570 4867 9570 4869 9570 4868 9571 4107 9571 4109 9571 4871 9572 4868 9572 4870 9572 4107 9573 4868 9573 4871 9573 4872 9574 4870 9574 4869 9574 4872 9575 4871 9575 4870 9575 4872 9576 4869 9576 4832 9576 4833 9577 4871 9577 4872 9577 4107 9578 4871 9578 4873 9578 4833 9579 4873 9579 4871 9579 4843 9580 4858 9580 4852 9580 4843 9581 4867 9581 4861 9581 4843 9582 4869 9582 4867 9582 4843 9583 4831 9583 4869 9583 4843 9584 4852 9584 4849 9584 4843 9585 4861 9585 4858 9585 4843 9586 4836 9586 4831 9586 4843 9587 4839 9587 4836 9587 4875 9588 4880 9588 4883 9588 4875 9589 4874 9589 4880 9589 4874 6339 4876 6339 4880 6339 4880 9590 4876 9590 4881 9590 4876 9591 4877 9591 4881 9591 4881 9592 4877 9592 4885 9592 4877 9593 4878 9593 4885 9593 4885 9594 4878 9594 4884 9594 4878 9595 4879 9595 4884 9595 4884 9596 4879 9596 4882 9596 4882 9597 4875 9597 4883 9597 4879 9598 4875 9598 4882 9598 4881 9599 4886 9599 4887 9599 4881 9600 4887 9600 4888 9600 4885 9601 4889 9601 4886 9601 4885 9602 4892 9602 4889 9602 4885 9603 4886 9603 4881 9603 4880 9604 4888 9604 4890 9604 4880 9605 4881 9605 4888 9605 4891 9606 4880 9606 4890 9606 4884 9607 4892 9607 4885 9607 4893 9608 4892 9608 4884 9608 4883 9609 4880 9609 4891 9609 4894 9610 4883 9610 4891 9610 4895 9611 4893 9611 4884 9611 4895 9612 4884 9612 4882 9612 4896 9613 4883 9613 4894 9613 4897 9614 4895 9614 4882 9614 4898 9615 4882 9615 4883 9615 4898 9616 4883 9616 4896 9616 4898 9617 4897 9617 4882 9617 4874 9618 4877 9618 4876 9618 4879 9619 4878 9619 4875 9619 4875 9620 4878 9620 4874 9620 4874 9621 4878 9621 4877 9621 4899 9622 4911 9622 4889 9622 4899 9623 4889 9623 4892 9623 4900 9624 4899 9624 4892 9624 4900 9625 4892 9625 4893 9625 4901 9626 4900 9626 4893 9626 4901 9627 4893 9627 4895 9627 4902 9628 4901 9628 4895 9628 4902 9629 4895 9629 4897 9629 4903 9630 4902 9630 4897 9630 4903 9631 4897 9631 4898 9631 4904 9632 4903 9632 4898 9632 4904 9633 4898 9633 4896 9633 4905 9634 4904 9634 4896 9634 4905 9635 4896 9635 4894 9635 4906 9636 4905 9636 4894 9636 4906 9637 4894 9637 4891 9637 4907 9638 4906 9638 4891 9638 4907 9639 4891 9639 4890 9639 4908 9640 4907 9640 4890 9640 4908 9641 4890 9641 4888 9641 4909 9642 4908 9642 4888 9642 4909 9643 4888 9643 4887 9643 4909 9644 4887 9644 4886 9644 4910 9645 4909 9645 4886 9645 4911 9646 4910 9646 4886 9646 4911 9647 4886 9647 4889 9647 4701 9648 4132 9648 4907 9648 4132 9649 4906 9649 4907 9649 4125 9650 4906 9650 4132 9650 4701 9651 4907 9651 4908 9651 4824 9652 4701 9652 4908 9652 4125 9653 4905 9653 4906 9653 4824 9654 4908 9654 4909 9654 4125 9655 4904 9655 4905 9655 4129 9656 4904 9656 4125 9656 4825 9657 4824 9657 4909 9657 4129 9658 4903 9658 4904 9658 4825 9659 4909 9659 4910 9659 4911 9660 4825 9660 4910 9660 4903 9661 4129 9661 4127 9661 4902 9662 4903 9662 4127 9662 4911 9663 4823 9663 4825 9663 4902 9664 4127 9664 4123 9664 4899 9665 4823 9665 4911 9665 4901 9666 4902 9666 4123 9666 4900 9667 4823 9667 4899 9667 4900 9668 4826 9668 4823 9668 4900 9669 4901 9669 4123 9669 4900 9670 4123 9670 4826 9670

+
+ + + +

4933 9671 4912 9671 4913 9671 4932 9672 4912 9672 4933 9672 4913 9673 4914 9673 4915 9673 4912 9674 4914 9674 4913 9674 4915 9675 4914 9675 4916 9675 4914 9676 4917 9676 4916 9676 4916 9677 4917 9677 4918 9677 4917 9678 4919 9678 4918 9678 4918 9679 4919 9679 4920 9679 4919 9680 4921 9680 4920 9680 4920 9681 4921 9681 4922 9681 4921 9682 4923 9682 4922 9682 4923 9683 4924 9683 4922 9683 4922 9684 4924 9684 4925 9684 4924 9685 4926 9685 4925 9685 4925 9686 4926 9686 4927 9686 4926 9687 4928 9687 4927 9687 4927 9688 4928 9688 4929 9688 4928 9689 4930 9689 4929 9689 4929 9690 4930 9690 4931 9690 4930 9691 4932 9691 4931 9691 4931 9692 4932 9692 4933 9692 4935 9693 4963 9693 4934 9693 4936 9694 4935 9694 4934 9694 4936 9695 4934 9695 4937 9695 4936 9696 4937 9696 4938 9696 4939 9697 4936 9697 4938 9697 4939 9698 4938 9698 4940 9698 4941 9699 4939 9699 4940 9699 4941 9700 4940 9700 4942 9700 4943 9701 4941 9701 4942 9701 4944 9702 4943 9702 4942 9702 4944 9703 4942 9703 4945 9703 4944 9704 4945 9704 4946 9704 4947 9705 4944 9705 4946 9705 4947 9706 4946 9706 4948 9706 4949 9707 4947 9707 4948 9707 4949 9708 4948 9708 4950 9708 4951 9709 4949 9709 4950 9709 4952 9710 4951 9710 4950 9710 4952 9711 4950 9711 4953 9711 4952 9712 4953 9712 4954 9712 4955 9713 4952 9713 4954 9713 4956 9714 4955 9714 4954 9714 4956 9715 4954 9715 4957 9715 4956 9716 4957 9716 4958 9716 4959 9717 4956 9717 4958 9717 4959 9718 4958 9718 4960 9718 4961 9719 4959 9719 4960 9719 4961 9720 4960 9720 4962 9720 4963 9721 4961 9721 4962 9721 4963 9722 4962 9722 4934 9722 4924 77 4960 77 4958 77 4926 77 4924 77 4958 77 4924 77 4962 77 4960 77 4923 9723 4962 9723 4924 9723 4926 77 4958 77 4957 77 4928 9724 4926 9724 4957 9724 4923 9725 4934 9725 4962 9725 4928 77 4957 77 4954 77 4921 77 4934 77 4923 77 4928 77 4954 77 4953 77 4921 9726 4937 9726 4934 9726 4930 77 4928 77 4953 77 4919 9727 4937 9727 4921 9727 4938 9728 4937 9728 4919 9728 4950 77 4930 77 4953 77 4950 9729 4932 9729 4930 9729 4938 77 4919 77 4917 77 4940 77 4938 77 4917 77 4948 77 4932 77 4950 77 4942 9730 4917 9730 4914 9730 4942 9731 4940 9731 4917 9731 4948 9732 4912 9732 4932 9732 4946 77 4912 77 4948 77 4945 77 4912 77 4946 77 4945 9733 4942 9733 4914 9733 4945 9734 4914 9734 4912 9734 4936 12 4918 12 4920 12 4929 9735 4931 9735 4952 9735 4931 12 4951 12 4952 12 4929 12 4952 12 4955 12 4931 9736 4949 9736 4951 9736 4933 12 4949 12 4931 12 4927 9737 4929 9737 4955 9737 4927 9738 4955 9738 4956 9738 4933 9739 4947 9739 4949 9739 4913 9740 4947 9740 4933 9740 4925 12 4956 12 4959 12 4925 9741 4927 9741 4956 9741 4913 9742 4944 9742 4947 9742 4961 9743 4925 9743 4959 9743 4944 9744 4913 9744 4915 9744 4963 12 4925 12 4961 12 4963 9745 4922 9745 4925 9745 4943 12 4944 12 4915 12 4941 9746 4915 9746 4916 9746 4941 12 4943 12 4915 12 4963 9747 4920 9747 4922 9747 4935 12 4920 12 4963 12 4941 12 4916 12 4918 12 4939 12 4941 12 4918 12 4936 12 4920 12 4935 12 4936 12 4939 12 4918 12

+
+ + + +

4985 9748 4964 9748 4965 9748 4984 9749 4964 9749 4985 9749 4965 9750 4966 9750 4967 9750 4964 9751 4966 9751 4965 9751 4966 9752 4968 9752 4967 9752 4967 9753 4968 9753 4969 9753 4968 9754 4970 9754 4969 9754 4969 9755 4970 9755 4971 9755 4970 9756 4972 9756 4971 9756 4971 9757 4972 9757 4973 9757 4973 9758 4972 9758 4974 9758 4972 9759 4975 9759 4974 9759 4975 9760 4976 9760 4974 9760 4974 9761 4976 9761 4977 9761 4976 9762 4978 9762 4977 9762 4977 9763 4978 9763 4979 9763 4978 9764 4980 9764 4979 9764 4979 9765 4980 9765 4981 9765 4980 9766 4982 9766 4981 9766 4981 9767 4982 9767 4983 9767 4982 9768 4984 9768 4983 9768 4983 9769 4984 9769 4985 9769 4988 9770 4986 9770 4987 9770 4988 9771 4987 9771 4989 9771 4990 9772 4988 9772 4989 9772 4990 9773 4989 9773 4991 9773 4992 9774 4990 9774 4991 9774 4992 9775 4991 9775 4993 9775 4994 9776 4992 9776 4993 9776 4994 9777 4993 9777 4995 9777 4996 9778 4994 9778 4995 9778 4996 9779 4995 9779 4997 9779 4996 9780 4997 9780 4998 9780 4999 9781 4996 9781 4998 9781 4999 9782 4998 9782 5000 9782 5001 9783 4999 9783 5000 9783 5001 9784 5000 9784 5002 9784 5003 9785 5001 9785 5002 9785 5004 9786 5003 9786 5002 9786 5004 9787 5002 9787 5005 9787 5004 9788 5005 9788 5006 9788 5007 9789 5004 9789 5006 9789 5008 9790 5007 9790 5006 9790 5008 9791 5006 9791 5009 9791 5008 9792 5009 9792 5010 9792 5011 9793 5008 9793 5010 9793 5011 9794 5010 9794 5012 9794 5013 9795 5011 9795 5012 9795 5013 9796 5012 9796 5014 9796 4986 9797 5013 9797 5014 9797 4986 9798 5014 9798 4987 9798 4976 77 5012 77 5010 77 4978 77 4976 77 5010 77 4976 77 5014 77 5012 77 4978 77 5010 77 5009 77 4975 9799 5014 9799 4976 9799 4980 9800 4978 9800 5009 9800 4975 9801 4987 9801 5014 9801 4980 77 5009 77 5006 77 4972 9802 4987 9802 4975 9802 4980 9803 5006 9803 5005 9803 4972 9804 4989 9804 4987 9804 4982 77 4980 77 5005 77 4970 9805 4989 9805 4972 9805 4991 77 4989 77 4970 77 5002 77 4982 77 5005 77 5002 9729 4984 9729 4982 9729 4991 77 4970 77 4968 77 4993 77 4991 77 4968 77 5000 77 4984 77 5002 77 4993 77 4968 77 4966 77 4998 77 4984 77 5000 77 4998 9806 4964 9806 4984 9806 4995 77 4993 77 4966 77 4997 77 4964 77 4998 77 4997 77 4995 77 4966 77 4997 9807 4966 9807 4964 9807 4983 9808 5004 9808 4981 9808 4983 12 5003 12 5004 12 4981 9809 5004 9809 5007 9809 4983 9810 5001 9810 5003 9810 4985 9811 5001 9811 4983 9811 4979 9812 4981 9812 5007 9812 4979 12 5007 12 5008 12 4985 9813 4999 9813 5001 9813 4965 12 4999 12 4985 12 4977 12 5008 12 5011 12 4977 12 4979 12 5008 12 4965 9814 4996 9814 4999 9814 5013 12 4977 12 5011 12 4996 12 4965 12 4967 12 4994 12 4996 12 4967 12 5013 9815 4974 9815 4977 9815 4986 9816 4974 9816 5013 9816 4986 12 4973 12 4974 12 4994 12 4967 12 4969 12 4992 9817 4994 9817 4969 9817 4988 9818 4973 9818 4986 9818 4990 12 4973 12 4988 12 4990 12 4971 12 4973 12 4990 12 4969 12 4971 12 4990 12 4992 12 4969 12

+
+ + + +

5805 9819 5016 9819 5015 9819 5805 9820 5017 9820 5016 9820 5015 9821 5016 9821 5799 9821 5016 9822 5018 9822 5799 9822 5019 9823 5017 9823 5805 9823 5799 9824 5018 9824 5020 9824 5019 9825 5021 9825 5017 9825 5022 9826 5021 9826 5019 9826 5022 9827 5023 9827 5021 9827 5020 9828 5018 9828 5792 9828 5024 9829 5023 9829 5022 9829 5018 9830 5025 9830 5792 9830 5024 9831 5026 9831 5023 9831 5024 9832 5027 9832 5026 9832 5026 9833 5027 9833 5028 9833 5034 9834 5031 9834 5030 9834 5034 9835 5033 9835 5031 9835 5036 9836 5033 9836 5034 9836 5036 9837 5035 9837 5033 9837 5036 9838 5037 9838 5035 9838 5032 9839 5037 9839 5036 9839 5032 9840 5038 9840 5037 9840 5039 9841 5038 9841 5032 9841 5039 9842 5040 9842 5038 9842 5041 9843 5040 9843 5039 9843 5041 9844 5042 9844 5040 9844 5043 9845 5042 9845 5041 9845 5043 9846 5044 9846 5042 9846 5043 9847 5045 9847 5044 9847 5046 9848 5045 9848 5043 9848 5046 9849 5047 9849 5045 9849 5046 9850 5048 9850 5047 9850 5049 9851 5048 9851 5046 9851 5049 9852 5050 9852 5048 9852 5051 9853 5050 9853 5049 9853 5051 9854 5052 9854 5050 9854 5051 9855 5053 9855 5052 9855 5054 9856 5053 9856 5051 9856 5054 9857 5055 9857 5053 9857 5056 9858 5055 9858 5054 9858 5056 9859 5057 9859 5055 9859 5056 9860 5058 9860 5057 9860 5059 9861 5058 9861 5056 9861 5059 9862 5060 9862 5058 9862 5061 9863 5060 9863 5059 9863 5061 9864 5062 9864 5060 9864 5063 9865 5062 9865 5061 9865 5063 9866 5064 9866 5062 9866 5065 9867 5064 9867 5063 9867 5065 9868 5066 9868 5064 9868 5065 9869 5067 9869 5066 9869 5068 9870 5067 9870 5065 9870 5069 9871 5067 9871 5068 9871 5069 9872 5070 9872 5067 9872 5069 9873 5071 9873 5070 9873 5072 9874 5071 9874 5069 9874 5072 9875 5073 9875 5071 9875 5074 9876 5073 9876 5072 9876 5074 9877 5075 9877 5073 9877 5074 9878 5076 9878 5075 9878 5077 9879 5076 9879 5074 9879 5077 9880 5078 9880 5076 9880 5079 9881 5078 9881 5077 9881 5079 9882 5080 9882 5078 9882 5081 9883 5080 9883 5079 9883 5081 9884 5082 9884 5080 9884 5081 9885 5083 9885 5082 9885 5084 9886 5083 9886 5081 9886 5084 9887 5085 9887 5083 9887 5084 9888 5086 9888 5085 9888 5087 9889 5086 9889 5084 9889 5087 9890 5088 9890 5086 9890 5089 9891 5088 9891 5087 9891 5089 9892 5090 9892 5088 9892 5089 9893 5091 9893 5090 9893 5092 9894 5091 9894 5089 9894 5092 9895 5093 9895 5091 9895 5094 9896 5093 9896 5092 9896 5094 9897 5095 9897 5093 9897 5096 9898 5095 9898 5094 9898 5096 9899 5097 9899 5095 9899 5098 9900 5097 9900 5096 9900 5098 9901 5099 9901 5097 9901 5098 9902 5100 9902 5099 9902 5101 9903 5100 9903 5098 9903 5101 9904 5102 9904 5100 9904 5101 9905 5103 9905 5102 9905 5104 9906 5103 9906 5101 9906 5104 9907 5105 9907 5103 9907 5106 9908 5105 9908 5104 9908 5106 9909 5107 9909 5105 9909 5108 9910 5107 9910 5106 9910 5108 9911 5109 9911 5107 9911 5108 9912 5110 9912 5109 9912 5111 9913 5110 9913 5108 9913 5112 9914 5110 9914 5111 9914 5112 9915 5113 9915 5110 9915 5112 9916 5114 9916 5113 9916 5115 9917 5114 9917 5112 9917 5115 9918 5116 9918 5114 9918 5117 9919 5118 9919 5115 9919 5115 9920 5118 9920 5116 9920 5117 9921 5119 9921 5118 9921 5120 9922 5119 9922 5117 9922 5120 9923 5121 9923 5119 9923 5122 9924 5121 9924 5120 9924 5122 9925 5123 9925 5121 9925 5124 9926 5123 9926 5122 9926 5124 9927 5125 9927 5123 9927 5126 9928 5125 9928 5124 9928 5126 9929 5127 9929 5125 9929 5128 9930 5127 9930 5126 9930 5128 9931 5129 9931 5127 9931 5130 9932 5129 9932 5128 9932 5130 9933 5131 9933 5129 9933 5130 9934 5132 9934 5131 9934 5133 9935 5132 9935 5130 9935 5133 9936 5134 9936 5132 9936 5133 9937 5135 9937 5134 9937 5136 9938 5135 9938 5133 9938 5136 9939 5137 9939 5135 9939 5138 9940 5137 9940 5136 9940 5138 9941 5139 9941 5137 9941 5138 9942 5140 9942 5139 9942 5141 9943 5140 9943 5138 9943 5141 9944 5142 9944 5140 9944 5143 9945 5142 9945 5141 9945 5143 9946 5144 9946 5142 9946 5145 9947 5144 9947 5143 9947 5145 9948 5146 9948 5144 9948 5147 9949 5146 9949 5145 9949 5147 9950 5148 9950 5146 9950 5149 9951 5148 9951 5147 9951 5149 9952 5150 9952 5148 9952 5149 9953 5151 9953 5150 9953 5152 9954 5151 9954 5149 9954 5152 9955 5153 9955 5151 9955 5154 9956 5153 9956 5152 9956 5154 9957 5155 9957 5153 9957 5156 9958 5155 9958 5154 9958 5156 9959 5157 9959 5155 9959 5158 9960 5157 9960 5156 9960 5158 9961 5159 9961 5157 9961 5160 9962 5159 9962 5158 9962 5160 9963 5161 9963 5159 9963 5162 9964 5161 9964 5160 9964 5162 9965 5163 9965 5161 9965 5164 9966 5163 9966 5162 9966 5165 9967 5163 9967 5164 9967 5165 9968 5166 9968 5163 9968 5167 9969 5166 9969 5165 9969 5167 9970 5168 9970 5166 9970 5169 9971 5168 9971 5167 9971 5169 9972 5170 9972 5168 9972 5171 9973 5170 9973 5169 9973 5171 9974 5172 9974 5170 9974 5171 9975 5173 9975 5172 9975 5174 9976 5173 9976 5171 9976 5174 9977 5175 9977 5173 9977 5176 9978 5175 9978 5174 9978 5176 9979 5177 9979 5175 9979 5178 9980 5177 9980 5176 9980 5178 9981 5179 9981 5177 9981 5178 9982 5180 9982 5179 9982 5181 9983 5180 9983 5178 9983 5181 9984 5182 9984 5180 9984 5181 9985 5183 9985 5182 9985 5184 9986 5183 9986 5181 9986 5184 9987 5185 9987 5183 9987 5186 9988 5185 9988 5184 9988 5186 9989 5187 9989 5185 9989 5186 9990 5188 9990 5187 9990 5189 9991 5188 9991 5186 9991 5189 9992 5190 9992 5188 9992 5191 9993 5190 9993 5189 9993 5191 9994 5192 9994 5190 9994 5193 9995 5192 9995 5191 9995 5193 9996 5194 9996 5192 9996 5193 9997 5195 9997 5194 9997 5196 9998 5195 9998 5193 9998 5196 9999 5197 9999 5195 9999 5198 10000 5197 10000 5196 10000 5198 10001 5199 10001 5197 10001 5200 10002 5199 10002 5198 10002 5200 10003 5201 10003 5199 10003 5202 10004 5201 10004 5200 10004 5202 10005 5203 10005 5201 10005 5204 10006 5203 10006 5202 10006 5204 10007 5205 10007 5203 10007 5206 10008 5207 10008 5204 10008 5204 10009 5207 10009 5205 10009 5208 10010 5207 10010 5206 10010 5208 10011 5209 10011 5207 10011 5208 10012 5210 10012 5209 10012 5211 10013 5210 10013 5208 10013 5211 10014 5212 10014 5210 10014 5211 10015 5213 10015 5212 10015 5214 10016 5213 10016 5211 10016 5214 10017 5215 10017 5213 10017 5214 10018 5216 10018 5215 10018 5217 10019 5216 10019 5214 10019 5217 10020 5218 10020 5216 10020 5217 10021 5219 10021 5218 10021 5220 10022 5219 10022 5217 10022 5220 10023 5221 10023 5219 10023 5222 10024 5221 10024 5220 10024 5222 10025 5223 10025 5221 10025 5224 10026 5223 10026 5222 10026 5224 10027 5225 10027 5223 10027 5226 10028 5225 10028 5224 10028 5226 10029 5227 10029 5225 10029 5226 10030 5228 10030 5227 10030 5229 10031 5228 10031 5226 10031 5229 10032 5230 10032 5228 10032 5231 10033 5230 10033 5229 10033 5231 10034 5232 10034 5230 10034 5233 10035 5232 10035 5231 10035 5233 10036 5234 10036 5232 10036 5235 10037 5234 10037 5233 10037 5235 10038 5236 10038 5234 10038 5237 10039 5236 10039 5235 10039 5237 10040 5238 10040 5236 10040 5237 10041 5239 10041 5238 10041 5240 10042 5239 10042 5237 10042 5240 10043 5241 10043 5239 10043 5242 10044 5241 10044 5240 10044 5242 10045 5243 10045 5241 10045 5242 10046 5244 10046 5243 10046 5245 10047 5244 10047 5242 10047 5245 10048 5246 10048 5244 10048 5247 10049 5246 10049 5245 10049 5247 10050 5248 10050 5246 10050 5247 10051 5249 10051 5248 10051 5250 10052 5249 10052 5247 10052 5250 10053 5251 10053 5249 10053 5252 10054 5251 10054 5250 10054 5252 10055 5253 10055 5251 10055 5254 10056 5255 10056 5252 10056 5252 10057 5255 10057 5253 10057 5256 10058 5255 10058 5254 10058 5256 10059 5257 10059 5255 10059 5258 10060 5257 10060 5256 10060 5258 10061 5259 10061 5257 10061 5258 10062 5260 10062 5259 10062 5261 10063 5260 10063 5258 10063 5261 10064 5262 10064 5260 10064 5261 10065 5263 10065 5262 10065 5264 10066 5263 10066 5261 10066 5265 10067 5263 10067 5264 10067 5265 10068 5266 10068 5263 10068 5265 10069 5267 10069 5266 10069 5268 10070 5267 10070 5265 10070 5268 10071 5269 10071 5267 10071 5270 10072 5269 10072 5268 10072 5270 10073 5271 10073 5269 10073 5272 10074 5271 10074 5270 10074 5272 10075 5273 10075 5271 10075 5274 10076 5273 10076 5272 10076 5274 10077 5275 10077 5273 10077 5274 10078 5276 10078 5275 10078 5277 10079 5276 10079 5274 10079 5277 10080 5278 10080 5276 10080 5279 10081 5278 10081 5277 10081 5280 10082 5281 10082 5279 10082 5279 10083 5281 10083 5278 10083 5280 10084 5282 10084 5281 10084 5283 10085 5282 10085 5280 10085 5283 10086 5284 10086 5282 10086 5285 10087 5284 10087 5283 10087 5285 10088 5286 10088 5284 10088 5285 10089 5287 10089 5286 10089 5288 10090 5287 10090 5285 10090 5288 10091 5289 10091 5287 10091 5290 10092 5289 10092 5288 10092 5290 10093 5291 10093 5289 10093 5292 10094 5291 10094 5290 10094 5292 10095 5293 10095 5291 10095 5292 10096 5294 10096 5293 10096 5295 10097 5294 10097 5292 10097 5295 10098 5296 10098 5294 10098 5297 10099 5296 10099 5295 10099 5297 10100 5298 10100 5296 10100 5299 10101 5298 10101 5297 10101 5299 10102 5300 10102 5298 10102 5299 10103 5301 10103 5300 10103 5302 10104 5301 10104 5299 10104 5302 10105 5303 10105 5301 10105 5302 10106 5304 10106 5303 10106 5305 10107 5304 10107 5302 10107 5305 10108 5306 10108 5304 10108 5305 10109 5307 10109 5306 10109 5308 10110 5307 10110 5305 10110 5308 10111 5309 10111 5307 10111 5310 10112 5309 10112 5308 10112 5310 10113 5311 10113 5309 10113 5310 10114 5312 10114 5311 10114 5313 10115 5312 10115 5310 10115 5313 10116 5314 10116 5312 10116 5315 10117 5314 10117 5313 10117 5315 10118 5316 10118 5314 10118 5317 10119 5316 10119 5315 10119 5317 10120 5318 10120 5316 10120 5317 10121 5319 10121 5318 10121 5320 10122 5319 10122 5317 10122 5321 10123 5319 10123 5320 10123 5321 10124 5322 10124 5319 10124 5323 10125 5322 10125 5321 10125 5323 10126 5324 10126 5322 10126 5325 10127 5324 10127 5323 10127 5325 10128 5326 10128 5324 10128 5327 10129 5326 10129 5325 10129 5327 10130 5328 10130 5326 10130 5327 10131 5329 10131 5328 10131 5330 10132 5329 10132 5327 10132 5330 10133 5331 10133 5329 10133 5332 10134 5331 10134 5330 10134 5332 10135 5333 10135 5331 10135 5334 10136 5333 10136 5332 10136 5334 10137 5335 10137 5333 10137 5334 10138 5336 10138 5335 10138 5337 10139 5336 10139 5334 10139 5337 10140 5338 10140 5336 10140 5339 10141 5338 10141 5337 10141 5339 10142 5340 10142 5338 10142 5341 10143 5340 10143 5339 10143 5341 10144 5342 10144 5340 10144 5343 10145 5342 10145 5341 10145 5344 10146 5345 10146 5343 10146 5343 10147 5345 10147 5342 10147 5346 10148 5347 10148 5344 10148 5344 10149 5347 10149 5345 10149 5346 10150 5348 10150 5347 10150 5349 10151 5348 10151 5346 10151 5349 10152 5350 10152 5348 10152 5351 10153 5350 10153 5349 10153 5351 10154 5352 10154 5350 10154 5351 10155 5353 10155 5352 10155 5354 10156 5353 10156 5351 10156 5354 10157 5355 10157 5353 10157 5356 10158 5355 10158 5354 10158 5356 10159 5357 10159 5355 10159 5358 10160 5357 10160 5356 10160 5358 10161 5359 10161 5357 10161 5358 10162 5360 10162 5359 10162 5361 10163 5360 10163 5358 10163 5361 10164 5362 10164 5360 10164 5363 10165 5362 10165 5361 10165 5363 10166 5364 10166 5362 10166 5365 10167 5364 10167 5363 10167 5365 10168 5366 10168 5364 10168 5367 10169 5366 10169 5365 10169 5367 10170 5368 10170 5366 10170 5367 10171 5369 10171 5368 10171 5370 10172 5369 10172 5367 10172 5370 10173 5371 10173 5369 10173 5372 10174 5371 10174 5370 10174 5372 10175 5373 10175 5371 10175 5374 10176 5373 10176 5372 10176 5374 10177 5375 10177 5373 10177 5376 10178 5375 10178 5374 10178 5376 10179 5377 10179 5375 10179 5376 10180 5378 10180 5377 10180 5379 10181 5378 10181 5376 10181 5379 10182 5380 10182 5378 10182 5381 10183 5380 10183 5379 10183 5381 10184 5382 10184 5380 10184 5383 10185 5382 10185 5381 10185 5383 10186 5384 10186 5382 10186 5385 10187 5384 10187 5383 10187 5385 10188 5386 10188 5384 10188 5387 10189 5386 10189 5385 10189 5387 10190 5388 10190 5386 10190 5389 10191 5388 10191 5387 10191 5389 10192 5390 10192 5388 10192 5389 10193 5391 10193 5390 10193 5392 10194 5391 10194 5389 10194 5392 10195 5393 10195 5391 10195 5394 10196 5393 10196 5392 10196 5394 10197 5395 10197 5393 10197 5396 10198 5395 10198 5394 10198 5396 10199 5397 10199 5395 10199 5398 10200 5397 10200 5396 10200 5398 10201 5399 10201 5397 10201 5398 10202 5400 10202 5399 10202 5401 10203 5400 10203 5398 10203 5401 10204 5402 10204 5400 10204 5401 10205 5403 10205 5402 10205 5404 10206 5403 10206 5401 10206 5404 10207 5405 10207 5403 10207 5406 10208 5405 10208 5404 10208 5406 10209 5407 10209 5405 10209 5408 10210 5407 10210 5406 10210 5408 10211 5409 10211 5407 10211 5410 10212 5409 10212 5408 10212 5410 10213 5411 10213 5409 10213 5410 10214 5412 10214 5411 10214 5413 10215 5412 10215 5410 10215 5413 10216 5414 10216 5412 10216 5413 10217 5415 10217 5414 10217 5416 10218 5415 10218 5413 10218 5416 10219 5417 10219 5415 10219 5418 10220 5417 10220 5416 10220 5418 10221 5419 10221 5417 10221 5418 10222 5420 10222 5419 10222 5421 10223 5420 10223 5418 10223 5421 10224 5422 10224 5420 10224 5423 10225 5422 10225 5421 10225 5423 10226 5424 10226 5422 10226 5425 10227 5424 10227 5423 10227 5425 10228 5426 10228 5424 10228 5427 10229 5426 10229 5425 10229 5427 10230 5428 10230 5426 10230 5429 10231 5428 10231 5427 10231 5429 10232 5430 10232 5428 10232 5431 10233 5432 10233 5429 10233 5429 10234 5432 10234 5430 10234 5433 10235 5432 10235 5431 10235 5433 10236 5434 10236 5432 10236 5435 10237 5434 10237 5433 10237 5435 10238 5436 10238 5434 10238 5435 10239 5437 10239 5436 10239 5438 10240 5437 10240 5435 10240 5439 10241 5437 10241 5438 10241 5439 10242 5440 10242 5437 10242 5441 10243 5440 10243 5439 10243 5441 10244 5442 10244 5440 10244 5443 10245 5444 10245 5441 10245 5441 10246 5444 10246 5442 10246 5443 10247 5445 10247 5444 10247 5446 10248 5445 10248 5443 10248 5446 10249 5447 10249 5445 10249 5448 10250 5447 10250 5446 10250 5448 10251 5449 10251 5447 10251 5450 10252 5449 10252 5448 10252 5450 10253 5451 10253 5449 10253 5452 10254 5451 10254 5450 10254 5452 10255 5453 10255 5451 10255 5454 10256 5453 10256 5452 10256 5454 10257 5455 10257 5453 10257 5456 10258 5455 10258 5454 10258 5456 10259 5457 10259 5455 10259 5456 10260 5458 10260 5457 10260 5459 10261 5458 10261 5456 10261 5459 10262 5460 10262 5458 10262 5461 10263 5460 10263 5459 10263 5461 10264 5462 10264 5460 10264 5463 10265 5462 10265 5461 10265 5463 10266 5464 10266 5462 10266 5465 10267 5464 10267 5463 10267 5465 10268 5466 10268 5464 10268 5467 10269 5466 10269 5465 10269 5467 10270 5468 10270 5466 10270 5467 10271 5469 10271 5468 10271 5470 10272 5469 10272 5467 10272 5470 10273 5471 10273 5469 10273 5470 10274 5472 10274 5471 10274 5473 10275 5472 10275 5470 10275 5473 10276 5474 10276 5472 10276 5475 10277 5476 10277 5473 10277 5473 10278 5476 10278 5474 10278 5477 10279 5478 10279 5475 10279 5475 10280 5478 10280 5476 10280 5479 10281 5478 10281 5477 10281 5479 10282 5480 10282 5478 10282 5479 10283 5481 10283 5480 10283 5482 10284 5481 10284 5479 10284 5482 10285 5483 10285 5481 10285 5484 10286 5483 10286 5482 10286 5484 10287 5485 10287 5483 10287 5486 10288 5485 10288 5484 10288 5487 10289 5485 10289 5486 10289 5487 10290 5488 10290 5485 10290 5487 10291 5489 10291 5488 10291 5487 10292 5490 10292 5489 10292 5491 10293 5490 10293 5487 10293 5491 10294 5492 10294 5490 10294 5493 10295 5492 10295 5491 10295 5493 10296 5494 10296 5492 10296 5495 10297 5494 10297 5493 10297 5495 10298 5496 10298 5494 10298 5497 10299 5496 10299 5495 10299 5497 10300 5498 10300 5496 10300 5497 10301 5499 10301 5498 10301 5500 10302 5499 10302 5497 10302 5500 10303 5501 10303 5499 10303 5502 10304 5501 10304 5500 10304 5502 10305 5503 10305 5501 10305 5502 10306 5504 10306 5503 10306 5505 10307 5504 10307 5502 10307 5506 10308 5504 10308 5505 10308 5506 10309 5507 10309 5504 10309 5508 10310 5507 10310 5506 10310 5508 10311 5509 10311 5507 10311 5508 10312 5510 10312 5509 10312 5511 10313 5510 10313 5508 10313 5511 10314 5512 10314 5510 10314 5513 10315 5512 10315 5511 10315 5513 10316 5514 10316 5512 10316 5515 10317 5514 10317 5513 10317 5515 10318 5516 10318 5514 10318 5517 10319 5516 10319 5515 10319 5517 10320 5518 10320 5516 10320 5519 10321 5518 10321 5517 10321 5519 10322 5520 10322 5518 10322 5519 10323 5521 10323 5520 10323 5522 10324 5521 10324 5519 10324 5522 10325 5523 10325 5521 10325 5524 10326 5525 10326 5522 10326 5522 10327 5525 10327 5523 10327 5524 10328 5526 10328 5525 10328 5524 10329 5527 10329 5526 10329 5528 10330 5527 10330 5524 10330 5529 10331 5530 10331 5528 10331 5528 10332 5530 10332 5527 10332 5529 10333 5531 10333 5530 10333 5532 10334 5531 10334 5529 10334 5532 10335 5533 10335 5531 10335 5532 10336 5534 10336 5533 10336 5535 10337 5534 10337 5532 10337 5535 10338 5536 10338 5534 10338 5537 10339 5536 10339 5535 10339 5537 10340 5538 10340 5536 10340 5539 10341 5538 10341 5537 10341 5539 10342 5540 10342 5538 10342 5539 10343 5541 10343 5540 10343 5542 10344 5541 10344 5539 10344 5542 10345 5543 10345 5541 10345 5544 10346 5543 10346 5542 10346 5544 10347 5545 10347 5543 10347 5544 10348 5546 10348 5545 10348 5547 10349 5546 10349 5544 10349 5547 10350 5548 10350 5546 10350 5549 10351 5548 10351 5547 10351 5549 10352 5550 10352 5548 10352 5551 10353 5550 10353 5549 10353 5551 10354 5552 10354 5550 10354 5551 10355 5553 10355 5552 10355 5554 10356 5553 10356 5551 10356 5554 10357 5555 10357 5553 10357 5556 10358 5555 10358 5554 10358 5556 10359 5557 10359 5555 10359 5556 10360 5558 10360 5557 10360 5559 10361 5558 10361 5556 10361 5559 10362 5560 10362 5558 10362 5561 10363 5560 10363 5559 10363 5561 10364 5562 10364 5560 10364 5563 10365 5562 10365 5561 10365 5563 10366 5564 10366 5562 10366 5563 10367 5565 10367 5564 10367 5566 10368 5565 10368 5563 10368 5566 10369 5567 10369 5565 10369 5566 10370 5568 10370 5567 10370 5569 10371 5568 10371 5566 10371 5569 10372 5570 10372 5568 10372 5571 10373 5570 10373 5569 10373 5571 10374 5572 10374 5570 10374 5573 10375 5572 10375 5571 10375 5573 10376 5574 10376 5572 10376 5575 10377 5574 10377 5573 10377 5575 10378 5576 10378 5574 10378 5575 10379 5577 10379 5576 10379 5578 10380 5577 10380 5575 10380 5578 10381 5579 10381 5577 10381 5580 10382 5581 10382 5578 10382 5578 10383 5581 10383 5579 10383 5582 10384 5581 10384 5580 10384 5582 10385 5583 10385 5581 10385 5584 10386 5583 10386 5582 10386 5584 10387 5585 10387 5583 10387 5584 10388 5586 10388 5585 10388 5587 10389 5586 10389 5584 10389 5587 10390 5588 10390 5586 10390 5589 10391 5588 10391 5587 10391 5589 10392 5590 10392 5588 10392 5591 10393 5590 10393 5589 10393 5591 10394 5592 10394 5590 10394 5591 10395 5593 10395 5592 10395 5594 10396 5593 10396 5591 10396 5594 10397 5595 10397 5593 10397 5596 10398 5595 10398 5594 10398 5596 10399 5597 10399 5595 10399 5598 10400 5597 10400 5596 10400 5598 10401 5599 10401 5597 10401 5600 10402 5599 10402 5598 10402 5600 10403 5601 10403 5599 10403 5602 10404 5601 10404 5600 10404 5602 10405 5603 10405 5601 10405 5604 10406 5603 10406 5602 10406 5604 10407 5605 10407 5603 10407 5604 10408 5606 10408 5605 10408 5607 10409 5606 10409 5604 10409 5607 10410 5608 10410 5606 10410 5609 10411 5608 10411 5607 10411 5609 10412 5610 10412 5608 10412 5611 10413 5610 10413 5609 10413 5611 10414 5612 10414 5610 10414 5613 10415 5612 10415 5611 10415 5613 10416 5782 10416 5612 10416 5613 10417 5029 10417 5782 10417 5614 10418 5029 10418 5613 10418 5614 10419 5028 10419 5029 10419 5615 10420 5028 10420 5614 10420 5615 10421 5026 10421 5028 10421 5043 10422 5041 10422 5616 10422 5617 10423 5043 10423 5616 10423 5046 10424 5043 10424 5617 10424 5618 10425 5046 10425 5617 10425 5049 10426 5046 10426 5618 10426 5051 10427 5049 10427 5618 10427 5054 10428 5051 10428 5619 10428 5620 10429 5054 10429 5619 10429 5056 10430 5054 10430 5620 10430 5621 10431 5059 10431 5056 10431 5061 10432 5059 10432 5621 10432 5063 10433 5061 10433 5621 10433 5065 10434 5063 10434 5622 10434 5068 10435 5065 10435 5622 10435 5623 10436 5074 10436 5072 10436 5077 10437 5074 10437 5623 10437 5077 10438 5623 10438 5624 10438 5079 10439 5077 10439 5624 10439 5625 10440 5081 10440 5079 10440 5084 10441 5081 10441 5625 10441 5626 10442 5084 10442 5625 10442 5087 10443 5084 10443 5626 10443 5089 10444 5087 10444 5627 10444 5092 10445 5089 10445 5627 10445 5094 10446 5092 10446 5628 10446 5629 10447 5094 10447 5628 10447 5096 10448 5094 10448 5629 10448 5630 10449 5096 10449 5629 10449 5098 10450 5096 10450 5630 10450 5631 10451 5098 10451 5630 10451 5101 10452 5098 10452 5631 10452 5632 10453 5101 10453 5631 10453 5104 10454 5101 10454 5632 10454 5633 10455 5106 10455 5104 10455 5108 10456 5106 10456 5633 10456 5634 10457 5108 10457 5633 10457 5111 10458 5108 10458 5634 10458 5635 10459 5115 10459 5112 10459 5117 10460 5115 10460 5635 10460 5120 10461 5117 10461 5636 10461 5122 10462 5120 10462 5636 10462 5637 10463 5124 10463 5122 10463 5126 10464 5124 10464 5637 10464 5638 10465 5126 10465 5637 10465 5128 10466 5126 10466 5638 10466 5639 10467 5128 10467 5638 10467 5130 10468 5128 10468 5639 10468 5640 10469 5130 10469 5639 10469 5133 10470 5130 10470 5640 10470 5136 10471 5133 10471 5640 10471 5138 10472 5136 10472 5641 10472 5642 10473 5143 10473 5141 10473 5145 10474 5143 10474 5642 10474 5643 10475 5147 10475 5145 10475 5149 10476 5147 10476 5643 10476 5644 10477 5149 10477 5643 10477 5152 10478 5149 10478 5644 10478 5152 10479 5644 10479 5154 10479 5156 10480 5154 10480 5645 10480 5158 10481 5156 10481 5645 10481 5646 10482 5171 10482 5169 10482 5647 10483 5171 10483 5646 10483 5174 10484 5171 10484 5647 10484 5648 10485 5174 10485 5647 10485 5176 10486 5174 10486 5648 10486 5649 10487 5178 10487 5176 10487 5650 10488 5178 10488 5649 10488 5181 10489 5178 10489 5650 10489 5184 10490 5181 10490 5650 10490 5186 10491 5184 10491 5651 10491 5652 10492 5186 10492 5651 10492 5189 10493 5186 10493 5652 10493 5653 10494 5189 10494 5652 10494 5191 10495 5189 10495 5653 10495 5193 10496 5191 10496 5653 10496 5654 10497 5193 10497 5653 10497 5196 10498 5193 10498 5654 10498 5206 10499 5204 10499 5655 10499 5208 10500 5206 10500 5655 10500 5656 10501 5208 10501 5655 10501 5211 10502 5208 10502 5656 10502 5657 10503 5211 10503 5656 10503 5658 10504 5211 10504 5657 10504 5214 10505 5211 10505 5658 10505 5659 10506 5214 10506 5658 10506 5217 10507 5214 10507 5659 10507 5660 10508 5217 10508 5659 10508 5220 10509 5217 10509 5660 10509 5220 10510 5660 10510 5661 10510 5222 10511 5220 10511 5661 10511 5662 10512 5222 10512 5661 10512 5224 10513 5222 10513 5662 10513 5663 10514 5229 10514 5226 10514 5231 10515 5229 10515 5663 10515 5233 10516 5231 10516 5663 10516 5237 10517 5235 10517 5664 10517 5240 10518 5237 10518 5664 10518 5245 10519 5242 10519 5665 10519 5666 10520 5245 10520 5665 10520 5247 10521 5245 10521 5666 10521 5250 10522 5247 10522 5666 10522 5667 10523 5252 10523 5250 10523 5254 10524 5252 10524 5667 10524 5258 10525 5256 10525 5668 10525 5669 10526 5258 10526 5668 10526 5261 10527 5258 10527 5669 10527 5264 10528 5261 10528 5669 10528 5265 10529 5264 10529 5670 10529 5671 10530 5265 10530 5670 10530 5268 10531 5265 10531 5671 10531 5270 10532 5268 10532 5671 10532 5272 10533 5270 10533 5672 10533 5673 10534 5272 10534 5672 10534 5274 10535 5272 10535 5673 10535 5674 10536 5274 10536 5673 10536 5277 10537 5274 10537 5674 10537 5279 10538 5277 10538 5674 10538 5283 10539 5280 10539 5675 10539 5676 10540 5283 10540 5675 10540 5285 10541 5283 10541 5676 10541 5288 10542 5285 10542 5676 10542 5290 10543 5288 10543 5677 10543 5678 10544 5290 10544 5677 10544 5292 10545 5290 10545 5678 10545 5679 10546 5292 10546 5678 10546 5295 10547 5292 10547 5679 10547 5680 10548 5295 10548 5679 10548 5297 10549 5295 10549 5680 10549 5681 10550 5297 10550 5680 10550 5299 10551 5297 10551 5681 10551 5682 10552 5299 10552 5681 10552 5302 10553 5299 10553 5682 10553 5683 10554 5302 10554 5682 10554 5305 10555 5302 10555 5683 10555 5684 10556 5305 10556 5683 10556 5308 10557 5305 10557 5684 10557 5685 10558 5310 10558 5308 10558 5313 10559 5310 10559 5685 10559 5332 10560 5330 10560 5686 10560 5687 10561 5332 10561 5686 10561 5334 10562 5332 10562 5687 10562 5688 10563 5334 10563 5687 10563 5337 10564 5334 10564 5688 10564 5339 10565 5337 10565 5688 10565 5689 10566 5349 10566 5346 10566 5351 10567 5349 10567 5689 10567 5690 10568 5351 10568 5689 10568 5354 10569 5351 10569 5690 10569 5358 10570 5356 10570 5691 10570 5692 10571 5358 10571 5691 10571 5361 10572 5358 10572 5692 10572 5693 10573 5361 10573 5692 10573 5363 10574 5361 10574 5693 10574 5694 10575 5363 10575 5693 10575 5365 10576 5363 10576 5694 10576 5695 10577 5367 10577 5365 10577 5370 10578 5367 10578 5695 10578 5696 10579 5370 10579 5695 10579 5372 10580 5370 10580 5696 10580 5374 10581 5372 10581 5697 10581 5376 10582 5374 10582 5697 10582 5698 10583 5376 10583 5697 10583 5379 10584 5376 10584 5698 10584 5699 10585 5381 10585 5379 10585 5383 10586 5381 10586 5699 10586 5383 10587 5699 10587 5700 10587 5385 10588 5383 10588 5700 10588 5387 10589 5385 10589 5700 10589 5701 10590 5387 10590 5700 10590 5389 10591 5387 10591 5701 10591 5702 10592 5392 10592 5389 10592 5394 10593 5392 10593 5702 10593 5703 10594 5396 10594 5394 10594 5398 10595 5396 10595 5703 10595 5401 10596 5398 10596 5704 10596 5705 10597 5401 10597 5704 10597 5404 10598 5401 10598 5705 10598 5706 10599 5404 10599 5705 10599 5406 10600 5404 10600 5706 10600 5707 10601 5406 10601 5706 10601 5408 10602 5406 10602 5707 10602 5410 10603 5408 10603 5707 10603 5413 10604 5410 10604 5708 10604 5709 10605 5413 10605 5708 10605 5416 10606 5413 10606 5709 10606 5710 10607 5416 10607 5709 10607 5418 10608 5416 10608 5710 10608 5421 10609 5418 10609 5710 10609 5711 10610 5429 10610 5427 10610 5431 10611 5429 10611 5711 10611 5712 10612 5433 10612 5431 10612 5435 10613 5433 10613 5712 10613 5438 10614 5435 10614 5712 10614 5713 10615 5441 10615 5439 10615 5443 10616 5441 10616 5713 10616 5714 10617 5443 10617 5713 10617 5446 10618 5443 10618 5714 10618 5715 10619 5446 10619 5714 10619 5448 10620 5446 10620 5715 10620 5716 10621 5461 10621 5459 10621 5463 10622 5461 10622 5716 10622 5717 10623 5465 10623 5463 10623 5467 10624 5465 10624 5717 10624 5718 10625 5470 10625 5467 10625 5719 10626 5470 10626 5718 10626 5473 10627 5470 10627 5719 10627 5720 10628 5473 10628 5719 10628 5475 10629 5473 10629 5720 10629 5477 10630 5475 10630 5720 10630 5479 10631 5477 10631 5720 10631 5484 10632 5482 10632 5721 10632 5486 10633 5484 10633 5721 10633 5722 10634 5487 10634 5486 10634 5491 10635 5487 10635 5722 10635 5723 10636 5497 10636 5495 10636 5724 10637 5497 10637 5723 10637 5500 10638 5497 10638 5724 10638 5502 10639 5500 10639 5724 10639 5725 10640 5502 10640 5724 10640 5505 10641 5502 10641 5725 10641 5726 10642 5505 10642 5725 10642 5506 10643 5505 10643 5726 10643 5508 10644 5506 10644 5726 10644 5513 10645 5511 10645 5727 10645 5728 10646 5513 10646 5727 10646 5515 10647 5513 10647 5728 10647 5517 10648 5515 10648 5728 10648 5522 10649 5519 10649 5729 10649 5524 10650 5522 10650 5729 10650 5730 10651 5524 10651 5729 10651 5528 10652 5524 10652 5730 10652 5532 10653 5529 10653 5731 10653 5535 10654 5532 10654 5731 10654 5732 10655 5537 10655 5535 10655 5539 10656 5537 10656 5732 10656 5733 10657 5539 10657 5732 10657 5542 10658 5539 10658 5733 10658 5734 10659 5542 10659 5733 10659 5544 10660 5542 10660 5734 10660 5735 10661 5544 10661 5734 10661 5547 10662 5544 10662 5735 10662 5736 10663 5547 10663 5735 10663 5549 10664 5547 10664 5736 10664 5737 10665 5549 10665 5736 10665 5551 10666 5549 10666 5737 10666 5738 10667 5551 10667 5737 10667 5554 10668 5551 10668 5738 10668 5739 10669 5554 10669 5738 10669 5556 10670 5554 10670 5739 10670 5740 10671 5556 10671 5739 10671 5559 10672 5556 10672 5740 10672 5741 10673 5561 10673 5559 10673 5563 10674 5561 10674 5741 10674 5742 10675 5563 10675 5741 10675 5566 10676 5563 10676 5742 10676 5743 10677 5566 10677 5742 10677 5569 10678 5566 10678 5743 10678 5744 10679 5569 10679 5743 10679 5571 10680 5569 10680 5744 10680 5745 10681 5571 10681 5744 10681 5573 10682 5571 10682 5745 10682 5746 10683 5573 10683 5745 10683 5575 10684 5573 10684 5746 10684 5747 10685 5575 10685 5746 10685 5578 10686 5575 10686 5747 10686 5748 10687 5580 10687 5578 10687 5582 10688 5580 10688 5748 10688 5749 10689 5584 10689 5582 10689 5587 10690 5584 10690 5749 10690 5750 10691 5589 10691 5587 10691 5591 10692 5589 10692 5750 10692 5594 10693 5591 10693 5750 10693 5596 10694 5594 10694 5751 10694 5598 10695 5596 10695 5751 10695 5607 10696 5604 10696 5752 10696 5753 10697 5607 10697 5752 10697 5609 10698 5607 10698 5753 10698 5754 10699 5026 10699 5615 10699 5023 10700 5026 10700 5754 10700 5021 10701 5023 10701 5754 10701 5756 10702 5617 10702 5616 10702 5757 10703 5617 10703 5756 10703 5757 10704 5618 10704 5617 10704 5757 10705 5051 10705 5618 10705 5755 10706 5051 10706 5757 10706 5755 10707 5619 10707 5051 10707 5758 10708 5619 10708 5755 10708 5758 10709 5620 10709 5619 10709 5030 10710 5620 10710 5758 10710 5031 10711 5620 10711 5030 10711 5031 10712 5056 10712 5620 10712 5033 10713 5056 10713 5031 10713 5033 10714 5621 10714 5056 10714 5035 10715 5621 10715 5033 10715 5037 10716 5621 10716 5035 10716 5037 10717 5063 10717 5621 10717 5038 10718 5063 10718 5037 10718 5038 10719 5622 10719 5063 10719 5040 10720 5622 10720 5038 10720 5040 10721 5068 10721 5622 10721 5042 10722 5068 10722 5040 10722 5042 10723 5069 10723 5068 10723 5044 10724 5069 10724 5042 10724 5045 10725 5069 10725 5044 10725 5045 10726 5072 10726 5069 10726 5047 10727 5072 10727 5045 10727 5047 10728 5623 10728 5072 10728 5048 10729 5623 10729 5047 10729 5050 10730 5623 10730 5048 10730 5050 10731 5624 10731 5623 10731 5052 10732 5624 10732 5050 10732 5053 10733 5624 10733 5052 10733 5053 10734 5079 10734 5624 10734 5055 10735 5079 10735 5053 10735 5055 10736 5625 10736 5079 10736 5057 10737 5625 10737 5055 10737 5057 10738 5626 10738 5625 10738 5058 10739 5626 10739 5057 10739 5060 10740 5626 10740 5058 10740 5060 10741 5087 10741 5626 10741 5062 10742 5087 10742 5060 10742 5062 10743 5627 10743 5087 10743 5064 10744 5627 10744 5062 10744 5066 10745 5627 10745 5064 10745 5066 10746 5092 10746 5627 10746 5070 10747 5092 10747 5066 10747 5070 10748 5628 10748 5092 10748 5071 10749 5628 10749 5070 10749 5071 10750 5629 10750 5628 10750 5073 10751 5629 10751 5071 10751 5073 10752 5630 10752 5629 10752 5075 10753 5630 10753 5073 10753 5076 10754 5630 10754 5075 10754 5076 10755 5631 10755 5630 10755 5078 10756 5631 10756 5076 10756 5080 10757 5632 10757 5078 10757 5078 10758 5632 10758 5631 10758 5082 10759 5632 10759 5080 10759 5082 10760 5104 10760 5632 10760 5083 10761 5104 10761 5082 10761 5083 10762 5633 10762 5104 10762 5085 10763 5633 10763 5083 10763 5085 10764 5634 10764 5633 10764 5086 10765 5634 10765 5085 10765 5086 10766 5111 10766 5634 10766 5088 10767 5111 10767 5086 10767 5088 10768 5112 10768 5111 10768 5090 10769 5112 10769 5088 10769 5091 10770 5112 10770 5090 10770 5091 10771 5635 10771 5112 10771 5093 10772 5635 10772 5091 10772 5093 10773 5117 10773 5635 10773 5759 10774 5117 10774 5093 10774 5759 10775 5636 10775 5117 10775 5095 10776 5636 10776 5759 10776 5097 10777 5636 10777 5095 10777 5097 10778 5122 10778 5636 10778 5099 10779 5122 10779 5097 10779 5099 10780 5637 10780 5122 10780 5100 10781 5637 10781 5099 10781 5102 10782 5637 10782 5100 10782 5102 10783 5638 10783 5637 10783 5103 10784 5638 10784 5102 10784 5105 10785 5638 10785 5103 10785 5105 10786 5639 10786 5638 10786 5107 10787 5640 10787 5105 10787 5105 10788 5640 10788 5639 10788 5109 10789 5640 10789 5107 10789 5109 10790 5136 10790 5640 10790 5110 10791 5136 10791 5109 10791 5110 10792 5641 10792 5136 10792 5113 10793 5641 10793 5110 10793 5113 10794 5138 10794 5641 10794 5114 10795 5138 10795 5113 10795 5114 10796 5141 10796 5138 10796 5116 10797 5141 10797 5114 10797 5116 10798 5642 10798 5141 10798 5118 10799 5642 10799 5116 10799 5119 10800 5642 10800 5118 10800 5119 10801 5145 10801 5642 10801 5121 10802 5145 10802 5119 10802 5121 10803 5643 10803 5145 10803 5123 10804 5643 10804 5121 10804 5123 10805 5644 10805 5643 10805 5125 10806 5644 10806 5123 10806 5127 10807 5644 10807 5125 10807 5127 10808 5154 10808 5644 10808 5129 10809 5154 10809 5127 10809 5129 10810 5645 10810 5154 10810 5131 10811 5645 10811 5129 10811 5131 10812 5158 10812 5645 10812 5132 10813 5158 10813 5131 10813 5132 10814 5160 10814 5158 10814 5135 10815 5160 10815 5132 10815 5135 10816 5162 10816 5160 10816 5137 10817 5162 10817 5135 10817 5137 10818 5164 10818 5162 10818 5139 10819 5164 10819 5137 10819 5139 10820 5165 10820 5164 10820 5140 10821 5165 10821 5139 10821 5140 10822 5167 10822 5165 10822 5142 10823 5167 10823 5140 10823 5142 10824 5169 10824 5167 10824 5144 10825 5169 10825 5142 10825 5144 10826 5646 10826 5169 10826 5146 10827 5646 10827 5144 10827 5146 10828 5647 10828 5646 10828 5148 10829 5647 10829 5146 10829 5150 10830 5647 10830 5148 10830 5150 10831 5648 10831 5647 10831 5151 10832 5648 10832 5150 10832 5151 10833 5176 10833 5648 10833 5153 10834 5176 10834 5151 10834 5153 10835 5649 10835 5176 10835 5155 10836 5649 10836 5153 10836 5155 10837 5650 10837 5649 10837 5157 10838 5650 10838 5155 10838 5157 10839 5184 10839 5650 10839 5159 10840 5184 10840 5157 10840 5159 10841 5651 10841 5184 10841 5161 10842 5651 10842 5159 10842 5161 10843 5652 10843 5651 10843 5163 10844 5652 10844 5161 10844 5163 10845 5653 10845 5652 10845 5166 10846 5653 10846 5163 10846 5168 10847 5653 10847 5166 10847 5168 10848 5654 10848 5653 10848 5170 10849 5654 10849 5168 10849 5170 10850 5196 10850 5654 10850 5172 10851 5196 10851 5170 10851 5173 10852 5196 10852 5172 10852 5173 10853 5198 10853 5196 10853 5175 10854 5198 10854 5173 10854 5175 10855 5200 10855 5198 10855 5175 10856 5202 10856 5200 10856 5177 10857 5202 10857 5175 10857 5177 10858 5204 10858 5202 10858 5179 10859 5204 10859 5177 10859 5179 10860 5655 10860 5204 10860 5180 10861 5655 10861 5179 10861 5182 10862 5655 10862 5180 10862 5182 10863 5656 10863 5655 10863 5183 10864 5656 10864 5182 10864 5185 10865 5656 10865 5183 10865 5185 10866 5657 10866 5656 10866 5187 10867 5657 10867 5185 10867 5187 10868 5658 10868 5657 10868 5188 10869 5658 10869 5187 10869 5190 10870 5658 10870 5188 10870 5190 10871 5659 10871 5658 10871 5192 10872 5659 10872 5190 10872 5194 10873 5659 10873 5192 10873 5194 10874 5660 10874 5659 10874 5194 10875 5661 10875 5660 10875 5195 10876 5661 10876 5194 10876 5197 10877 5661 10877 5195 10877 5197 10878 5662 10878 5661 10878 5199 10879 5662 10879 5197 10879 5199 10880 5224 10880 5662 10880 5201 10881 5224 10881 5199 10881 5201 10882 5226 10882 5224 10882 5203 10883 5226 10883 5201 10883 5203 10884 5663 10884 5226 10884 5205 10885 5663 10885 5203 10885 5207 10886 5663 10886 5205 10886 5207 10887 5233 10887 5663 10887 5209 10888 5233 10888 5207 10888 5209 10889 5235 10889 5233 10889 5210 10890 5235 10890 5209 10890 5210 10891 5664 10891 5235 10891 5212 10892 5664 10892 5210 10892 5212 10893 5240 10893 5664 10893 5213 10894 5240 10894 5212 10894 5215 10895 5240 10895 5213 10895 5215 10896 5242 10896 5240 10896 5216 10897 5242 10897 5215 10897 5216 10898 5665 10898 5242 10898 5218 10899 5665 10899 5216 10899 5218 10900 5666 10900 5665 10900 5219 10901 5666 10901 5218 10901 5221 10902 5666 10902 5219 10902 5221 10903 5250 10903 5666 10903 5223 10904 5250 10904 5221 10904 5225 10905 5250 10905 5223 10905 5225 10906 5667 10906 5250 10906 5225 10907 5254 10907 5667 10907 5227 10908 5254 10908 5225 10908 5228 10909 5254 10909 5227 10909 5228 10910 5256 10910 5254 10910 5228 10911 5668 10911 5256 10911 5230 10912 5668 10912 5228 10912 5232 10913 5668 10913 5230 10913 5232 10914 5669 10914 5668 10914 5234 10915 5669 10915 5232 10915 5238 10916 5669 10916 5234 10916 5238 10917 5264 10917 5669 10917 5239 10918 5264 10918 5238 10918 5239 10919 5670 10919 5264 10919 5241 10920 5670 10920 5239 10920 5241 10921 5671 10921 5670 10921 5243 10922 5671 10922 5241 10922 5243 10923 5270 10923 5671 10923 5244 10924 5270 10924 5243 10924 5244 10925 5672 10925 5270 10925 5246 10926 5672 10926 5244 10926 5248 10927 5672 10927 5246 10927 5248 10928 5673 10928 5672 10928 5249 10929 5673 10929 5248 10929 5249 10930 5674 10930 5673 10930 5251 10931 5674 10931 5249 10931 5253 10932 5674 10932 5251 10932 5255 10933 5674 10933 5253 10933 5255 10934 5279 10934 5674 10934 5760 10935 5279 10935 5255 10935 5760 10936 5280 10936 5279 10936 5760 10937 5675 10937 5280 10937 5257 10938 5675 10938 5760 10938 5259 10939 5675 10939 5257 10939 5259 10940 5676 10940 5675 10940 5260 10941 5676 10941 5259 10941 5262 10942 5676 10942 5260 10942 5262 10943 5288 10943 5676 10943 5262 10944 5677 10944 5288 10944 5263 10945 5677 10945 5262 10945 5266 10946 5678 10946 5263 10946 5263 10947 5678 10947 5677 10947 5267 10948 5678 10948 5266 10948 5267 10949 5679 10949 5678 10949 5269 10950 5679 10950 5267 10950 5269 10951 5680 10951 5679 10951 5271 10952 5680 10952 5269 10952 5273 10953 5680 10953 5271 10953 5273 10954 5681 10954 5680 10954 5275 10955 5681 10955 5273 10955 5275 10956 5682 10956 5681 10956 5761 10957 5682 10957 5275 10957 5761 10958 5683 10958 5682 10958 5278 10959 5683 10959 5761 10959 5278 10960 5684 10960 5683 10960 5282 10961 5684 10961 5278 10961 5284 10962 5684 10962 5282 10962 5284 10963 5308 10963 5684 10963 5284 10964 5685 10964 5308 10964 5286 10965 5685 10965 5284 10965 5287 10966 5685 10966 5286 10966 5289 10967 5313 10967 5287 10967 5287 10968 5313 10968 5685 10968 5289 10969 5315 10969 5313 10969 5291 10970 5315 10970 5289 10970 5291 10971 5317 10971 5315 10971 5293 10972 5317 10972 5291 10972 5293 10973 5320 10973 5317 10973 5294 10974 5320 10974 5293 10974 5294 10975 5321 10975 5320 10975 5296 10976 5321 10976 5294 10976 5296 10977 5323 10977 5321 10977 5298 10978 5323 10978 5296 10978 5298 10979 5325 10979 5323 10979 5300 10980 5325 10980 5298 10980 5301 10981 5325 10981 5300 10981 5301 10982 5327 10982 5325 10982 5303 10983 5327 10983 5301 10983 5303 10984 5330 10984 5327 10984 5304 10985 5330 10985 5303 10985 5306 10986 5330 10986 5304 10986 5306 10987 5686 10987 5330 10987 5307 10988 5686 10988 5306 10988 5307 10989 5687 10989 5686 10989 5309 10990 5687 10990 5307 10990 5309 10991 5688 10991 5687 10991 5311 10992 5688 10992 5309 10992 5311 10993 5339 10993 5688 10993 5312 10994 5339 10994 5311 10994 5314 10995 5339 10995 5312 10995 5316 10996 5339 10996 5314 10996 5316 10997 5341 10997 5339 10997 5316 10998 5343 10998 5341 10998 5762 10999 5343 10999 5316 10999 5318 11000 5343 11000 5762 11000 5318 11001 5344 11001 5343 11001 5763 11002 5344 11002 5318 11002 5763 11003 5346 11003 5344 11003 5324 11004 5346 11004 5763 11004 5324 11005 5689 11005 5346 11005 5326 11006 5689 11006 5324 11006 5326 11007 5690 11007 5689 11007 5328 11008 5690 11008 5326 11008 5328 11009 5354 11009 5690 11009 5329 11010 5354 11010 5328 11010 5329 11011 5356 11011 5354 11011 5331 11012 5356 11012 5329 11012 5331 11013 5691 11013 5356 11013 5333 11014 5691 11014 5331 11014 5335 11015 5691 11015 5333 11015 5335 11016 5692 11016 5691 11016 5336 11017 5692 11017 5335 11017 5336 11018 5693 11018 5692 11018 5338 11019 5693 11019 5336 11019 5338 11020 5694 11020 5693 11020 5340 11021 5694 11021 5338 11021 5340 11022 5365 11022 5694 11022 5342 11023 5365 11023 5340 11023 5342 11024 5695 11024 5365 11024 5345 11025 5695 11025 5342 11025 5345 11026 5696 11026 5695 11026 5347 11027 5696 11027 5345 11027 5348 11028 5696 11028 5347 11028 5348 11029 5372 11029 5696 11029 5350 11030 5372 11030 5348 11030 5350 11031 5697 11031 5372 11031 5352 11032 5697 11032 5350 11032 5353 11033 5697 11033 5352 11033 5353 11034 5698 11034 5697 11034 5355 11035 5698 11035 5353 11035 5355 11036 5379 11036 5698 11036 5357 11037 5379 11037 5355 11037 5357 11038 5699 11038 5379 11038 5359 11039 5699 11039 5357 11039 5360 11040 5699 11040 5359 11040 5360 11041 5700 11041 5699 11041 5362 11042 5700 11042 5360 11042 5364 11043 5700 11043 5362 11043 5364 11044 5701 11044 5700 11044 5366 11045 5701 11045 5364 11045 5368 11046 5389 11046 5366 11046 5366 11047 5389 11047 5701 11047 5368 11048 5702 11048 5389 11048 5369 11049 5702 11049 5368 11049 5371 11050 5394 11050 5369 11050 5369 11051 5394 11051 5702 11051 5371 11052 5703 11052 5394 11052 5373 11053 5703 11053 5371 11053 5373 11054 5398 11054 5703 11054 5375 11055 5398 11055 5373 11055 5375 11056 5704 11056 5398 11056 5377 11057 5704 11057 5375 11057 5377 11058 5705 11058 5704 11058 5378 11059 5705 11059 5377 11059 5378 11060 5706 11060 5705 11060 5380 11061 5706 11061 5378 11061 5382 11062 5706 11062 5380 11062 5382 11063 5707 11063 5706 11063 5384 11064 5707 11064 5382 11064 5386 11065 5707 11065 5384 11065 5386 11066 5410 11066 5707 11066 5386 11067 5708 11067 5410 11067 5388 11068 5708 11068 5386 11068 5388 11069 5709 11069 5708 11069 5390 11070 5709 11070 5388 11070 5391 11071 5709 11071 5390 11071 5391 11072 5710 11072 5709 11072 5393 11073 5710 11073 5391 11073 5395 11074 5710 11074 5393 11074 5395 11075 5421 11075 5710 11075 5397 11076 5421 11076 5395 11076 5399 11077 5421 11077 5397 11077 5399 11078 5423 11078 5421 11078 5399 11079 5425 11079 5423 11079 5400 11080 5425 11080 5399 11080 5402 11081 5425 11081 5400 11081 5402 11082 5427 11082 5425 11082 5403 11083 5427 11083 5402 11083 5403 11084 5711 11084 5427 11084 5405 11085 5711 11085 5403 11085 5405 11086 5431 11086 5711 11086 5407 11087 5431 11087 5405 11087 5407 11088 5712 11088 5431 11088 5409 11089 5712 11089 5407 11089 5411 11090 5712 11090 5409 11090 5411 11091 5438 11091 5712 11091 5412 11092 5438 11092 5411 11092 5412 11093 5439 11093 5438 11093 5414 11094 5439 11094 5412 11094 5414 11095 5713 11095 5439 11095 5417 11096 5713 11096 5414 11096 5417 11097 5714 11097 5713 11097 5419 11098 5714 11098 5417 11098 5420 11099 5714 11099 5419 11099 5420 11100 5715 11100 5714 11100 5422 11101 5715 11101 5420 11101 5422 11102 5448 11102 5715 11102 5424 11103 5448 11103 5422 11103 5424 11104 5450 11104 5448 11104 5426 11105 5450 11105 5424 11105 5428 11106 5450 11106 5426 11106 5428 11107 5452 11107 5450 11107 5430 11108 5452 11108 5428 11108 5430 11109 5454 11109 5452 11109 5432 11110 5454 11110 5430 11110 5432 11111 5456 11111 5454 11111 5434 11112 5456 11112 5432 11112 5434 11113 5459 11113 5456 11113 5436 11114 5459 11114 5434 11114 5436 11115 5716 11115 5459 11115 5437 11116 5716 11116 5436 11116 5437 11117 5463 11117 5716 11117 5440 11118 5463 11118 5437 11118 5440 11119 5717 11119 5463 11119 5442 11120 5717 11120 5440 11120 5444 11121 5717 11121 5442 11121 5444 11122 5467 11122 5717 11122 5444 11123 5718 11123 5467 11123 5445 11124 5718 11124 5444 11124 5447 11125 5718 11125 5445 11125 5447 11126 5719 11126 5718 11126 5449 11127 5719 11127 5447 11127 5449 11128 5720 11128 5719 11128 5451 11129 5720 11129 5449 11129 5451 11130 5479 11130 5720 11130 5453 11131 5479 11131 5451 11131 5455 11132 5482 11132 5453 11132 5453 11133 5482 11133 5479 11133 5455 11134 5721 11134 5482 11134 5457 11135 5721 11135 5455 11135 5458 11136 5721 11136 5457 11136 5458 11137 5486 11137 5721 11137 5460 11138 5486 11138 5458 11138 5460 11139 5722 11139 5486 11139 5462 11140 5722 11140 5460 11140 5464 11141 5722 11141 5462 11141 5464 11142 5491 11142 5722 11142 5466 11143 5491 11143 5464 11143 5466 11144 5493 11144 5491 11144 5468 11145 5493 11145 5466 11145 5468 11146 5495 11146 5493 11146 5469 11147 5495 11147 5468 11147 5469 11148 5723 11148 5495 11148 5471 11149 5723 11149 5469 11149 5472 11150 5723 11150 5471 11150 5472 11151 5724 11151 5723 11151 5474 11152 5724 11152 5472 11152 5476 11153 5724 11153 5474 11153 5476 11154 5725 11154 5724 11154 5478 11155 5725 11155 5476 11155 5478 11156 5726 11156 5725 11156 5480 11157 5726 11157 5478 11157 5480 11158 5508 11158 5726 11158 5481 11159 5508 11159 5480 11159 5481 11160 5511 11160 5508 11160 5483 11161 5511 11161 5481 11161 5485 11162 5511 11162 5483 11162 5485 11163 5727 11163 5511 11163 5488 11164 5727 11164 5485 11164 5488 11165 5728 11165 5727 11165 5489 11166 5728 11166 5488 11166 5490 11167 5517 11167 5489 11167 5489 11168 5517 11168 5728 11168 5492 11169 5517 11169 5490 11169 5492 11170 5519 11170 5517 11170 5494 11171 5519 11171 5492 11171 5496 11172 5519 11172 5494 11172 5496 11173 5729 11173 5519 11173 5498 11174 5729 11174 5496 11174 5498 11175 5730 11175 5729 11175 5499 11176 5730 11176 5498 11176 5499 11177 5528 11177 5730 11177 5501 11178 5528 11178 5499 11178 5503 11179 5528 11179 5501 11179 5503 11180 5529 11180 5528 11180 5504 11181 5529 11181 5503 11181 5504 11182 5731 11182 5529 11182 5507 11183 5731 11183 5504 11183 5507 11184 5535 11184 5731 11184 5509 11185 5535 11185 5507 11185 5509 11186 5732 11186 5535 11186 5510 11187 5732 11187 5509 11187 5512 11188 5732 11188 5510 11188 5512 11189 5733 11189 5732 11189 5514 11190 5733 11190 5512 11190 5516 11191 5733 11191 5514 11191 5516 11192 5734 11192 5733 11192 5518 11193 5734 11193 5516 11193 5518 11194 5735 11194 5734 11194 5520 11195 5735 11195 5518 11195 5521 11196 5735 11196 5520 11196 5523 11197 5736 11197 5521 11197 5521 11198 5736 11198 5735 11198 5525 11199 5736 11199 5523 11199 5525 11200 5737 11200 5736 11200 5526 11201 5737 11201 5525 11201 5526 11202 5738 11202 5737 11202 5527 11203 5738 11203 5526 11203 5530 11204 5738 11204 5527 11204 5530 11205 5739 11205 5738 11205 5531 11206 5739 11206 5530 11206 5533 11207 5739 11207 5531 11207 5533 11208 5740 11208 5739 11208 5534 11209 5740 11209 5533 11209 5534 11210 5559 11210 5740 11210 5536 11211 5559 11211 5534 11211 5536 11212 5741 11212 5559 11212 5538 11213 5741 11213 5536 11213 5540 11214 5741 11214 5538 11214 5540 11215 5742 11215 5741 11215 5541 11216 5742 11216 5540 11216 5541 11217 5743 11217 5742 11217 5543 11218 5743 11218 5541 11218 5545 11219 5743 11219 5543 11219 5545 11220 5744 11220 5743 11220 5546 11221 5744 11221 5545 11221 5548 11222 5744 11222 5546 11222 5548 11223 5745 11223 5744 11223 5550 11224 5745 11224 5548 11224 5550 11225 5746 11225 5745 11225 5550 11226 5747 11226 5746 11226 5552 11227 5747 11227 5550 11227 5553 11228 5747 11228 5552 11228 5553 11229 5578 11229 5747 11229 5555 11230 5578 11230 5553 11230 5555 11231 5748 11231 5578 11231 5557 11232 5748 11232 5555 11232 5558 11233 5748 11233 5557 11233 5558 11234 5582 11234 5748 11234 5558 11235 5749 11235 5582 11235 5560 11236 5749 11236 5558 11236 5560 11237 5587 11237 5749 11237 5562 11238 5587 11238 5560 11238 5564 11239 5587 11239 5562 11239 5564 11240 5750 11240 5587 11240 5565 11241 5750 11241 5564 11241 5567 11242 5750 11242 5565 11242 5567 11243 5594 11243 5750 11243 5568 11244 5594 11244 5567 11244 5568 11245 5751 11245 5594 11245 5570 11246 5751 11246 5568 11246 5572 11247 5751 11247 5570 11247 5572 11248 5598 11248 5751 11248 5574 11249 5598 11249 5572 11249 5574 11250 5600 11250 5598 11250 5574 11251 5602 11251 5600 11251 5576 11252 5602 11252 5574 11252 5576 11253 5604 11253 5602 11253 5577 11254 5604 11254 5576 11254 5577 11255 5752 11255 5604 11255 5579 11256 5752 11256 5577 11256 5581 11257 5752 11257 5579 11257 5581 11258 5753 11258 5752 11258 5583 11259 5753 11259 5581 11259 5583 11260 5609 11260 5753 11260 5585 11261 5609 11261 5583 11261 5585 11262 5611 11262 5609 11262 5586 11263 5611 11263 5585 11263 5586 11264 5613 11264 5611 11264 5588 11265 5613 11265 5586 11265 5588 11266 5614 11266 5613 11266 5590 11267 5614 11267 5588 11267 5590 11268 5615 11268 5614 11268 5592 11269 5615 11269 5590 11269 5592 11270 5754 11270 5615 11270 5593 11271 5754 11271 5592 11271 5595 11272 5754 11272 5593 11272 5595 11273 5021 11273 5754 11273 5597 11274 5021 11274 5595 11274 5597 11275 5017 11275 5021 11275 5599 11276 5017 11276 5597 11276 5599 11277 5016 11277 5017 11277 5601 11278 5016 11278 5599 11278 5601 11279 5018 11279 5016 11279 5603 11280 5018 11280 5601 11280 5605 11281 5018 11281 5603 11281 5606 11282 5018 11282 5605 11282 5606 11283 5025 11283 5018 11283 5606 11284 5608 11284 5025 11284 5070 11285 5066 11285 5067 11285 5095 11286 5759 11286 5093 11286 5135 11287 5132 11287 5134 11287 5238 11288 5234 11288 5236 11288 5257 11289 5760 11289 5255 11289 5761 11290 5275 11290 5276 11290 5278 11291 5761 11291 5276 11291 5282 11292 5278 11292 5281 11292 5318 11293 5762 11293 5316 11293 5763 11294 5318 11294 5319 11294 5322 11295 5763 11295 5319 11295 5324 11296 5763 11296 5322 11296 5417 11297 5414 11297 5415 11297 5612 11298 5784 11298 5610 11298 5782 11299 5783 11299 5612 11299 5765 11300 5802 11300 5764 11300 5766 11301 5802 11301 5765 11301 5766 11302 5022 11302 5019 11302 5767 11303 5765 11303 5764 11303 5767 11304 5766 11304 5765 11304 5022 11305 5766 11305 5767 11305 5769 11306 5767 11306 5764 11306 5024 11307 5022 11307 5767 11307 5769 11308 5764 11308 5768 11308 5770 11309 5767 11309 5769 11309 5770 11310 5024 11310 5767 11310 5769 11311 5768 11311 5772 11311 5771 11312 5770 11312 5769 11312 5771 11313 5024 11313 5770 11313 5772 11314 5768 11314 5773 11314 5771 11315 5769 11315 5772 11315 5771 11316 5027 11316 5024 11316 5774 11317 5771 11317 5772 11317 5773 11318 5768 11318 5775 11318 5027 11319 5771 11319 5774 11319 5776 11320 5772 11320 5773 11320 5774 11321 5772 11321 5776 11321 5028 11322 5027 11322 5774 11322 5777 11323 5774 11323 5776 11323 5028 11324 5774 11324 5777 11324 5778 11325 5777 11325 5776 11325 5775 11326 5776 11326 5773 11326 5778 11327 5776 11327 5775 11327 5029 11328 5028 11328 5777 11328 5778 11329 5029 11329 5777 11329 5780 11330 5778 11330 5775 11330 5780 11331 5775 11331 5781 11331 5029 11332 5778 11332 5780 11332 5782 11333 5029 11333 5780 11333 5781 11334 5775 11334 5779 11334 5783 11335 5780 11335 5781 11335 5783 11336 5782 11336 5780 11336 5783 11337 5781 11337 5784 11337 5784 11338 5781 11338 5779 11338 5785 11339 5784 11339 5779 11339 5784 11340 5612 11340 5783 11340 5785 11341 5779 11341 5786 11341 5610 11342 5784 11342 5785 11342 5788 11343 5785 11343 5786 11343 5789 11344 5785 11344 5788 11344 5608 11345 5610 11345 5785 11345 5608 11346 5785 11346 5789 11346 5788 11347 5786 11347 5787 11347 5025 11348 5608 11348 5789 11348 5790 11349 5789 11349 5788 11349 5790 11350 5025 11350 5789 11350 5791 11351 5788 11351 5787 11351 5790 11352 5788 11352 5791 11352 5790 11353 5792 11353 5025 11353 5791 11354 5787 11354 5793 11354 5794 11355 5790 11355 5791 11355 5795 11356 5791 11356 5793 11356 5794 11357 5792 11357 5790 11357 5794 11358 5791 11358 5795 11358 5020 11359 5794 11359 5795 11359 5794 11360 5020 11360 5792 11360 5797 11361 5020 11361 5795 11361 5798 11362 5795 11362 5793 11362 5798 11363 5797 11363 5795 11363 5797 11364 5799 11364 5020 11364 5798 11365 5793 11365 5796 11365 5799 11366 5797 11366 5798 11366 5800 11367 5798 11367 5796 11367 5801 11368 5798 11368 5800 11368 5801 11369 5799 11369 5798 11369 5015 11370 5799 11370 5801 11370 5800 11371 5796 11371 5802 11371 5803 11372 5801 11372 5800 11372 5802 11373 5804 11373 5800 11373 5803 11374 5800 11374 5804 11374 5805 11375 5015 11375 5801 11375 5803 11376 5805 11376 5801 11376 5805 11377 5803 11377 5804 11377 5766 11378 5804 11378 5802 11378 5766 11379 5805 11379 5804 11379 5019 11380 5805 11380 5766 11380 5779 11381 5787 11381 5786 11381 5775 11382 5802 11382 5796 11382 5775 11383 5768 11383 5764 11383 5775 11384 5764 11384 5802 11384 5775 11385 5793 11385 5787 11385 5775 11386 5787 11386 5779 11386 5775 11387 5796 11387 5793 11387 5807 11388 5812 11388 5815 11388 5807 11389 5806 11389 5812 11389 5806 11390 5808 11390 5812 11390 5812 11391 5808 11391 5813 11391 5808 11392 5809 11392 5813 11392 5813 11393 5809 11393 5817 11393 5809 11394 5810 11394 5817 11394 5817 11395 5810 11395 5816 11395 5810 11396 5811 11396 5816 11396 5816 11397 5811 11397 5814 11397 5814 11398 5807 11398 5815 11398 5811 11399 5807 11399 5814 11399 5813 11400 5821 11400 5818 11400 5813 11401 5818 11401 5819 11401 5813 11402 5819 11402 5820 11402 5817 11403 5822 11403 5821 11403 5817 11404 5821 11404 5813 11404 5812 11405 5820 11405 5823 11405 5812 11406 5813 11406 5820 11406 5824 11407 5812 11407 5823 11407 5816 11408 5825 11408 5822 11408 5816 11409 5822 11409 5817 11409 5826 11410 5825 11410 5816 11410 5815 11411 5812 11411 5824 11411 5827 11412 5815 11412 5824 11412 5828 11413 5826 11413 5816 11413 5828 11414 5816 11414 5814 11414 5829 11415 5815 11415 5827 11415 5830 11416 5828 11416 5814 11416 5831 11417 5814 11417 5815 11417 5831 11418 5815 11418 5829 11418 5831 11419 5830 11419 5814 11419 5806 9618 5809 9618 5808 9618 5811 11420 5810 11420 5807 11420 5807 11421 5810 11421 5806 11421 5806 11422 5810 11422 5809 11422 5843 11423 5821 11423 5822 11423 5832 11424 5843 11424 5822 11424 5832 11425 5822 11425 5825 11425 5833 11426 5832 11426 5825 11426 5833 11427 5825 11427 5826 11427 5834 11428 5833 11428 5826 11428 5834 11429 5826 11429 5828 11429 5835 11430 5834 11430 5828 11430 5835 11431 5828 11431 5830 11431 5836 11432 5835 11432 5830 11432 5836 11433 5830 11433 5831 11433 5836 11434 5831 11434 5829 11434 5837 11435 5836 11435 5829 11435 5837 11436 5829 11436 5827 11436 5838 11437 5837 11437 5827 11437 5838 11438 5827 11438 5824 11438 5838 11439 5824 11439 5823 11439 5839 11440 5838 11440 5823 11440 5839 11441 5823 11441 5820 11441 5840 11442 5839 11442 5820 11442 5840 11443 5820 11443 5819 11443 5841 11444 5840 11444 5819 11444 5841 11445 5819 11445 5818 11445 5842 11446 5841 11446 5818 11446 5842 11447 5818 11447 5821 11447 5843 11448 5842 11448 5821 11448 5041 11449 5838 11449 5839 11449 5616 11450 5041 11450 5839 11450 5039 11451 5838 11451 5041 11451 5756 11452 5616 11452 5839 11452 5039 11453 5837 11453 5838 11453 5756 11454 5839 11454 5840 11454 5032 11455 5837 11455 5039 11455 5032 11456 5836 11456 5837 11456 5756 11457 5840 11457 5841 11457 5036 11458 5836 11458 5032 11458 5757 11459 5756 11459 5841 11459 5757 11460 5841 11460 5842 11460 5835 11461 5836 11461 5036 11461 5843 11462 5757 11462 5842 11462 5835 11463 5036 11463 5034 11463 5843 11464 5755 11464 5757 11464 5834 11465 5835 11465 5034 11465 5834 11466 5034 11466 5030 11466 5832 11467 5755 11467 5843 11467 5833 11468 5834 11468 5030 11468 5832 11469 5758 11469 5755 11469 5833 11470 5030 11470 5758 11470 5833 11471 5758 11471 5832 11471

+
+ + + +

5846 11472 5845 11472 5847 11472 5846 11473 5844 11473 5845 11473 5846 11474 5847 11474 5848 11474 5849 11475 5846 11475 5848 11475 5849 11476 5848 11476 5850 11476 5851 11477 5849 11477 5850 11477 5851 11478 5850 11478 5852 11478 5853 11479 5851 11479 5852 11479 5853 11480 5852 11480 5854 11480 5855 11481 5853 11481 5854 11481 5855 11482 5854 11482 5856 11482 5857 11483 5855 11483 5856 11483 5857 11484 5856 11484 5858 11484 5859 11485 5857 11485 5858 11485 5859 11486 5858 11486 5860 11486 5861 11487 5860 11487 5862 11487 5861 11488 5859 11488 5860 11488 5861 11489 5862 11489 5863 11489 5864 11490 5861 11490 5863 11490 5864 11491 5863 11491 5865 11491 5866 11492 5864 11492 5865 11492 5867 11493 5866 11493 5865 11493 5867 11494 5865 11494 5868 11494 5844 11495 5867 11495 5868 11495 5844 11496 5868 11496 5845 11496 5847 11497 5850 11497 5848 11497 5862 11498 5858 11498 5856 11498 5862 12 5860 12 5858 12 5862 11499 5856 11499 5854 11499 5845 11500 5850 11500 5847 11500 5845 11501 5852 11501 5850 11501 5845 11502 5854 11502 5852 11502 5865 12 5863 12 5862 12 5865 12 5854 12 5845 12 5865 12 5862 12 5854 12 5865 12 5845 12 5868 12 5869 11503 5870 11503 5871 11503 5872 12 5870 12 5869 12 5873 12 5869 12 5871 12 5874 12 5870 12 5872 12 5875 12 5873 12 5871 12 5875 11504 5871 11504 5876 11504 5877 12 5878 12 5870 12 5877 12 5870 12 5874 12 5879 11505 5876 11505 5880 11505 5879 12 5875 12 5876 12 5883 12 5881 12 5882 12 5883 12 5882 12 5884 12 5881 11506 5885 11506 5882 11506 5886 12 5883 12 5884 12 5887 12 5885 12 5881 12 5888 11507 5878 11507 5877 11507 5887 11508 5880 11508 5885 11508 5889 11509 5886 11509 5884 11509 5890 12 5880 12 5887 12 5888 12 5891 12 5878 12 5890 12 5879 12 5880 12 5889 12 5884 12 5892 12 5896 11510 5891 11510 5888 11510 5893 11511 5889 11511 5892 11511 5894 12 5879 12 5890 12 5893 12 5892 12 5895 12 5897 11512 5893 11512 5895 11512 5898 11513 5891 11513 5896 11513 5899 11514 5897 11514 5895 11514 5898 12 5896 12 5900 12 5899 11515 5917 11515 5897 11515 5853 12 5879 12 5894 12 5855 12 5879 12 5853 12 5855 11516 5901 11516 5879 11516 5851 12 5853 12 5894 12 5857 11517 5901 11517 5855 11517 5851 11518 5894 11518 5902 11518 5857 11519 5903 11519 5901 11519 5849 12 5851 12 5902 12 5904 12 5898 12 5900 12 5857 11520 5905 11520 5903 11520 5849 11521 5902 11521 5906 11521 5859 11522 5905 11522 5857 11522 5846 12 5849 12 5906 12 5907 11523 5917 11523 5899 11523 5908 11524 5905 11524 5859 11524 5908 11525 5900 11525 5905 11525 5909 11526 5859 11526 5861 11526 5909 12 5908 12 5859 12 5910 12 5904 12 5900 12 5910 11527 5900 11527 5908 11527 5910 12 5911 12 5904 12 5912 11528 5909 11528 5861 11528 5913 11529 5911 11529 5910 11529 5912 11530 5861 11530 5864 11530 5913 12 5914 12 5911 12 5915 11531 5912 11531 5864 11531 5918 12 5846 12 5906 12 5918 12 5917 12 5916 12 5918 11532 5906 11532 5917 11532 5916 12 5917 12 5907 12 5918 11533 5844 11533 5846 11533 5919 12 5916 12 5907 12 5915 11534 5864 11534 5866 11534 5919 11535 5907 11535 5920 11535 5921 12 5844 12 5918 12 5921 11536 5867 11536 5844 11536 5919 12 5920 12 5922 12 5914 11537 5913 11537 5927 11537 5923 11538 5867 11538 5921 11538 5924 12 5919 12 5922 12 5923 11539 5866 11539 5867 11539 5923 11540 5915 11540 5866 11540 5925 12 5915 12 5923 12 5925 12 5926 12 5915 12 5922 12 5928 12 5924 12 5929 11541 5914 11541 5927 11541 5930 11542 5928 11542 5922 11542 5930 11543 5931 11543 5928 11543 5929 11544 5927 11544 5932 11544 5930 11545 5933 11545 5931 11545 5934 12 5932 12 5935 12 5934 11546 5929 11546 5932 11546 5936 11547 5933 11547 5930 11547 5936 11548 5937 11548 5933 11548 5938 11549 5935 11549 5939 11549 5938 12 5934 12 5935 12 5936 11550 5940 11550 5937 11550 5941 11551 5940 11551 5936 11551 5941 11552 5942 11552 5940 11552 5943 11553 5939 11553 5944 11553 5943 12 5938 12 5939 12 5945 11554 5925 11554 5942 11554 5945 12 5942 12 5941 12 5946 11555 5943 11555 5944 11555 5946 11556 5944 11556 5926 11556 5946 11557 5926 11557 5925 11557 5946 12 5925 12 5945 12 5957 11558 5896 11558 5947 11558 5896 11559 5888 11559 5947 11559 5947 11560 5888 11560 5948 11560 5888 11561 5877 11561 5948 11561 5948 11562 5877 11562 5949 11562 5877 11563 5874 11563 5949 11563 5949 11564 5874 11564 5950 11564 5874 11565 5872 11565 5950 11565 5950 11566 5872 11566 5951 11566 5872 11567 5869 11567 5951 11567 5869 11568 5873 11568 5951 11568 5951 11569 5873 11569 5952 11569 5873 11570 5875 11570 5952 11570 5952 11571 5875 11571 5953 11571 5875 11572 5879 11572 5953 11572 5953 11573 5879 11573 5954 11573 5879 11574 5901 11574 5954 11574 5954 11575 5901 11575 5955 11575 5901 11576 5903 11576 5955 11576 5955 11577 5903 11577 5956 11577 5903 11578 5905 11578 5956 11578 5905 11579 5900 11579 5956 11579 5956 11580 5900 11580 5957 11580 5900 11581 5896 11581 5957 11581 5969 11582 5902 11582 5958 11582 5902 11583 5894 11583 5958 11583 5958 11584 5894 11584 5959 11584 5894 11585 5890 11585 5959 11585 5959 11586 5890 11586 5960 11586 5890 11587 5887 11587 5960 11587 5887 11588 5881 11588 5960 11588 5960 11589 5881 11589 5961 11589 5961 11590 5881 11590 5962 11590 5881 11591 5883 11591 5962 11591 5962 11592 5883 11592 5963 11592 5883 11593 5886 11593 5963 11593 5886 11594 5889 11594 5963 11594 5963 11595 5889 11595 5964 11595 5964 11596 5889 11596 5965 11596 5889 11597 5893 11597 5965 11597 5965 11598 5897 11598 5966 11598 5893 11599 5897 11599 5965 11599 5966 11600 5897 11600 5967 11600 5897 11601 5917 11601 5967 11601 5967 11602 5917 11602 5968 11602 5917 11603 5906 11603 5968 11603 5968 11604 5906 11604 5969 11604 5906 11605 5902 11605 5969 11605 5932 11606 5927 11606 5970 11606 5970 11607 5927 11607 5971 11607 5971 11608 5927 11608 5972 11608 5927 11609 5913 11609 5972 11609 5972 11610 5913 11610 5973 11610 5913 11611 5910 11611 5973 11611 5973 11612 5910 11612 5974 11612 5910 11613 5908 11613 5974 11613 5974 11614 5908 11614 5975 11614 5908 11615 5909 11615 5975 11615 5975 11616 5909 11616 5976 11616 5909 11617 5912 11617 5976 11617 5912 11618 5915 11618 5976 11618 5976 11619 5915 11619 5977 11619 5977 11620 5915 11620 5978 11620 5915 11621 5926 11621 5978 11621 5926 11622 5944 11622 5978 11622 5978 11623 5944 11623 5979 11623 5979 11624 5944 11624 5980 11624 5944 11625 5939 11625 5980 11625 5980 11626 5935 11626 5981 11626 5939 11627 5935 11627 5980 11627 5935 11628 5932 11628 5981 11628 5981 11629 5932 11629 5970 11629 5982 11630 5925 11630 5983 11630 5942 11631 5925 11631 5982 11631 5983 11632 5925 11632 5984 11632 5925 11633 5923 11633 5984 11633 5984 11634 5923 11634 5985 11634 5923 11635 5921 11635 5985 11635 5921 11636 5918 11636 5985 11636 5985 11637 5918 11637 5986 11637 5918 11638 5916 11638 5986 11638 5986 11639 5916 11639 5987 11639 5916 11640 5919 11640 5987 11640 5987 11641 5919 11641 5988 11641 5919 11642 5924 11642 5988 11642 5988 11643 5928 11643 5989 11643 5924 11644 5928 11644 5988 11644 5989 11645 5931 11645 5990 11645 5928 11646 5931 11646 5989 11646 5990 11647 5933 11647 5991 11647 5931 11648 5933 11648 5990 11648 5933 11649 5937 11649 5991 11649 5991 11650 5937 11650 5992 11650 5937 11651 5940 11651 5992 11651 5992 11652 5940 11652 5982 11652 5940 11653 5942 11653 5982 11653 5929 11654 5993 11654 5994 11654 5914 11655 5994 11655 5995 11655 5914 11656 5929 11656 5994 11656 5914 11657 5995 11657 5996 11657 5911 11658 5914 11658 5996 11658 5911 11659 5996 11659 5997 11659 5904 11660 5911 11660 5997 11660 5904 11661 5997 11661 5998 11661 5898 11662 5904 11662 5998 11662 5898 11663 5998 11663 5999 11663 5898 11664 5999 11664 6000 11664 5891 11665 5898 11665 6000 11665 5878 11666 5891 11666 6000 11666 5878 11667 6000 11667 6001 11667 5870 11668 5878 11668 6001 11668 5870 11669 6001 11669 6002 11669 5870 11670 6002 11670 6003 11670 5871 11671 5870 11671 6003 11671 5871 11672 6003 11672 6004 11672 5871 11673 6004 11673 6005 11673 5876 11674 5871 11674 6005 11674 5876 11675 6005 11675 6006 11675 5880 11676 5876 11676 6006 11676 5880 11677 6006 11677 6007 11677 5885 11678 5880 11678 6007 11678 5885 11679 6007 11679 6008 11679 5885 11680 6008 11680 6009 11680 5882 11681 5885 11681 6009 11681 5882 11682 6009 11682 6010 11682 5884 11683 5882 11683 6010 11683 5884 11684 6010 11684 6011 11684 5892 11685 5884 11685 6011 11685 5892 11686 6011 11686 6012 11686 5895 11687 5892 11687 6012 11687 5895 11688 6012 11688 6013 11688 5899 11689 5895 11689 6013 11689 5899 11690 6013 11690 6014 11690 5899 11691 6014 11691 6015 11691 5907 11692 5899 11692 6015 11692 5907 11693 6015 11693 6016 11693 5920 11694 6016 11694 6017 11694 5920 11695 5907 11695 6016 11695 5922 11696 5920 11696 6017 11696 5922 11697 6017 11697 6018 11697 5930 11698 5922 11698 6018 11698 5930 11699 6018 11699 6019 11699 5936 11700 6019 11700 6020 11700 5936 11701 5930 11701 6019 11701 5936 11702 6020 11702 6021 11702 5941 11703 5936 11703 6021 11703 5941 11704 6021 11704 6022 11704 5945 11705 5941 11705 6022 11705 5945 11706 6022 11706 6023 11706 5946 11707 5945 11707 6023 11707 5946 11708 6023 11708 6024 11708 5943 11709 5946 11709 6024 11709 5943 11710 6024 11710 6025 11710 5938 11711 5943 11711 6025 11711 5938 11712 6025 11712 6026 11712 5934 11713 5938 11713 6026 11713 5934 11714 6026 11714 5993 11714 5929 11715 5934 11715 5993 11715 5956 12 5954 12 5955 12 5954 11716 5952 11716 5953 11716 5956 11717 5952 11717 5954 11717 5957 11718 5951 11718 5956 11718 5956 11719 5951 11719 5952 11719 5949 12 5951 12 5948 12 5947 12 5951 12 5957 12 5948 11720 5951 11720 5947 11720 5950 12 5951 12 5949 12 5966 11721 5963 11721 5965 11721 5967 11722 5963 11722 5966 11722 5968 12 5963 12 5967 12 5965 12 5963 12 5964 12 5958 12 5960 12 5969 12 5959 11723 5960 11723 5958 11723 5968 11724 5962 11724 5963 11724 5960 11725 5961 11725 5969 11725 5969 11726 5961 11726 5968 11726 5968 11727 5961 11727 5962 11727 5979 11728 5977 11728 5978 11728 5970 12 5973 12 5981 12 5971 11729 5973 11729 5970 11729 5972 12 5973 12 5971 12 5973 12 5975 12 5981 12 5981 12 5975 12 5980 12 5974 12 5975 12 5973 12 5979 11730 5975 11730 5977 11730 5980 11731 5975 11731 5979 11731 5977 12 5975 12 5976 12 5992 11732 5990 11732 5991 11732 5982 12 5984 12 5992 12 5983 12 5984 12 5982 12 5985 12 5986 12 5984 12 5989 12 5986 12 5988 12 5984 12 5986 12 5992 12 5990 12 5986 12 5989 12 5988 11733 5986 11733 5987 11733 5992 12 5986 12 5990 12 6044 11734 6028 11734 6027 11734 6027 11735 6028 11735 6029 11735 6028 11736 6030 11736 6029 11736 6029 11737 6030 11737 6031 11737 6030 11738 6032 11738 6031 11738 6031 11739 6032 11739 6033 11739 6032 11740 6034 11740 6033 11740 6033 11741 6034 11741 6035 11741 6034 11742 6036 11742 6035 11742 6035 11743 6036 11743 6037 11743 6036 11744 6038 11744 6037 11744 6037 11745 6038 11745 6039 11745 6038 11746 6040 11746 6039 11746 6039 11747 6040 11747 6041 11747 6040 11748 6042 11748 6041 11748 6041 11749 6042 11749 6043 11749 6042 11750 6044 11750 6043 11750 6043 11751 6044 11751 6045 11751 6045 11752 6044 11752 6027 11752 6030 11753 6036 11753 6032 11753 6028 11754 6036 11754 6030 11754 6032 77 6036 77 6034 77 6028 11755 6038 11755 6036 11755 6044 11756 6038 11756 6028 11756 6040 77 6038 77 6042 77 6042 11757 6038 11757 6044 11757 6066 11758 6046 11758 6065 11758 6065 11759 6046 11759 6047 11759 6047 11760 6046 11760 6048 11760 6046 11761 6049 11761 6048 11761 6048 11762 6049 11762 6050 11762 6049 11763 6051 11763 6050 11763 6050 11764 6051 11764 6052 11764 6051 11765 6053 11765 6052 11765 6052 11766 6053 11766 6054 11766 6053 11767 6055 11767 6054 11767 6054 11768 6055 11768 6056 11768 6056 11769 6055 11769 6057 11769 6055 11770 6058 11770 6057 11770 6057 11771 6059 11771 6060 11771 6058 11772 6059 11772 6057 11772 6060 11773 6059 11773 6061 11773 6059 11774 6062 11774 6061 11774 6061 11775 6062 11775 6063 11775 6062 11776 6064 11776 6063 11776 6063 11777 6064 11777 6065 11777 6064 11778 6066 11778 6065 11778 6046 77 6053 77 6049 77 6049 11779 6053 11779 6051 11779 6064 11780 6062 11780 6066 11780 6066 77 6062 77 6046 77 6059 77 6058 77 6062 77 6046 77 6058 77 6053 77 6053 11781 6058 11781 6055 11781 6062 11782 6058 11782 6046 11782 6085 11783 6067 11783 6068 11783 6067 11784 6069 11784 6068 11784 6068 11785 6069 11785 6070 11785 6069 11786 6071 11786 6070 11786 6070 11787 6071 11787 6072 11787 6071 11788 6073 11788 6072 11788 6072 11789 6073 11789 6074 11789 6073 11790 6075 11790 6074 11790 6074 11791 6076 11791 6077 11791 6075 11792 6076 11792 6074 11792 6076 11793 6078 11793 6077 11793 6077 11794 6078 11794 6079 11794 6078 11795 6080 11795 6079 11795 6079 11796 6080 11796 6081 11796 6080 11797 6082 11797 6081 11797 6081 11798 6082 11798 6083 11798 6082 11799 6084 11799 6083 11799 6083 11800 6084 11800 6085 11800 6084 11801 6067 11801 6085 11801 6075 77 6078 77 6076 77 6071 11802 6078 11802 6073 11802 6080 77 6078 77 6082 77 6067 77 6078 77 6069 77 6073 11803 6078 11803 6075 11803 6082 77 6078 77 6084 77 6084 11804 6078 11804 6067 11804 6069 77 6078 77 6071 77 6103 11805 6104 11805 6086 11805 6104 11806 6087 11806 6086 11806 6086 11807 6087 11807 6088 11807 6087 11808 6089 11808 6088 11808 6088 11809 6089 11809 6090 11809 6089 11810 6091 11810 6090 11810 6090 11811 6091 11811 6092 11811 6091 11812 6093 11812 6092 11812 6092 11813 6094 11813 6095 11813 6093 11814 6094 11814 6092 11814 6094 11815 6096 11815 6095 11815 6095 11816 6096 11816 6097 11816 6097 11817 6096 11817 6098 11817 6096 11818 6099 11818 6098 11818 6099 11819 6100 11819 6098 11819 6098 11820 6100 11820 6101 11820 6100 11821 6102 11821 6101 11821 6101 11822 6102 11822 6103 11822 6102 11823 6104 11823 6103 11823 6087 11824 6096 11824 6089 11824 6099 11825 6096 11825 6100 11825 6104 11826 6096 11826 6087 11826 6091 77 6096 77 6093 77 6102 11827 6096 11827 6104 11827 6093 77 6096 77 6094 77 6089 77 6096 77 6091 77 6100 77 6096 77 6102 77 5994 11828 6105 11828 6106 11828 5994 11829 5993 11829 6105 11829 5995 11830 5994 11830 6106 11830 5996 11831 5995 11831 6106 11831 5996 11832 6106 11832 6107 11832 5997 11833 5996 11833 6107 11833 5997 11834 6107 11834 6108 11834 5998 11835 5997 11835 6108 11835 5999 11836 6108 11836 6109 11836 5999 11837 5998 11837 6108 11837 6000 11838 5999 11838 6109 11838 6001 11839 6000 11839 6109 11839 6001 11840 6109 11840 6110 11840 6002 11841 6001 11841 6110 11841 6003 11842 6002 11842 6110 11842 6003 11843 6110 11843 6111 11843 6004 11844 6003 11844 6111 11844 6005 11845 6004 11845 6111 11845 6006 11846 6005 11846 6111 11846 6006 11847 6111 11847 6112 11847 6007 11848 6006 11848 6112 11848 6007 11849 6112 11849 6113 11849 6008 11850 6007 11850 6113 11850 6009 11851 6008 11851 6113 11851 6009 11852 6113 11852 6114 11852 6010 11853 6009 11853 6114 11853 6010 11854 6114 11854 6115 11854 6011 11855 6010 11855 6115 11855 6012 11856 6011 11856 6115 11856 6012 11857 6115 11857 6116 11857 6013 11858 6012 11858 6116 11858 6014 11859 6013 11859 6116 11859 6015 11860 6014 11860 6116 11860 6015 11861 6116 11861 6117 11861 6016 11862 6015 11862 6117 11862 6016 11863 6117 11863 6118 11863 6017 11864 6016 11864 6118 11864 6018 11865 6017 11865 6118 11865 6019 11866 6018 11866 6118 11866 6019 11867 6118 11867 6119 11867 6020 11868 6019 11868 6119 11868 6021 11869 6020 11869 6119 11869 6021 11870 6119 11870 6120 11870 6022 11871 6021 11871 6120 11871 6023 11872 6022 11872 6120 11872 6023 11873 6120 11873 6121 11873 6024 11874 6023 11874 6121 11874 6025 11875 6024 11875 6121 11875 6025 11876 6121 11876 6105 11876 6026 11877 6025 11877 6105 11877 5993 11878 6026 11878 6105 11878 6052 11879 6121 11879 6120 11879 6054 11880 6121 11880 6052 11880 6050 11881 6052 11881 6120 11881 6056 11882 6121 11882 6054 11882 6050 11883 6120 11883 6119 11883 6048 11884 6050 11884 6119 11884 6056 11885 6105 11885 6121 11885 6057 11886 6105 11886 6056 11886 6047 11887 6048 11887 6119 11887 6092 11888 6106 11888 6105 11888 6074 11889 6119 11889 6118 11889 6092 11890 6105 11890 6057 11890 6074 11891 6047 11891 6119 11891 6090 77 6092 77 6057 77 6072 11892 6074 11892 6118 11892 6090 11893 6057 11893 6060 11893 6074 11894 6065 11894 6047 11894 6095 11895 6106 11895 6092 11895 6077 77 6065 77 6074 77 6095 11896 6107 11896 6106 11896 6072 11897 6118 11897 6117 11897 6088 11898 6060 11898 6061 11898 6088 77 6090 77 6060 77 6070 11899 6072 11899 6117 11899 6077 11900 6063 11900 6065 11900 6097 11901 6107 11901 6095 11901 6088 11902 6061 11902 6063 11902 6079 11903 6063 11903 6077 11903 6068 11904 6070 11904 6117 11904 6079 11905 6088 11905 6063 11905 6108 11906 6107 11906 6097 11906 6116 11907 6068 11907 6117 11907 6108 11908 6097 11908 6098 11908 6116 11909 6085 11909 6068 11909 6109 11910 6108 11910 6098 11910 6109 11911 6098 11911 6101 11911 6033 11912 6088 11912 6079 11912 6033 11913 6086 11913 6088 11913 6035 77 6086 77 6033 77 6031 77 6033 77 6079 77 6031 11914 6079 11914 6081 11914 6037 77 6086 77 6035 77 6037 11915 6103 11915 6086 11915 6031 11916 6081 11916 6083 11916 6037 11917 6101 11917 6103 11917 6029 77 6031 77 6083 77 6039 77 6101 77 6037 77 6115 11918 6085 11918 6116 11918 6115 11919 6083 11919 6085 11919 6110 11920 6101 11920 6039 11920 6110 11921 6109 11921 6101 11921 6115 11922 6029 11922 6083 11922 6114 11923 6029 11923 6115 11923 6111 11924 6110 11924 6039 11924 6114 11925 6027 11925 6029 11925 6111 11926 6039 11926 6041 11926 6113 11927 6027 11927 6114 11927 6113 11928 6045 11928 6027 11928 6112 11929 6111 11929 6041 11929 6112 11930 6041 11930 6043 11930 6112 11931 6045 11931 6113 11931 6112 11932 6043 11932 6045 11932

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 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 + + + + + + + +
\ No newline at end of file diff --git a/models/gimbal_small_3d/meshes/roll_arm.dae b/models/gimbal_small_3d/meshes/roll_arm.dae new file mode 100644 index 0000000..27485a8 --- /dev/null +++ b/models/gimbal_small_3d/meshes/roll_arm.dae @@ -0,0 +1,526 @@ + + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-05-11T22:44:28 + 2023-05-11T22:44:28 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1000 + 29.99998 + 75 + 0.15 + 0 + 1 + 2 + 0.04999995 + 30.002 + 1 + 3 + 2880 + 3 + 1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.06039255 -0.007305622 0.01964914 0.05925875 -0.007339 0.02532035 0.0602948 -0.007963836 0.01945525 0.05886811 -0.008469104 0.02556568 0.06020295 -0.008470654 0.01876062 0.05834001 -0.009199798 0.02559953 0.05970239 -0.009150564 0.01885014 0.0591802 -0.009568393 0.01898837 0.05773013 -0.009654104 0.02560716 0.05861479 -0.009916305 0.01810455 0.05693924 -0.009996592 0.02555668 0.05797803 -0.01006513 0.01826012 0.05673521 0.01486492 0.02571189 0.05901443 -0.006557166 0.02654677 0.05910325 -0.007839977 0.02558547 0.05883508 -0.006478846 0.02720987 0.05857634 -0.006012022 0.02816092 0.0564509 -0.008807241 0.02759259 0.05844515 -0.004490792 0.02917855 0.05829292 -0.005648195 0.02898776 0.05616086 -0.007775485 0.02889287 0.05592054 -0.005342423 0.03101146 0.0556001 -0.001442015 0.03288364 0.05799823 0.00236231 0.03147679 0.05538505 3.92166e-4 0.03330898 0.05807763 0.004188954 0.0312004 0.0555101 0.00251919 0.03344452 0.05552846 0.003884077 0.033369 0.05558961 0.00575447 0.03305566 0.05879157 0.0101692 0.02769196 0.05579352 0.009279668 0.03165179 0.05594879 0.01093131 0.03053957 0.05615299 0.0122354 0.02939063 0.05638474 0.01356947 0.02785289 0.05866432 -0.007038891 0.02730369 0.0565679 -0.009629309 0.02629238 0.05793547 -0.006596028 0.02887231 0.05847811 -0.003573238 0.02924716 0.05832391 -0.003206133 0.02989727 0.05817103 -0.001119256 0.03073787 0.05803716 -0.003154039 0.03058636 0.05602478 -0.006565332 0.03007537 0.05775922 -6.73414e-4 0.03170877 0.05576026 -0.003622293 0.03203606 0.05644679 -0.00361669 0.03184348 0.05807262 6.75839e-4 0.03121316 0.05777019 0.001796126 0.0319736 0.0581181 0.005941569 0.03090268 0.0578202 0.005276143 0.03168386 0.05621564 0.002052605 0.03326928 0.05739951 0.00375843 0.03242641 0.05829924 0.007617175 0.03008526 0.05631756 0.004900515 0.03304314 0.05800133 0.007718801 0.03076118 0.05753833 0.00749737 0.0314992 0.0563569 0.008087873 0.03208816 0.05732673 0.009299457 0.03095674 0.05845487 0.009181976 0.02922666 0.05822217 0.009582757 0.0296368 0.05565518 0.007498502 0.03248727 0.05782216 0.009541034 0.03028136 0.05653798 0.01000535 0.03102493 0.0588032 0.01122444 0.02742624 0.05692881 0.01139193 0.0298773 0.05768626 0.01159965 0.02910965 0.05858558 0.01161772 0.02775633 0.05728745 0.01370221 0.02728664 0.05706578 0.01265412 0.02866321 0.05798989 0.01324987 0.02719187 0.05822336 -0.007691085 0.02754402 0.05731302 -0.008843123 0.02716702 0.05704665 -0.0079782 0.02837002 0.05845838 -0.00534892 0.02878439 0.05661761 -0.006560921 0.02992868 0.05733466 -0.006964445 0.02918493 0.05774456 -0.004881739 0.0302447 0.05669385 -0.00492829 0.03104978 0.05734896 -0.00583297 0.03003609 0.05761307 -0.003046333 0.03124374 0.05718517 -0.003951311 0.03125518 0.05703145 -0.001921713 0.03217136 0.05735027 -0.001581549 0.03199654 0.05615651 -0.001950502 0.03259915 0.05661344 -0.002186059 0.03234314 0.05710625 3.45987e-4 0.03261715 0.05636823 6.68192e-5 0.03302544 0.05734032 0.002154052 0.03254902 0.05678731 0.001615226 0.03296703 0.05682492 0.003784179 0.03292411 0.05610442 0.003501117 0.0332784 0.05727523 0.005942463 0.0322113 0.05662685 0.006570279 0.03252506 0.05807912 0.01119357 0.02893733 0.05835783 0.01255494 0.02741742 0.05757892 0.01457053 0.02578389 0.05792069 -0.008450686 0.02710765 0.0583142 0.01400828 0.0258041 0.05863511 -0.008268058 0.02626663 0.05864578 0.01360005 0.02580809 0.05904453 0.01285433 0.02568125 0.05921572 0.01217997 0.0255289 0.05934345 -0.009586215 0.01692599 0.0600211 -0.00895226 0.01703643 0.06056588 -0.007477641 0.01821833 0.06042104 -0.00829637 0.01688051 0.06066346 -0.007460415 0.01688903 0.06067013 -0.00759387 0.006458878 0.0603277 -0.008460879 0.004481554 0.05987715 -0.009117722 0.004750013 0.05938267 -0.009541988 0.004514515 0.05860757 -0.009939968 0.004452288 0.0576356 -0.01007539 7.96499e-4 0.04762232 -0.007315158 -0.02139043 0.0582444 -0.009966135 0.001424252 0.05895435 -0.009670615 0.001741051 0.05954873 -0.009215593 0.001650929 0.06061655 -0.007539033 0.004216015 0.0600875 -0.008636116 0.002526283 0.06047505 -0.007694482 0.002498447 0.05770319 -0.00990647 -0.002269208 0.05989336 -0.008433997 1.23027e-4 0.05826985 -0.009690821 -0.001952528 0.05905282 -0.009142041 -0.001641094 0.06028854 -0.007539093 8.18809e-4 0.05999499 -0.007611036 -8.54104e-4 0.05652087 -0.009975016 -0.005420506 0.05942302 -0.008255004 -0.002527177 0.05796235 -0.009378612 -0.004615008 0.05443423 -0.01007384 -0.008903324 0.05963355 -0.007406055 -0.002564668 0.0587272 -0.008735179 -0.004089474 0.05666822 -0.009630799 -0.007147252 0.05916148 -0.007671058 -0.00418967 0.05792945 -0.00878334 -0.006351351 0.05819791 -0.00805068 -0.006673216 0.05695718 -0.009115576 -0.008026003 0.05529552 -0.009945094 -0.008516132 0.05839186 -0.007380664 -0.006568551 0.0547409 -0.00976932 -0.010508 0.05711877 -0.00836575 -0.008849501 0.05528742 -0.009364545 -0.01075553 0.05733382 -0.007539033 -0.00900352 0.05297595 -0.009935915 -0.01262539 0.05573874 -0.008850693 -0.01093757 0.05601727 -0.008090078 -0.01126968 0.05014008 -0.01007664 -0.01518625 0.05619573 -0.007344186 -0.01126748 0.05397522 -0.009366035 -0.01292163 0.05412191 -0.00854671 -0.01389151 0.05230355 -0.009606957 -0.0146746 0.05483543 -0.007598757 -0.01343506 0.05319309 -0.00917226 -0.01437586 0.05053168 -0.00996226 -0.01562839 0.05034708 -0.009816288 -0.01644653 0.05385738 -0.007621884 -0.01483207 0.05165654 -0.009180068 -0.01630669 0.05197286 -0.008517086 -0.0167036 0.05010324 -0.009380459 -0.01771372 0.05281484 -0.007598817 -0.01618468 0.04710888 -0.01003444 -0.01871842 0.05170893 -0.007526934 -0.01749026 0.04972219 -0.008510947 -0.01908695 0.0471028 -0.009791076 -0.01963901 0.04754436 -0.009536564 -0.01984012 0.05055636 -0.007611095 -0.01870173 0.04879963 -0.00903654 -0.01944243 0.0470615 -0.009313285 -0.02057963 0.0493074 -0.007549583 -0.01991355 0.04732584 -0.008817493 -0.0209369 0.04770201 -0.008046686 -0.02114814 0.02882814 -0.007324397 -0.03549468 0.02878332 -0.007994174 -0.03537219 0.0277872 -0.009859383 -0.03399175 0.02164596 -0.007265746 -0.03798478 0.02129721 -0.007985949 -0.03786754 0.02293843 -0.007973968 -0.03772532 0.02362567 -0.00732702 -0.03772604 0.02134019 -0.008817851 -0.0374509 0.02245908 -0.008609414 -0.0374962 0.02187162 -0.009403765 -0.03688204 0.0229606 -0.009288728 -0.03689229 0.02183675 -0.009712338 -0.03642487 0.02487516 -0.008032441 -0.03726869 0.02554136 -0.007526457 -0.03717488 0.02384418 -0.008689641 -0.03720819 0.02173197 -0.009967327 -0.03583836 0.02658516 -0.007326722 -0.03676646 0.02447974 -0.008976936 -0.03683865 0.02334499 -0.01007825 -0.03500682 0.02385187 -0.00977534 -0.03597241 0.02417528 -0.00999552 -0.03527766 0.02574288 -0.008750915 -0.03658354 0.02654618 -0.008041262 -0.03662598 0.02531039 -0.009360253 -0.03618073 0.0278151 -0.007611155 -0.0361126 0.02711689 -0.008489727 -0.03613156 0.02709418 -0.00906676 -0.03570997 0.02580076 -0.009654045 -0.03555291 0.0282166 -0.008725047 -0.03535252 0.02610707 -0.00998032 -0.03457695 0.02712088 -0.009620487 -0.03494173 0.02795183 -0.009364247 -0.03484481 0.02695107 -0.01006042 -0.03361594 0.004769265 -0.01006245 -0.03541857 0.003755331 -0.009764015 -0.03636974 0.002387046 -0.009208858 -0.03712707 9.62094e-4 -0.008419036 -0.03770184 -3.89187e-4 -0.007412731 -0.03799575 0.002706468 -0.009349942 -0.03474444 0.001256883 -0.008589804 -0.03500258 -8.75679e-5 -0.007661104 -0.03519135 -0.001485407 -0.006344974 -0.03521782 -0.002084553 -0.005705237 -0.03799998 -0.002502143 -0.005094528 -0.03534597 -0.003225088 -0.003982543 -0.03555136 -0.003745555 -0.003039598 -0.03799998 -0.003900229 -0.002598166 -0.03554517 -0.00462985 -3.52693e-4 -0.03799998 -0.004638493 -2.15522e-4 -0.03565454 -0.004803419 0.001084387 -0.03544837 -0.00491929 0.002160727 -0.03799998 -0.004865586 0.00320667 -0.03564321 -0.004603445 0.005279302 -0.03799998 -0.004586756 0.005176663 -0.03560894 -0.00401169 0.007032632 -0.03558701 -0.003367483 0.00849086 -0.03799998 -0.003241598 0.00865519 -0.03551477 -0.002283871 0.01007974 -0.03520083 -0.00173223 0.01080703 -0.03799998 -0.001786351 0.01072287 -0.03539788 -5.7229e-4 0.01194691 -0.03518587 -2.3994e-4 0.01223784 -0.03799617 5.74153e-4 0.01283651 -0.03499597 0.001295864 0.01333349 -0.03767359 0.00181359 0.0136156 -0.03497451 0.003188371 0.01426118 -0.03690367 0.003239333 0.01426476 -0.03462278 0.004967808 0.01481634 -0.03585642 0.004807233 0.01475971 -0.03446024 0.005526185 0.01492989 -0.03482162 0.0559659 -0.01007574 0.00154978 0.02301973 -0.01006782 -0.03177475 0.05360954 -0.01007133 -0.006813287 0.02715736 -0.01007449 -0.03011852 0.05606895 0.01492112 0.02559256 0.05520355 0.01475471 0.0259369 0.05427634 0.01406341 0.02713686 0.05387777 0.01341539 0.02805376 0.05367934 0.01269406 0.02892065 0.05367743 0.01092058 0.03059965 0.05367743 0.008336305 0.03216004 0.05367743 0.006122887 0.03296935 0.05367743 0.00370115 0.03341668 0.05367743 0.001023054 0.03339332 0.05367743 -0.001617074 0.03285467 0.05367743 -0.004098713 0.03180992 0.05367743 -0.006325721 0.03031516 0.05368292 -0.007978379 0.02868264 0.05409765 -0.008994817 0.02734673 0.05493241 -0.009778201 0.02602708 0.05592417 -0.0100786 0.02540117 0.05795258 0.01490682 0.01828294 0.05874764 0.01472008 0.01779204 0.05911016 0.01445055 0.01900613 0.0596826 0.01399385 0.01892626 0.06008052 0.01346611 0.01896148 0.06037092 0.01288527 0.01884907 0.060485 0.01236206 0.01896172 0.06041264 0.01199334 0.0195561 0.06066703 0.01233929 0.01672035 0.06038904 0.01318556 0.01709091 0.06003385 0.01378196 0.01688981 0.05948609 0.01431542 0.01690113 0.06046152 0.01302164 0.00454539 0.06067341 0.01231831 0.006244242 0.04874384 0.01491355 -0.01678293 0.04648762 0.01479524 -0.01963591 0.04713225 0.01429933 -0.02031803 0.04737472 0.01359534 -0.02095812 0.04905742 0.01473391 -0.01754081 0.04906517 0.01437723 -0.01844227 0.04754608 0.01290231 -0.02125388 0.04959279 0.01382178 -0.01878225 0.04765009 0.01224678 -0.02135986 0.04965233 0.01307046 -0.01933854 0.05415821 0.01491779 -0.009493112 0.04994362 0.01227766 -0.01934343 0.05118256 0.01447898 -0.01597785 0.05171245 0.01401364 -0.01625841 0.05190974 0.01479274 -0.01401406 0.05192452 0.01338237 -0.01673114 0.05167275 0.01243883 -0.01751971 0.05340284 0.01468312 -0.01240897 0.0534718 0.01428711 -0.01349854 0.05278038 0.01246196 -0.01622301 0.05354064 0.01341861 -0.01467174 0.05424344 0.01234561 -0.0143342 0.05498355 0.01484018 -0.008720636 0.0549885 0.01347512 -0.0124911 0.05513143 0.01413995 -0.01121503 0.05473935 0.0128746 -0.0133689 0.05571395 0.01452475 -0.009010791 0.05571711 0.01243889 -0.01203268 0.05617696 0.01354986 -0.01031672 0.0564773 0.0128141 -0.01047623 0.05719023 0.01382327 -0.007792234 0.0568602 0.01463699 -0.005833745 0.05699503 0.01220422 -0.009756922 0.05715751 0.01313161 -0.008874773 0.05727684 0.01435184 -0.006091892 0.05690681 0.01484811 -0.003844082 0.05825185 0.01290327 -0.006533861 0.05768078 0.01491266 0.001054465 0.05853158 0.01353979 -0.004819214 0.05834567 0.01216679 -0.006697595 0.05793511 0.01455438 -0.003075122 0.0585491 0.01406663 -0.003247261 0.05915105 0.01246196 -0.004244685 0.05914705 0.01360476 -0.002488672 0.05849462 0.01464217 1.90639e-4 0.05971902 0.01291728 -0.001599907 0.05912518 0.01420843 3.0455e-5 0.05959063 0.01374691 1.01504e-4 0.05983489 0.01218426 -0.001773357 0.05830287 0.01485097 0.004028081 0.05899465 0.01461178 0.004038691 0.06024801 0.01299184 0.00171113 0.05961585 0.01418483 0.003777146 0.06027972 0.01236701 7.50883e-4 0.06009268 0.01364517 0.003743708 0.06057798 0.01222366 0.003226161 0.02598661 0.01491415 -0.03408688 0.02709305 0.01479583 -0.03411471 0.02751374 0.01458239 -0.03446233 0.02767074 0.0142579 -0.03495383 0.02865731 0.01365721 -0.03496801 0.02830922 0.01300317 -0.03562188 0.02880305 0.01237404 -0.0354954 0.02122139 0.01211285 -0.03799462 0.0278061 0.01221358 -0.03614103 0.02716499 0.01300764 -0.03628438 0.02657169 0.01228219 -0.0367648 0.02754092 0.01375126 -0.03559732 0.02556109 0.0130214 -0.03697979 0.02500849 0.01236814 -0.03735208 0.02631235 0.01360529 -0.03633415 0.02588874 0.0141595 -0.03600317 0.02364099 0.0123254 -0.03770816 0.02507966 0.01377248 -0.03668892 0.02598327 0.01453435 -0.03537756 0.02384972 0.01304405 -0.03745985 0.02472043 0.01477074 -0.03534203 0.02253258 0.01214218 -0.03789788 0.02349072 0.01358497 -0.03725445 0.02458018 0.01448154 -0.03602635 0.02256172 0.01314312 -0.03764533 0.02371507 0.01403832 -0.03681898 0.02165156 0.01274991 -0.03787541 0.02282899 0.01490712 -0.03524684 0.02271032 0.01424223 -0.03678643 0.02162814 0.01391464 -0.03724014 0.02213031 0.01451015 -0.0364955 0.02130347 0.0133816 -0.03761857 0.02186924 0.01478791 -0.0358836 0.02136009 -0.001982748 -0.03799051 0.02136993 -0.001561403 -0.03799015 0.02117097 -0.002383053 -0.03799641 0.02134078 0.006420195 -0.03799128 0.02135491 0.007037341 -0.03799092 0.02118259 -0.00114417 -0.03799611 0.02107954 0.006022512 -0.03799819 0.021066 0.007482349 -0.03799849 0.02071928 -7.9092e-4 -0.0380004 0.02067083 0.005772411 -0.0380001 0.02064985 0.007723033 -0.03800004 0.06067776 -0.005463898 0.01630419 0.0606774 -0.006114363 0.01561212 0.0606774 -0.006487071 0.01480233 0.0606774 -0.006571531 0.01377755 0.0606774 -0.002980053 0.0114358 0.0606774 -0.004071712 0.01132607 0.0606774 -0.004869818 0.01152908 0.0606774 -0.005577862 0.01194566 0.0606774 -0.006238877 0.01273268 0.0606774 -0.001315951 0.01525723 0.0606774 0.006392478 0.01382374 0.0606774 0.007312238 0.01450419 0.06067758 -0.001949965 0.01611632 0.0606774 0.005905151 0.01310354 0.0606774 -0.001054644 0.01419293 0.0606774 0.005637645 0.0119695 0.0606774 -0.001226842 0.01311063 0.0606774 -0.001881003 0.01209139 0.0606774 0.005912899 0.01076614 0.0606774 0.008806943 0.01470452 0.0606774 0.009912669 0.0142681 0.0606774 0.006442308 0.0100218 0.0606774 0.01067912 0.01354944 0.0606774 0.007214367 0.009451091 0.0606774 0.01112687 0.01249748 0.0606774 0.01115357 0.01162707 0.0606774 0.01011556 0.009743392 0.0606774 0.009097218 0.009276032 0.0606774 0.008257269 0.009189128 0.0606774 0.01091933 0.01076823 0.06067472 -0.002717494 0.0166077 0.06066918 -0.003661453 0.01684254 0.06067252 -0.004623651 0.01671755 0.05941462 -0.005779623 0.02456152 0.05955594 -0.004683852 0.02385491 0.05921012 -0.0064345 0.02560323 0.0595743 -0.003383696 0.02376312 0.05851686 -0.002749681 0.02905046 0.05862051 -0.00192821 0.02853208 0.05984061 0.006456017 0.02243155 0.05952537 -0.002627015 0.02400779 0.05943667 -0.001940548 0.02445125 0.05994832 0.007212162 0.02189302 0.05964338 0.005825579 0.02341777 0.05923128 -0.001217424 0.02547824 0.05941128 0.005673527 0.02457839 0.05878698 -0.00131303 0.0276997 0.0589869 -0.001044154 0.02670007 0.05916208 0.00605756 0.02582436 0.06000423 0.008141934 0.02161347 0.05990099 0.01004391 0.02212983 0.05998247 0.009241998 0.02172225 0.05978661 0.01063579 0.02270156 0.0595892 0.01112216 0.02368861 0.0589807 0.00699371 0.02673125 0.05935591 0.01115566 0.02485525 0.05892074 0.007730305 0.02703088 0.05890005 0.008633494 0.02713435 0.05912774 0.01068526 0.02599602 0.05896687 0.009750306 0.02680045 0.0536769 0.01267147 0.002062857 0.05383968 0.01337057 0.002051949 0.05452537 0.01431405 0.001984834 0.02070552 -0.002720415 -0.03800028 0.003144562 0.007727265 -0.03799998 0.002705693 0.007497131 -0.03799998 0.002411365 0.007043957 -0.03799998 0.002426922 0.006370961 -0.03799998 0.002995729 -8.03558e-4 -0.03799998 0.002985119 0.005794703 -0.03799998 0.002528965 -0.001214623 -0.03799998 0.002357721 -0.001788735 -0.03799998 0.002608299 -0.002413392 -0.03799998 0.003109037 -0.002732276 -0.03799998 0.0274918 0.01490461 -0.0297212 0.02336156 0.01491498 -0.03181642 0.04748648 0.01280498 -0.01090627 0.04795718 0.01351284 -0.01080131 0.0486347 0.01280248 -0.009821712 0.04840099 0.01399582 -0.01082473 0.04843109 0.0145235 -0.01155716 0.04966372 0.01325571 -0.008862674 0.0493474 0.01443016 -0.01049697 0.04965871 0.01481914 -0.01134896 0.04979902 0.01272946 -0.008482992 0.0495792 0.01391428 -0.009483218 0.05055445 0.01491302 -0.01116734 0.05066931 0.01470345 -0.009729683 0.05061066 0.01281136 -0.007377028 0.05055058 0.01439344 -0.009060442 0.0507515 0.01393413 -0.00802356 0.05099081 0.01331609 -0.007064759 0.05130612 0.01277232 -0.006265521 0.0517143 0.01446896 -0.007600307 0.05200606 0.01476204 -0.00816214 0.05196309 0.01395219 -0.00613439 0.05175292 0.01355606 -0.005959928 0.05234658 0.01435261 -0.006251275 0.05213993 0.0127834 -0.004625022 0.05229163 0.01338404 -0.004681944 0.05377185 0.01491391 -0.006581902 0.05322951 0.01468974 -0.005672633 0.05288124 0.0127148 -0.002668678 0.05401843 0.01484215 -0.005050718 0.05296528 0.01399534 -0.004027545 0.05290794 0.0133205 -0.003042161 0.0533446 0.01439726 -0.004191994 0.05327808 0.01290267 -0.001239955 0.05347406 0.01393842 -0.002338171 0.05401468 0.01453483 -0.002864956 0.05366164 0.01353925 -4.74644e-4 0.05356264 0.01278299 4.92764e-4 0.05406403 0.0141164 -4.19865e-4 0.05371737 0.0133419 4.98557e-4 0.05575799 0.01491057 -3.63897e-4 0.05478435 0.01476347 -0.001706123 0.05463945 0.01457059 -3.73383e-4 0.0541796 0.01396232 0.001583158 0.05544906 0.01482629 0.001095592 0.05497395 0.01463013 0.001549363 0.02776294 0.0147131 -0.02868211 0.02767598 0.01443231 -0.02814602 0.02738869 0.013938 -0.02772891 0.02686709 0.01326382 -0.02766919 0.02684217 0.01276916 -0.02753484 0.0255509 0.01466739 -0.02991312 0.02627474 0.01434838 -0.02896541 0.02457845 0.01482403 -0.03079646 0.0260598 0.01387417 -0.02857691 0.025276 0.01338255 -0.02870833 0.02480441 0.01398873 -0.02933472 0.02406305 0.01450604 -0.03027117 0.02550303 0.01283353 -0.02838647 0.0222314 0.01482582 -0.03154963 0.02327907 0.0142275 -0.03016453 0.02379006 0.01369422 -0.02954095 0.0243076 0.012721 -0.02896881 0.0237199 0.01318782 -0.02931994 0.02171355 0.01452434 -0.03096097 0.02249264 0.01396179 -0.03015214 0.02236729 0.01326942 -0.02978056 0.02302604 0.01259332 -0.02944958 0.02130031 0.01391988 -0.03038227 0.02125364 0.01323753 -0.03002977 0.0214954 0.01266562 -0.02986252 0.004860877 0.01250272 -0.03233939 0.00525248 0.01301652 -0.03234475 0.005262613 0.01358675 -0.0325638 0.005289793 0.01409286 -0.03290987 0.005277693 0.01444464 -0.03331595 0.005337834 0.0147866 -0.03395384 0.05542296 -0.009975671 0.001545965 0.05482077 -0.009701013 0.001691102 0.05433571 -0.009305238 0.001508176 0.05405163 -0.008950829 0.001540899 0.05388182 -0.00860846 0.002014935 0.05368131 -0.007966935 0.002003908 0.05361652 -0.008072495 8.97596e-4 0.05342984 -0.007964909 -4.08851e-4 0.05366957 -0.008711338 -4.47389e-4 0.0545507 -0.009594917 3.64558e-4 0.05400657 -0.009213924 -5.06615e-4 0.05307537 -0.008069813 -0.002035498 0.05564916 -0.01007318 -0.001023471 0.05468142 -0.009820342 -0.001129329 0.05348521 -0.008913159 -0.001825928 0.05405139 -0.009505212 -0.001716792 0.05522495 -0.01001363 -0.001162767 0.05282819 -0.008213758 -0.003022015 0.05305355 -0.008804321 -0.003087103 0.05241793 -0.00802499 -0.003982663 0.05327612 -0.009320676 -0.003657221 0.05422765 -0.009902715 -0.00352168 0.05250984 -0.008906245 -0.00465244 0.05173027 -0.007816553 -0.005464076 0.05347651 -0.009648084 -0.004200637 0.05439871 -0.01003694 -0.004460632 0.05185794 -0.008481264 -0.005537927 0.05344051 -0.009902715 -0.005467951 0.05252939 -0.009516894 -0.005885362 0.05084604 -0.00782907 -0.007009029 0.05170726 -0.009052097 -0.006473362 0.05095577 -0.008375883 -0.007050216 0.0523591 -0.009902417 -0.007507145 0.05061793 -0.008861482 -0.007944345 0.04981911 -0.007940053 -0.008464336 0.05160617 -0.009494543 -0.007429838 0.04966378 -0.008530855 -0.008934617 0.050516 -0.009501934 -0.008975923 0.04863393 -0.007881999 -0.009812772 0.04955238 -0.008997678 -0.0094437 0.05092108 -0.00991863 -0.00961709 0.05053097 -0.01007127 -0.01113641 0.04791706 -0.008379161 -0.01067304 0.04917997 -0.009384095 -0.01032555 0.04748117 -0.007885754 -0.01090151 0.04806685 -0.00883305 -0.0108177 0.04955339 -0.009760499 -0.0106486 0.04790174 -0.009209394 -0.01130813 0.04816174 -0.009716868 -0.01185035 0.04903972 -0.009989678 -0.01195102 0.02758723 -0.009775102 -0.02857673 0.0271874 -0.009554862 -0.02845293 0.02732425 -0.009043991 -0.02773207 0.02718263 -0.008544325 -0.02749359 0.02710747 -0.007943868 -0.02733463 0.02126353 -0.007961034 -0.02991038 0.02612066 -0.007998883 -0.02802205 0.02622485 -0.008784174 -0.02828168 0.02494591 -0.008025467 -0.02868634 0.02647292 -0.009336709 -0.02861863 0.02397549 -0.007809996 -0.02911245 0.02502197 -0.008676826 -0.02889674 0.02517443 -0.00921899 -0.02921414 0.0272926 -0.009970784 -0.02935516 0.02370434 -0.008327841 -0.0293219 0.02516776 -0.009720861 -0.02987921 0.02379757 -0.008869409 -0.02954572 0.0224201 -0.007953822 -0.0296415 0.02406829 -0.009450733 -0.02994614 0.02244204 -0.008645117 -0.02986574 0.02520561 -0.01000016 -0.03058141 0.02285444 -0.009182691 -0.03010207 0.02255529 -0.009907007 -0.03124606 0.02200287 -0.009588122 -0.03077727 0.02120429 -0.008763015 -0.03019702 0.02132481 -0.009268939 -0.03054672 0.004658639 -0.008473038 -0.0325281 0.00463736 -0.00906974 -0.03285443 0.004650831 -0.009539186 -0.03332221 0.004737138 -0.009919643 -0.03395736 0.004787802 -0.01006877 -0.03461676 0.003516018 0.01426488 -0.0341776 0.001423358 0.01328748 -0.03446972 0.003523468 0.01263165 -0.03263145 8.23878e-4 0.01127874 -0.03308832 0.001643538 0.01122105 -0.03282445 -0.002627015 0.009430587 -0.03490114 -7.74814e-4 0.009788691 -0.03332054 -3.30003e-4 0.009471476 -0.03311252 -0.003418743 0.008140921 -0.03504776 -0.002048075 0.008030891 -0.03350573 -0.00154531 0.007977068 -0.03330761 -0.002994656 0.005919754 -0.03363674 -0.002545118 0.005696415 -0.03344255 -0.00488311 0.001966297 -0.03560441 -0.004527628 9.78962e-5 -0.03496271 -0.0036785 0.002154171 -0.03377574 -0.003080904 0.002769291 -0.03352105 -0.004311084 -0.001376569 -0.03538525 -0.003224849 4.95653e-4 -0.03360623 -0.003000438 -0.004172861 -0.03499674 -0.002418279 -0.00237286 -0.03350597 0.00105679 -0.00834763 -0.03447061 -0.00117582 -0.004892349 -0.03344833 -6.31193e-4 -0.004576146 -0.03317588 0.002492725 -0.009099602 -0.03422784 3.56685e-4 -0.006203055 -0.03315651 0.004060924 -0.009831368 -0.03446161 0.002229094 -0.00765711 -0.03293567 0.004315674 -0.007837772 -0.03243076 0.003832638 0.01411736 -0.03359979 0.004050254 0.0136407 -0.03297364 0.002318918 0.01319801 -0.03345191 0.001979291 0.01340222 -0.03399413 -6.81326e-4 0.01174497 -0.03474402 0.00220412 0.0125696 -0.03304338 4.07355e-4 0.01232767 -0.03404968 -0.001019835 0.0108751 -0.03404086 -0.001772761 0.0103603 -0.03449338 -0.001153826 0.009897172 -0.03354012 3.8398e-4 0.01169925 -0.03349429 -0.00234586 0.009249806 -0.03420853 -0.00250405 0.008402347 -0.03390908 -0.003975629 0.006614029 -0.03487354 -0.003004491 0.007216215 -0.03389549 -0.004432976 0.005184233 -0.03504425 -0.003454327 0.00597006 -0.03394567 -0.004078924 0.003805696 -0.03412985 -0.004712343 0.003644645 -0.03511023 -0.003583371 0.004179239 -0.03378725 -0.004647374 0.002226889 -0.03480684 -0.004197716 0.001736521 -0.03420269 -0.003839313 8.16593e-4 -0.03394448 -0.003893911 -0.002064883 -0.03481006 -0.003770351 -0.001645326 -0.03436243 -0.003137409 -0.002200305 -0.03391164 -0.002262055 -0.00157088 -0.03339511 -0.003386259 -0.003366947 -0.03487241 -0.002473473 -0.004670798 -0.03452485 -0.002213835 -0.003820002 -0.03373122 -0.001789152 -0.005824267 -0.03476339 -1.59846e-4 -0.006416857 -0.03350293 -4.61385e-4 -0.007207989 -0.0346651 -1.17797e-5 -0.007373094 -0.03423422 6.71093e-5 -0.007027626 -0.03376257 0.001485645 -0.007323801 -0.03309899 0.002811968 -0.008917152 -0.03361153 0.001804292 -0.00802505 -0.03334861 0.003639519 -0.008760154 -0.03300273 0.003511667 -0.009477198 -0.03397673 -0.003291189 0.007726967 -0.03444272 -0.00378865 0.006074786 -0.03430414 -0.004356563 0.004449963 -0.03458446 -0.004357576 7.35107e-4 -0.03448826 -0.003530681 -7.02783e-4 -0.03389149 -0.002540707 -0.004024088 -0.03408902 -9.80674e-4 -0.006320297 -0.03414726 -0.001582741 -0.005471825 -0.03404933 0.001490294 -0.008275866 -0.03383374 0.001377642 -0.006322503 -0.03286051 0.001933276 -0.003477036 -0.03276795 0.001382529 -0.002641797 -0.03284955 0.002977013 -0.004100263 -0.03261333 0.001223564 -0.001826405 -0.03287309 0.001333296 -0.001004457 -0.03285682 0.001698851 -3.21238e-4 -0.03280264 0.002244591 2.24898e-4 -0.03272181 0.001933276 0.005022943 -0.03276795 0.001382529 0.005858123 -0.03284955 0.002977013 0.004399657 -0.03261333 0.003174066 6.20356e-4 -0.03258413 0.001213073 0.006939291 -0.03287464 0.001662969 0.008180618 -0.032808 0.002574324 0.00891596 -0.03267294 0.00333631 0.009135127 -0.03256011 0.02069473 -0.004111588 -0.02999007 0.02069514 0.004388451 -0.02998995 0.02035325 6.3858e-4 -0.03003907 0.02110713 4.59247e-4 -0.02992475 0.02035325 0.009138524 -0.03003907 0.02110731 0.008959174 -0.02992457 0.02196913 0.008317232 -0.02974361 0.02168691 0.004894852 -0.02980923 0.02196902 -1.82635e-4 -0.02974361 0.02239149 0.007569372 -0.02963298 0.02168703 -0.003605008 -0.02980917 0.02254098 0.006830215 -0.02959072 0.0223658 0.005801856 -0.02964067 0.02239149 -9.3057e-4 -0.02963304 0.02254098 -0.001669764 -0.02959078 0.0223658 -0.002698063 -0.02964067 0.05367743 -0.005009591 0.0274263 0.05367743 -0.004447281 0.02786082 0.05367743 -0.005316793 0.02662301 0.05367743 -0.003867208 0.02800887 0.05367743 -0.003169596 0.02787429 0.05367743 -0.005173683 0.02585089 0.05367743 -0.002613842 0.02743178 0.05367743 -0.002361714 0.0269311 0.05367743 -6.50328e-4 0.02197951 0.05367743 -0.002821505 0.02534765 0.05367743 5.06857e-4 0.02287673 0.05367743 -0.002462327 0.02581107 0.05367743 -0.00360006 0.02498131 0.05367743 -0.001387536 0.02079415 0.05367743 -0.002296209 0.02637338 0.05367743 -0.004599273 0.02519428 0.05367743 0.001715183 0.02325654 0.05367743 -0.001657366 0.01959586 0.05367743 0.003009974 0.02326631 0.05367743 -0.005031108 0.0149796 0.05367743 -0.004447221 0.01546645 0.05367743 -0.005343854 0.01421737 0.05367743 -0.001605033 0.01860004 0.05367743 -0.003594517 0.01557874 0.05367743 -0.001248776 0.0174905 0.05367743 -0.003003478 0.01534354 0.05367743 0.007221221 0.02526932 0.05367743 0.007739961 0.02571696 0.05367743 0.006934583 0.0246188 0.05367743 0.004322826 0.02278798 0.05367743 0.008330762 0.02586984 0.05367743 -5.94896e-4 0.0165705 0.05367743 -0.002538144 0.01489216 0.05367743 0.008889079 0.02580958 0.05367743 0.006984651 0.02394759 0.05367743 0.005428314 0.02188533 0.05367743 0.00723654 0.0234462 0.05367743 4.42365e-4 0.01573884 0.05367743 0.00946933 0.02546864 0.05367743 -0.002325117 0.01426613 0.05367743 0.007720291 0.02303361 0.05367743 0.009793341 0.02501112 0.05367743 0.006162941 0.02054625 0.05367743 -0.002398073 0.01352077 0.05367743 0.009949207 0.02440637 0.05367743 0.008332192 0.02286148 0.05367743 0.006361663 0.01896232 0.05367743 0.009166002 0.02302181 0.05367743 -0.005188882 0.0134468 0.05367743 -0.004794955 0.01291531 0.05367743 -0.004167139 0.01260888 0.05367743 -0.003557145 0.01259064 0.05367743 0.007508099 0.01316571 0.05367743 0.004063069 0.01564854 0.05367743 0.005264043 0.01654297 0.05367743 0.00703597 0.01256996 0.05367743 0.008127927 0.01342785 0.05367743 0.005945801 0.01752644 0.05367743 0.006906688 0.01194751 0.05367743 0.002241849 0.0152592 0.05367743 0.008801698 0.01341682 0.05367743 0.00702393 0.01136082 0.05367743 -0.002935588 0.01284903 0.05367743 0.0094527 0.01304894 0.05367743 0.007533133 0.01069808 0.05367743 0.009779214 0.02367806 0.05367743 0.009901344 0.0123142 0.05367743 0.008390784 0.01043307 0.05367743 0.009854853 0.01149225 0.05367743 0.008941054 0.01053929 0.05367743 0.009477972 0.01085984 0.02051097 -0.002749919 -0.0345 0.02093261 -0.002605378 -0.0345 0.02132612 -0.002129912 -0.0345 0.02137565 -0.001604139 -0.0345 0.02118849 -0.001142144 -0.0345 0.02069145 -7.86273e-4 -0.0345 0.003366947 -0.004145562 -0.0345 0.002627015 -0.003952741 -0.0345 0.001944839 -0.00347501 -0.0345 0.001452386 -0.002800703 -0.0345 0.001218676 -0.001878976 -0.0345 0.001312017 -0.001109659 -0.0345 0.001639962 -3.85258e-4 -0.0345 0.002418577 3.43719e-4 -0.0345 0.003305792 6.31514e-4 -0.0345 0.02061736 6.15586e-4 -0.0345 0.02154999 1.9954e-4 -0.0345 0.02218931 -4.93651e-4 -0.0345 0.02254444 -0.00151515 -0.0345 0.02244406 -0.002413213 -0.0345 0.02212375 -0.00311923 -0.0345 0.02152723 -0.003717303 -0.0345 0.0206626 -0.004118978 -0.0345 0.003231406 -7.6134e-4 -0.0345 0.002816796 -9.13783e-4 -0.0345 0.002473711 -0.001309156 -0.0345 0.002369821 -0.001873075 -0.0345 0.00258696 -0.002377092 -0.0345 0.00304538 -0.00271821 -0.0345 0.003158271 0.007730245 -0.0345 0.002717971 0.00750792 -0.0345 0.002423286 0.007075369 -0.0345 0.002382159 0.006628036 -0.0345 0.002525389 0.006202816 -0.0345 0.003020524 0.005787551 -0.0345 0.02051097 0.00575006 -0.0345 0.02061736 0.009115576 -0.0345 0.02154999 0.008699536 -0.0345 0.02218931 0.008006334 -0.0345 0.02254444 0.006984829 -0.0345 0.02244406 0.006086707 -0.0345 0.02212375 0.00538069 -0.0345 0.02152723 0.004782617 -0.0345 0.0206626 0.004381 -0.0345 0.02093261 0.005894541 -0.0345 0.02132612 0.006370007 -0.0345 0.02137565 0.00689578 -0.0345 0.02118849 0.007357835 -0.0345 0.02069145 0.007713675 -0.0345 0.001498043 0.005590617 -0.0345 0.00222212 0.004781961 -0.0345 0.003137946 0.004377365 -0.0345 0.001218676 0.006620943 -0.0345 0.001312017 0.00739026 -0.0345 0.001639962 0.008114695 -0.0345 0.002418577 0.00884366 -0.0345 0.003305792 0.009131491 -0.0345 0.0566889 -0.004252016 0.01134854 0.0566889 -0.003781318 0.01254993 0.0566889 -0.003224432 0.01137518 0.0566889 -0.004741787 0.01286029 0.0566889 -0.005344748 0.01175588 0.0566889 -0.002399206 0.01171576 0.0566889 -0.002967059 0.01282817 0.0566889 -0.006231427 0.01270955 0.0566889 -0.001557469 0.01245248 0.0566889 -0.005232036 0.01353639 0.0566889 -0.002547085 0.01327085 0.0566889 -0.006576061 0.01382249 0.0566889 -0.002319812 0.01386505 0.0566889 -0.001079916 0.01368778 0.0566889 -0.006474971 0.01484549 0.0566889 -0.005317449 0.01439303 0.0566889 -0.001143336 0.01478236 0.0566889 -0.002400636 0.01460856 0.0566889 -0.006014406 0.01576507 0.0566889 -0.001626789 0.01576644 0.0566889 -0.002800822 0.01519548 0.0566889 -0.005133569 0.01651942 0.0566889 -0.004746258 0.01529985 0.0566889 -0.002382159 0.01643675 0.0566889 -0.003316283 0.01549887 0.0566889 -0.003908216 0.01558792 0.0566889 -0.004030108 0.01683735 0.0566889 -0.003139376 0.01675021 0.0566889 -0.00435692 0.02376854 0.0566889 -0.003915965 0.02498775 0.0566889 -0.003054976 0.02383369 0.0566889 -0.004524111 0.02517306 0.0566889 -0.003119528 0.02513808 0.0566889 -0.005530118 0.02433538 0.0566889 -0.002140939 0.02429014 0.0566889 -0.005091667 0.02567994 0.0566889 -0.006273686 0.02523678 0.0566889 -0.002465248 0.02576988 0.0566889 -0.001360654 0.02517306 0.0566889 -0.005322456 0.02657306 0.0566889 -0.006575286 0.02644187 0.0566889 -0.001039326 0.02636408 0.0566889 -0.002291917 0.02654838 0.0566889 -0.006348133 0.02758777 0.0566889 -0.001244425 0.02758121 0.0566889 -0.005109846 0.02725136 0.0566889 -0.002463459 0.0271992 0.0566889 -0.005730688 0.02848351 0.0566889 -0.001975059 0.02857518 0.0566889 -0.00304979 0.02782958 0.0566889 -0.004629075 0.02777516 0.0566889 -0.004946649 0.0290094 0.0566889 -0.002803504 0.02907109 0.0566889 -0.003901362 0.02927339 0.0566889 -0.003891527 0.02800768 0.0566889 0.007684111 0.02170222 0.0566889 0.008721649 0.02287715 0.0566889 0.007938623 0.02293527 0.0566889 0.008781433 0.02162265 0.0566889 0.006705522 0.02220535 0.0566889 0.01000052 0.02206724 0.0566889 0.007398784 0.0232706 0.0566889 0.009343385 0.02316606 0.0566889 0.006084084 0.02291822 0.0566889 0.007054805 0.02374565 0.0566889 0.01085984 0.02303946 0.0566889 0.009859621 0.02380836 0.0566889 0.005720138 0.02381092 0.0566889 0.006917059 0.02446842 0.0566889 0.01118671 0.02408778 0.0566889 0.005719006 0.02491223 0.0566889 0.00990355 0.0247305 0.0566889 0.0110771 0.02518194 0.0566889 0.006252348 0.02610093 0.0566889 0.007125854 0.02512139 0.0566889 0.01070529 0.0259242 0.0566889 0.009519696 0.02542948 0.0566889 0.007636725 0.02566856 0.0566889 0.009993314 0.0266717 0.0566889 0.00729084 0.02688884 0.0566889 0.008970797 0.02577364 0.0566889 0.008569121 0.0271486 0.0566889 0.008419513 0.02588021 0.0566889 0.007620811 0.009291827 0.0566889 0.008554518 0.0104472 0.0566889 0.007995724 0.01049798 0.0566889 0.008921325 0.009216487 0.0566889 0.009208559 0.01065176 0.0566889 0.007344424 0.01086682 0.0566889 0.006712496 0.009776473 0.0566889 0.01008969 0.009739995 0.0566889 0.00614804 0.01037496 0.0566889 0.009703457 0.01116186 0.0566889 0.01079851 0.01054853 0.0566889 0.00698316 0.01147872 0.0566889 0.005754351 0.01119822 0.0566889 0.009917259 0.01176059 0.0566889 0.006910324 0.01214861 0.0566889 0.01119017 0.01171875 0.0566889 0.005665957 0.01229155 0.0566889 0.009863197 0.01236844 0.0566889 0.006107032 0.01349347 0.0566889 0.010944 0.01309025 0.0566889 0.007228791 0.01289379 0.0566889 0.009568035 0.01293206 0.0566889 0.01034104 0.01392388 0.0566889 0.006972908 0.01430678 0.0566889 0.007816433 0.01333677 0.0566889 0.009553551 0.0144729 0.0566889 0.009091436 0.01329332 0.0566889 0.007867157 0.01465547 0.0566889 0.008515954 0.01346015 0.0566889 0.008668303 0.01469331 0.05531597 0.002234876 0.01530826 0.05530774 0.002821266 0.01532942 0.05552071 0.002831339 0.01544165 0.05567133 0.002485692 0.01566869 0.05560672 0.003068327 0.01559185 0.0553199 0.003568351 0.01549804 0.05551415 0.003939449 0.0157541 0.05527997 0.004099905 0.01570647 0.05566972 0.003792285 0.01596939 0.05530744 0.004569053 0.01598161 0.05560272 0.004350244 0.01609617 0.05555576 0.004768371 0.01630914 0.05529499 0.004928231 0.01625233 0.05532801 0.005278646 0.01659411 0.05567222 0.005014598 0.01685661 0.05554038 0.005366146 0.01690155 0.05533599 0.005591571 0.01698744 0.05531859 0.005903124 0.01748543 0.0555194 0.005803704 0.01755845 0.05566638 0.005532324 0.0174995 0.05543792 0.00613445 0.01821291 0.05525588 0.006218671 0.01829862 0.05561351 0.005969882 0.01829755 0.05530774 0.006323993 0.01899749 0.05555468 0.006179451 0.01903474 0.05567264 0.005931019 0.01894032 0.0553106 0.006318867 0.01967984 0.05559957 0.006103038 0.01971578 0.05550187 0.006182014 0.01994508 0.05528962 0.006167471 0.0204606 0.05567467 0.005801856 0.02034664 0.05555468 0.005986213 0.02052217 0.05543887 0.005941629 0.02088493 0.05527007 0.005807936 0.02130228 0.05560052 0.005716919 0.02100533 0.05546009 0.00548458 0.02165526 0.05529147 0.005197882 0.02209913 0.05560594 0.005224108 0.02174359 0.05567169 0.005071163 0.0216763 0.05551803 0.004751682 0.0223397 0.05527287 0.004506647 0.02266126 0.05544346 0.004470825 0.02260559 0.05564832 0.004359781 0.02238076 0.05532616 0.003922939 0.02295887 0.05560457 0.003681838 0.02283358 0.05549186 0.003590524 0.02298855 0.05533301 0.003373563 0.02314651 0.05567657 0.003203332 0.02279835 0.0553168 0.00296384 0.02323704 0.05556994 0.00285387 0.02308553 0.05525118 0.002434551 0.02329772 0.05543273 0.002473592 0.0232315 0.05541694 0.001854479 0.02321457 0.05527031 0.001527011 0.0232166 0.05561572 0.002174139 0.02305233 0.05553722 0.001385986 0.02304023 0.05566865 0.001387298 0.02280354 0.0552417 7.18659e-4 0.02295553 0.05541807 7.37255e-4 0.02290302 0.05557441 6.94678e-4 0.02273648 0.05527675 7.64463e-5 0.02259445 0.05542176 1.38313e-4 0.02256584 0.05567163 1.17305e-4 0.02217191 0.05555963 6.49954e-6 0.0223419 0.05531811 -3.90233e-4 0.02220249 0.05529373 -8.25722e-4 0.02173399 0.05561399 -3.46971e-4 0.02192199 0.05546396 -7.28048e-4 0.02173811 0.05557954 -8.42327e-4 0.02138352 0.05529081 -0.001186966 0.02117067 0.05567175 -8.58005e-4 0.02097493 0.05544179 -0.001247406 0.02091985 0.05528289 -0.001521348 0.02034002 0.05565309 -0.001101493 0.0206384 0.05552119 -0.001346409 0.02047777 0.0554924 -0.001501083 0.01993012 0.05529803 -0.001640796 0.01959192 0.05561435 -0.001383364 0.01978933 0.05551528 -0.001535892 0.01934647 0.05529636 -0.001635611 0.01892387 0.05567562 -0.001239001 0.01899957 0.0554986 -0.001499235 0.01863694 0.05563777 -0.001333177 0.01870203 0.05526924 -0.001506268 0.0181936 0.05545401 -0.001286089 0.01779454 0.05528348 -0.001207709 0.01746219 0.05558437 -0.001110196 0.01770043 0.05567216 -8.99905e-4 0.01769888 0.05525755 -9.08662e-4 0.01696723 0.05545771 -9.5202e-4 0.01716822 0.05546003 -5.48542e-4 0.01664036 0.05560398 -6.65232e-4 0.01701539 0.05527687 -4.36627e-4 0.01641929 0.05567413 -5.08023e-5 0.01660001 0.05561488 -2.11935e-4 0.01654636 0.05529242 1.58165e-4 0.01594793 0.05554354 1.3325e-4 0.01613062 0.05532866 7.09243e-4 0.01565587 0.05551815 0.001038253 0.01563984 0.05564534 0.001080572 0.01580661 0.05527931 0.001330256 0.01542949 0.05532413 0.001762747 0.01535046 0.05552977 0.001880347 0.01545822 0.05566877 0.001866459 0.01569461 0.05352729 9.5306e-4 0.01965421 0.05341476 0.001021981 0.02008217 0.05366206 9.53081e-4 0.01998323 0.053869 8.18481e-4 0.01961719 0.05396568 8.56928e-4 0.02023404 0.05371594 0.001060783 0.02034139 0.05408459 6.70398e-4 0.01994264 0.05348217 0.001204848 0.02047872 0.05353915 0.001427412 0.0207532 0.05408293 9.94079e-4 0.02070754 0.05381155 0.001233756 0.02068471 0.05430239 4.65796e-4 0.02060115 0.0541982 6.61711e-4 0.02043688 0.05352044 0.001729011 0.0209729 0.05393648 0.001520395 0.02105331 0.0541917 0.001368343 0.02127414 0.05371934 0.001596033 0.02095592 0.05423384 9.80229e-4 0.02103984 0.05353116 0.00200206 0.02109014 0.05405986 0.001755356 0.02130669 0.05385357 0.001995921 0.0212146 0.05352717 0.002351522 0.02115899 0.05434298 0.001077115 0.02155065 0.05431878 0.001412272 0.0216304 0.05349272 0.002726078 0.02113825 0.05392658 0.002310693 0.02132773 0.05422413 0.001996278 0.02161377 0.05412292 0.002316057 0.02150809 0.05372869 0.002522468 0.02122288 0.0535075 0.003034651 0.0210489 0.05376076 0.002855539 0.02118569 0.05407834 0.002740323 0.02143812 0.05352163 0.003311514 0.02090424 0.0543071 0.002098381 0.02184081 0.05378854 0.003177523 0.02108591 0.05434381 0.00246793 0.02202177 0.05425745 0.002963602 0.02166354 0.05405151 0.003100752 0.02131819 0.053532 0.003621995 0.02063184 0.05434048 0.003385484 0.02182322 0.05380505 0.003534913 0.0208562 0.0540117 0.003467202 0.02108961 0.05421602 0.00345236 0.02138406 0.05407327 0.003884792 0.02077478 0.0538612 0.00384128 0.02054429 0.0535196 0.003810584 0.02034389 0.05418288 0.003811597 0.02105909 0.05431354 0.003967046 0.02130222 0.05348092 0.003969728 0.01984864 0.05400824 0.004029273 0.02043032 0.05379724 0.00396043 0.02022415 0.05371594 0.004001319 0.01996928 0.05423104 0.004238665 0.0206201 0.0543428 0.004683673 0.02054172 0.05408799 0.004249215 0.02003097 0.05398702 0.004202008 0.01972764 0.05381751 0.004077315 0.01948374 0.05425912 0.004526078 0.01995915 0.05359172 0.003963351 0.01937526 0.0542075 0.004426538 0.01929873 0.05351835 0.003843069 0.01901906 0.05371803 0.003820776 0.01885253 0.05429899 0.00465095 0.01948082 0.05403614 0.004155099 0.01910847 0.05355572 0.003607213 0.01864838 0.05400764 0.003948211 0.01873797 0.05425804 0.004225552 0.01854741 0.05353468 0.003352284 0.01842302 0.05391353 0.003640413 0.01846241 0.05352574 0.003073334 0.01826506 0.05434304 0.004730463 0.01887172 0.05420982 0.003826141 0.01820212 0.05383652 0.003255188 0.01822507 0.05404084 0.003372013 0.01811569 0.05350637 0.002745091 0.01816266 0.05434882 0.003604412 0.01742613 0.05386573 0.002515673 0.01801365 0.05433207 0.003861308 0.01779657 0.05425226 0.003248929 0.01773786 0.0540632 0.002755701 0.01786637 0.05383449 0.002830147 0.01806551 0.05354082 0.00242263 0.01813507 0.05355805 0.002066552 0.01818609 0.05432271 0.003007948 0.01744949 0.05384624 0.002137839 0.01804929 0.05423194 0.002588689 0.0176258 0.05404257 0.002068459 0.01791334 0.05358177 0.001674294 0.01834982 0.05421799 0.001895606 0.01772153 0.05434674 0.002135813 0.01724338 0.05428671 0.002142429 0.0175268 0.05351632 0.001435935 0.01854187 0.05393826 0.001618027 0.01818776 0.05413067 0.001559615 0.0180059 0.05352306 0.001242458 0.01876264 0.05390709 0.00127995 0.0184797 0.0542671 0.001385688 0.01783841 0.05392336 0.001042366 0.01877421 0.05350512 0.001069962 0.01906496 0.0541318 0.001078903 0.01837265 0.05434221 0.001030504 0.01776748 0.05385798 9.14944e-4 0.01912474 0.0542851 7.67417e-4 0.01834845 0.05352181 9.75405e-4 0.01939058 0.05409181 7.32464e-4 0.01904612 0.05425387 4.87703e-4 0.01902306 0.05434602 2.87121e-4 0.0186311 0.05415707 5.61716e-4 0.01961314 0.0543096 2.4795e-4 0.01961839 0.05434691 9.15364e-5 0.02039551 0.04884999 0.00120449 0.02049517 0.04884999 0.001702129 0.02094942 0.04884999 0.002229154 0.02114099 0.04884999 0.002901017 0.02110153 0.04884999 0.003454566 0.02078801 0.04884999 0.003842234 0.02028435 0.04884999 0.003978073 0.01954895 0.04884999 0.00377953 0.01890558 0.04884999 0.003329813 0.0184049 0.04884999 0.00270307 0.01815897 0.04884999 0.001994192 0.01820659 0.04884999 0.001283884 0.01869124 0.04884999 9.36837e-4 0.01959925 0.05434995 -1.07712e-4 0.02203822 0.05434995 8.58154e-4 0.02278643 0.05434995 -7.41407e-4 0.0210973 0.05434995 0.0020563 0.02313852 0.05434995 -0.001062154 0.01970952 0.05434995 0.003014981 0.02311533 0.05434995 -7.97741e-4 0.01833921 0.05434995 0.004152774 0.02274721 0.05434995 -2.07073e-4 0.01737141 0.05434995 0.005371212 0.02166527 0.05434995 6.55856e-4 0.01663434 0.05434995 0.001968264 0.01615643 0.05434995 0.00598669 0.02000224 0.05434995 0.003447294 0.0162667 0.05434995 0.005798697 0.01853024 0.05434995 0.004538476 0.01681387 0.05434995 0.005282402 0.01755076 0.05334997 -0.00802809 0.02057254 0.05335003 -0.01030111 0.02124994 0.05334997 -0.007324576 0.02097368 0.05334997 -0.008349001 0.01993906 0.05335003 -0.009215474 0.02502191 0.05334997 -0.00833851 0.01930648 0.05334997 -0.006528437 0.02090746 0.05334997 -0.01024222 0.01794445 0.05334997 -0.007911264 0.01860433 0.05334997 0.001415908 0.02850157 0.05335003 -0.001934647 0.03174114 0.05334997 0.001893401 0.02886378 0.05335003 0.001826763 0.03246307 0.05334997 0.00113368 0.02786183 0.05334997 0.002477109 0.02900201 0.05334997 -0.005273044 0.02986717 0.05334997 0.001186251 0.02723139 0.05334997 0.004375696 0.03231883 0.05334997 0.003210663 0.02878236 0.05334991 -0.009544134 0.01518917 0.05334991 0.00637871 0.03185707 0.05334997 0.003651738 0.02828341 0.05334997 -0.007044911 0.01829135 0.05334997 0.003814101 0.02770632 0.05334991 0.00894469 0.03070324 0.05334997 2.76724e-4 0.02303987 0.05334991 -0.007294178 0.02794951 0.05334997 -8.11275e-4 0.02196806 0.05334991 -0.008581817 0.01314198 0.05334997 -0.005951762 0.02045589 0.05334997 -0.001373171 0.02083426 0.05334997 0.001494646 0.02671754 0.05334997 0.00176841 0.02360677 0.05334997 -0.005714178 0.0199058 0.05334997 0.002088367 0.02634841 0.05334997 -0.001548588 0.01954984 0.05334997 -0.005729079 0.01930648 0.05334997 0.002964854 0.02363002 0.05334997 0.002864956 0.02635699 0.05334997 -0.001337647 0.01837193 0.05334997 0.004118621 0.02331233 0.05334997 0.003454506 0.02673292 0.05334997 -0.006164193 0.01859605 0.05334991 0.01100641 0.02920043 0.05334997 0.003722071 0.02718186 0.05334997 -7.01381e-4 0.01716506 0.05334997 0.005250036 0.02254962 0.05335003 -0.006462872 0.01041442 0.05335003 0.01288247 0.02713888 0.05334997 0.00161153 0.01268482 0.05334997 4.28894e-4 0.01618474 0.05334997 0.001932442 0.01565247 0.05334997 0.001272857 0.01227396 0.05334997 0.002273559 0.01300269 0.05334997 0.001108944 0.01147991 0.05335003 -0.003669381 0.008383274 0.05334997 0.003426551 0.01575219 0.05334997 0.003153264 0.01281809 0.05334997 0.01115351 0.02072268 0.05334997 0.00597316 0.02159398 0.05334997 0.01077288 0.02027398 0.05334997 0.00639975 0.02047747 0.05334991 -0.001084625 0.007339894 0.05334997 0.01183068 0.02100312 0.05335003 0.01451808 0.02409678 0.05334997 0.01062858 0.01976078 0.05334997 0.004357099 0.01611828 0.05334997 0.003618657 0.01234173 0.05334997 0.006433069 0.01895052 0.05334997 0.01073384 0.01906895 0.05334997 0.01256006 0.02085846 0.05334997 0.005986511 0.01773291 0.05334997 0.005274176 0.01677095 0.05334997 0.001588702 0.01060432 0.05334997 0.01517868 0.02124309 0.05334997 0.01300269 0.02050578 0.05334997 0.001462519 0.006869614 0.05334997 0.01326525 0.02000421 0.05334997 0.01525926 0.01869118 0.05334997 0.01327288 0.01928228 0.05334997 0.002354443 0.0103054 0.05334991 0.004411101 0.006971538 0.05334997 0.003053188 0.01043087 0.05334997 0.01285946 0.01863771 0.05335003 0.01446831 0.01503837 0.05334997 0.01215761 0.01830488 0.05334997 0.003628253 0.01095277 0.05334991 0.007224917 0.007754564 0.05334997 0.01133805 0.01844906 0.05335003 0.01020646 0.009397864 0.05334997 0.01288676 0.01215797 0.05334997 0.003818571 0.01171749 0.05234962 0.002662539 0.005847752 0.05234968 5.98236e-4 0.005956053 0.05235427 -0.00160396 0.006454885 0.05235165 -0.003527283 0.007204473 0.05234575 -0.005354106 0.008266389 0.05235421 -0.006949186 0.009545862 0.05234968 -0.008641123 0.01142561 0.05235189 -0.009850621 0.01340162 0.05234611 -0.01074814 0.0156123 0.05234771 -0.01116931 0.01748853 0.05234611 -0.01135122 0.01968669 0.05235165 -0.01113742 0.02204871 0.05235427 -0.01062333 0.02404785 0.05235165 -0.009826004 0.02595186 0.0523501 -0.008355498 0.02826029 0.05234771 -0.006747364 0.02993148 0.05234217 -0.004952847 0.03131073 0.05234915 -0.002640664 0.03249377 0.05235278 -4.86414e-5 0.03323692 0.05235165 0.002466142 0.03346347 0.05234611 0.004829347 0.0332638 0.05234098 0.007852613 0.03239703 0.05234217 0.01061034 0.03081631 0.05234932 0.0124759 0.02916556 0.05234819 0.01367771 0.02771043 0.05235165 0.01475834 0.02595186 0.05234968 0.01571649 0.02357947 0.05235278 0.01622635 0.02090919 0.052338 0.01619702 0.01792931 0.05234956 0.01539868 0.01474893 0.05234587 0.01383471 0.01178354 0.05234611 0.01214021 0.009784221 0.05234587 0.009886324 0.007985234 0.05234467 0.007123649 0.006623923 0.05234932 0.004349052 0.005967974 0.04884999 0.003154397 0.00585854 0.04884999 0.005446314 0.006154119 0.04884999 0.008152067 0.007048666 0.04884999 0.01024478 0.008240818 0.04884999 0.01186186 0.009523808 0.04884999 0.01331746 0.01110643 0.04884999 0.01465034 0.01312583 0.04884999 0.01588213 0.0162338 0.04884999 0.01627552 0.01930564 0.04884999 0.01611781 0.02180629 0.04884999 0.01530545 0.0248003 0.04884999 0.0136947 0.02772277 0.04884999 0.01168417 0.02994781 0.04884999 0.009460985 0.03157019 0.04884999 0.006545066 0.03287374 0.04884999 0.00315535 0.03346216 0.04884999 8.10064e-4 0.03335416 0.04884999 -0.001183032 0.0329805 0.04884999 -0.004152238 0.03180325 0.04884999 -0.007018923 0.02972006 0.04884999 -0.009210467 0.02706819 0.04884999 -0.0106799 0.02395749 0.04884999 -0.01124811 0.02128159 0.04884999 -0.01132452 0.01861649 0.04884999 -0.01085168 0.0159924 0.04884999 -0.00998944 0.0136516 0.04884999 -0.008491754 0.01122725 0.04884999 -0.006864368 0.009467422 0.04884999 -0.004744946 0.007849514 0.04884999 -0.001936793 0.006545126 0.04884999 8.44502e-4 0.005924463 0.05314999 -2.48537e-4 0.02262294 0.05314999 -3.40418e-4 0.02177584 0.05314999 7.53557e-4 0.02273535 0.05314999 -0.001091837 0.02150893 0.05314999 0.001119375 0.02344399 0.05314999 -9.40568e-4 0.02054643 0.05314999 -0.001488804 0.02034735 0.05314999 0.001942992 0.02312058 0.05314999 0.002366185 0.02365726 0.05314999 -0.001025497 0.01921242 0.05314999 -0.001492857 0.01891928 0.05314999 0.002990067 0.02312636 0.05314999 0.003358602 0.02356058 0.05314999 -5.75617e-4 0.017861 0.05314999 0.004385709 0.0226221 0.05314999 0.004413187 0.02316051 0.05314999 -9.94769e-4 0.01761597 0.05314999 0.005264997 0.02251952 0.05314999 -3.8187e-4 0.01683264 0.05314999 3.43414e-4 0.01684755 0.05314999 0.005486547 0.02146273 0.05314999 3.99496e-4 0.01620846 0.05314999 0.005944073 0.021658 0.05314999 0.001651406 0.01620942 0.05314999 0.001505672 0.01575219 0.05314999 0.00591433 0.02031934 0.05314999 0.006378293 0.02054291 0.05314999 0.002999782 0.01565247 0.05314999 0.006458759 0.01908099 0.05314999 0.005952537 0.01918512 0.05314999 0.003049314 0.01618617 0.05314999 0.005653321 0.01818299 0.05314999 0.004203081 0.01658529 0.05314999 0.004322111 0.01609557 0.05314999 0.005988836 0.01773166 0.05314999 0.00513935 0.01737141 0.05314999 0.005271553 0.0167737 0.04884999 -0.007364928 0.02095001 0.04884999 -0.007931292 0.02066695 0.04884999 -0.00829631 0.02010947 0.04884999 -0.008375048 0.0194478 0.04884999 -0.008060276 0.01877439 0.04884999 -0.007546842 0.01840496 0.04884999 -0.007023274 0.01830786 0.04884999 -0.006405711 0.01844906 0.04884999 -0.005838394 0.01901155 0.04884999 -0.00568968 0.01966071 0.04884999 -0.005862772 0.02033895 0.04884999 -0.00631535 0.02078151 0.04884999 -0.006810307 0.02098053 0.04884999 0.002199411 0.01296901 0.04884999 0.001718819 0.01276481 0.04884999 0.001314103 0.01235395 0.04884999 0.001104414 0.01153665 0.04884999 0.001501262 0.01069337 0.04884999 0.002049088 0.01037615 0.04884999 0.002577841 0.0103054 0.04884999 0.003207266 0.0105226 0.04884999 0.003618657 0.01095825 0.04884999 0.003803551 0.01149332 0.04884999 0.003755211 0.01202362 0.04884999 0.003452003 0.01257985 0.04884999 0.002821028 0.01295161 0.04884999 0.002090156 0.02894568 0.04884999 0.001516282 0.02860814 0.04884999 0.001161634 0.02800554 0.04884999 0.001161396 0.02730649 0.04884999 0.001463711 0.02675086 0.04884999 0.00201404 0.02637571 0.04884999 0.002666652 0.02631926 0.04884999 0.003254234 0.0265538 0.04884999 0.003686368 0.02707445 0.04884999 0.003813028 0.02772814 0.04884999 0.003579616 0.02842253 0.04884999 0.002889394 0.02894496 0.04884999 0.01185441 0.02099454 0.04884999 0.01110798 0.02070814 0.04884999 0.01066553 0.02001589 0.04884999 0.01064372 0.01941674 0.04884999 0.01085758 0.0188809 0.04884999 0.01138943 0.01842707 0.04884999 0.01197665 0.01830786 0.04884999 0.01249915 0.01841342 0.04884999 0.01299893 0.01878333 0.04884999 0.01331543 0.01948088 0.04884999 0.01321488 0.02014011 0.04884999 0.01290881 0.02061647 0.04884999 0.01241523 0.02091473 0.05805802 -0.003442943 0.02520078 0.05806976 -0.004770517 0.02556014 0.05816763 -0.003411114 0.02506738 0.0582087 -0.004843711 0.02548921 0.05807036 -0.005089938 0.02691984 0.05820792 -0.005186855 0.02694767 0.05806827 -0.004071772 0.02787232 0.05820602 -0.004095554 0.02797347 0.05807083 -0.002733767 0.02747398 0.05820989 -0.002660989 0.02754241 0.05805742 -0.002461552 0.02612721 0.05816447 -0.002328872 0.02608728 0.05973911 -0.002634465 0.02756798 0.05973821 -0.00228542 0.02607417 0.05973839 -0.00410372 0.02800804 0.05973875 -0.005221068 0.02695971 0.05973917 -0.004870951 0.02546381 0.05973869 -0.003399848 0.02502298 0.05974853 -0.006245851 0.0262205 0.05099886 -0.005011439 0.02678322 0.05101317 -0.004973709 0.02610158 0.05099993 -0.005187869 0.0261842 0.05099993 -0.005126535 0.02704763 0.05099946 -0.005015194 0.02574539 0.05101704 -0.004655778 0.02741712 0.05099964 -0.004904448 0.0274446 0.05100005 -0.004634857 0.02545565 0.05099982 -0.004601418 0.0253027 0.05100476 -0.004166543 0.02772462 0.05099272 -0.003985464 0.0250585 0.05100089 -0.003512144 0.02780812 0.05099695 -0.00350821 0.02506089 0.05099987 -0.002827465 0.02751517 0.05100303 -0.002289533 0.02671253 0.0567314 -0.003326356 0.02793866 0.05673754 -0.002902448 0.02771395 0.05667638 -0.002485394 0.02729308 0.05665886 -0.002280175 0.02674388 0.05675029 -0.002702176 0.02578175 0.05675005 -0.002465665 0.02700388 0.05663073 -0.002324223 0.02609658 0.05674999 -0.002438843 0.02636754 0.0566098 -0.002578794 0.02559018 0.05673986 -0.003055155 0.02545332 0.05658727 -0.003000676 0.02522891 0.05673319 -0.003438413 0.0252822 0.05656397 -0.003468573 0.0250535 0.0566774 -0.004177331 0.02529793 0.05655086 -0.004034638 0.02505838 0.05653041 -0.004411399 0.02518665 0.05664628 -0.004752874 0.02571636 0.0565108 -0.004855513 0.02551722 0.05649393 -0.005085825 0.02587252 0.05662232 -0.004987597 0.02619886 0.05647981 -0.005212783 0.02625882 0.05659401 -0.004998743 0.02684193 0.05646121 -0.005206286 0.02682983 0.05643558 -0.004995524 0.02733272 0.05656784 -0.004704594 0.02736169 0.05641818 -0.004598617 0.02773296 0.05654162 -0.004210472 0.0277186 0.05639791 -0.004100978 0.02796453 0.05651253 -0.003571808 0.02778041 0.05637568 -0.003651857 0.0279951 0.05636072 -0.003163158 0.02787661 0.05648422 -0.002957999 0.02752882 0.05633687 -0.00266242 0.02753525 0.05645799 -0.002601683 0.02706152 0.05631411 -0.002354741 0.02701103 0.05643457 -0.002473175 0.02654439 0.05629128 -0.002266168 0.02642023 0.05641257 -0.002565324 0.02604925 0.05626612 -0.00242871 0.0258392 0.05638718 -0.002892255 0.02556514 0.0562486 -0.002775311 0.02539914 0.05622541 -0.003260493 0.02510923 0.05635267 -0.003597557 0.02523022 0.05620318 -0.003796577 0.02502965 0.05619603 -0.00414735 0.02508258 0.05631619 -0.004414379 0.02541142 0.05617618 -0.004660606 0.02533221 0.05628979 -0.004827737 0.02583378 0.05614829 -0.00504899 0.02579611 0.05626654 -0.005018889 0.02633017 0.05612438 -0.005231678 0.02635294 0.05610525 -0.005183637 0.02692002 0.05624437 -0.004987418 0.02683299 0.05622023 -0.004739642 0.02733027 0.05608612 -0.004859566 0.0275135 0.05618923 -0.00417453 0.02773392 0.05605697 -0.004377663 0.02787309 0.05602514 -0.003751933 0.02800643 0.05616146 -0.003534018 0.02777147 0.05600923 -0.003056764 0.02783632 0.05613851 -0.003043115 0.02758353 0.05598253 -0.002592921 0.02744024 0.0561046 -0.002552449 0.02699637 0.05595862 -0.002320587 0.02692109 0.05594772 -0.002272129 0.02641814 0.05607616 -0.002488374 0.0263524 0.05592411 -0.002373754 0.02596455 0.05605304 -0.002658545 0.0258556 0.05589735 -0.002654552 0.0255137 0.05602324 -0.003154575 0.02537041 0.05588376 -0.003094851 0.02517855 0.05586516 -0.003650009 0.02503788 0.05603265 -0.003763318 0.02525365 0.05583781 -0.004241824 0.0251047 0.05597037 -0.004324376 0.0253691 0.05581557 -0.004768252 0.02543568 0.0559377 -0.004867434 0.02586758 0.05579322 -0.005105316 0.02589768 0.05578011 -0.005218327 0.02630168 0.05591058 -0.005026102 0.02646493 0.05576193 -0.005219936 0.02672982 0.05588734 -0.004941582 0.02698314 0.05573952 -0.005017995 0.02730154 0.05586463 -0.004653334 0.02742266 0.05571156 -0.004600346 0.02773904 0.05583798 -0.004134833 0.02773916 0.05569851 -0.004158914 0.02794927 0.05570441 -0.003733396 0.02799701 0.0558052 -0.003398537 0.02775698 0.05567729 -0.003058314 0.02782946 0.05576729 -0.002682983 0.02724784 0.05565208 -0.002549231 0.02737474 0.05561041 -0.002345144 0.0270003 0.05573719 -0.002482116 0.02660542 0.05559307 -0.002271533 0.02644103 0.05570912 -0.002579927 0.02597767 0.05557161 -0.002408325 0.02587574 0.05554223 -0.002723395 0.02544742 0.05567318 -0.003164768 0.02536362 0.05553394 -0.003084719 0.02518731 0.05551522 -0.003609299 0.02503138 0.05564218 -0.003835558 0.02524185 0.05549132 -0.004167854 0.02508848 0.05565601 -0.00430274 0.02538013 0.05547159 -0.004733979 0.0253911 0.05559921 -0.004709959 0.02566623 0.05544388 -0.005118608 0.02592819 0.05557656 -0.00495702 0.02609997 0.05542016 -0.005232214 0.02645236 0.05555409 -0.005026221 0.02661967 0.05539685 -0.005149424 0.02704823 0.05552971 -0.004864275 0.02714949 0.0554071 -0.004948198 0.02738302 0.05549931 -0.004370987 0.0276457 0.05536955 -0.004658281 0.02769529 0.05534958 -0.00423026 0.0279237 0.05547142 -0.00377053 0.02779173 0.05533063 -0.003715932 0.0280022 0.05544364 -0.003135859 0.02764672 0.05531203 -0.003182888 0.02788555 0.05529189 -0.002718389 0.0275911 0.05541479 -0.002677083 0.02720451 0.05526983 -0.002470254 0.02726227 0.05538976 -0.002480268 0.02665632 0.05525618 -0.002295792 0.0267924 0.05523139 -0.002302646 0.02615022 0.05535936 -0.002585589 0.02596819 0.05520719 -0.002599775 0.02558302 0.05532777 -0.003058373 0.02544081 0.05518794 -0.003013908 0.02522689 0.05530083 -0.003642499 0.02523756 0.05516082 -0.003551363 0.02504086 0.05514413 -0.004127681 0.02508056 0.055274 -0.00424695 0.02533882 0.0551185 -0.004644513 0.02532088 0.05524557 -0.004762053 0.02571517 0.05510658 -0.004953086 0.02562516 0.05508065 -0.005217432 0.02623724 0.05521059 -0.005042076 0.02647405 0.05506759 -0.005229473 0.02671927 0.05518299 -0.004896521 0.02707487 0.05504029 -0.005026221 0.02727472 0.05515968 -0.004573643 0.02749764 0.05502098 -0.004668414 0.02768564 0.05513757 -0.004128754 0.0277341 0.05500298 -0.00422281 0.02792412 0.05511343 -0.003575384 0.02778333 0.05498188 -0.003722608 0.02799886 0.05495929 -0.003236413 0.02790701 0.05508244 -0.002935647 0.0275132 0.0549463 -0.002793669 0.02765405 0.05492508 -0.002437949 0.02720087 0.05505466 -0.002568304 0.02698707 0.05492019 -0.002269983 0.02659308 0.05503171 -0.002471387 0.02647042 0.05487447 -0.002370655 0.0259782 0.0549978 -0.002714812 0.02574497 0.05485522 -0.002655684 0.0255137 0.05483722 -0.003055453 0.02520477 0.05496937 -0.003229916 0.02535331 0.05481606 -0.003536462 0.02504831 0.05494743 -0.003713071 0.02524095 0.05479353 -0.004030883 0.02505844 0.05491882 -0.004364967 0.02537763 0.05480003 -0.004498362 0.02523475 0.05475151 -0.005026161 0.02574628 0.05487924 -0.004961907 0.02604901 0.05472999 -0.005227386 0.02627706 0.05484724 -0.005004286 0.02676075 0.05470645 -0.005190551 0.02688479 0.05482488 -0.004801392 0.02724599 0.05470508 -0.004913747 0.02745431 0.05480378 -0.004462599 0.02757436 0.05465507 -0.004336953 0.02787876 0.05478179 -0.004005253 0.02776598 0.05463379 -0.003731846 0.02800637 0.05475318 -0.003339231 0.02774059 0.05460572 -0.003126382 0.02786409 0.05458819 -0.002673268 0.02753424 0.05476129 -0.002816855 0.0273621 0.05456227 -0.002339124 0.02700287 0.05469715 -0.002505302 0.02683556 0.05453586 -0.002275943 0.02631908 0.05467027 -0.002514779 0.02621471 0.05454283 -0.002414703 0.02587437 0.05464601 -0.002750515 0.02571177 0.05451744 -0.002830803 0.02535724 0.05460989 -0.00342828 0.02526199 0.05447727 -0.003264844 0.02511 0.05445122 -0.003813683 0.02502369 0.05457949 -0.004122316 0.02529478 0.05443191 -0.004414677 0.02518916 0.05459314 -0.004577159 0.02556025 0.05441319 -0.004869639 0.02553373 0.05453407 -0.00489974 0.02594208 0.05438762 -0.005148351 0.02600252 0.05450838 -0.005027532 0.02651774 0.05437177 -0.005234122 0.02655655 0.05447864 -0.004868924 0.02716827 0.05434495 -0.005052804 0.02725476 0.05431681 -0.004618465 0.02771985 0.05444729 -0.004330873 0.02765542 0.0543161 -0.004037976 0.02798497 0.0544241 -0.003822445 0.02779185 0.05426615 -0.003318965 0.02793383 0.0543974 -0.003222703 0.02768313 0.05424326 -0.002791464 0.02765381 0.05436354 -0.002645015 0.02718389 0.05421131 -0.002378523 0.02709841 0.05419564 -0.002257704 0.02649343 0.05432498 -0.002473175 0.02632647 0.05418848 -0.002336978 0.02604722 0.05429679 -0.002743005 0.02573972 0.05415523 -0.002634048 0.025541 0.05427062 -0.003207683 0.02534937 0.05413335 -0.003072619 0.02519285 0.05411773 -0.003590166 0.02503961 0.05424439 -0.00378555 0.02524268 0.05409687 -0.004047632 0.02505826 0.05422097 -0.004305005 0.02536165 0.05407083 -0.004514634 0.02523934 0.0541898 -0.004858613 0.02584457 0.05405366 -0.004940032 0.02561926 0.05403608 -0.005183458 0.02611857 0.05415344 -0.005033016 0.02662497 0.05401408 -0.005236327 0.02665698 0.05399733 -0.005120396 0.02710938 0.05412858 -0.004848957 0.02716284 0.05398041 -0.004752099 0.02762204 0.05410254 -0.004438698 0.02760535 0.05394822 -0.004177749 0.02794224 0.05407619 -0.003875136 0.02778321 0.05392754 -0.003599584 0.02799063 0.05405288 -0.003345906 0.02772951 0.05389708 -0.003016591 0.02781373 0.05403077 -0.002911508 0.02747422 0.05391263 -0.002742886 0.02759391 0.05400383 -0.002552926 0.02697747 0.05387496 -0.002469122 0.02726715 0.05386865 -0.002265512 0.02654004 0.05397844 -0.002481937 0.02640175 0.05381238 -0.002478897 0.02573704 0.05395305 -0.002659142 0.02584624 0.05382221 -0.002736568 0.02543753 0.05392491 -0.003120422 0.02540057 0.05377984 -0.003008127 0.02523052 0.05376762 -0.00348854 0.02505677 0.053891 -0.003865957 0.02522814 0.05374836 -0.004033625 0.02505701 0.05372798 -0.004432141 0.02519911 0.05386257 -0.004469335 0.02546197 0.05371516 -0.004773437 0.02543902 0.05383938 -0.004835605 0.02583807 0.05369651 -0.005096495 0.02588266 0.05380958 -0.0050444 0.02649998 0.05366927 -0.005242168 0.02645432 0.05365365 -0.005164682 0.02697473 0.05377972 -0.004860281 0.02714687 0.05362951 -0.004869043 0.02750843 0.05375796 -0.004538357 0.02752548 0.05361235 -0.004380941 0.02786672 0.05373036 -0.003972709 0.02777719 0.05358517 -0.003756463 0.02800065 0.05370712 -0.003436684 0.02775275 0.05356353 -0.003230214 0.02791041 0.05368143 -0.002922654 0.02749252 0.05354243 -0.002781391 0.02763712 0.05352169 -0.002434313 0.02720654 0.05365705 -0.002586781 0.02703702 0.05349427 -0.002281606 0.02670747 0.05363571 -0.002478182 0.02656978 0.05348598 -0.002287328 0.02626216 0.05365353 -0.002549171 0.02613455 0.05346721 -0.002473831 0.02574813 0.05359357 -0.002791285 0.02567386 0.05344754 -0.002898275 0.02529585 0.05357098 -0.003190219 0.02537298 0.05341678 -0.003489077 0.02505278 0.053541 -0.003857553 0.02522343 0.05339992 -0.004029452 0.02505618 0.05337828 -0.004441559 0.02520352 0.05350619 -0.004597187 0.02555054 0.05335706 -0.004893004 0.02555978 0.05348163 -0.004919886 0.02600115 0.0533449 -0.005122959 0.02595221 0.05332505 -0.005229592 0.02638709 0.05345624 -0.005033135 0.02657175 0.05330342 -0.00517553 0.02694672 0.05342727 -0.004841983 0.02719295 0.05328267 -0.004923641 0.02743017 0.05343014 -0.004417002 0.02758926 0.05326491 -0.004524767 0.02778053 0.05323463 -0.00396955 0.02799177 0.05338072 -0.003970444 0.02777397 0.05324989 -0.00361824 0.027987 0.05335903 -0.003492534 0.02776455 0.05321186 -0.003201544 0.02789729 0.05333793 -0.003037869 0.02757143 0.05318886 -0.002577543 0.02743548 0.05331611 -0.002684831 0.02722138 0.05315923 -0.002316951 0.02688735 0.05329287 -0.002497851 0.0267325 0.05313998 -0.002276897 0.0263428 0.0532701 -0.002507209 0.02621412 0.05311346 -0.002446055 0.02580267 0.05324739 -0.002734243 0.02575087 0.05309814 -0.002801895 0.02537846 0.05321812 -0.003243982 0.02532678 0.05306917 -0.003311991 0.02509069 0.05305773 -0.003750622 0.02502065 0.05318993 -0.003885149 0.02524948 0.05304032 -0.004269838 0.02512276 0.05316382 -0.00446105 0.02544105 0.0530188 -0.004772961 0.02542573 0.0531376 -0.0048545 0.02587747 0.05299228 -0.005120217 0.02594351 0.05311411 -0.005025088 0.02638232 0.05297166 -0.005240857 0.02651029 0.05309212 -0.004973828 0.02688336 0.05294793 -0.005132913 0.0270642 0.05306792 -0.004705786 0.0273692 0.05292922 -0.004837751 0.02752643 0.05291169 -0.004499971 0.02779513 0.05304306 -0.004252552 0.02769237 0.05289828 -0.004097104 0.02796351 0.05301696 -0.003657221 0.02779394 0.05287563 -0.003517866 0.02797967 0.0529921 -0.003116428 0.02762299 0.05285656 -0.002971351 0.02778893 0.0529707 -0.002753376 0.0273084 0.05282419 -0.002461314 0.02724879 0.05294609 -0.00250554 0.02680486 0.05280727 -0.002286612 0.02676355 0.05279034 -0.002278983 0.02636063 0.05292397 -0.002495646 0.02630114 0.05277287 -0.002385616 0.02594071 0.05290198 -0.002672374 0.02583783 0.05275374 -0.002720892 0.0254414 0.05287438 -0.003126561 0.02538776 0.05273133 -0.003199398 0.02513796 0.052881 -0.003786563 0.02525413 0.05270713 -0.003696739 0.02503085 0.05282533 -0.004220545 0.02532601 0.0526852 -0.004346787 0.02514702 0.05279934 -0.004697322 0.0256524 0.05266195 -0.004835307 0.02550274 0.05263984 -0.005139231 0.02597987 0.05276846 -0.005023121 0.02629017 0.05261874 -0.005233228 0.02644205 0.05260711 -0.005197882 0.02685695 0.05274283 -0.004973888 0.02686393 0.0525884 -0.004976868 0.02736061 0.05272132 -0.004763662 0.02730429 0.05256074 -0.004549622 0.0277782 0.05269831 -0.004356265 0.02763777 0.05257099 -0.004175543 0.02792853 0.05266809 -0.003678441 0.02780979 0.05253404 -0.003753304 0.02800542 0.05250787 -0.003219068 0.02790993 0.0526337 -0.002965986 0.02752566 0.05248159 -0.002645611 0.02750909 0.05260282 -0.002537369 0.02695071 0.05247199 -0.002404808 0.027134 0.052455 -0.00228542 0.02674829 0.05257445 -0.002494454 0.02632063 0.05243343 -0.002299726 0.02622222 0.0525527 -0.0026654 0.02583909 0.05242478 -0.002464056 0.02578002 0.0523926 -0.002759218 0.02540421 0.05252885 -0.0030393 0.02545839 0.05237567 -0.003302156 0.02510291 0.05254417 -0.003504097 0.0252788 0.05236089 -0.003869235 0.02503055 0.05248677 -0.003966629 0.02525615 0.05232739 -0.004539847 0.02525675 0.05245435 -0.004633426 0.02556574 0.05231237 -0.004907965 0.02558326 0.05229008 -0.005173504 0.02607327 0.05242043 -0.00500077 0.02623212 0.05226594 -0.005230188 0.0266484 0.05239677 -0.004998624 0.02678459 0.05224221 -0.005108296 0.02712041 0.05237495 -0.004805684 0.0272426 0.05223232 -0.004867315 0.0274949 0.05234688 -0.004322826 0.02766424 0.05220186 -0.004374623 0.0278694 0.05218744 -0.003811299 0.02800697 0.05232048 -0.003745794 0.02779424 0.05216652 -0.003257215 0.0279119 0.05229854 -0.003255486 0.0276879 0.0521453 -0.002802252 0.02765733 0.05227756 -0.002849638 0.02742081 0.05212271 -0.002442598 0.02722328 0.05225348 -0.002560675 0.02697658 0.05210137 -0.002277195 0.02666443 0.05223113 -0.002478957 0.02645963 0.05207651 -0.00233978 0.02602601 0.05220931 -0.002592384 0.02597558 0.05205237 -0.002685487 0.02548617 0.05218607 -0.002911031 0.02556031 0.05202835 -0.003164112 0.02514863 0.05216324 -0.003357589 0.02529692 0.0520057 -0.003738224 0.02502804 0.05214059 -0.003871142 0.02524787 0.05198812 -0.00428456 0.02512919 0.05211132 -0.004499316 0.02546006 0.05197125 -0.004773914 0.02542829 0.05207502 -0.004990696 0.02615314 0.0519427 -0.005114912 0.02593034 0.05192059 -0.005238771 0.02648192 0.05204492 -0.004992008 0.02682691 0.05189752 -0.005153179 0.0270099 0.0518831 -0.004915475 0.02743864 0.05201262 -0.004631519 0.02746742 0.05188769 -0.004569768 0.0277481 0.05186724 -0.004085898 0.02795535 0.05197364 -0.00379163 0.02780884 0.0518282 -0.003627717 0.0279954 0.05179756 -0.003053188 0.02783328 0.05193489 -0.002982437 0.02755117 0.05178403 -0.002625524 0.02748888 0.05190372 -0.002555012 0.02696758 0.05179059 -0.002403259 0.0271123 0.05175364 -0.002292215 0.02680546 0.05187225 -0.002489209 0.02624553 0.05173259 -0.002290964 0.0262382 0.05170458 -0.002559065 0.02562451 0.05183929 -0.002853333 0.02560478 0.05168849 -0.00298655 0.02523517 0.05181717 -0.003277361 0.02533262 0.05166602 -0.003527641 0.02504783 0.05179512 -0.003764569 0.02524065 0.05164957 -0.004095196 0.02506685 0.05176532 -0.004438161 0.02541619 0.05162662 -0.004600882 0.02529799 0.05160611 -0.004956722 0.02564972 0.05177217 -0.004871904 0.02593415 0.05160093 -0.00522238 0.02628964 0.05171126 -0.005032896 0.02645587 0.05155164 -0.005152881 0.02700877 0.0516774 -0.00484997 0.02719885 0.05153918 -0.004923701 0.02742713 0.05151408 -0.0045951 0.02773731 0.05164897 -0.004368722 0.02763152 0.05150002 -0.004106879 0.02795803 0.05162066 -0.003750622 0.02780473 0.05147379 -0.003576815 0.02798992 0.0514509 -0.003046452 0.02782648 0.05159282 -0.003137171 0.0276339 0.05143451 -0.002609193 0.02746379 0.05156129 -0.002611279 0.02713024 0.05141198 -0.002341568 0.02699601 0.05139529 -0.002261042 0.02653789 0.0515269 -0.002480328 0.02637445 0.05138289 -0.002332091 0.02608513 0.05149304 -0.002775847 0.02566283 0.05135989 -0.002607345 0.02555859 0.05133265 -0.003080248 0.02519494 0.05146062 -0.003423213 0.02528131 0.05131256 -0.003657758 0.02502822 0.05143386 -0.004033923 0.02526283 0.05129534 -0.004219591 0.02510762 0.05140799 -0.004554688 0.02552682 0.0512737 -0.004616081 0.02530515 0.05138725 -0.004867136 0.02588951 0.05125099 -0.0049299 0.0256133 0.05122876 -0.005202293 0.02615815 0.05136376 -0.005021333 0.02638316 0.05120939 -0.005214631 0.02680611 0.05133342 -0.004920959 0.02707058 0.05119532 -0.005049586 0.02725017 0.05116784 -0.004680991 0.02767354 0.05130499 -0.004485845 0.02755647 0.05114775 -0.004198372 0.02794098 0.05128026 -0.003959596 0.02778404 0.05115574 -0.003779709 0.02799993 0.05125391 -0.003370821 0.02773255 0.05111891 -0.003358423 0.0279566 0.05123239 -0.002935767 0.02749532 0.05111116 -0.002700626 0.02755886 0.0512098 -0.002616524 0.02710545 0.05106949 -0.002403438 0.0271399 0.05118548 -0.002477943 0.0265603 0.0510466 -0.002270877 0.02662491 0.05104792 -0.002364635 0.02599591 0.05115467 -0.002623677 0.02587962 0.05102211 -0.002691209 0.02548837 0.05116206 -0.003140926 0.0254122 0.05109894 -0.003674089 0.02523446 0.05107194 -0.004272401 0.0253511 0.0510509 -0.004664719 0.02562206 0.05674922 -0.003932893 0.02524715 0.05674183 -0.004568219 0.02551543 0.05669981 -0.004980683 0.02613937 0.0566706 -0.005001187 0.02679818 0.0566346 -0.004636704 0.02745944 0.05660796 -0.004042029 0.02775579 0.05658686 -0.003561079 0.02777981 0.05655646 -0.002939939 0.02751755 0.05652153 -0.00250554 0.02684175 0.0564838 -0.002569139 0.02598834 0.05644905 -0.003120183 0.02539819 0.05642098 -0.003726959 0.02523767 0.05638933 -0.004411756 0.02540349 0.0563547 -0.004935264 0.02601134 0.05632895 -0.005023062 0.02660089 0.05629926 -0.004826545 0.02724057 0.05626952 -0.004285931 0.02767282 0.05624222 -0.003693878 0.02780377 0.05621463 -0.003088057 0.02760273 0.05618906 -0.00267142 0.0272122 0.05615264 -0.002461314 0.02641111 0.05612182 -0.002733826 0.02574533 0.05609464 -0.003201425 0.02535861 0.05604815 -0.004251837 0.02533727 0.05601549 -0.004809677 0.02577626 0.05598068 -0.00504148 0.02656984 0.05594819 -0.004798829 0.02725553 0.05592185 -0.004347562 0.02764737 0.05590128 -0.003895044 0.02778154 0.05588001 -0.003403961 0.02774345 0.05584996 -0.002835035 0.0274232 0.0558151 -0.002472758 0.02667933 0.05578261 -0.002596318 0.02596318 0.05575621 -0.002975702 0.02550041 0.05573618 -0.003396451 0.02529281 0.05571419 -0.003878414 0.02524673 0.05567038 -0.004747331 0.02571201 0.0556457 -0.004996776 0.0262221 0.05561369 -0.004978656 0.02692615 0.05558055 -0.004511475 0.02755182 0.05554538 -0.00378257 0.0278061 0.05551612 -0.003122627 0.02762758 0.05548632 -0.002626061 0.02714383 0.05545926 -0.002479255 0.02655565 0.05543231 -0.002594053 0.02595651 0.05540615 -0.002980172 0.02550089 0.0553798 -0.003526508 0.02525258 0.05535179 -0.004159331 0.02530187 0.05532068 -0.004756987 0.02570718 0.05528253 -0.005045354 0.02649515 0.05525153 -0.004841446 0.02718782 0.05522978 -0.004494667 0.02755004 0.05520313 -0.003942847 0.02778923 0.05517804 -0.003362178 0.02772772 0.05515217 -0.002861618 0.02744114 0.05512005 -0.002499938 0.02681136 0.05509066 -0.002529561 0.02613842 0.05506259 -0.002860426 0.02559232 0.05503636 -0.003380417 0.02529442 0.05501496 -0.003875494 0.02524453 0.05498784 -0.004449903 0.02544051 0.05495482 -0.004942119 0.02600902 0.05492234 -0.005013525 0.02673375 0.05490112 -0.004828751 0.02719581 0.05487388 -0.004381418 0.0276423 0.05484664 -0.003788769 0.02778857 0.05482232 -0.003246068 0.02769315 0.05477029 -0.002497017 0.02681553 0.05473917 -0.002540171 0.02610635 0.05471521 -0.002829492 0.02563625 0.05469369 -0.003228366 0.02534866 0.05467092 -0.003735363 0.02524274 0.05464941 -0.004210829 0.02532237 0.05459803 -0.00499159 0.02613997 0.05456477 -0.004969894 0.02691566 0.05453771 -0.004636287 0.02744245 0.05450588 -0.004015266 0.02777868 0.05447256 -0.003240585 0.02769625 0.0544458 -0.002770423 0.02732586 0.05442386 -0.002528429 0.02689188 0.05440068 -0.00248748 0.02635776 0.0543757 -0.002677202 0.02581703 0.05434286 -0.003225624 0.02533847 0.05430793 -0.004024982 0.02525615 0.0542702 -0.004757523 0.02569836 0.0542401 -0.00501579 0.02634179 0.05421888 -0.004987001 0.02683305 0.05419296 -0.004731535 0.02734982 0.05416655 -0.004229784 0.02769702 0.05414104 -0.003668308 0.02779895 0.05411535 -0.00310266 0.02761101 0.05408799 -0.002653777 0.02719169 0.05406105 -0.002481043 0.02658599 0.05403113 -0.002597391 0.02592825 0.05400139 -0.003081262 0.02543312 0.05397504 -0.003617644 0.02523696 0.05393904 -0.004429101 0.02541124 0.05390816 -0.004899978 0.02595502 0.05388104 -0.005033791 0.02654695 0.05384802 -0.004807174 0.02726399 0.05381554 -0.004227101 0.02770435 0.05379432 -0.003736734 0.02778887 0.05376708 -0.003122031 0.02764147 0.05373984 -0.002687156 0.02721315 0.05371546 -0.002484261 0.02670085 0.05366343 -0.002839744 0.02560317 0.05363237 -0.003466546 0.02526861 0.05360841 -0.004018604 0.02526897 0.0535869 -0.004472374 0.02545815 0.05356413 -0.004828095 0.02583461 0.05353522 -0.005047678 0.02646684 0.05349904 -0.00481683 0.0272305 0.05345797 -0.004049301 0.02776241 0.05343204 -0.003452599 0.02775871 0.05340003 -0.002832472 0.02742445 0.05336695 -0.002485334 0.02672505 0.05334419 -0.002518534 0.0262168 0.0533207 -0.002733647 0.02572846 0.05329513 -0.003198742 0.02536946 0.05326902 -0.003784835 0.02522885 0.05324441 -0.004317283 0.02537608 0.05321872 -0.004774749 0.02573502 0.05319249 -0.00500679 0.02628505 0.05316621 -0.004981577 0.02688485 0.05313813 -0.004651725 0.02742713 0.05310702 -0.004020273 0.02777725 0.05306893 -0.003186881 0.0276786 0.05303424 -0.002615213 0.027116 0.05299782 -0.002475142 0.02629959 0.05296695 -0.002804696 0.02565973 0.05293983 -0.003303766 0.0253151 0.05288785 -0.004452466 0.02543109 0.05285674 -0.004911303 0.02597367 0.05282586 -0.005032062 0.026681 0.05279862 -0.004796326 0.02724474 0.05277425 -0.004396855 0.02762377 0.05274122 -0.003667235 0.02780616 0.05270874 -0.002988398 0.02754247 0.05268752 -0.002659618 0.02716892 0.05266028 -0.00246334 0.02656811 0.05262774 -0.002648711 0.02586477 0.05260139 -0.003066301 0.02543705 0.05255925 -0.003996908 0.0252633 0.05252957 -0.004592061 0.02553606 0.05249953 -0.004975676 0.02614122 0.05247229 -0.0050143 0.02674466 0.05244314 -0.0047279 0.02734696 0.05242073 -0.004313766 0.02766036 0.0523948 -0.003759384 0.0277974 0.05236744 -0.00314939 0.02764624 0.05234503 -0.00275582 0.02730584 0.05232065 -0.002498865 0.02680951 0.052289 -0.002540647 0.02609789 0.05226248 -0.002872705 0.02558588 0.05223441 -0.003415167 0.02528017 0.05220431 -0.004104018 0.02527803 0.05217862 -0.004622936 0.0255863 0.05214869 -0.004992783 0.02614086 0.05211132 -0.004945933 0.02700376 0.05207896 -0.004496932 0.02755796 0.05204832 -0.003832161 0.02780091 0.05202323 -0.003258407 0.02768915 0.05199736 -0.002784848 0.02736061 0.05197328 -0.002529263 0.02687156 0.05194574 -0.002493917 0.02623575 0.05190902 -0.002902507 0.02554714 0.05188155 -0.003487288 0.02526688 0.05186015 -0.003985524 0.02526009 0.05183303 -0.004540503 0.02550488 0.05178105 -0.005043089 0.02654421 0.05174994 -0.004821121 0.02721929 0.05171906 -0.004281759 0.02769249 0.05169183 -0.003678023 0.02778685 0.05166876 -0.003172397 0.02765601 0.05164825 -0.002806127 0.02736854 0.05162739 -0.002551674 0.02695029 0.05160194 -0.002477705 0.02640247 0.05156958 -0.002735912 0.02571606 0.05153888 -0.003331482 0.02530777 0.05151611 -0.003846108 0.02524602 0.05149459 -0.004312217 0.02536636 0.05147451 -0.004686713 0.02565014 0.05144321 -0.005019485 0.02624857 0.0514099 -0.004930555 0.02701997 0.05138289 -0.00455302 0.02751529 0.05135101 -0.003904461 0.0277968 0.05131775 -0.00314027 0.02764737 0.05128955 -0.002686083 0.02721458 0.05126911 -0.00250411 0.02678364 0.05124706 -0.002498209 0.02627658 0.05122089 -0.002741515 0.02572679 0.05116939 -0.003762543 0.02522629 0.05114203 -0.004372239 0.02540111 0.05111616 -0.00480014 0.02577948 0.05109506 -0.004993259 0.02622753 0.05106884 -0.00500065 0.02682965 0.05674993 -0.005030572 0.0260362 0.05674302 -0.00444895 0.02782917 0.05674946 -0.005134522 0.02695608 0.05674046 -0.003787279 0.02800208 0.05667352 -0.002828776 0.02766537 0.05564659 -0.003376245 0.02795457 0.05561852 -0.002729773 0.02758836 0.05487906 -0.002265751 0.02665501 0.05474966 -0.004636228 0.02531957 0.05465668 -0.004843652 0.02752608 0.05448478 -0.002604484 0.02556592 0.05433207 -0.005163192 0.02695661 0.05426901 -0.003971338 0.0279867 0.05383735 -0.002318263 0.02686882 0.0538156 -0.002285778 0.02630972 0.05317431 -0.00284034 0.02767717 0.0528196 -0.002753615 0.02760654 0.05231982 -0.004173934 0.02509868 0.05183333 -0.004339337 0.02788227 0.05156743 -0.005148828 0.02603358 0.05154699 -0.005230963 0.02655404 0.05107617 -0.002843916 0.02769148 0.05075788 -0.002746403 0.02566891 0.05089563 -0.002711176 0.0254969 0.05076408 -0.002576291 0.02592217 0.05075567 -0.002467811 0.02632963 0.05089521 -0.002484381 0.02580028 0.05085742 -0.002362072 0.02614814 0.05100125 -0.002326786 0.02612835 0.05085629 -0.002313196 0.0264796 0.05075812 -0.002482593 0.02683019 0.05088216 -0.002337396 0.02682298 0.05075919 -0.002729654 0.02734071 0.05083024 -0.002504885 0.02717763 0.05098968 -0.002406835 0.02713453 0.05097454 -0.002608835 0.02745574 0.05075103 -0.003317236 0.02773052 0.05088835 -0.002821803 0.02762919 0.0508008 -0.003028035 0.02769595 0.05099511 -0.003029644 0.02780687 0.05085819 -0.003336608 0.02789121 0.05079597 -0.003699898 0.02789425 0.05099576 -0.003541648 0.02798324 0.05075377 -0.004202425 0.02772194 0.05090695 -0.003882765 0.02796685 0.05084156 -0.004148662 0.02788329 0.05099916 -0.004060029 0.02795809 0.05080312 -0.004513919 0.0276817 0.05099678 -0.004400789 0.02784365 0.05075168 -0.0047701 0.02728116 0.05090779 -0.004652321 0.02766561 0.05087184 -0.004842221 0.02746331 0.05080163 -0.004911959 0.02727085 0.05075925 -0.00504589 0.02675676 0.05089998 -0.005109667 0.02705019 0.05084061 -0.005140602 0.02683532 0.05075246 -0.004997313 0.02620905 0.05082178 -0.005151808 0.02638232 0.05099391 -0.005235612 0.02652645 0.05076819 -0.004912853 0.02585953 0.05088263 -0.005145847 0.02612423 0.0508852 -0.005045354 0.02585977 0.05075341 -0.004222691 0.0253027 0.0508809 -0.004790663 0.0255022 0.05078476 -0.004561185 0.0254206 0.05088418 -0.004318654 0.02517628 0.05078232 -0.003781735 0.02516376 0.05087578 -0.003852605 0.02507346 0.05075454 -0.003375291 0.02527409 0.05087292 -0.00349003 0.0250954 0.05080699 -0.002999901 0.02534848 0.05088412 -0.003186583 0.02518093 0.05099618 -0.003029286 0.02522498 0.05693656 -0.005164206 0.0288195 0.05680412 -0.005236506 0.02867829 0.05675607 -0.004862964 0.02879559 0.05683302 -0.004811406 0.02893817 0.05691581 -0.004559874 0.02908796 0.05691504 -0.004091918 0.02918803 0.05677282 -0.004294633 0.0290293 0.05694949 -0.003558754 0.02921468 0.05679136 -0.003704428 0.0291202 0.05675494 -0.003416001 0.0290212 0.05681163 -0.003072381 0.02905517 0.05693864 -0.00300908 0.02910983 0.05690068 -0.002563476 0.02893114 0.05675613 -0.002563476 0.02875226 0.05686181 -0.00220859 0.02868908 0.05696058 -0.002021968 0.02859419 0.05680477 -0.00197941 0.02844846 0.05693006 -0.001583814 0.02812719 0.05675154 -0.001767218 0.02804219 0.056809 -0.00154519 0.02793234 0.05691814 -0.001295268 0.0276196 0.05680334 -0.001312077 0.02745151 0.05690109 -0.001133024 0.02713632 0.05675631 -0.001277983 0.02709919 0.05688607 -0.001067936 0.02662497 0.056755 -0.001224398 0.02640438 0.05695307 -0.001066803 0.02622514 0.05678921 -0.001187741 0.02605217 0.05692416 -0.001172244 0.02573227 0.05688399 -0.001329123 0.02535849 0.05675578 -0.001523792 0.02531105 0.05686789 -0.001539528 0.0250222 0.05692398 -0.001656532 0.02481389 0.05678927 -0.001937091 0.02464634 0.05690848 -0.002054989 0.02442657 0.05675208 -0.002301573 0.02444535 0.05691677 -0.002510905 0.02411973 0.05679744 -0.002670168 0.02414065 0.0569604 -0.003012776 0.0239169 0.05683517 -0.003220379 0.0239191 0.05676364 -0.003445863 0.023979 0.05694675 -0.003554522 0.02382242 0.05689126 -0.003915905 0.02383214 0.05675768 -0.004096448 0.0240001 0.05686479 -0.004444956 0.02393645 0.05694371 -0.004619657 0.02395188 0.05675888 -0.004676699 0.02414882 0.05684286 -0.004924595 0.02413886 0.05694383 -0.005217969 0.02424788 0.0567556 -0.005214631 0.02444911 0.05681174 -0.005356967 0.02443343 0.05692201 -0.005576908 0.02453279 0.05684387 -0.005880475 0.02491724 0.0569545 -0.006002545 0.02501142 0.05675721 -0.005945742 0.02522319 0.05689853 -0.006268918 0.02556222 0.05676043 -0.006247758 0.02598303 0.05691492 -0.006420135 0.02611362 0.05680108 -0.006354391 0.02630066 0.05689412 -0.006431341 0.02675622 0.05675625 -0.006263434 0.02682459 0.05692428 -0.006339967 0.02728253 0.05678242 -0.006239235 0.02724218 0.05689203 -0.006099998 0.02782779 0.05675393 -0.005842983 0.02795153 0.05693292 -0.005740225 0.02834898 0.0568152 -0.005612909 0.0283758 0.05960589 -0.005387902 0.02865213 0.05960524 -0.005039155 0.028876 0.05955374 -0.004741013 0.02902907 0.05955332 -0.004127383 0.0291953 0.05958402 -0.003549098 0.02920222 0.05958735 -0.003125131 0.02913826 0.05957216 -0.002003431 0.02857285 0.05955737 -0.001586794 0.02812826 0.05958271 -0.001323819 0.02768516 0.05958467 -0.001066803 0.02631646 0.05957931 -0.001301467 0.02538347 0.05960649 -0.00159502 0.02491253 0.05957221 -0.002389729 0.02418202 0.05957609 -0.005342185 0.02433735 0.05960136 -0.006331324 0.02575457 0.05954313 -0.006446599 0.02628469 0.059583 -0.00642842 0.02684605 0.05957096 -0.006303369 0.02739691 0.05955761 -0.005774676 0.02830195 0.05968624 -0.005754351 0.02822369 0.05974555 -0.005467832 0.0283876 0.05957722 -0.006045579 0.02793478 0.05968457 -0.006148219 0.02760171 0.05974203 -0.006161153 0.02731758 0.05970078 -0.006326854 0.02697432 0.0596807 -0.006382048 0.02628773 0.0595625 -0.006192624 0.02536433 0.05970597 -0.006134748 0.02545773 0.05974733 -0.005860567 0.02515262 0.05958348 -0.005999386 0.02502948 0.05969941 -0.005677342 0.02473628 0.05957645 -0.005715727 0.02466708 0.05974799 -0.005072534 0.02436101 0.05967694 -0.005002915 0.02418977 0.05958193 -0.004799246 0.02402901 0.05968427 -0.004421293 0.02397292 0.05956023 -0.004144787 0.02384233 0.05974072 -0.004023194 0.02398967 0.05968689 -0.003804266 0.02388334 0.05957585 -0.003548026 0.02382695 0.05974268 -0.003264784 0.02402871 0.05959928 -0.003063678 0.02391326 0.0596823 -0.002696275 0.02409899 0.05974763 -0.002516984 0.02431917 0.05970925 -0.00207889 0.02452933 0.05958515 -0.001904189 0.02455383 0.0597437 -0.001693606 0.025038 0.05968815 -0.001481711 0.02519881 0.05969458 -0.001225352 0.02580523 0.05974763 -0.001348733 0.02581721 0.05960071 -0.001134514 0.02590256 0.05972206 -0.001176118 0.02643281 0.05957984 -0.001073658 0.02684164 0.05973553 -0.001219928 0.02689534 0.05959975 -0.001175165 0.02727925 0.05973988 -0.001431584 0.02758407 0.05967402 -0.001681268 0.02815812 0.0597431 -0.002037048 0.02838295 0.05966544 -0.00205177 0.02854102 0.05958449 -0.002479434 0.02889186 0.05974298 -0.002580225 0.02877664 0.05967938 -0.002919912 0.02901941 0.05972814 -0.003442406 0.0290659 0.05968093 -0.003958106 0.02914559 0.059744 -0.004280388 0.02898955 0.05967622 -0.004577159 0.02901887 0.05974304 -0.00491023 0.02877229 0.05805808 0.008789718 0.02306157 0.05806976 0.007463455 0.02342063 0.05816739 0.008822858 0.02292758 0.05820703 0.007390737 0.02335017 0.05806922 0.007145583 0.02477997 0.05820792 0.007047116 0.02480787 0.05805838 0.008171856 0.02569222 0.05816763 0.008140206 0.02582484 0.05805772 0.009465515 0.02530002 0.0581665 0.009564816 0.02539616 0.05806106 0.00978893 0.02398145 0.05817908 0.009910047 0.02394688 0.05973875 0.009597599 0.02542883 0.05973857 0.00995016 0.02393579 0.05973875 0.008128464 0.02586942 0.05973875 0.007012009 0.02481704 0.05973839 0.007364869 0.02332603 0.05973911 0.008832871 0.02288186 0.05099862 0.007226347 0.02467542 0.05099886 0.006996631 0.02447092 0.05101245 0.007250666 0.02399802 0.05099809 0.007132589 0.02376151 0.05099999 0.007166981 0.02505141 0.0510115 0.007666945 0.02536237 0.05099976 0.007593274 0.02556174 0.05099958 0.007477998 0.02328926 0.05099028 0.007808685 0.02306181 0.05100345 0.008161723 0.02560842 0.05099284 0.008259296 0.02292138 0.05100089 0.008722126 0.02566862 0.05099982 0.008629202 0.02584236 0.05099838 0.00883907 0.02293843 0.05099987 0.009084582 0.02572828 0.05099987 0.009406566 0.02537572 0.05099993 0.009508013 0.02543568 0.05099993 0.009793877 0.02505421 0.05100458 0.009937465 0.02464222 0.05100429 0.009931921 0.02407526 0.05670303 0.009319961 0.02560186 0.0566768 0.009716749 0.02520394 0.05674999 0.009442567 0.02541452 0.05665874 0.009952485 0.02461832 0.05675029 0.009531855 0.0236423 0.05675005 0.009768366 0.02486443 0.05662614 0.009915649 0.02396482 0.05674999 0.009795188 0.02422809 0.05660516 0.009603261 0.0233981 0.05674034 0.009158253 0.02329909 0.05658555 0.00915122 0.02305436 0.05673265 0.008718192 0.0231269 0.05655521 0.008580803 0.02288788 0.05657017 0.008234202 0.02291995 0.0566774 0.0080567 0.02315843 0.05653303 0.007855892 0.02302926 0.05664628 0.007481157 0.02357691 0.05650806 0.007418751 0.0233367 0.05651521 0.007128834 0.02377659 0.05661875 0.007221162 0.02414429 0.05649358 0.007006585 0.02434599 0.05658549 0.007294774 0.02488565 0.05645197 0.007036745 0.02473247 0.05643248 0.007286787 0.02526056 0.05654805 0.007889747 0.02552813 0.05641871 0.007667124 0.0256139 0.05639988 0.008097529 0.02581053 0.0565139 0.008633136 0.02564716 0.05637878 0.008663117 0.02585697 0.05649149 0.009126663 0.02547419 0.05635565 0.009203493 0.02568197 0.05646735 0.009540736 0.02510637 0.05634945 0.009716868 0.02519118 0.05631059 0.009914457 0.02477443 0.05643576 0.009761929 0.02443349 0.05628454 0.009964883 0.02427572 0.05641257 0.009668648 0.0239098 0.05626738 0.009819209 0.02372443 0.05638718 0.009341776 0.02342569 0.05624979 0.009484589 0.02328109 0.05623048 0.009025454 0.02298909 0.05635374 0.008665084 0.02309757 0.05620378 0.008475244 0.0228917 0.05619513 0.008087158 0.02294367 0.05631738 0.007842004 0.02325576 0.05617612 0.007573187 0.02319288 0.05628979 0.007406294 0.02369427 0.05614829 0.007184863 0.02365696 0.05626654 0.007215142 0.02419072 0.05612432 0.007002234 0.02421391 0.05610525 0.007050454 0.02478086 0.05624437 0.007246613 0.02469354 0.05622023 0.00749439 0.02519083 0.05608403 0.007312655 0.02528876 0.05605906 0.007729232 0.02566105 0.05619168 0.008007109 0.02556961 0.05604326 0.008181333 0.02583414 0.05616647 0.008584618 0.02564579 0.05603134 0.008647859 0.02584952 0.05614572 0.009045779 0.02552378 0.05600672 0.009196221 0.02568489 0.05612099 0.009474217 0.02518087 0.05598253 0.009641289 0.0253005 0.05608886 0.009772717 0.02449703 0.05595862 0.009913563 0.02478122 0.0559619 0.009955108 0.02424079 0.05605822 0.009626746 0.02381986 0.05591833 0.009706795 0.02352434 0.05603706 0.009344637 0.02343291 0.05588823 0.009197175 0.02307099 0.05600804 0.008743107 0.02311307 0.0558654 0.008650302 0.02290248 0.05597299 0.007959127 0.02320021 0.05584132 0.008216142 0.02291709 0.05583274 0.007772266 0.02307027 0.05580967 0.007347583 0.02342122 0.05594271 0.00744003 0.0236352 0.05578029 0.00703907 0.0239849 0.05592077 0.007235407 0.02409923 0.05576193 0.00701189 0.02459055 0.0558927 0.007245123 0.02473419 0.05574101 0.00720328 0.02514195 0.05586463 0.007580697 0.02528315 0.05571871 0.00755465 0.0255441 0.05583798 0.008099198 0.02559971 0.05569964 0.008042991 0.02579712 0.05567777 0.008619129 0.0258643 0.0558052 0.008835494 0.02561753 0.05565696 0.009127676 0.02572095 0.05564457 0.009501099 0.02545487 0.05577468 0.009429275 0.02523386 0.05561846 0.009834587 0.02500075 0.05575263 0.00968343 0.02480584 0.05560326 0.00996977 0.02441519 0.05572932 0.009755611 0.02429068 0.05556869 0.009846031 0.02378427 0.05570739 0.009619295 0.02379703 0.05555778 0.009569287 0.0233671 0.05568629 0.009328305 0.02342194 0.05553525 0.009177207 0.02306628 0.05569994 0.008863627 0.02317333 0.05551207 0.008710861 0.02291065 0.05564087 0.008369743 0.02309846 0.05550193 0.008214175 0.02291315 0.05561643 0.007838487 0.02327758 0.05547451 0.007680535 0.02312678 0.05558663 0.007351636 0.02374058 0.05546069 0.007356882 0.02341401 0.05544286 0.007121086 0.02377229 0.0554201 0.007001817 0.02431321 0.05555409 0.00720781 0.02448022 0.05539619 0.007084667 0.02491092 0.05552971 0.007369756 0.02501004 0.05540972 0.007246196 0.02518755 0.05549931 0.007863044 0.02550625 0.05537068 0.007550179 0.02553284 0.05534869 0.007961928 0.02576577 0.05533063 0.008518934 0.0258665 0.055462 0.008697867 0.02565318 0.0553013 0.009196162 0.02568268 0.05542218 0.009468793 0.02521204 0.0552836 0.009650707 0.02530682 0.05525928 0.009916424 0.02475887 0.05538976 0.009753763 0.02451688 0.05526566 0.009960889 0.0243237 0.05536055 0.009658038 0.02385616 0.05522513 0.009926497 0.0239951 0.05520719 0.009634077 0.02344334 0.05532896 0.009200572 0.02331542 0.05518794 0.009220004 0.02308732 0.05530577 0.008705556 0.0231207 0.05516082 0.00868237 0.02290135 0.05528157 0.008151054 0.02314031 0.05514413 0.008106112 0.02294117 0.05512386 0.007615208 0.02316641 0.05525672 0.007657885 0.02339863 0.05510169 0.007248699 0.02354913 0.05523538 0.007356226 0.02378088 0.05508381 0.007011532 0.02411627 0.05520939 0.007194042 0.02436208 0.05505603 0.007049322 0.02477639 0.05518299 0.00733751 0.02493536 0.05503439 0.007304251 0.02527761 0.05515968 0.007660329 0.02535814 0.05501025 0.007677674 0.02562469 0.05513757 0.008105218 0.02559459 0.05500632 0.008025527 0.02578788 0.05511343 0.008658647 0.02564382 0.05498188 0.008511543 0.02585935 0.05495929 0.008997857 0.02576744 0.05508244 0.009298384 0.02537369 0.05494838 0.009432017 0.0255205 0.05493807 0.009871721 0.02490395 0.05504614 0.009742975 0.02466094 0.05491107 0.0099532 0.02421951 0.05501413 0.009686708 0.02395188 0.05487209 0.009841084 0.02377349 0.05499172 0.009411811 0.02350282 0.05484789 0.009555935 0.02334702 0.05496704 0.00895363 0.02318376 0.05483806 0.009121954 0.02303779 0.054816 0.008697688 0.02290511 0.05493617 0.008261859 0.02311086 0.05479425 0.008254349 0.02291017 0.05477595 0.007729053 0.02309066 0.05490285 0.007560729 0.02346819 0.05475831 0.007305383 0.02347433 0.05473554 0.007030129 0.02402412 0.05486738 0.00721234 0.02417832 0.05470991 0.007022976 0.02464413 0.05483716 0.007291555 0.02484899 0.05468535 0.007237493 0.02519315 0.05480462 0.007758677 0.02545094 0.0546714 0.007526338 0.0255087 0.05465626 0.007865309 0.02572631 0.05463975 0.008428335 0.02586317 0.05476808 0.00854212 0.02565973 0.05460727 0.009028851 0.02576071 0.05474251 0.009102702 0.02549034 0.05459052 0.009512305 0.02544331 0.05476033 0.009436607 0.02520167 0.05457091 0.009858191 0.024953 0.05469715 0.009723663 0.02469468 0.05454415 0.009964406 0.02435374 0.05467152 0.009727358 0.0241031 0.05452519 0.009838998 0.02376341 0.05464601 0.009483516 0.02357232 0.05451619 0.009378015 0.02319514 0.05460989 0.008805692 0.02312254 0.05449032 0.008750796 0.0229206 0.05444973 0.008422493 0.02288317 0.05457949 0.008111715 0.02315527 0.05443191 0.007819294 0.02304971 0.05455774 0.007673621 0.023391 0.05441027 0.007370471 0.02338838 0.05453658 0.007363915 0.02375489 0.05438953 0.007089912 0.0238558 0.05451345 0.007211983 0.0242604 0.05437177 0.006999731 0.02437895 0.05448997 0.007273197 0.02479976 0.05435317 0.007086634 0.02488982 0.05433613 0.007261574 0.02521574 0.05446845 0.007516741 0.02520602 0.05432152 0.007538318 0.02552163 0.0544461 0.007928431 0.02553117 0.05430096 0.00799489 0.02577918 0.0544216 0.008468151 0.02565371 0.05428415 0.008495151 0.02586221 0.05439966 0.008953809 0.02555871 0.05426383 0.008980572 0.02577489 0.05437189 0.009472191 0.02520495 0.05424183 0.009394347 0.02554571 0.05422377 0.009771406 0.02512347 0.05433923 0.009757518 0.02450197 0.05419445 0.009968817 0.02445006 0.05420362 0.009916424 0.02401399 0.05430573 0.009618461 0.02376306 0.05416613 0.009814202 0.02371066 0.05414813 0.009453177 0.02325516 0.05427062 0.009026348 0.02320992 0.0541225 0.008916795 0.02294701 0.05424189 0.008389711 0.02310252 0.05410033 0.008288741 0.02290612 0.05421733 0.007854104 0.02326267 0.05407756 0.00772196 0.02309519 0.05419641 0.007491946 0.0235725 0.05405241 0.007278025 0.02350372 0.05417466 0.007259428 0.0240122 0.05403828 0.007019102 0.02409321 0.05414497 0.007224678 0.02467912 0.05400872 0.007027804 0.02471113 0.05398714 0.007251441 0.02521234 0.05410617 0.007721602 0.02542638 0.05398041 0.007823407 0.02571004 0.05407619 0.008358836 0.02564376 0.05393105 0.008531332 0.02586019 0.05405288 0.008888065 0.02559006 0.05391269 0.009070158 0.02574414 0.05403077 0.009322464 0.02533477 0.05389273 0.009501218 0.02545434 0.05400782 0.009639918 0.02491492 0.05387151 0.00980997 0.02503514 0.05385726 0.009937286 0.02464562 0.05397927 0.009765565 0.02428883 0.05383861 0.009961605 0.02421581 0.05382055 0.009786486 0.02367383 0.05395281 0.009567499 0.02371096 0.05393213 0.009250223 0.02335458 0.05379688 0.009514629 0.02330827 0.05378788 0.009099364 0.02302742 0.05390614 0.008722543 0.02311933 0.05376523 0.008678197 0.02290225 0.05387288 0.007954597 0.02319169 0.05374127 0.007924795 0.02299284 0.05371397 0.007436633 0.02332413 0.05383938 0.007398366 0.02369862 0.05369681 0.007103681 0.02381336 0.05381667 0.00721687 0.02419131 0.05366837 0.006994247 0.02436679 0.05378997 0.007270872 0.02479714 0.0536499 0.007147789 0.02504748 0.05376523 0.007573246 0.02527368 0.05361229 0.007723927 0.02566164 0.05374056 0.008032917 0.0255751 0.05359297 0.008250176 0.02584385 0.05376428 0.008499145 0.02563649 0.05357885 0.008659005 0.02584838 0.05369979 0.008960902 0.02556723 0.05355924 0.009037494 0.0257532 0.05354285 0.00944817 0.02550369 0.05367243 0.009453415 0.02520304 0.05352604 0.009781777 0.02510529 0.05364507 0.009744286 0.02463656 0.05351161 0.009939968 0.02464652 0.0534873 0.009948492 0.02415645 0.05361175 0.009666264 0.02388167 0.05346685 0.009732663 0.02355766 0.05357915 0.009205162 0.02331036 0.05343317 0.009144723 0.02304774 0.05343836 0.008701026 0.02291435 0.05355 0.008567929 0.02310091 0.0534166 0.008142709 0.0229358 0.05352854 0.008099079 0.02316087 0.05337792 0.007769227 0.02307486 0.05350613 0.007640242 0.02341431 0.0533573 0.007314085 0.02345043 0.05348294 0.007324099 0.02383482 0.05333906 0.007097601 0.02385097 0.05332505 0.007004439 0.0242474 0.05345624 0.007200837 0.0244323 0.05330634 0.007060289 0.02481532 0.05343103 0.007355034 0.02497792 0.05328643 0.007305502 0.02528643 0.05340796 0.007693171 0.02538084 0.05326563 0.007630884 0.02559947 0.05338436 0.008183181 0.02561938 0.05324333 0.008117675 0.02581858 0.05336034 0.008712947 0.02563297 0.05321735 0.008761882 0.02584105 0.05337506 0.009196996 0.02541434 0.05319988 0.009334802 0.02559351 0.05331742 0.009535312 0.02510678 0.05318409 0.009690344 0.02524304 0.05315929 0.00991702 0.02474808 0.05329287 0.00973618 0.02459305 0.0531364 0.009954094 0.02415198 0.05326509 0.009706139 0.02396619 0.05311131 0.009741306 0.02358728 0.05323243 0.009256601 0.023355 0.05309718 0.009291946 0.02312636 0.05320876 0.008776724 0.02313596 0.05306696 0.008684039 0.02289605 0.05318289 0.008172094 0.02312695 0.05303955 0.007928729 0.02299904 0.05315417 0.007606923 0.02344405 0.05301874 0.007456004 0.02329552 0.05313241 0.007325708 0.02384257 0.05299347 0.007127404 0.02377212 0.05310165 0.007192015 0.0245226 0.05297422 0.006997823 0.02430266 0.0529471 0.007075846 0.02486616 0.05306798 0.007528126 0.02522963 0.05293041 0.007372617 0.02536177 0.05291801 0.007756769 0.02567231 0.05303812 0.008083224 0.02560007 0.05288696 0.008154749 0.02582269 0.05287969 0.008593916 0.02585524 0.05300188 0.008925378 0.02559375 0.05286419 0.00908041 0.02573484 0.05284005 0.009499013 0.02545928 0.05296748 0.009525001 0.02511793 0.05282068 0.009818673 0.02501708 0.05293411 0.009778261 0.02438604 0.05279022 0.009972691 0.02442747 0.05280578 0.009928405 0.02407938 0.05289947 0.009533226 0.02364701 0.05276811 0.009792864 0.02367508 0.05274623 0.009525239 0.02332168 0.05287545 0.009125769 0.02327245 0.05273336 0.009081482 0.02301412 0.05284881 0.008542895 0.02309602 0.05271059 0.008521854 0.02289336 0.05268985 0.007947444 0.02298027 0.05282407 0.00798875 0.02319854 0.05280053 0.007558465 0.02349293 0.05266153 0.007479786 0.0232703 0.05277693 0.007270753 0.0239672 0.05264276 0.007103264 0.02382248 0.05262172 0.007003426 0.02425825 0.05275577 0.007208347 0.0244354 0.05260711 0.007038295 0.02471703 0.05273252 0.007337033 0.02494436 0.05258351 0.007285833 0.02526396 0.05270278 0.007791638 0.02546876 0.05256134 0.00771737 0.0256555 0.05254137 0.008270502 0.02584648 0.05267292 0.008439242 0.02565062 0.05252414 0.008841216 0.02582424 0.05265116 0.008930325 0.0255745 0.05249619 0.009381532 0.02555495 0.05262356 0.009440839 0.0252245 0.05247408 0.00976032 0.02513462 0.05260032 0.009700775 0.02475488 0.05245476 0.009951114 0.02460342 0.05257463 0.00974816 0.02418076 0.0524339 0.009901165 0.02391695 0.05254083 0.009410142 0.02347224 0.05242055 0.009479463 0.02328008 0.05238056 0.009062826 0.02300751 0.05250495 0.008680284 0.023108 0.05237495 0.008351743 0.02289754 0.05247968 0.008121669 0.023153 0.05235177 0.007771074 0.02308404 0.0524519 0.00755757 0.02347803 0.05231076 0.00733298 0.02342593 0.05242437 0.007260739 0.02400952 0.05230242 0.007022261 0.02411341 0.05240303 0.0072124 0.02450233 0.05225259 0.007064044 0.0248335 0.05237287 0.007448732 0.02515864 0.05223721 0.007316946 0.02529579 0.05221468 0.007684171 0.02562713 0.05237948 0.008002161 0.02554351 0.05219745 0.008122444 0.02581548 0.05231916 0.00851655 0.02565622 0.05217647 0.008590281 0.0258603 0.05229604 0.009032249 0.02552425 0.05215477 0.009155869 0.02569806 0.05226743 0.009536743 0.02512437 0.05213218 0.009639739 0.02531588 0.0521149 0.009938895 0.02468985 0.052235 0.009761154 0.02440667 0.05208462 0.009949624 0.0241416 0.05220931 0.009641647 0.02383613 0.05206888 0.009779512 0.02365118 0.05218607 0.009323 0.02342087 0.05204892 0.009477734 0.02327215 0.05216324 0.008876323 0.02315747 0.05202805 0.009092867 0.02302306 0.052006 0.008553981 0.02288961 0.05213356 0.00818628 0.02312368 0.05198931 0.007983088 0.02297908 0.05196666 0.007517158 0.02324318 0.05210435 0.007616639 0.02343469 0.05195051 0.00721091 0.02359986 0.05208313 0.007333159 0.02382636 0.05193507 0.007031857 0.02406042 0.05205702 0.007194817 0.0244174 0.05191081 0.007016897 0.0246706 0.05203074 0.007360696 0.02498108 0.05188548 0.007278561 0.02524292 0.05200612 0.007723331 0.02541023 0.05186367 0.007689535 0.02563542 0.0518518 0.008141756 0.02582025 0.05197566 0.008383572 0.02566027 0.05182826 0.008605778 0.02585595 0.05194097 0.009135544 0.02548575 0.05180412 0.009090781 0.02573066 0.05179142 0.009535312 0.02542716 0.05191498 0.009554147 0.02506226 0.05177026 0.009850561 0.02494484 0.05188894 0.009763538 0.02449631 0.05174529 0.00995481 0.02454978 0.05173677 0.009937882 0.02408075 0.05185931 0.009645521 0.02384936 0.05171382 0.009726762 0.02357149 0.05182731 0.009168684 0.02327662 0.05169522 0.009424865 0.02323323 0.05167794 0.009038507 0.02299845 0.05165898 0.008500933 0.02289384 0.0517863 0.008262574 0.02309972 0.05164641 0.008078575 0.0229516 0.05162703 0.00765258 0.0231387 0.05175584 0.007642745 0.0234152 0.0516175 0.007137358 0.02374064 0.0517342 0.007340133 0.02380943 0.05171251 0.007204711 0.02428865 0.05156874 0.006993234 0.02439826 0.05168128 0.007342934 0.02498012 0.05154806 0.007120311 0.02496403 0.05152106 0.007468104 0.02547222 0.0516541 0.007766127 0.02543246 0.05149495 0.008072733 0.02580916 0.05162829 0.008307218 0.02564644 0.05148369 0.008562088 0.02586239 0.05159598 0.009051084 0.02553606 0.05145841 0.009081542 0.02573895 0.05143922 0.009531199 0.02542644 0.05160558 0.009504258 0.02511626 0.05141508 0.00987327 0.02492076 0.05153661 0.0097754 0.02444297 0.05142349 0.009949207 0.02454555 0.0513857 0.009946823 0.02412188 0.05150324 0.009574413 0.02370959 0.05136537 0.009785473 0.02366232 0.05134975 0.009460806 0.02325755 0.05148059 0.009230732 0.0233457 0.05132997 0.009104132 0.02302968 0.05145812 0.008754253 0.02312767 0.05130827 0.008550167 0.02288925 0.05143493 0.0082286 0.02312386 0.05129534 0.008015096 0.02296793 0.05140823 0.007674455 0.02338039 0.0512737 0.007618427 0.02316534 0.05124258 0.007094979 0.02381128 0.05137926 0.00728929 0.02390325 0.05122059 0.006996572 0.02438902 0.05135124 0.007213354 0.02454692 0.05120557 0.007082343 0.02487337 0.05132395 0.007434129 0.02511572 0.05117863 0.007327616 0.02531158 0.05116331 0.007695853 0.02563655 0.05129516 0.00794804 0.02554237 0.0511496 0.008163213 0.02583092 0.05126231 0.008693814 0.02565044 0.05112046 0.008741319 0.02583986 0.05110657 0.009242773 0.0256471 0.05123239 0.009298205 0.02535587 0.05108428 0.009553551 0.02539879 0.05121105 0.009602367 0.02499049 0.05107325 0.00980705 0.02504992 0.05118918 0.009747803 0.02450835 0.05104696 0.009960532 0.02450811 0.05116182 0.009679198 0.02389591 0.05104297 0.009842514 0.02375769 0.05113309 0.009270191 0.02337408 0.05101639 0.009368002 0.02319687 0.05111271 0.008855938 0.023157 0.05109161 0.008384823 0.02310252 0.05107045 0.007930696 0.02323043 0.05104815 0.007521569 0.02352279 0.05675083 0.008099198 0.02315229 0.05673968 0.007627665 0.02341789 0.05669981 0.007253289 0.02399992 0.0566706 0.007232844 0.02465891 0.05663812 0.00756216 0.02527785 0.05660265 0.008303642 0.02565813 0.05656969 0.009040474 0.02552831 0.05654573 0.009469568 0.02518075 0.05652028 0.009732425 0.02467441 0.05649453 0.009719669 0.02407819 0.05646479 0.009418368 0.02348124 0.0564351 0.008812189 0.02314585 0.0564078 0.008207023 0.02311676 0.05638015 0.007643342 0.02341699 0.0563547 0.007298767 0.02387189 0.05632895 0.007210969 0.02446144 0.05630159 0.007382333 0.02505135 0.05627465 0.007844746 0.02547901 0.05624479 0.008484065 0.02567225 0.05621248 0.009195625 0.0254364 0.05618625 0.009586811 0.02502322 0.05615264 0.009772717 0.0242716 0.05612176 0.009500205 0.02360582 0.05609464 0.009032547 0.0232191 0.05607181 0.008524 0.02310252 0.05604267 0.007878541 0.02323502 0.05601155 0.007374107 0.02373552 0.05598068 0.007192552 0.02443033 0.0559535 0.00737822 0.02501177 0.05593037 0.007721781 0.0254054 0.05589872 0.00839436 0.02566683 0.05586469 0.009131968 0.02548098 0.05584239 0.009513497 0.02512204 0.0558151 0.009761273 0.02453988 0.05578261 0.009637713 0.02382373 0.05575627 0.009258389 0.02336096 0.05570483 0.008153021 0.02312386 0.05567157 0.007503509 0.02354842 0.05564451 0.007229387 0.02410846 0.0556184 0.007243275 0.02469676 0.05559307 0.007509052 0.02520567 0.05556213 0.008074104 0.0256024 0.05553311 0.008748829 0.02562493 0.05551117 0.009209513 0.02542567 0.05548375 0.009629786 0.02495241 0.05545926 0.009754717 0.02441626 0.05543231 0.009639978 0.02381706 0.05540615 0.009253978 0.0233615 0.05538517 0.008820056 0.02314829 0.05536031 0.008265852 0.02311009 0.05533605 0.007742464 0.02333974 0.05531418 0.007405996 0.02368533 0.05528253 0.007188677 0.02435559 0.05524414 0.007476866 0.02519178 0.05520558 0.008235454 0.02564585 0.05517804 0.008871734 0.02558827 0.05515217 0.009372353 0.02530169 0.05512809 0.009669303 0.02483707 0.05510568 0.009758591 0.02432316 0.05507951 0.009611427 0.02377361 0.05504584 0.009068489 0.02322161 0.05501496 0.008358597 0.02310502 0.05498784 0.007784247 0.02330094 0.05495482 0.007291972 0.02386945 0.05492234 0.007220447 0.02459412 0.05490112 0.007405161 0.02505624 0.05487394 0.007852494 0.0255028 0.05484664 0.008445084 0.02564913 0.05482232 0.008987784 0.02555376 0.0547716 0.009726703 0.02470391 0.05474036 0.009705424 0.02399402 0.05471521 0.009404659 0.02349692 0.05469369 0.009005844 0.02320933 0.05467092 0.008498847 0.02310329 0.05464208 0.007845282 0.02324718 0.05460995 0.007361471 0.02376753 0.0545895 0.00721544 0.02421206 0.05456614 0.007257401 0.02474695 0.05454009 0.007559239 0.02526444 0.05450689 0.008188962 0.02563589 0.05447375 0.008966624 0.0255655 0.05444288 0.009506821 0.02514541 0.05441546 0.009748876 0.02456521 0.05438184 0.009638547 0.02379357 0.05434131 0.008982419 0.02318423 0.05430668 0.008182764 0.0231257 0.05428093 0.007656514 0.02340626 0.05425119 0.007259964 0.02394467 0.05421388 0.007266581 0.02480846 0.05417579 0.00778681 0.02546691 0.05414104 0.008565425 0.0256595 0.05411535 0.009131193 0.02547162 0.05408877 0.009579062 0.02505427 0.05406087 0.009752869 0.02444815 0.05403119 0.0096367 0.02378898 0.05400145 0.009152948 0.02329379 0.05397504 0.008616626 0.02309751 0.05393904 0.007805109 0.02327162 0.05390816 0.007334172 0.02381527 0.05388104 0.007200241 0.0244072 0.05384802 0.007426738 0.02512437 0.05381554 0.008006632 0.02556473 0.05376827 0.009086132 0.02551281 0.05374109 0.009532153 0.02509915 0.05371552 0.00974971 0.02456164 0.0536825 0.009647488 0.02381706 0.05364507 0.009059369 0.02322411 0.05361872 0.00844717 0.02310353 0.05359309 0.007876038 0.02324014 0.05356675 0.007438719 0.02364617 0.05353766 0.007189393 0.02427196 0.0535016 0.007385909 0.02504122 0.05347669 0.007788777 0.02544981 0.05345571 0.008242964 0.02562689 0.0534321 0.008782088 0.02562332 0.05338305 0.009636342 0.0249502 0.05334591 0.009749293 0.02412742 0.05330866 0.009313821 0.02338802 0.05327266 0.008533477 0.02308779 0.05324566 0.007942259 0.02322238 0.05321812 0.007441103 0.02361476 0.05318582 0.007203936 0.02428734 0.05315512 0.007344782 0.02498108 0.05313003 0.007740378 0.02541148 0.05310672 0.008213639 0.02562743 0.05308502 0.008707046 0.02563118 0.0530588 0.009266555 0.02539402 0.05303031 0.009648382 0.02489799 0.05299782 0.009758889 0.02416044 0.05296695 0.009429574 0.02352052 0.05294114 0.008956313 0.02318835 0.05290865 0.008236765 0.02310645 0.05287581 0.007572293 0.02347278 0.0528531 0.007294416 0.02391654 0.05282592 0.00720191 0.02454113 0.05279862 0.007437467 0.02510499 0.05277431 0.007836878 0.02548414 0.05274122 0.008566379 0.02566671 0.05270874 0.009245276 0.02540332 0.05268758 0.009574174 0.02502983 0.05266028 0.009770631 0.02442908 0.0526278 0.009585499 0.02372562 0.05260145 0.009168088 0.02329784 0.05258136 0.008730351 0.02312719 0.05255007 0.008046269 0.02315682 0.05251234 0.007379174 0.02370637 0.05248248 0.007201671 0.02437978 0.05245989 0.00731343 0.02488249 0.05243825 0.007584095 0.02528643 0.05239504 0.008473813 0.02565342 0.05236351 0.00916469 0.02547591 0.052329 0.009675204 0.02485132 0.0522992 0.009749174 0.02418792 0.05227267 0.009519338 0.02363026 0.05224174 0.008988916 0.02318817 0.05220675 0.008183836 0.02312409 0.05218118 0.007655382 0.02340763 0.05215936 0.007350444 0.02378046 0.05212771 0.007191777 0.02446776 0.05209308 0.007500469 0.02520751 0.05206733 0.007988512 0.02555054 0.05203998 0.008592069 0.02566146 0.05201303 0.009182214 0.02543967 0.05198311 0.009640991 0.02495503 0.05194956 0.009747624 0.02418369 0.05192351 0.009537041 0.02365553 0.05190181 0.009165525 0.02330219 0.05187517 0.008590936 0.02309107 0.05183643 0.007755339 0.02330392 0.05179888 0.007246673 0.02400392 0.05176752 0.007243871 0.02470189 0.0517463 0.007468163 0.0251469 0.05171912 0.007951796 0.0255528 0.05169183 0.008555471 0.0256474 0.05166751 0.009087681 0.02550572 0.05161547 0.009758293 0.02456653 0.05158436 0.009653866 0.02386361 0.05155467 0.009222626 0.02332383 0.05151915 0.008475303 0.02308648 0.05148345 0.007684707 0.02335906 0.05145257 0.007290422 0.02392047 0.05142366 0.007205009 0.02457135 0.05139023 0.007556438 0.0252673 0.05135911 0.008155047 0.02561837 0.05132406 0.008971869 0.02557641 0.05129081 0.009533166 0.02510035 0.05126911 0.009729802 0.02464473 0.05124837 0.00973916 0.02416712 0.05122101 0.009496808 0.02358478 0.05118393 0.008819997 0.02312815 0.05114942 0.008022904 0.02317577 0.05111306 0.00737828 0.02369636 0.05108201 0.007205009 0.0243982 0.0510537 0.007363617 0.02501016 0.05674993 0.00728631 0.02374655 0.05674904 0.00750792 0.02550035 0.05674958 0.007066309 0.02459299 0.05673533 0.00806117 0.02579975 0.05669987 0.008774876 0.02582901 0.05646353 0.007055222 0.02395677 0.05631572 0.009555339 0.02540135 0.05591011 0.009931087 0.02404564 0.05490183 0.00976926 0.02509945 0.05487769 0.009962201 0.02448225 0.05448114 0.009557127 0.02335762 0.05445975 0.009085953 0.02303123 0.05394923 0.007546484 0.02551907 0.05392771 0.008040726 0.02579069 0.0537278 0.008253097 0.02291744 0.0536077 0.007385075 0.02537643 0.05342799 0.009492397 0.02329951 0.05338448 0.008432805 0.02289009 0.05302894 0.008293807 0.02291268 0.05238682 0.009661376 0.02347093 0.05234283 0.00865072 0.02290898 0.05231708 0.007996857 0.0229696 0.05226069 0.007027506 0.02403259 0.05157738 0.007185995 0.02363693 0.05123472 0.00729531 0.02349179 0.05674993 0.008686363 0.02585124 0.05075687 0.009522616 0.02358061 0.05089485 0.009480059 0.02331548 0.05088788 0.009705901 0.02359765 0.05075258 0.009772658 0.02446633 0.0507875 0.009763181 0.02391445 0.0509178 0.009867131 0.02389991 0.05080521 0.009872674 0.02437919 0.05090004 0.009935855 0.02430325 0.0507552 0.009680211 0.02487701 0.05084264 0.009842753 0.02477788 0.05086928 0.009780168 0.02501112 0.05075317 0.009084403 0.02552843 0.05078464 0.009509086 0.02526468 0.05090612 0.009580612 0.02533507 0.05088162 0.009289026 0.02558004 0.05080646 0.00895071 0.02568715 0.05091452 0.008904218 0.02577644 0.05083268 0.008502483 0.02579355 0.05076354 0.008373916 0.02568686 0.05090677 0.008458316 0.02583384 0.05075347 0.007861852 0.02551001 0.05082297 0.008090138 0.02572494 0.05099493 0.00813049 0.02581411 0.05085098 0.007855415 0.0256654 0.05075508 0.007478415 0.02519118 0.05089002 0.007551372 0.02549451 0.05082118 0.00747323 0.02535355 0.05077338 0.007275283 0.0249657 0.05091255 0.007262766 0.02517968 0.05075526 0.007203698 0.02458095 0.05090594 0.00713694 0.02493846 0.05085742 0.00706619 0.02462655 0.05075359 0.007327973 0.02379393 0.05078357 0.00712347 0.02430576 0.05089646 0.007031857 0.02427941 0.05084747 0.007100582 0.02399742 0.05089312 0.007168829 0.02375316 0.05075585 0.007714509 0.02331972 0.05081695 0.0074144 0.02346909 0.05090087 0.007464051 0.02332818 0.05083113 0.007837772 0.02311849 0.05075854 0.008442461 0.02306115 0.05080986 0.008195757 0.02301204 0.05092161 0.008108317 0.02296334 0.05090886 0.00849092 0.0229184 0.05086302 0.008786857 0.02296888 0.05076164 0.009114921 0.0232132 0.05083048 0.00914216 0.02312582 0.0509392 0.009150624 0.02307105 0.05693274 0.006603777 0.026322 0.05678409 0.00715357 0.02662181 0.05694383 0.007136344 0.02671766 0.05689954 0.007614195 0.02692365 0.05675458 0.008067131 0.02687728 0.05686712 0.00801295 0.02700412 0.05694061 0.008238255 0.02706778 0.05680447 0.008574247 0.02699905 0.05692291 0.008802413 0.02705383 0.05676084 0.009202837 0.02681416 0.05684471 0.009308457 0.02690333 0.05694383 0.009346902 0.0269342 0.05693113 0.009824514 0.02671653 0.05688184 0.01008141 0.02653187 0.05675452 0.009904146 0.0264784 0.05695468 0.0104773 0.02619713 0.05681967 0.01042652 0.02615445 0.0569179 0.01077914 0.02578407 0.05681103 0.01080906 0.0256074 0.05675041 0.01073122 0.02549946 0.05691969 0.01099503 0.02535301 0.05692261 0.01112896 0.02488869 0.05676805 0.01102936 0.02472722 0.05691874 0.01117086 0.02450674 0.05692571 0.01116394 0.02409368 0.05680871 0.01110112 0.02427405 0.05694216 0.01108264 0.02365952 0.05675262 0.01090931 0.02374392 0.05681121 0.01103967 0.02379113 0.05681699 0.01090741 0.02334779 0.05694675 0.01091766 0.02321076 0.05683147 0.01065039 0.02285218 0.05675309 0.01045042 0.02278667 0.0569638 0.01058006 0.02266991 0.05691576 0.0103597 0.02243697 0.05682283 0.01019585 0.02236992 0.05691426 0.009829998 0.02204322 0.05676054 0.009756147 0.02216649 0.05681288 0.009473919 0.02194404 0.05695354 0.009355604 0.02182018 0.05686652 0.00895667 0.02174401 0.05695104 0.008764445 0.02168738 0.05675512 0.008944571 0.02188646 0.05679267 0.008453786 0.02177703 0.05691444 0.008198916 0.02169549 0.05675786 0.007799565 0.02192026 0.05685251 0.007565081 0.0218715 0.05694699 0.007607698 0.0218209 0.05691486 0.007137775 0.02204161 0.05676352 0.007053256 0.0222553 0.05692791 0.006795287 0.02227103 0.05681377 0.006682515 0.02246397 0.05689525 0.006425619 0.02264285 0.05688792 0.006187379 0.02297413 0.05675661 0.006452202 0.02285921 0.05689162 0.005985796 0.02337437 0.05677461 0.006109893 0.02338159 0.05694651 0.005863726 0.02371209 0.05682796 0.005858719 0.02402979 0.05691015 0.005792081 0.02422982 0.05675166 0.005992889 0.02407509 0.05695521 0.005801618 0.02473646 0.05681627 0.005864799 0.02470171 0.05691426 0.00592339 0.02521389 0.05689942 0.006041347 0.02550727 0.05675733 0.006058275 0.02516704 0.05696117 0.006215631 0.02584511 0.05675053 0.00652796 0.02596539 0.0568248 0.006333231 0.02591401 0.05678689 0.006833374 0.02639168 0.05959832 0.006977438 0.02661097 0.05954825 0.008001863 0.02703475 0.05957376 0.008591353 0.02707386 0.05955785 0.009276509 0.0269593 0.05954021 0.009880781 0.02669095 0.0595839 0.01028937 0.02637344 0.05954658 0.01066124 0.02597594 0.05958569 0.01088631 0.02558577 0.05955594 0.0110833 0.02510845 0.05957329 0.01117491 0.02452439 0.05954521 0.01105719 0.02356082 0.05957752 0.0108245 0.02303636 0.05955296 0.009999334 0.02213913 0.05957061 0.009347856 0.02181553 0.0595743 0.008217394 0.02168965 0.059578 0.006047487 0.023216 0.05960708 0.006251871 0.02588051 0.05958235 0.006545543 0.02625322 0.05972939 0.006690919 0.02622073 0.05974489 0.006349861 0.02573829 0.05961954 0.006022572 0.0254541 0.05972439 0.006025314 0.02516746 0.05956768 0.005829751 0.02490353 0.05965763 0.005833804 0.02449434 0.05974417 0.005971491 0.02467936 0.05954903 0.0057832 0.0242536 0.05974358 0.005961775 0.02404767 0.05964249 0.005864024 0.02386432 0.05955362 0.005864202 0.02371114 0.05970662 0.006026625 0.02351444 0.05973118 0.006234526 0.02312159 0.05957466 0.006347537 0.02272409 0.0596897 0.006582796 0.02256387 0.05974638 0.006813049 0.0224989 0.05958712 0.00675249 0.02231085 0.0596885 0.007081508 0.02215653 0.05957525 0.007179021 0.02201372 0.05974823 0.00761497 0.02201402 0.05968892 0.007535874 0.02192986 0.05957603 0.007643282 0.02181339 0.05970388 0.008068382 0.02179908 0.05960935 0.008714437 0.02169966 0.05974239 0.008820831 0.0218569 0.05968612 0.009232819 0.02185708 0.05967223 0.009933352 0.02216118 0.05974358 0.00987786 0.02225893 0.05960994 0.01045054 0.02254641 0.05974298 0.01033347 0.02264672 0.05967813 0.01069599 0.02295017 0.05974864 0.01070147 0.02320683 0.05969387 0.01092696 0.02343279 0.05960667 0.0111373 0.02395474 0.05971467 0.01106125 0.0240615 0.05965214 0.01112633 0.02465826 0.05974066 0.01100611 0.02467477 0.05969053 0.01092433 0.02534145 0.05969053 0.01058852 0.02594733 0.05974858 0.01068824 0.02557349 0.05969107 0.01020699 0.02634781 0.05974811 0.009912788 0.0264461 0.05967044 0.009811937 0.02666461 0.05966544 0.009350478 0.0268746 0.05973547 0.00915873 0.02683436 0.05967789 0.00881958 0.02699249 0.05974686 0.008053123 0.02687132 0.0596854 0.00808537 0.02698224 0.05958288 0.007497251 0.02688562 0.05973577 0.007347226 0.02667331 0.05806988 0.008775055 0.010598 0.05805802 0.007471203 0.01103109 0.05816763 0.007371544 0.01093679 0.05820691 0.008798599 0.0104987 0.05806881 0.007120192 0.0123586 0.05820697 0.007021009 0.01238828 0.05807077 0.008134841 0.01331794 0.05820906 0.008111894 0.01341491 0.05805742 0.009437263 0.01288026 0.05816543 0.009538471 0.01297599 0.05805766 0.00974816 0.01156741 0.05816763 0.009880363 0.01152801 0.05973875 0.009571313 0.01300913 0.05973857 0.009923875 0.01151609 0.05973875 0.008102178 0.01344972 0.05973875 0.006985664 0.01239734 0.05973875 0.007338821 0.01090431 0.05973869 0.008807897 0.01046377 0.05099987 0.007208585 0.0122475 0.05099987 0.007021903 0.0123226 0.05100971 0.007204771 0.01166367 0.05099993 0.007080197 0.01141726 0.05101859 0.007456719 0.01274538 0.05100029 0.007602274 0.01083898 0.05099672 0.007400929 0.01091045 0.05100601 0.00794363 0.01313608 0.05099135 0.007850229 0.01060783 0.05098813 0.008365988 0.01048123 0.05100089 0.008694827 0.01324921 0.05099892 0.008864283 0.01053738 0.05099987 0.00938028 0.01295602 0.05099993 0.009779632 0.01243323 0.05100744 0.009922206 0.01179093 0.05674821 0.008755266 0.01340371 0.0567376 0.009304404 0.01315546 0.05668061 0.009657859 0.01283025 0.05667382 0.009925067 0.01217424 0.05675041 0.009505152 0.01122188 0.05675005 0.009742081 0.01244467 0.05663317 0.009916424 0.01167243 0.05674999 0.009768903 0.01180839 0.05661606 0.009753704 0.01122027 0.05659568 0.009495139 0.01089918 0.0567404 0.009131968 0.01087939 0.05657762 0.009046316 0.01059377 0.05673265 0.008691847 0.01070719 0.05656492 0.008624434 0.01048505 0.05654847 0.008227229 0.01048755 0.0566774 0.008030414 0.01073873 0.05652827 0.007716655 0.01067048 0.05664622 0.007454872 0.01115721 0.05651652 0.007340013 0.01097393 0.05648958 0.007023394 0.01153582 0.05661439 0.007167041 0.01184117 0.05647981 0.00701338 0.01229548 0.05658078 0.007326722 0.01256161 0.0564357 0.007211029 0.01277178 0.05654805 0.007863461 0.01310837 0.05641824 0.007607877 0.01317292 0.05640071 0.008043766 0.01338428 0.0565139 0.008606851 0.01322746 0.05638074 0.008505403 0.01344388 0.05636078 0.009045064 0.0133199 0.05648422 0.009249746 0.01296967 0.05633479 0.009533882 0.01298981 0.05645799 0.009606003 0.01250237 0.05631417 0.009852409 0.01245349 0.05643332 0.009737432 0.01195627 0.05629014 0.009941279 0.01187485 0.05626809 0.00979501 0.01130956 0.05640506 0.009573817 0.01132911 0.05624538 0.009412884 0.01081472 0.05637836 0.009152293 0.01088637 0.0562542 0.009077012 0.01061385 0.0563547 0.008664667 0.01069509 0.05621504 0.008713603 0.01048994 0.05632233 0.007912993 0.01077979 0.05618482 0.008027374 0.01052844 0.05619287 0.007541954 0.01078647 0.05629241 0.007412374 0.01122558 0.05614364 0.007094979 0.01135665 0.05626767 0.0071913 0.01174247 0.05612909 0.006974518 0.01182478 0.05623525 0.00728178 0.012501 0.05609959 0.007027089 0.01237589 0.05611366 0.007171273 0.01268196 0.05607712 0.007424235 0.01303184 0.05620026 0.007806301 0.01306319 0.05604797 0.007851719 0.01331937 0.0561766 0.008322715 0.01322293 0.05602663 0.008525669 0.0134449 0.05615055 0.008923292 0.01315617 0.05603599 0.008954346 0.01335144 0.05599045 0.009566605 0.01295125 0.05612093 0.009447991 0.01276105 0.05609852 0.009686529 0.0122919 0.0559597 0.009890317 0.0123471 0.05607062 0.009708046 0.01164638 0.05593842 0.009934365 0.0118066 0.05591952 0.009776353 0.01128196 0.05603945 0.009357631 0.01105099 0.05590713 0.009534001 0.0109418 0.05588829 0.009172141 0.01065194 0.05601745 0.00893861 0.01077598 0.05586409 0.00862205 0.01048237 0.05598855 0.008276104 0.01067936 0.05584448 0.008186638 0.01049995 0.05583149 0.007756412 0.01064383 0.05595552 0.00760883 0.01099312 0.05580973 0.007322311 0.01100027 0.05592083 0.007189393 0.01167583 0.05578404 0.007018387 0.01154875 0.05576199 0.006987631 0.0121693 0.05588734 0.007266163 0.01242399 0.05573958 0.007188975 0.01274108 0.05585759 0.007673859 0.0129857 0.05572241 0.007515132 0.01310265 0.05570518 0.007902622 0.01333159 0.05582773 0.008303523 0.01322245 0.05568587 0.008446633 0.01344418 0.05580598 0.008799552 0.01318901 0.05566233 0.008869946 0.01337939 0.05564987 0.009277284 0.01319074 0.05577838 0.009337782 0.01288425 0.05562758 0.00968635 0.01279115 0.05575513 0.009637594 0.01243829 0.05561506 0.009896576 0.01231378 0.05572938 0.009733974 0.01187103 0.05559045 0.009934425 0.01184463 0.05556976 0.00979495 0.01130896 0.05569559 0.009458065 0.01113551 0.05554229 0.009485661 0.01088953 0.055534 0.0091241 0.01062875 0.05570244 0.008891761 0.010773 0.05553865 0.008680939 0.01049268 0.05564218 0.008371949 0.0106787 0.05551683 0.008120417 0.01051831 0.05561065 0.007679343 0.01092493 0.05547922 0.007722854 0.01066219 0.05545663 0.007168054 0.01120269 0.05557662 0.007242858 0.01153737 0.05542165 0.006988942 0.01174908 0.05541461 0.006992697 0.01225769 0.05554425 0.007208764 0.01228904 0.05539131 0.007244586 0.0128147 0.0555076 0.007682561 0.01299393 0.05536961 0.007548451 0.01313543 0.05534964 0.007976353 0.01336413 0.05547398 0.008380234 0.01323485 0.05532878 0.008500814 0.01344341 0.05545079 0.008904933 0.01314771 0.05531287 0.009047091 0.01331555 0.05542218 0.009442508 0.01279228 0.05529218 0.009463667 0.01305276 0.0552752 0.009747564 0.01268786 0.05538976 0.009727418 0.01209706 0.05525743 0.00990957 0.0122686 0.055233 0.009878933 0.01151341 0.05536413 0.009657502 0.01151794 0.05520606 0.009586393 0.01099807 0.05534088 0.009375989 0.01107728 0.05518674 0.009165823 0.01065176 0.05531805 0.008952975 0.01077604 0.05516594 0.008647263 0.01048225 0.0552954 0.008446395 0.01068305 0.05514371 0.008084297 0.01052081 0.0552687 0.007853567 0.01081901 0.05513077 0.007678389 0.01069504 0.05510687 0.007377386 0.01093357 0.05524313 0.007422327 0.01121091 0.05509281 0.007089793 0.01137763 0.05521297 0.007162809 0.01185894 0.05507993 0.006970822 0.01189309 0.05505239 0.007005274 0.01226902 0.05518174 0.007322907 0.01254278 0.05504029 0.007181107 0.01271486 0.05515849 0.007656693 0.01295471 0.05502098 0.007538795 0.01312601 0.0551294 0.008275747 0.01323467 0.05499488 0.008060812 0.01339286 0.0549798 0.008743524 0.01341825 0.05509829 0.008958041 0.01313215 0.0549494 0.009311079 0.01317858 0.05506944 0.009495556 0.01271975 0.05492824 0.009690642 0.01278507 0.05503892 0.009728252 0.01207661 0.05492156 0.009938478 0.01206636 0.05501741 0.009676933 0.01159745 0.05487221 0.009812772 0.01135557 0.05499404 0.009429216 0.01112627 0.05485528 0.00952655 0.01092612 0.05483841 0.009207189 0.01067996 0.05496484 0.00887382 0.01073884 0.05482083 0.008806705 0.01051592 0.05480366 0.008215188 0.01048767 0.05493497 0.008210003 0.01070231 0.05491328 0.007750153 0.01089292 0.05477529 0.007686734 0.01068317 0.05474895 0.007222235 0.01112484 0.05488175 0.007267475 0.01143813 0.05473411 0.006992757 0.01166802 0.05484735 0.007199108 0.01220226 0.05470877 0.007003426 0.01225763 0.05468952 0.007207691 0.01276308 0.05481404 0.007553339 0.01288819 0.05467313 0.007572233 0.01315206 0.05477547 0.008346319 0.01324081 0.05465096 0.007969379 0.01336026 0.05463093 0.008455991 0.01344144 0.05461269 0.008962929 0.01335364 0.0547477 0.008972048 0.01312363 0.05459254 0.009432256 0.01307213 0.05471611 0.009539544 0.01266658 0.05459004 0.009822368 0.01254224 0.05468171 0.009734869 0.01192539 0.05454069 0.009934604 0.0118311 0.05453813 0.009741723 0.01119196 0.0546478 0.009501338 0.01119041 0.05448746 0.009240448 0.01069957 0.05461543 0.008889555 0.01075512 0.05447155 0.008704423 0.01048946 0.05458629 0.008225083 0.010688 0.05444085 0.008125185 0.01050513 0.05442363 0.00758773 0.01075398 0.05459564 0.007675588 0.01096487 0.0544027 0.007182657 0.0111798 0.05452919 0.00725162 0.0114839 0.05437839 0.006989181 0.01173311 0.05448931 0.007231354 0.01238465 0.05435389 0.007012784 0.01232206 0.0543428 0.007259309 0.01283967 0.05445855 0.007656455 0.01295024 0.0543285 0.00785613 0.01331776 0.05443024 0.008246481 0.0132302 0.0543015 0.008535325 0.01343417 0.0543974 0.008985161 0.01312386 0.0542798 0.009098231 0.01328456 0.05424273 0.009405672 0.01310002 0.05437093 0.009453296 0.01275628 0.05422377 0.009741485 0.01270252 0.05434429 0.009713709 0.01219934 0.05420625 0.009920954 0.01218694 0.05430942 0.009634733 0.01141995 0.05418395 0.009931445 0.01180899 0.05417543 0.009799003 0.0113216 0.05415171 0.00950396 0.0109052 0.05427908 0.009167611 0.0108996 0.05412811 0.008852839 0.01051646 0.05425733 0.00871092 0.01070266 0.0540992 0.008228421 0.01049143 0.05423408 0.008188009 0.01071184 0.05407851 0.007682144 0.01068484 0.05421125 0.00770998 0.0109145 0.05405545 0.00726813 0.01106411 0.0541886 0.007365524 0.01129752 0.05403786 0.007032871 0.01154047 0.0541644 0.007181465 0.01181727 0.05401718 0.006973445 0.01197171 0.05400419 0.007036626 0.01240307 0.05414152 0.007238388 0.01233714 0.05411732 0.007511317 0.01282089 0.05398237 0.007311701 0.01290035 0.05395966 0.007795155 0.0132966 0.05408692 0.008098483 0.01319533 0.05393457 0.008402168 0.01343858 0.05405533 0.008806705 0.01318693 0.05391532 0.008942842 0.01335984 0.05402511 0.009411394 0.01282405 0.05388432 0.009431183 0.01308023 0.05387508 0.009740829 0.01270961 0.05385762 0.009930551 0.01219123 0.05399388 0.00971049 0.01219785 0.05396419 0.009664118 0.0114966 0.05383086 0.009897112 0.01159536 0.05380898 0.009647667 0.01106631 0.05393213 0.009223937 0.01093488 0.05378878 0.009229063 0.01067864 0.05391061 0.008788764 0.0107277 0.05376529 0.008651375 0.01048505 0.05388724 0.008257627 0.01069211 0.05376988 0.008185684 0.01050287 0.05385756 0.007638096 0.01096141 0.05374467 0.007575631 0.01075804 0.05369102 0.007080912 0.01138079 0.05382877 0.007259011 0.01150679 0.05367958 0.00697565 0.01182085 0.05380523 0.007179379 0.01202982 0.0536502 0.007036328 0.01239711 0.05377244 0.007424414 0.01274275 0.05363953 0.007280766 0.01286751 0.05361509 0.007581412 0.013152 0.05374044 0.008008897 0.01315158 0.05360186 0.007953822 0.01335203 0.0535795 0.008518338 0.01344269 0.05371809 0.008528172 0.01323258 0.05356889 0.008996188 0.01333767 0.05369675 0.008984088 0.01311647 0.05354404 0.009352207 0.01313668 0.05367428 0.009407937 0.01280802 0.05352753 0.009715974 0.01274263 0.05364394 0.009726405 0.01218873 0.05349773 0.009919703 0.0122202 0.05348598 0.009920239 0.01170253 0.05360686 0.009597539 0.01135689 0.0534662 0.009734332 0.01118969 0.05344456 0.009384572 0.01079326 0.05357611 0.009122669 0.01086705 0.05345094 0.008999109 0.01058536 0.05355364 0.008624672 0.010692 0.05341631 0.008692741 0.01048672 0.05352985 0.008099317 0.01072651 0.05339705 0.008194386 0.01048791 0.05337643 0.007654309 0.01070618 0.05349874 0.007482886 0.01110941 0.05335325 0.007279574 0.01104736 0.05333548 0.00703454 0.01152306 0.05347132 0.007216095 0.01166158 0.05331677 0.006976604 0.01206856 0.05344116 0.00722295 0.01235884 0.05329352 0.007134616 0.01265132 0.05340921 0.007638275 0.01293629 0.05326503 0.007566809 0.01314765 0.05325573 0.008069634 0.01339322 0.05338025 0.008233964 0.01322811 0.05322098 0.008551657 0.01343679 0.05334591 0.00902462 0.01311123 0.05321168 0.009005904 0.01333534 0.05321633 0.009402811 0.01309168 0.0533173 0.009505867 0.01268428 0.05319458 0.009757339 0.01265954 0.0532906 0.00972718 0.01211625 0.05315577 0.009917557 0.01222789 0.05312967 0.009924411 0.01172775 0.05326163 0.009642779 0.01147133 0.05310815 0.009700834 0.01113522 0.05323356 0.009251832 0.01095533 0.05309736 0.009285032 0.01071679 0.05320137 0.008586227 0.01067095 0.05306327 0.008660912 0.01048284 0.05304479 0.008106768 0.01051503 0.05316501 0.007768452 0.01086467 0.05301821 0.007528245 0.0107842 0.05300271 0.007138252 0.01126044 0.05313754 0.007353127 0.0113185 0.0531091 0.007164478 0.01193648 0.05297476 0.006968677 0.01190942 0.05296617 0.007124423 0.01261746 0.05308181 0.007323205 0.01254016 0.05305242 0.007755219 0.01304394 0.05292463 0.007471084 0.01307404 0.05290305 0.007868051 0.01332432 0.05301618 0.008581042 0.01324075 0.05288493 0.008388102 0.01343917 0.05286657 0.008931159 0.01336419 0.0529837 0.00925374 0.01295942 0.05284416 0.009399354 0.01311129 0.05295228 0.009667813 0.01238596 0.05282294 0.009764015 0.01265829 0.05280154 0.009934127 0.01213461 0.05292159 0.00970894 0.0116834 0.05277973 0.009892284 0.01157951 0.05289065 0.009381473 0.01106739 0.05276137 0.009651124 0.01107722 0.05274522 0.009364545 0.01078659 0.05286651 0.008917093 0.01076871 0.05272722 0.009020328 0.01058089 0.05283629 0.008221387 0.01068222 0.05270981 0.00846517 0.0104742 0.05268949 0.008058905 0.01052922 0.05267655 0.007642984 0.01071101 0.05280637 0.007626295 0.01098972 0.05265486 0.007241904 0.01110458 0.05278164 0.007283866 0.01143598 0.05262994 0.006983578 0.01169288 0.05279397 0.007193028 0.01198095 0.05260527 0.00701791 0.01231783 0.05273377 0.007296323 0.01249939 0.05258274 0.007261872 0.012847 0.05270624 0.007698237 0.01299399 0.05257207 0.00762844 0.01319015 0.05254167 0.008133053 0.01340639 0.05268037 0.008240401 0.0132119 0.05265378 0.008853852 0.01318353 0.05251634 0.008768558 0.01341426 0.05253022 0.00908035 0.01329523 0.05249249 0.009439349 0.01307183 0.052621 0.009453117 0.01275962 0.05247223 0.009746372 0.01269364 0.05258798 0.009745836 0.01205855 0.05245643 0.00992912 0.01216948 0.05243027 0.009828507 0.01137566 0.05255514 0.009570062 0.0113272 0.05239355 0.009440004 0.01084041 0.05253022 0.009193658 0.01091396 0.0523768 0.008937239 0.01055365 0.05250728 0.008710324 0.01070755 0.05236375 0.008530139 0.01047748 0.05248552 0.008213281 0.01070022 0.05234146 0.008123815 0.01050859 0.05232691 0.00767064 0.01069629 0.05246293 0.007751226 0.01089727 0.05233138 0.007321715 0.01100754 0.05243921 0.007363379 0.0112788 0.05230998 0.007048487 0.01149755 0.05240732 0.00716865 0.01199442 0.05227077 0.006967961 0.0119518 0.05224645 0.007053613 0.01245629 0.05237859 0.007357835 0.01261216 0.05221921 0.007415354 0.01302689 0.05235195 0.007781445 0.01304692 0.05222696 0.00789386 0.01333332 0.05232715 0.008318364 0.01322609 0.05217707 0.008590459 0.01343727 0.05230247 0.008863568 0.01316976 0.05216175 0.00907886 0.01330006 0.05227226 0.009438395 0.01278847 0.05213809 0.009487926 0.01302343 0.0521242 0.009778439 0.01263302 0.05224496 0.009702622 0.0122202 0.05210131 0.00993067 0.01210379 0.05222141 0.00970453 0.01167589 0.05207073 0.009875118 0.01149874 0.05208641 0.009714066 0.01118397 0.05219644 0.009461641 0.01116991 0.05204886 0.009449958 0.01085102 0.05216294 0.008854806 0.01072192 0.05202275 0.009027183 0.01058417 0.05201607 0.008547663 0.01047617 0.0521329 0.008161783 0.01071792 0.05199372 0.008060216 0.01052689 0.05211156 0.007717847 0.01091253 0.05198895 0.007448375 0.01086217 0.05209088 0.007392585 0.01125317 0.05193907 0.007053434 0.01146799 0.05206805 0.007195591 0.01174151 0.05192667 0.006971418 0.01193976 0.05203896 0.007247507 0.01240688 0.05190372 0.007052421 0.01245069 0.05188184 0.007315218 0.01290816 0.05199968 0.007806539 0.01308041 0.05186039 0.007736861 0.01326155 0.05183857 0.008267819 0.01343029 0.05196833 0.008505642 0.0132305 0.05182027 0.008887648 0.01338177 0.05193799 0.009182453 0.01303035 0.05179476 0.009392142 0.01312071 0.05190372 0.009652853 0.01240813 0.0517733 0.009759426 0.01267176 0.05174964 0.009917199 0.01222056 0.05187809 0.009728789 0.01182937 0.05173438 0.009916484 0.01168578 0.05185484 0.009565293 0.01133316 0.05171495 0.009717583 0.01117908 0.05183196 0.00922966 0.0109359 0.05169242 0.00936824 0.01078438 0.05170005 0.008989095 0.01057672 0.05180913 0.008763968 0.01072096 0.051674 0.008271753 0.01048129 0.0517857 0.008213579 0.01069837 0.05162465 0.007602155 0.01073837 0.05176228 0.007731616 0.01090681 0.05173808 0.007350504 0.01131069 0.05160641 0.007224321 0.01113265 0.05158168 0.007031261 0.01153981 0.05170887 0.007168769 0.01195359 0.05156987 0.006970345 0.01199293 0.05154919 0.007081747 0.01251465 0.05167853 0.00735408 0.01260697 0.05151951 0.007426857 0.0130403 0.05164682 0.007879197 0.01311588 0.05150765 0.007824838 0.01331156 0.05148911 0.008480429 0.01344764 0.05161398 0.008622527 0.01322591 0.05145776 0.009084522 0.0133031 0.05159276 0.009069263 0.01307153 0.05156993 0.009473145 0.01273304 0.05143761 0.009527385 0.01298099 0.05142074 0.009797811 0.01258641 0.05154675 0.009696006 0.01225519 0.05140161 0.009929358 0.01214432 0.05152422 0.009714961 0.01175624 0.05138218 0.00989443 0.01159995 0.05150324 0.009545266 0.01129239 0.05136787 0.009729027 0.01120054 0.05134665 0.00944662 0.01084381 0.05147922 0.009183943 0.01090419 0.05132597 0.008916556 0.01054739 0.0514568 0.008699297 0.01070719 0.05129593 0.008317828 0.01047128 0.05143624 0.008229672 0.01069664 0.05129283 0.007940649 0.01056426 0.05140823 0.007647812 0.01096093 0.05127078 0.007401704 0.01090222 0.0513755 0.007226705 0.01156258 0.05124121 0.007069766 0.01139736 0.05121976 0.006968021 0.01196795 0.05134212 0.007225751 0.0123257 0.05120015 0.007053077 0.01245129 0.05131787 0.007502257 0.01280331 0.05117905 0.007318615 0.01291626 0.05129498 0.00792396 0.01311856 0.05116009 0.0077672 0.01327025 0.05113953 0.008243858 0.01342588 0.05127179 0.008439242 0.01323485 0.05112046 0.00871694 0.0134198 0.05124515 0.009031534 0.01310145 0.05110651 0.009218752 0.01322609 0.05110222 0.009658813 0.01282566 0.05121451 0.009551703 0.01263076 0.05106121 0.009904205 0.01226127 0.05118674 0.009726524 0.01203787 0.05105894 0.009914517 0.01171994 0.05115938 0.009630739 0.01142477 0.05101215 0.009760677 0.01125663 0.05100905 0.009359538 0.01078271 0.05113041 0.00913763 0.01087331 0.051099 0.008533895 0.01067525 0.05106794 0.007852673 0.01082402 0.05103957 0.007381558 0.0112577 0.05675083 0.008072912 0.01073253 0.05673968 0.00760132 0.01099818 0.05669981 0.007227003 0.01158022 0.0566706 0.007206499 0.01223897 0.05663466 0.007570922 0.01290017 0.05660802 0.008165478 0.01319658 0.05658692 0.008646607 0.01322066 0.05656605 0.00908786 0.01306217 0.05653548 0.00958991 0.01258295 0.05650418 0.009729027 0.01187992 0.05647552 0.009538292 0.01126027 0.05644744 0.009056985 0.01083046 0.05642253 0.008506476 0.01067739 0.05640047 0.008018076 0.01076012 0.05637103 0.007462501 0.01112896 0.05633974 0.007188141 0.01178848 0.05631613 0.007234275 0.01232653 0.05629301 0.007480144 0.01278644 0.05626952 0.007921934 0.01311373 0.05624222 0.008513808 0.01324456 0.05621063 0.009196221 0.01300114 0.05618542 0.009573519 0.0125758 0.05615264 0.009746432 0.01185196 0.05612182 0.009473919 0.01118612 0.05609464 0.009006261 0.0107994 0.05606085 0.008262097 0.01067805 0.05602943 0.007607877 0.01099759 0.05600798 0.007312357 0.01139575 0.05598241 0.007170796 0.01195722 0.05594789 0.007400751 0.0127049 0.05591231 0.008057415 0.01318049 0.05588734 0.008634209 0.01321566 0.05586498 0.009107351 0.01306033 0.05584239 0.00948733 0.01270216 0.0558151 0.009734988 0.01212 0.05578786 0.009649991 0.01151615 0.05576354 0.009358942 0.01104795 0.05571281 0.008295178 0.01067924 0.05568158 0.007644236 0.01096343 0.05565643 0.007295131 0.01142805 0.05563491 0.007176756 0.01190561 0.0556122 0.007267534 0.01241511 0.05559062 0.007519125 0.01282721 0.05556106 0.008077323 0.01318871 0.05552715 0.00885576 0.01317995 0.05550116 0.009360373 0.01285213 0.05548006 0.009632587 0.0124551 0.05544966 0.009734153 0.01178872 0.05541354 0.009368002 0.01104283 0.05537468 0.008568465 0.01066565 0.0553444 0.007888972 0.0108143 0.05531817 0.007420122 0.01119607 0.05528253 0.007162392 0.01193636 0.05524665 0.007420718 0.01272457 0.05521959 0.007915139 0.01311028 0.05519473 0.008455514 0.01324123 0.05517041 0.00900942 0.01310282 0.0551486 0.009399771 0.01281821 0.05511695 0.009726226 0.01219463 0.05508226 0.009614408 0.01139974 0.05505657 0.009229183 0.01094543 0.05502921 0.008672118 0.01068502 0.05500227 0.008046388 0.01075077 0.05497235 0.007478952 0.0111044 0.05494004 0.007187545 0.01179456 0.05491387 0.007240176 0.01236128 0.0548802 0.007682919 0.01299643 0.05484938 0.008362829 0.01323062 0.05482226 0.008962273 0.01313376 0.05478924 0.009542763 0.01265633 0.0547567 0.009735047 0.01195311 0.05473554 0.00963062 0.01146721 0.0547083 0.009264111 0.01095157 0.05468106 0.008705079 0.01070809 0.05465668 0.008153736 0.01071113 0.05460464 0.007268071 0.01145035 0.05457359 0.007191359 0.01215666 0.05454266 0.007489085 0.01281148 0.05451023 0.008108496 0.01319026 0.05448383 0.008707344 0.01320999 0.05445271 0.009331822 0.01290565 0.05442386 0.009676098 0.01233047 0.05439913 0.00972259 0.01176708 0.0543732 0.009496092 0.01121419 0.05435115 0.00913155 0.01087534 0.05432558 0.008584141 0.0106818 0.05429387 0.007882118 0.01080191 0.05426555 0.007397592 0.01124227 0.05424243 0.007196545 0.01172542 0.05421763 0.007226586 0.01230347 0.05419164 0.007498085 0.0128113 0.05415987 0.008112549 0.0131964 0.05413371 0.00870943 0.01320648 0.05410742 0.009256303 0.01295918 0.05407935 0.009636461 0.01245081 0.05405586 0.009728491 0.011909 0.05402857 0.009577393 0.01132172 0.05400097 0.00912404 0.01087236 0.0539754 0.008587121 0.01067745 0.05393898 0.00777775 0.01085257 0.05390816 0.007307291 0.01139682 0.05388104 0.007173955 0.01198887 0.05385303 0.007347226 0.01260143 0.05382812 0.00774759 0.01301753 0.05380588 0.008193016 0.01320779 0.05378419 0.008705139 0.01320523 0.05375754 0.00926721 0.01295918 0.05372965 0.009630858 0.01244568 0.05369997 0.009739756 0.01178401 0.05366224 0.009344577 0.01102489 0.05363231 0.008739948 0.01070916 0.05360144 0.00802201 0.01074141 0.05356895 0.007439255 0.01117575 0.05354255 0.007198214 0.01172357 0.05352252 0.007203578 0.01219266 0.05350047 0.007384777 0.01265114 0.05347073 0.007859885 0.01310151 0.05344194 0.008535683 0.01323103 0.0534147 0.009115159 0.01305967 0.0533843 0.009590566 0.01255089 0.05336189 0.009726762 0.01204979 0.05333739 0.009654879 0.01151335 0.05331468 0.009375631 0.01107209 0.05328613 0.008821964 0.01071965 0.05325537 0.008127212 0.01071983 0.05323296 0.00766617 0.01095753 0.05321019 0.00733143 0.01134306 0.0531888 0.007188975 0.01182097 0.05316686 0.007227718 0.01230412 0.05313789 0.007548809 0.01287609 0.05310451 0.008245289 0.01322388 0.05306887 0.009022116 0.0131188 0.05303305 0.009608387 0.01253151 0.05300593 0.009728431 0.01191645 0.05297869 0.009579122 0.01132434 0.05295163 0.009130835 0.01087689 0.05292302 0.008529722 0.01066631 0.05288565 0.007700026 0.01090776 0.0528534 0.007269918 0.01147812 0.05280756 0.007303833 0.01251691 0.05278325 0.007650494 0.01294428 0.05275619 0.008193135 0.01321905 0.05272513 0.008912384 0.01315277 0.05269384 0.009465217 0.01275426 0.05266022 0.009744465 0.01200735 0.05262178 0.009502708 0.01119804 0.05258685 0.008844137 0.01073098 0.05255949 0.008207321 0.01070481 0.05252945 0.007614195 0.01097822 0.05249464 0.007192969 0.01169002 0.0524621 0.007258176 0.01241385 0.05243575 0.007598936 0.01290595 0.05240476 0.008224725 0.01322895 0.05237025 0.008991301 0.01312279 0.05233615 0.009585916 0.0125882 0.05230426 0.009730637 0.01188367 0.05228269 0.009602844 0.011406 0.05226123 0.009314835 0.01100534 0.05223715 0.008837044 0.01074212 0.05221551 0.008364617 0.01068216 0.05219566 0.007918655 0.01080119 0.0521658 0.007378339 0.01123583 0.05213099 0.007174253 0.01199007 0.05210459 0.007332861 0.01256859 0.05208444 0.007631599 0.01292848 0.0520612 0.008081018 0.01317799 0.05203741 0.008623301 0.01322501 0.05201554 0.009108245 0.0130496 0.05199366 0.009471654 0.0127322 0.05196654 0.009721696 0.01216918 0.05193269 0.009616613 0.01138776 0.05190086 0.009131312 0.01087373 0.05187022 0.008450508 0.01066136 0.05183166 0.007638692 0.01095819 0.0518012 0.007247626 0.01153504 0.05177509 0.007187485 0.01213335 0.05174183 0.007472097 0.01279467 0.05170702 0.008187949 0.01321822 0.0516684 0.009044885 0.01311033 0.05163568 0.009574592 0.0125758 0.05160945 0.00973469 0.01199579 0.0515778 0.009577929 0.01132375 0.05155026 0.009117424 0.01086497 0.0515263 0.008592784 0.01068246 0.05149114 0.007813334 0.01083028 0.05146169 0.007347345 0.01132947 0.05143737 0.007179737 0.01182949 0.05141502 0.007244169 0.01234912 0.05139261 0.007497131 0.01280438 0.05135971 0.00810045 0.01320034 0.05132156 0.008998692 0.01313334 0.05129075 0.009510755 0.01266956 0.05126458 0.00972855 0.01213788 0.0512306 0.009596109 0.0113511 0.05119866 0.009087085 0.01084363 0.05117458 0.008557558 0.01068603 0.05114829 0.007959127 0.0107674 0.05111867 0.007438957 0.01118433 0.05109679 0.007223188 0.01162093 0.05107283 0.007197499 0.01219034 0.05674546 0.007704555 0.01322913 0.05674958 0.007129251 0.01152378 0.05674946 0.007163465 0.0126416 0.05673658 0.008226215 0.01342087 0.05668771 0.009026646 0.01333737 0.05663901 0.009878396 0.01236772 0.05644428 0.006975293 0.01208806 0.05613982 0.007375001 0.01093965 0.05598086 0.009219944 0.01322627 0.05548483 0.008420407 0.01047253 0.05544131 0.007392346 0.01093095 0.05521982 0.009928584 0.01184779 0.05488914 0.009876966 0.01236444 0.05486768 0.009926438 0.0118041 0.05454355 0.009855806 0.01248455 0.05449098 0.009698927 0.01114141 0.05429911 0.007525205 0.01310169 0.05427742 0.008038043 0.01337671 0.05424988 0.008726894 0.01341837 0.05411291 0.009131371 0.01064306 0.05371564 0.007928311 0.01056605 0.05369204 0.007406473 0.01091885 0.05316215 0.009594798 0.01291215 0.05292886 0.007057666 0.01245343 0.05241936 0.009926557 0.01184499 0.05227708 0.007163524 0.01121997 0.05217581 0.008080244 0.01338803 0.0519551 0.00766766 0.0107069 0.05193465 0.007277786 0.0110616 0.05164587 0.008737921 0.01049786 0.05162101 0.008050978 0.01053518 0.05105853 0.009673297 0.01282012 0.05075991 0.009443521 0.01108491 0.05089145 0.009560048 0.01100599 0.05085432 0.009708583 0.01126611 0.05075997 0.00972402 0.01159471 0.05090987 0.009839892 0.01149827 0.05088996 0.009909987 0.01188248 0.05077713 0.009804248 0.01202154 0.05075228 0.009619593 0.01249039 0.05099505 0.009875535 0.01238828 0.05081194 0.00978899 0.01237434 0.050884 0.009723186 0.01265317 0.05081802 0.009484887 0.01291346 0.0507788 0.009363234 0.01295512 0.05075091 0.00899446 0.01312154 0.05098927 0.009585797 0.01291388 0.05099326 0.009342491 0.01314353 0.05080354 0.008909404 0.01327347 0.05088746 0.009073615 0.0132718 0.05075585 0.008488237 0.01325345 0.05099707 0.008658707 0.01342648 0.05085569 0.008420407 0.01339149 0.05090105 0.008220553 0.01339322 0.05075991 0.008103311 0.01322937 0.0508303 0.007858097 0.01323699 0.0509929 0.007939219 0.01334458 0.05076825 0.007610261 0.01298266 0.05075109 0.007372379 0.01261144 0.05089211 0.007569253 0.01311153 0.0509997 0.007541537 0.0131148 0.05081105 0.00732398 0.0127747 0.05091708 0.007315874 0.01287573 0.05080193 0.007117569 0.01232492 0.05075162 0.007180452 0.01204109 0.05088824 0.007059752 0.01237648 0.05099964 0.007207155 0.01274269 0.05089628 0.007001996 0.01193332 0.05080294 0.007091999 0.0116837 0.05076009 0.007223784 0.01152908 0.05099272 0.007005214 0.01163387 0.05075353 0.007594287 0.0109927 0.05088937 0.007155239 0.01131087 0.05081802 0.007355511 0.01107931 0.05079847 0.007634103 0.0108509 0.0509001 0.007606506 0.01077318 0.05075645 0.007976055 0.01074689 0.05084961 0.007992386 0.01060819 0.05099385 0.008103132 0.01052153 0.05078774 0.008363127 0.01058864 0.05075156 0.009013712 0.01080572 0.050776 0.008765041 0.0106486 0.05088466 0.008621633 0.01051753 0.05088931 0.008898019 0.01057374 0.05085718 0.009153246 0.01069724 0.05694454 0.006782948 0.01407676 0.05681061 0.006736457 0.01393783 0.05675679 0.006934523 0.01398497 0.056845 0.0072425 0.01432228 0.05695015 0.007160186 0.01432484 0.05675578 0.007413208 0.01426529 0.05694699 0.00759232 0.01451569 0.0568121 0.007758319 0.01448452 0.05691927 0.008081614 0.01462715 0.0567559 0.008263885 0.01448434 0.05685067 0.008283138 0.01460874 0.0569458 0.00873351 0.01464521 0.05684107 0.008877336 0.01457619 0.05677086 0.008945703 0.01447224 0.05694353 0.009259998 0.01453208 0.05681663 0.00938028 0.01441711 0.05675119 0.009562969 0.01420724 0.05692219 0.009668529 0.01436471 0.05681419 0.009934782 0.01413422 0.05691939 0.01003116 0.01414287 0.05691176 0.01050698 0.01370775 0.05678379 0.01031887 0.01376587 0.05693793 0.01081722 0.01326107 0.05680119 0.01078087 0.01315647 0.05691123 0.0110082 0.01282393 0.05675256 0.01070135 0.013094 0.05680489 0.01100862 0.01252645 0.05692183 0.011137 0.0122376 0.05675202 0.01095288 0.01218491 0.0568158 0.01108664 0.01189732 0.05694973 0.01113724 0.01161801 0.05681395 0.01103627 0.01147699 0.05675876 0.01089757 0.01125067 0.05689889 0.01099115 0.01105493 0.05692416 0.01076668 0.01056718 0.05676245 0.01060837 0.01057159 0.05689615 0.01050019 0.01020818 0.05681884 0.01027143 0.01004755 0.05691391 0.01003009 0.009766697 0.05675381 0.009892463 0.009885549 0.05691838 0.009560346 0.009497761 0.05679911 0.009576439 0.009601294 0.0569179 0.008949577 0.00930345 0.05683791 0.008915483 0.009343624 0.05675476 0.009036123 0.009492099 0.05689686 0.008374333 0.009268403 0.05677366 0.008287787 0.00939083 0.05694419 0.00782907 0.009324669 0.05675154 0.007751345 0.009552717 0.05681681 0.007692933 0.009437441 0.05693084 0.007232129 0.009551823 0.05679428 0.007163226 0.009689211 0.05693107 0.006780266 0.009841442 0.05675184 0.006770312 0.01009964 0.0567947 0.00669384 0.01003473 0.05690312 0.006412386 0.01020282 0.05690026 0.006110489 0.01063412 0.05677348 0.006308913 0.01054829 0.05675601 0.00603336 0.01118248 0.05689328 0.005894064 0.01113623 0.05692881 0.005756616 0.01180458 0.0568059 0.005856633 0.0116409 0.05682766 0.005816519 0.01212894 0.0567528 0.005963087 0.01229465 0.05691665 0.005812942 0.01248848 0.05681544 0.005941927 0.01272249 0.05694806 0.005966782 0.01300668 0.05684512 0.006092369 0.01316589 0.05675566 0.006147205 0.01299339 0.05691564 0.006259381 0.01352125 0.05678158 0.006388366 0.0135076 0.05691152 0.006498932 0.01380527 0.05955266 0.006937444 0.01419329 0.05955386 0.007466673 0.01446986 0.05957806 0.008069753 0.01462769 0.0595532 0.008922278 0.01461666 0.05957978 0.009526371 0.01443314 0.05960631 0.01039373 0.01382148 0.05958116 0.01072305 0.01341563 0.05959558 0.01099067 0.01286822 0.05954706 0.01112902 0.01234126 0.05956178 0.01114726 0.01169717 0.05957317 0.01093542 0.01090276 0.05955159 0.01072317 0.01048547 0.0595768 0.009673714 0.009550273 0.05957823 0.009205162 0.009366691 0.05959647 0.008776366 0.009285151 0.05958682 0.008235096 0.009267508 0.05960702 0.007587492 0.009411871 0.05955231 0.007221996 0.00955373 0.05957806 0.006817698 0.009817004 0.05956864 0.005819141 0.01137804 0.05957436 0.005863487 0.01270663 0.0595597 0.006060004 0.01319795 0.05954992 0.006296396 0.01357972 0.05961245 0.006668448 0.01396363 0.05974316 0.006744146 0.01382964 0.05968892 0.006399035 0.01358944 0.0596832 0.006159424 0.01324123 0.05974596 0.006164848 0.01299715 0.05968278 0.005972862 0.01283442 0.05966448 0.005825757 0.01224684 0.05974304 0.005933761 0.01219737 0.05954682 0.005751371 0.0120725 0.05965334 0.005815029 0.01168638 0.05974125 0.005931913 0.01167768 0.05968719 0.005933642 0.01122885 0.05956888 0.005972325 0.01090103 0.05974274 0.006152272 0.01090335 0.05960971 0.006141304 0.01058822 0.0597409 0.006456434 0.01038098 0.05960571 0.00645256 0.0101605 0.05963987 0.006876587 0.009799122 0.05972963 0.006919562 0.009905993 0.05974274 0.007438421 0.009625554 0.05968779 0.007966637 0.009375393 0.05973535 0.008398234 0.009394228 0.05974477 0.008910477 0.009469091 0.05970621 0.009338438 0.009503841 0.05960899 0.009953558 0.009726643 0.05973702 0.01002454 0.009937107 0.05958276 0.0103749 0.01006376 0.05974024 0.01045769 0.01037073 0.05967694 0.01076418 0.01067328 0.05974251 0.01090759 0.0112912 0.0596103 0.01104837 0.01125729 0.05968451 0.01109182 0.01204478 0.05972671 0.01099932 0.01235312 0.05970287 0.01075345 0.01320856 0.059749 0.01077729 0.01289087 0.05974179 0.01021879 0.01378279 0.0595805 0.01002025 0.01415175 0.05974125 0.009747207 0.01416033 0.05967301 0.009213864 0.01448905 0.05974382 0.008640766 0.01448941 0.05960851 0.00863099 0.0146377 0.05971324 0.008307993 0.0145443 0.05968052 0.007676243 0.01447552 0.05974739 0.007509648 0.01428937 0.05967909 0.00722754 0.01428985 0.05805802 -0.003469228 0.01278108 0.05805742 -0.004760742 0.0131725 0.05816543 -0.00486195 0.01307678 0.05816763 -0.003437399 0.01264762 0.05805838 -0.005073189 0.01448583 0.05816763 -0.005203843 0.01452475 0.05806827 -0.004098057 0.01545262 0.05820775 -0.004121959 0.01555436 0.05805808 -0.002795934 0.01502227 0.05816549 -0.002695381 0.01511472 0.05806934 -0.002442955 0.01369398 0.05820691 -0.002344489 0.01366448 0.05973833 -0.002662479 0.01514655 0.05973857 -0.002310156 0.01365554 0.05973917 -0.004130542 0.01559078 0.05973875 -0.005248308 0.01453685 0.05973875 -0.00489521 0.01304376 0.05973869 -0.003426134 0.01260322 0.0510078 -0.005059242 0.01390618 0.05099445 -0.005245208 0.01389044 0.05100035 -0.004901349 0.01473796 0.05100029 -0.004631638 0.01297837 0.05099934 -0.00476396 0.01298803 0.05100595 -0.004289984 0.01527571 0.05099993 -0.004255115 0.01269817 0.0509957 -0.003784239 0.01262676 0.05100095 -0.003539383 0.01538872 0.05099993 -0.003309071 0.01549863 0.05099761 -0.003347039 0.01268011 0.05099987 -0.002853751 0.01509547 0.05099964 -0.002600491 0.01498335 0.05100536 -0.002317249 0.01433181 0.05099993 -0.00237745 0.01456296 0.05100238 -0.002344429 0.01374089 0.05674821 -0.003478944 0.01554322 0.05670309 -0.002942442 0.01532304 0.05667692 -0.002545535 0.01492649 0.05674999 -0.00281769 0.01513421 0.05665922 -0.002308487 0.01434135 0.05675041 -0.002728879 0.01336139 0.05675005 -0.00249195 0.01458412 0.05663263 -0.002326309 0.01378268 0.05674999 -0.002465128 0.01394784 0.05663096 -0.002638101 0.01314342 0.05674034 -0.003121674 0.01300555 0.05658417 -0.003306865 0.01268321 0.05669611 -0.003769397 0.01279842 0.05655252 -0.003905534 0.01261383 0.05653232 -0.004408419 0.01275426 0.0566641 -0.004461705 0.01301908 0.05651289 -0.004873991 0.01308786 0.05663448 -0.004940986 0.01352339 0.05648344 -0.005153536 0.01353883 0.0564751 -0.005260288 0.0139718 0.05659514 -0.005034387 0.01439601 0.0564565 -0.005209147 0.0145173 0.05643254 -0.004948198 0.01501393 0.05656784 -0.00473088 0.01494199 0.05643761 -0.004594802 0.01532536 0.05654162 -0.004236757 0.01529884 0.05639886 -0.003997445 0.0155723 0.05651646 -0.00368601 0.01536524 0.05636739 -0.003406465 0.01553052 0.0564953 -0.003206968 0.015239 0.05634725 -0.002902984 0.015298 0.05646616 -0.002701282 0.01480358 0.05632346 -0.002533614 0.01490825 0.0563094 -0.002338111 0.01446348 0.05643457 -0.002499401 0.01412463 0.05630064 -0.002296864 0.01402223 0.05641257 -0.002591609 0.01362955 0.05627185 -0.002412199 0.01350647 0.05638718 -0.002918541 0.01314544 0.05624365 -0.00279504 0.01298063 0.0562303 -0.003322541 0.01267564 0.05635374 -0.003595232 0.01281732 0.05620205 -0.003929436 0.01262104 0.05631738 -0.004418313 0.01297551 0.05618077 -0.004487693 0.0127871 0.05615234 -0.004899263 0.01312392 0.0562911 -0.004836797 0.01339036 0.05614364 -0.005138874 0.01349574 0.05626767 -0.005042731 0.01388192 0.05612915 -0.005259454 0.01396387 0.05627989 -0.004994809 0.01443529 0.05610173 -0.005206525 0.01451528 0.05608409 -0.004950523 0.01500827 0.05621618 -0.004714608 0.01498162 0.05606412 -0.004548788 0.01537144 0.05618828 -0.004170179 0.01531124 0.05604642 -0.003986358 0.01557034 0.05615669 -0.003441095 0.01534706 0.05602002 -0.00336349 0.01552367 0.05599814 -0.002940058 0.01532971 0.0561223 -0.002803087 0.01492488 0.05597788 -0.002537786 0.01491171 0.05608886 -0.002487599 0.01421678 0.05597239 -0.00229752 0.01422941 0.05592292 -0.002347946 0.01367962 0.05605429 -0.002668201 0.01346015 0.05590397 -0.002682983 0.01308995 0.05602324 -0.003180861 0.01295071 0.05588269 -0.003117442 0.01276516 0.05585819 -0.003706753 0.01261007 0.05598729 -0.003985166 0.01282554 0.05584341 -0.004268646 0.01268577 0.05595552 -0.004625201 0.01313257 0.05581563 -0.004793286 0.01301485 0.05579638 -0.005117833 0.01345294 0.05592083 -0.005044639 0.01381534 0.05577504 -0.005247354 0.01389074 0.0557608 -0.005241692 0.01434236 0.05588734 -0.004967868 0.01456338 0.05574184 -0.005033075 0.01490002 0.05585867 -0.004581332 0.01510512 0.05572003 -0.004641711 0.01530313 0.0556997 -0.004190802 0.01552128 0.05583018 -0.003987491 0.0153532 0.05567902 -0.003732025 0.01558101 0.05580729 -0.00346136 0.01533818 0.05566585 -0.003240883 0.0154801 0.05578333 -0.002990305 0.01509428 0.05564504 -0.002842545 0.01525181 0.05576121 -0.002649009 0.01470369 0.05562204 -0.002547681 0.01492446 0.05561316 -0.002347588 0.0144912 0.05573701 -0.002508521 0.01418715 0.05559122 -0.002298772 0.01401358 0.05571115 -0.002596735 0.01358669 0.05557298 -0.002422034 0.01348936 0.05554592 -0.002746701 0.01302421 0.0556758 -0.003138184 0.01297253 0.05552935 -0.003237128 0.0127148 0.05550515 -0.003759324 0.01260781 0.05564403 -0.003828465 0.01281881 0.05549126 -0.004191994 0.01266282 0.0556178 -0.004391133 0.01297211 0.05547624 -0.004630148 0.01287835 0.05558544 -0.004919171 0.01348656 0.05545157 -0.005030751 0.01328474 0.05543428 -0.005235433 0.01379275 0.05555409 -0.005052506 0.01420003 0.05540859 -0.005227506 0.01443785 0.055525 -0.004837214 0.0148316 0.05538231 -0.004997372 0.01494729 0.05536824 -0.004657983 0.01529502 0.05553323 -0.004331648 0.01523017 0.05537408 -0.004273891 0.01548945 0.05547523 -0.003881871 0.01537042 0.0553357 -0.003910124 0.01558512 0.05545336 -0.003384709 0.01530665 0.05531096 -0.003288567 0.01549893 0.05542325 -0.002807021 0.0149548 0.05529433 -0.002780854 0.01519769 0.05527067 -0.002490758 0.01483333 0.05538976 -0.002506554 0.0142365 0.05525505 -0.002316296 0.01434028 0.05525046 -0.002352595 0.01365399 0.05536413 -0.00257647 0.01365745 0.05534088 -0.002858042 0.01321679 0.05520373 -0.002692461 0.0130859 0.05531305 -0.003380417 0.01286756 0.05518227 -0.003090798 0.01278084 0.0551694 -0.003544986 0.01263016 0.05528396 -0.004051268 0.01285058 0.05514323 -0.004075646 0.01264095 0.05512845 -0.004560589 0.01283574 0.0552529 -0.004676997 0.01316154 0.0551086 -0.004914164 0.01313799 0.05508929 -0.005180656 0.01361346 0.05521297 -0.005071222 0.01399844 0.05506658 -0.005266189 0.01423275 0.05518049 -0.004898965 0.01470911 0.05504149 -0.005070447 0.01482445 0.05502223 -0.004720985 0.01524448 0.0551573 -0.004554212 0.01511013 0.05512845 -0.003929197 0.01538097 0.05499511 -0.004222273 0.01551717 0.05498224 -0.003559052 0.01556897 0.05508846 -0.003074944 0.01518106 0.05494892 -0.002991318 0.01536214 0.05492937 -0.002566516 0.01494997 0.05505603 -0.002600133 0.01459586 0.05491 -0.002328455 0.01442849 0.05502563 -0.00250411 0.01390671 0.05488145 -0.002303063 0.01394516 0.05487221 -0.0024212 0.0134952 0.0549941 -0.002804815 0.01326572 0.05485528 -0.002707421 0.01306569 0.05483657 -0.003019571 0.01282382 0.05497199 -0.00320357 0.0129581 0.05482202 -0.00339359 0.01266312 0.05494743 -0.003739118 0.01281702 0.05480456 -0.003952682 0.01261979 0.05491983 -0.004362046 0.01295202 0.05477714 -0.004540443 0.01281487 0.05489403 -0.004801392 0.01333713 0.05475699 -0.004979312 0.0132271 0.05487328 -0.005013763 0.01376515 0.05473893 -0.005228102 0.01374477 0.05484735 -0.005034923 0.01434177 0.05470532 -0.005209982 0.01449847 0.05471098 -0.005025744 0.01489031 0.05481648 -0.004715621 0.01498365 0.05467206 -0.004797399 0.01519036 0.05478805 -0.004172801 0.01530665 0.05465173 -0.004293441 0.01548749 0.05476748 -0.003693699 0.01537168 0.05462896 -0.003730177 0.01558393 0.0545988 -0.003072023 0.01541042 0.05474382 -0.003182291 0.015226 0.05460655 -0.002635776 0.01504689 0.05471366 -0.002669751 0.0147553 0.05455774 -0.002323389 0.01440292 0.05468297 -0.00250101 0.01409429 0.05453598 -0.002319276 0.01383489 0.05465018 -0.002700746 0.01337528 0.05451005 -0.002530932 0.01328027 0.05449557 -0.002948403 0.01286202 0.05461674 -0.003316164 0.01290303 0.05446398 -0.003558933 0.01262426 0.05458515 -0.004037976 0.01283019 0.05444365 -0.004118204 0.01264894 0.05442482 -0.004618346 0.01287317 0.05455529 -0.004630923 0.01314806 0.05440735 -0.005034625 0.01329165 0.05453473 -0.004918873 0.0135191 0.05437958 -0.005240201 0.01383793 0.05450606 -0.005063235 0.01414841 0.05436223 -0.005236029 0.01438629 0.05447995 -0.004894495 0.01471602 0.05433738 -0.005091249 0.01480078 0.05445617 -0.00453341 0.01512897 0.05432099 -0.004719555 0.01524209 0.05430167 -0.004243433 0.01550728 0.05447071 -0.004020452 0.0153349 0.05428177 -0.003782331 0.01557928 0.05441004 -0.003531694 0.01534938 0.05426496 -0.003312587 0.01550358 0.05442541 -0.003077745 0.0151453 0.05424654 -0.00281924 0.01523238 0.05436593 -0.002714872 0.01480424 0.05422246 -0.002476394 0.01481097 0.0543428 -0.002521455 0.01430803 0.05420595 -0.002310752 0.01430094 0.05432039 -0.00253421 0.01380264 0.05418366 -0.002310216 0.0138784 0.05416744 -0.002465665 0.01340126 0.05429935 -0.002734363 0.01336723 0.05414813 -0.00280708 0.01297616 0.05427181 -0.003207921 0.01293927 0.0541231 -0.003364026 0.01265966 0.05428063 -0.003798186 0.01283395 0.05409914 -0.00400561 0.01263093 0.0542159 -0.004437327 0.01298582 0.05407738 -0.004541516 0.01281917 0.05405795 -0.004953205 0.01318436 0.05422449 -0.004855275 0.01343697 0.05403876 -0.005240797 0.01380228 0.0541644 -0.005052506 0.01395672 0.053999 -0.005164027 0.01465684 0.05414152 -0.004995644 0.01447665 0.05411612 -0.004704356 0.01498377 0.05398255 -0.00478518 0.01519447 0.05408555 -0.004106342 0.01533961 0.0539512 -0.004241943 0.01551151 0.05392986 -0.003693819 0.01557862 0.05405533 -0.003427326 0.01532644 0.05390822 -0.003101348 0.01542806 0.05403333 -0.002981662 0.01509195 0.0538842 -0.002659499 0.01507812 0.05401128 -0.002663075 0.01471328 0.05386573 -0.00237441 0.01459103 0.05399072 -0.002512276 0.01425826 0.0538429 -0.002285599 0.01403641 0.05396944 -0.002542376 0.01378178 0.05382132 -0.00242722 0.01347488 0.05393934 -0.002875983 0.0131703 0.05379664 -0.002719581 0.01305115 0.05378609 -0.003162682 0.01274627 0.05391186 -0.003417491 0.01287657 0.05376404 -0.003617346 0.01261997 0.05388844 -0.00394839 0.01282542 0.05373936 -0.004112064 0.01264894 0.05386519 -0.004447221 0.01301032 0.05373394 -0.004538297 0.01282179 0.05383431 -0.004935204 0.0135129 0.05371063 -0.004876911 0.01309877 0.05369192 -0.005166292 0.01356166 0.05380386 -0.005050361 0.01419854 0.05367028 -0.005265474 0.01407688 0.05366539 -0.00508809 0.01480054 0.05377244 -0.004809617 0.0148822 0.05361658 -0.004607439 0.01533108 0.05374044 -0.004225075 0.01529103 0.05359482 -0.004081964 0.01554745 0.05370903 -0.003512918 0.01536536 0.05356651 -0.003459095 0.01555466 0.05355322 -0.002928555 0.01531785 0.05367916 -0.00291115 0.01502794 0.05352497 -0.002481222 0.0148254 0.05364996 -0.002537012 0.01446855 0.05350625 -0.002311348 0.0143156 0.05348443 -0.002322614 0.01381117 0.05360931 -0.002606213 0.01354396 0.053465 -0.002469956 0.01340246 0.05345195 -0.002737522 0.01303416 0.05357372 -0.003159999 0.01297289 0.05342042 -0.003301262 0.01268523 0.05353987 -0.003911077 0.01280951 0.05343079 -0.003758072 0.01261645 0.05339497 -0.004071176 0.01263499 0.05350863 -0.004575133 0.01309716 0.05337643 -0.004579901 0.01284575 0.05335158 -0.00494647 0.01317852 0.05347836 -0.004993021 0.01365429 0.05333673 -0.005190253 0.01363021 0.0533179 -0.005260109 0.01417386 0.05344849 -0.005032658 0.01432585 0.05330604 -0.005122721 0.01474219 0.05342674 -0.004853963 0.01478993 0.05329275 -0.004708945 0.01524055 0.05340415 -0.004499137 0.0151444 0.05327057 -0.004167854 0.01552778 0.05337905 -0.003972768 0.01536923 0.05322074 -0.003713905 0.01557964 0.05335175 -0.003350257 0.01529687 0.05321168 -0.003227949 0.01547473 0.05332344 -0.002802968 0.01494073 0.05320918 -0.002674162 0.01510596 0.05315923 -0.002342998 0.01446676 0.0532906 -0.002506852 0.01425564 0.05313992 -0.002303302 0.01392209 0.05326294 -0.002582788 0.01363795 0.0531159 -0.002463102 0.01340276 0.05323493 -0.002957761 0.01311177 0.05309909 -0.00280863 0.01297599 0.05308163 -0.003202557 0.01272952 0.0532037 -0.003591179 0.01282298 0.05306184 -0.00365138 0.01261556 0.05304241 -0.00419408 0.01267278 0.05317485 -0.004254877 0.01291024 0.05301761 -0.004763007 0.01297062 0.05315172 -0.004692792 0.0132029 0.05299347 -0.00513339 0.01349306 0.05312502 -0.005005776 0.01372534 0.05297476 -0.005265355 0.01404917 0.05309849 -0.005037844 0.01432037 0.05296617 -0.005109369 0.01475739 0.05307662 -0.00485152 0.01478159 0.0530551 -0.004517436 0.01513868 0.05292463 -0.004762768 0.01521372 0.05303472 -0.00409156 0.01533216 0.05291771 -0.004129946 0.01553606 0.05301052 -0.003536522 0.01535284 0.052868 -0.003577709 0.0155732 0.05285054 -0.002930104 0.01532232 0.05298489 -0.003003597 0.01511454 0.05282652 -0.002523958 0.0148859 0.05296164 -0.002666413 0.01471549 0.0528047 -0.002314567 0.01435762 0.05293381 -0.002487361 0.01411247 0.05278098 -0.002318143 0.01382052 0.05276733 -0.002485513 0.01336216 0.05290317 -0.002681732 0.01344233 0.05275487 -0.002774953 0.01300144 0.05288153 -0.003020524 0.01306867 0.05272907 -0.003207445 0.01272463 0.05286008 -0.003455996 0.01286226 0.0527113 -0.003727912 0.01261514 0.05282878 -0.004175841 0.01286172 0.0526809 -0.004312217 0.01270306 0.05269598 -0.004616439 0.01287937 0.05279862 -0.004733085 0.01325356 0.05265831 -0.004933834 0.01315921 0.05276745 -0.005055248 0.01386195 0.05263596 -0.005201101 0.01364719 0.05260771 -0.005252122 0.01432919 0.05273801 -0.004967033 0.01455336 0.05258274 -0.004971921 0.01498669 0.05270999 -0.004608094 0.01508843 0.05258756 -0.004606008 0.01532357 0.05253899 -0.003918886 0.01558023 0.05268043 -0.00399363 0.01535135 0.05265259 -0.003352463 0.01531672 0.05254197 -0.003434956 0.01554304 0.05249267 -0.002796292 0.01520913 0.0526185 -0.002744793 0.01485288 0.05249714 -0.002503871 0.01484489 0.05258995 -0.002505302 0.01425462 0.05247443 -0.002308845 0.01428353 0.05243545 -0.00231415 0.01381963 0.05255758 -0.002629518 0.01351058 0.05241107 -0.002478361 0.01337194 0.05239194 -0.002862453 0.01292568 0.05252885 -0.003065884 0.01303845 0.05237442 -0.003362476 0.01267188 0.05254358 -0.003556311 0.01285368 0.05234843 -0.003987431 0.01261597 0.05248552 -0.00402069 0.01283961 0.05232042 -0.004656434 0.01288884 0.05246293 -0.004482924 0.01303684 0.05233138 -0.004912734 0.01314753 0.05243915 -0.004870593 0.01341819 0.05229151 -0.005129992 0.01347595 0.05241435 -0.00504446 0.01395767 0.05227416 -0.005257725 0.01398926 0.05238831 -0.004980027 0.01455914 0.05225133 -0.005186676 0.01458191 0.0522347 -0.004907608 0.01505899 0.05235272 -0.004458785 0.01519638 0.05221343 -0.004545688 0.01536768 0.05219233 -0.003972947 0.01557826 0.05231875 -0.00372231 0.01537644 0.05216163 -0.003208637 0.01546728 0.05228418 -0.002999782 0.01512807 0.05214703 -0.00278908 0.01520323 0.05211925 -0.002475917 0.01480942 0.05225652 -0.002613186 0.0146113 0.05210483 -0.002315342 0.01434594 0.05223488 -0.002503335 0.01412618 0.05210942 -0.002316057 0.01387977 0.05220592 -0.002646267 0.01347368 0.05208897 -0.002485096 0.01338177 0.05205005 -0.002760291 0.01301538 0.05217605 -0.003125429 0.01300156 0.05204463 -0.003392219 0.01265996 0.05215364 -0.00359869 0.01282852 0.05199784 -0.003888964 0.01260745 0.05212271 -0.004298985 0.01291781 0.05197989 -0.004531979 0.01281589 0.05209606 -0.004773914 0.01329839 0.05195254 -0.004934728 0.01316177 0.05193907 -0.005180716 0.01360785 0.05207186 -0.005022168 0.01379436 0.05192667 -0.005262553 0.01407986 0.0520392 -0.004992544 0.01454836 0.05190157 -0.005199134 0.01452583 0.05188536 -0.004980266 0.01496475 0.05204516 -0.004553735 0.01509183 0.05186355 -0.004568755 0.01535642 0.05198669 -0.004140198 0.01532202 0.05184608 -0.003984808 0.01557242 0.05196201 -0.003581464 0.01535791 0.05181825 -0.003339052 0.01551866 0.05193096 -0.002918362 0.01506519 0.05179405 -0.002910315 0.01530545 0.05177682 -0.002530813 0.01489722 0.05189132 -0.002497553 0.01427131 0.05175477 -0.002318203 0.01437336 0.05173695 -0.002310216 0.01388949 0.05185437 -0.002668499 0.01343888 0.0517196 -0.002450048 0.01343816 0.05169904 -0.002767264 0.01300889 0.0518223 -0.003190517 0.01295864 0.0516842 -0.003157496 0.01274722 0.05179512 -0.003790915 0.01281678 0.05166375 -0.003717064 0.01261138 0.05180943 -0.004321277 0.01295608 0.05163902 -0.004219293 0.01267725 0.0516209 -0.004676759 0.01291286 0.0517438 -0.00482732 0.0133444 0.05160439 -0.005036532 0.01331168 0.05157953 -0.005203425 0.01368302 0.05171364 -0.005051672 0.01398098 0.05157089 -0.005263805 0.0141502 0.05169183 -0.00499624 0.01446825 0.05153876 -0.005102157 0.0147795 0.05166321 -0.004682779 0.01501846 0.05152273 -0.004743576 0.01523429 0.05150538 -0.004153311 0.01553833 0.05167323 -0.004159688 0.01529979 0.05161398 -0.003611564 0.01536536 0.05147325 -0.003578841 0.01556825 0.05145859 -0.003100037 0.01541668 0.0516287 -0.00310564 0.01516556 0.05156993 -0.002760887 0.01487249 0.05143862 -0.002704381 0.01512193 0.05141007 -0.002326667 0.01444888 0.05154073 -0.002502799 0.01425719 0.05138581 -0.002316534 0.01383906 0.0515092 -0.002615332 0.01355797 0.05137336 -0.002474427 0.01338845 0.05134624 -0.0027951 0.01298028 0.05148559 -0.002938151 0.01313722 0.05146193 -0.003421008 0.01286745 0.0513271 -0.003285288 0.01269805 0.05131393 -0.003702223 0.01261764 0.05142933 -0.004174947 0.01286309 0.05128914 -0.004195392 0.01266318 0.05127078 -0.004832863 0.01304221 0.05139082 -0.004861176 0.0133937 0.05124121 -0.005164504 0.0135374 0.05135756 -0.00506103 0.0141111 0.05122166 -0.005239844 0.01438003 0.05133122 -0.004909873 0.01469242 0.05118626 -0.004990458 0.01497006 0.05130529 -0.004517257 0.01514363 0.05116373 -0.004558742 0.01536267 0.0512802 -0.003984987 0.01535606 0.05113673 -0.00409466 0.01554858 0.05112123 -0.003542959 0.0155645 0.05125778 -0.00348109 0.01533865 0.05110788 -0.003056108 0.01538902 0.05123484 -0.003007173 0.01511085 0.05110347 -0.002591729 0.01499211 0.05121314 -0.002673923 0.01474177 0.05104976 -0.002304792 0.01429456 0.05118 -0.002488017 0.01403164 0.05105888 -0.002319633 0.01385843 0.0510323 -0.002550721 0.01325976 0.05115228 -0.002697288 0.01342105 0.05113041 -0.003096401 0.01301282 0.05101048 -0.002946138 0.01287716 0.051099 -0.003700017 0.0128147 0.05106794 -0.004381239 0.01296347 0.05104428 -0.004794538 0.01332521 0.05674833 -0.003837108 0.01280325 0.0567438 -0.004497408 0.01303619 0.05670452 -0.00497967 0.01361018 0.0566706 -0.005027472 0.01437848 0.05663472 -0.004663109 0.01503962 0.05660265 -0.003954291 0.01536643 0.05657255 -0.003269374 0.01527684 0.05653548 -0.002644121 0.01472246 0.05650418 -0.002505004 0.01401937 0.05647552 -0.002695679 0.01339977 0.05644738 -0.003176987 0.01296997 0.05642253 -0.003727555 0.01281684 0.05640047 -0.004215896 0.01289963 0.05637103 -0.00477153 0.01326841 0.05633974 -0.00504589 0.01392799 0.05629301 -0.004753887 0.01492589 0.05626952 -0.004312098 0.01525318 0.05624222 -0.003720223 0.01538407 0.05621063 -0.00303781 0.01514059 0.05618542 -0.002660453 0.01471519 0.05616343 -0.002512037 0.01422655 0.05613839 -0.002567172 0.01366817 0.05611425 -0.002878665 0.01319593 0.05608403 -0.003455221 0.01284068 0.05604803 -0.004280328 0.01291298 0.05601954 -0.004775822 0.01329618 0.05599784 -0.0050053 0.01375406 0.0559712 -0.005040109 0.01436668 0.05594331 -0.004746675 0.01492327 0.05591362 -0.004205882 0.01531976 0.05588001 -0.003428637 0.01532769 0.05584877 -0.002843022 0.01497983 0.0558151 -0.002498984 0.01425945 0.05578792 -0.00258404 0.0136556 0.05576354 -0.002875149 0.0131874 0.05573052 -0.003533899 0.01282632 0.05569797 -0.004258811 0.01290971 0.05567681 -0.004670441 0.01318728 0.05564951 -0.00501275 0.01372003 0.05561703 -0.005011439 0.01444613 0.05559062 -0.004714906 0.01496672 0.05553925 -0.003665208 0.01538598 0.05550599 -0.002954006 0.01507681 0.05548006 -0.002601385 0.01459443 0.05544811 -0.002500951 0.01389807 0.05541378 -0.002874433 0.01318079 0.0553857 -0.003420591 0.01287257 0.05535793 -0.004050076 0.01283556 0.05532962 -0.004634082 0.01314955 0.05530095 -0.004995763 0.01367092 0.05526542 -0.005009233 0.01448118 0.05523413 -0.004609346 0.01507097 0.05520313 -0.003968536 0.01536959 0.05517756 -0.003385841 0.01530712 0.05515253 -0.002886295 0.01501989 0.05511695 -0.002507746 0.01433396 0.05508589 -0.002592504 0.01361614 0.0550642 -0.002873182 0.01320147 0.05503749 -0.003377735 0.01287263 0.05501246 -0.003959715 0.01283586 0.05498659 -0.0045017 0.01303458 0.05496251 -0.004872322 0.01344245 0.05494004 -0.005046486 0.01393413 0.05491387 -0.004993796 0.01450091 0.0548802 -0.004550993 0.015136 0.05484938 -0.003870964 0.01537007 0.05481857 -0.003191947 0.01524496 0.05479192 -0.002740085 0.01483273 0.05476301 -0.002493441 0.01422733 0.05473554 -0.002603471 0.01360654 0.0547083 -0.002970039 0.0130909 0.05467289 -0.003703892 0.01281142 0.05464464 -0.004337072 0.012946 0.0546177 -0.004819512 0.01334404 0.05458873 -0.005048692 0.01393812 0.0545578 -0.004949569 0.01463824 0.05452805 -0.004491031 0.01515901 0.05448383 -0.003526449 0.01534938 0.05443239 -0.0026201 0.01467412 0.05439913 -0.002511441 0.01390635 0.0543732 -0.002738058 0.01335346 0.05434578 -0.003201484 0.0129491 0.05429124 -0.004404664 0.01296937 0.0542351 -0.005067288 0.01403802 0.05420494 -0.004905641 0.01470017 0.05417466 -0.004445433 0.01520031 0.05413985 -0.003665208 0.01537954 0.05411273 -0.003078103 0.01515996 0.05408304 -0.002620398 0.01467567 0.05404579 -0.002519249 0.01381772 0.05401486 -0.002856552 0.0132097 0.05398386 -0.003458976 0.01284694 0.05394619 -0.00429964 0.01291173 0.05391436 -0.004858851 0.0134083 0.05389004 -0.00504148 0.01392734 0.05386298 -0.00499165 0.01453351 0.05383193 -0.004558622 0.01511168 0.05380457 -0.004013597 0.01535451 0.05377101 -0.003243446 0.01527613 0.05374127 -0.002726435 0.01481628 0.05371177 -0.002492666 0.01419705 0.05368512 -0.002607583 0.01359629 0.05366379 -0.002881467 0.01318794 0.05363506 -0.003414452 0.01286172 0.05360257 -0.004185199 0.01287478 0.05357545 -0.004693686 0.01320779 0.05355381 -0.004962265 0.01362258 0.05352753 -0.005061447 0.01421856 0.05349791 -0.004817128 0.01483863 0.05346953 -0.004345953 0.01525157 0.05343586 -0.003555595 0.01536673 0.05340862 -0.003004491 0.01510703 0.05338299 -0.002627968 0.01466584 0.05335938 -0.002504885 0.01413178 0.05333477 -0.002600371 0.01359796 0.05331468 -0.002861201 0.0132128 0.05329233 -0.00327742 0.01291686 0.0532664 -0.003867208 0.01282066 0.05324429 -0.004346668 0.01295417 0.05321872 -0.004797935 0.01331955 0.05319625 -0.005016565 0.01379048 0.05317038 -0.005032539 0.01436102 0.05314421 -0.004771471 0.01490324 0.0531224 -0.004368245 0.01522457 0.05310052 -0.003907501 0.01536804 0.05307614 -0.003354191 0.01530289 0.05305069 -0.002867162 0.01499122 0.05302286 -0.002543151 0.01445424 0.05299562 -0.002531826 0.01382601 0.05297249 -0.002739846 0.01334774 0.05294775 -0.00317806 0.0129702 0.05292046 -0.003761768 0.01281005 0.05288684 -0.00450921 0.01303374 0.05284863 -0.005007445 0.01369708 0.05281382 -0.004993617 0.01452875 0.0527752 -0.004453063 0.01520246 0.05274248 -0.003720283 0.01537394 0.05271625 -0.003142237 0.01520663 0.05269032 -0.002722561 0.01481682 0.05266022 -0.002489507 0.01414638 0.05263298 -0.00262773 0.01355183 0.05260491 -0.003019869 0.01305288 0.0525493 -0.004243493 0.01289057 0.05252188 -0.004747211 0.01326972 0.05249464 -0.005041122 0.01382988 0.0524674 -0.005005061 0.01443868 0.05243706 -0.004667341 0.01504009 0.05240285 -0.003948926 0.01536631 0.05237138 -0.003266572 0.01527589 0.05234622 -0.00279802 0.01490813 0.05232518 -0.002562105 0.01448911 0.05230301 -0.002507567 0.01399385 0.05228137 -0.002642512 0.01351833 0.0522564 -0.003003597 0.01306986 0.05222809 -0.003595471 0.01283335 0.05220729 -0.00405693 0.01285082 0.05218696 -0.004492998 0.01304024 0.05216324 -0.004872977 0.0134319 0.05213326 -0.005065441 0.01407098 0.05210334 -0.004889428 0.01473319 0.05205863 -0.004096865 0.01533377 0.05202984 -0.003441274 0.01533895 0.05200386 -0.002915859 0.01503252 0.05197793 -0.002578437 0.01456499 0.05194634 -0.002523005 0.01384162 0.05192381 -0.002732813 0.01336687 0.0519008 -0.003103137 0.013013 0.05187183 -0.003730058 0.01280754 0.05181974 -0.004783868 0.01329606 0.05179238 -0.005036473 0.01387459 0.05176901 -0.005019187 0.01440602 0.05173975 -0.004717588 0.01497477 0.05168932 -0.003640055 0.01537001 0.051642 -0.002741575 0.01483595 0.05161321 -0.002492189 0.01421904 0.05158096 -0.002637565 0.01352006 0.05155211 -0.00308603 0.01301079 0.05152487 -0.003669619 0.0128259 0.0514993 -0.004242181 0.01290071 0.05147641 -0.00467658 0.01319211 0.05145269 -0.00497955 0.0136516 0.05142533 -0.005050361 0.01424443 0.05139505 -0.004780828 0.01490676 0.05136418 -0.004213452 0.01529973 0.0513401 -0.003665208 0.01536583 0.05131512 -0.003114759 0.01519745 0.05128681 -0.002674758 0.01473611 0.05125701 -0.002488434 0.01410824 0.05122452 -0.002718806 0.01337087 0.05119198 -0.003276884 0.01291102 0.05115592 -0.00411725 0.01284492 0.0511142 -0.004856348 0.01337897 0.05108386 -0.005055487 0.01406639 0.05105417 -0.004898488 0.01473814 0.05674546 -0.00453031 0.0153681 0.05674958 -0.00510478 0.01366329 0.05674946 -0.005070567 0.01478105 0.05673813 -0.004043877 0.0155521 0.05669856 -0.003460824 0.01554131 0.05659437 -0.002496778 0.01334792 0.0565716 -0.002898752 0.0129112 0.05638378 -0.004364907 0.01545959 0.05593657 -0.002332985 0.01442587 0.05520761 -0.00234878 0.01368731 0.05469942 -0.00525701 0.01407003 0.05455541 -0.002527594 0.01488608 0.0539928 -0.005254685 0.01425415 0.0536217 -0.005101382 0.01479566 0.05326086 -0.004939794 0.01501905 0.05323392 -0.004369854 0.01545602 0.05316215 -0.002639293 0.01505166 0.05292886 -0.005176365 0.01459288 0.05288332 -0.004355013 0.01546424 0.05253481 -0.004410028 0.01543909 0.05248928 -0.003219008 0.01546782 0.0524429 -0.002383112 0.01460957 0.052154 -0.003596305 0.01556336 0.05205523 -0.002368986 0.01362287 0.05200999 -0.003172814 0.01274627 0.05140161 -0.002480447 0.01480084 0.05120277 -0.005250096 0.01398342 0.05105853 -0.002560555 0.01495933 0.05078095 -0.002794086 0.01316833 0.05091959 -0.002704381 0.01309573 0.05075567 -0.002625703 0.01351022 0.05084753 -0.002637207 0.01324123 0.05078297 -0.002453505 0.01380366 0.0507577 -0.002465784 0.01416903 0.05089485 -0.002447068 0.0135011 0.05089569 -0.002357244 0.01379388 0.05089753 -0.00232464 0.01407903 0.0508362 -0.002395749 0.0144121 0.05075573 -0.002572178 0.01457542 0.05083078 -0.002636492 0.01493763 0.05091482 -0.002473175 0.01475632 0.05075591 -0.002933859 0.0150941 0.05098772 -0.002859354 0.01525712 0.0508297 -0.003042161 0.01530289 0.05075943 -0.003486573 0.01537603 0.05089324 -0.003288805 0.015468 0.05075585 -0.004119217 0.01535022 0.05086928 -0.003726303 0.01554113 0.05081844 -0.004125416 0.01545923 0.05099457 -0.004010796 0.01556146 0.05075323 -0.004729509 0.01497799 0.05099189 -0.004364252 0.01545405 0.0507915 -0.004598557 0.01518863 0.05088555 -0.004575371 0.01530879 0.05087369 -0.004969954 0.01492184 0.0509938 -0.004830241 0.01513707 0.05075484 -0.005064785 0.01426309 0.05079835 -0.005035758 0.01465934 0.0508508 -0.005176723 0.01441544 0.05099976 -0.005129873 0.01470255 0.05075532 -0.005034387 0.01379102 0.05098837 -0.005250453 0.0142365 0.05082821 -0.005182147 0.01395601 0.05086171 -0.005153298 0.01366764 0.05075764 -0.004868447 0.0133627 0.05098617 -0.005080163 0.01339179 0.05087423 -0.004868149 0.01314246 0.05075359 -0.004406392 0.01297748 0.05080199 -0.004648804 0.01302462 0.05091023 -0.004562675 0.01286429 0.05080586 -0.004255712 0.01279407 0.05075347 -0.003911435 0.01281279 0.05089282 -0.004288315 0.01273667 0.0508123 -0.003817856 0.01270616 0.05091029 -0.003918826 0.01264107 0.05089962 -0.003583133 0.01265329 0.05076968 -0.003509402 0.01279199 0.05081361 -0.003196775 0.01282 0.05075168 -0.003052115 0.01305609 0.05089884 -0.003032684 0.01284712 0.05690658 -0.005613088 0.0160709 0.05689585 -0.005155384 0.01640456 0.05676138 -0.005233466 0.0161944 0.05694383 -0.004884183 0.01655972 0.05680948 -0.004655063 0.01657342 0.05693274 -0.004257321 0.01675719 0.05675643 -0.004120647 0.01661294 0.05685716 -0.003883779 0.01675683 0.05692583 -0.003487527 0.01678001 0.05680501 -0.003339767 0.01667732 0.05691391 -0.003003358 0.01667374 0.05693882 -0.002598345 0.01652628 0.05678218 -0.002808868 0.01649612 0.05681884 -0.002255439 0.01625007 0.05675476 -0.002902567 0.01650929 0.05694442 -0.002107322 0.01621538 0.05689942 -0.001796603 0.01591616 0.05675584 -0.001799464 0.0156843 0.05692028 -0.001485645 0.01551407 0.05681395 -0.001431345 0.01527982 0.05693739 -0.001195311 0.01489597 0.05675977 -0.001351237 0.01487165 0.05685108 -0.0011397 0.01442438 0.05694156 -0.001081228 0.01421022 0.05677318 -0.001205563 0.01415348 0.05689603 -0.001112222 0.01373863 0.05675655 -0.001332998 0.01341378 0.05688393 -0.001229465 0.01325768 0.05693 -0.001385211 0.01284742 0.05675739 -0.001623213 0.01273012 0.05691009 -0.001617193 0.0124939 0.056921 -0.001884043 0.01217794 0.05677205 -0.002016007 0.0122165 0.05690175 -0.002268195 0.0118668 0.05681556 -0.002497255 0.01179903 0.05693918 -0.002719521 0.01161503 0.05675506 -0.002961277 0.01170259 0.0568363 -0.003020882 0.01155829 0.05694466 -0.003121435 0.01147592 0.0568121 -0.003515005 0.01148396 0.05693149 -0.003536045 0.01141148 0.05675685 -0.003860771 0.01156365 0.05689883 -0.004003942 0.01141428 0.0569275 -0.004446566 0.0114817 0.05680918 -0.004460453 0.01156389 0.05675137 -0.00468564 0.01176381 0.05691528 -0.005042195 0.01171141 0.05679637 -0.004969716 0.0117743 0.05689495 -0.005459964 0.01200097 0.05688965 -0.005752742 0.01227182 0.05675828 -0.00548768 0.01221925 0.05691093 -0.006022393 0.01261037 0.0567584 -0.005929946 0.01273131 0.05689895 -0.00621736 0.01295834 0.05693995 -0.006361722 0.01331067 0.05677205 -0.006203949 0.01325345 0.05680572 -0.006356656 0.01360946 0.05694615 -0.006456792 0.01376318 0.05675458 -0.006293833 0.01445257 0.05690264 -0.00646919 0.01411706 0.05681324 -0.006390154 0.01442873 0.05691534 -0.006444215 0.01447629 0.05692529 -0.006354689 0.01489466 0.05681025 -0.006171107 0.01516866 0.05691629 -0.006162822 0.01535457 0.0567547 -0.006075024 0.01514565 0.05680853 -0.005880713 0.01566052 0.05692374 -0.005934953 0.01571011 0.05675619 -0.00560677 0.01584517 0.05954843 -0.005404889 0.01625537 0.05954056 -0.004432797 0.01672005 0.05955541 -0.00357145 0.01678872 0.05957454 -0.003026902 0.01668632 0.05955588 -0.002500891 0.01647764 0.05958986 -0.001991987 0.01611548 0.05956709 -0.001509428 0.01555997 0.05960541 -0.00112468 0.01453328 0.0596106 -0.001091957 0.014054 0.05958157 -0.001123011 0.0136277 0.0595991 -0.001829564 0.01223969 0.05957078 -0.003778636 0.01139634 0.05955314 -0.005802929 0.01231116 0.0595678 -0.006111681 0.01273614 0.05955427 -0.006466031 0.01383024 0.05957853 -0.005842387 0.01583474 0.05967515 -0.005342662 0.01622617 0.05969965 -0.005688488 0.01587224 0.0595991 -0.006108343 0.01544648 0.05970525 -0.00610274 0.01527547 0.05958932 -0.006295323 0.01504844 0.05974751 -0.005901694 0.01547163 0.05959808 -0.006413221 0.01464879 0.05973857 -0.006302654 0.01448559 0.059605 -0.006458401 0.01429915 0.0596854 -0.006398797 0.01388317 0.05974525 -0.006219387 0.01343917 0.0596165 -0.006375074 0.01342236 0.05959916 -0.006272733 0.01309049 0.05970692 -0.006064593 0.01285469 0.05974769 -0.005785763 0.01258218 0.05968475 -0.005734086 0.0123316 0.05957341 -0.005432069 0.01196169 0.05964022 -0.005221009 0.01185625 0.05974292 -0.005199253 0.01199877 0.05974096 -0.004775106 0.01174443 0.05957657 -0.004808664 0.01160132 0.05958664 -0.004270732 0.01144826 0.05970102 -0.004157543 0.01150852 0.0597462 -0.00366801 0.0115841 0.05968654 -0.003350973 0.01149958 0.05957496 -0.003159105 0.01147115 0.05974626 -0.002655088 0.01182508 0.0595808 -0.002624154 0.01165747 0.05969947 -0.002646744 0.0117433 0.05958223 -0.002198159 0.01191401 0.05970287 -0.002185046 0.01203531 0.05974185 -0.001683294 0.01265347 0.05969005 -0.001704871 0.01248741 0.05956494 -0.001511931 0.01263487 0.05967009 -0.001324951 0.01309996 0.05955666 -0.001290559 0.01304733 0.05974113 -0.001273632 0.01361942 0.0597468 -0.001263916 0.01441776 0.05956137 -0.001238942 0.01501089 0.05969083 -0.001315772 0.01500624 0.05963814 -0.001586914 0.01563346 0.05973315 -0.001671552 0.01554477 0.05974346 -0.002046942 0.01593995 0.05968225 -0.002425193 0.01635903 0.05974704 -0.002890646 0.01645678 0.05969893 -0.002951323 0.01657384 0.05968457 -0.003324568 0.01669049 0.05960917 -0.003896415 0.01678013 0.05974048 -0.004003524 0.01663655 0.05969309 -0.004497468 0.01662057 0.05961096 -0.00492841 0.01652389 0.05974471 -0.00500828 0.01630485 0.01440721 0.005973041 -0.03985518 0.01478433 0.006369888 -0.03984636 0.01500183 0.006549477 -0.03985619 0.01415878 0.00576502 -0.039855 0.01486945 0.006828665 -0.03985518 0.0137881 0.005883634 -0.03985506 0.01364946 0.005840361 -0.03985518 0.01476269 0.007159531 -0.03984981 0.01330018 0.006104767 -0.03984707 0.01450628 0.007454633 -0.03984177 0.01481425 0.007340312 -0.03985536 0.01452636 0.007600903 -0.03986543 0.0131402 0.006358087 -0.03984725 0.01407849 0.007719755 -0.03986454 0.01305377 0.006643414 -0.03985512 0.01354873 0.00759828 -0.03985798 0.01358306 0.007618606 -0.03410845 0.01413559 0.007732391 -0.03414893 0.01487708 0.006651401 -0.03411144 0.01424002 0.007636427 -0.03410494 0.01460701 0.007554709 -0.03417778 0.0148828 0.007248282 -0.03419458 0.01470172 0.007315099 -0.03410476 0.01499998 0.006952106 -0.03420704 0.01500642 0.006576359 -0.03422504 0.01482164 0.006137788 -0.0342437 0.01470607 0.006252765 -0.03411751 0.0145415 0.005888462 -0.03424865 0.01443737 0.006009757 -0.03415834 0.01407676 0.005910158 -0.03417581 0.01405256 0.005757629 -0.03427553 0.01371896 0.00596857 -0.03419327 0.01371288 0.005814075 -0.03429448 0.01332134 0.006056725 -0.03431087 0.0135017 0.00611031 -0.03417849 0.01310694 0.006393074 -0.03432589 0.0132637 0.006428301 -0.03420555 0.01304674 0.006726086 -0.03433442 0.01321423 0.006931245 -0.03424936 0.0131269 0.007124185 -0.03435486 0.01347744 0.007380723 -0.03427428 0.01331233 0.007416665 -0.03437077 0.01366049 0.007658183 -0.03438669 0.0140376 0.007596075 -0.03430336 0.01400214 0.007730007 -0.03439843 0.01439857 0.007663547 -0.03441393 0.01457917 0.007373809 -0.03430587 0.01480281 0.007378637 -0.03444272 0.01479321 0.007080137 -0.03432655 0.01502013 0.006874144 -0.03446042 0.01486206 0.006701588 -0.03434026 0.01498246 0.006456434 -0.0344721 0.01471179 0.00622642 -0.03439116 0.0147081 0.006015956 -0.03449648 0.01421129 0.00592035 -0.03441971 0.01421099 0.005767941 -0.03452259 0.01372063 0.00580722 -0.0345419 0.01382374 0.005939543 -0.03443837 0.01341271 0.005972564 -0.03455197 0.01347744 0.006112694 -0.03445678 0.01312619 0.006349146 -0.034572 0.01324933 0.006462812 -0.03447693 0.01305198 0.006868183 -0.03459644 0.01320266 0.006871283 -0.03449642 0.01318353 0.007258534 -0.03461205 0.0133388 0.007191598 -0.03448688 0.01354861 0.007613837 -0.03462982 0.01359641 0.007447183 -0.034505 0.014104 0.007591128 -0.03455591 0.01397424 0.007729589 -0.03464978 0.01426541 0.007699787 -0.03465902 0.01457327 0.00757265 -0.03467637 0.01458895 0.007362425 -0.03455591 0.01481038 0.007355093 -0.03468471 0.01480358 0.00705105 -0.03457224 0.0150035 0.006943941 -0.03470927 0.01486545 0.006690979 -0.03459489 0.01498705 0.006453096 -0.03471791 0.01465612 0.006168425 -0.0346449 0.01480966 0.006130039 -0.0347439 0.01449185 0.00587058 -0.03475803 0.01413226 0.005903899 -0.03467327 0.01418823 0.005774259 -0.03477114 0.01380795 0.005783915 -0.03478461 0.01358324 0.006030678 -0.03470051 0.0134803 0.005930006 -0.03480231 0.01319164 0.006230354 -0.03481751 0.01322829 0.006484687 -0.0347281 0.01304924 0.00666809 -0.03484213 0.01307773 0.006997108 -0.03485053 0.01322251 0.006921529 -0.03472214 0.01328355 0.007396757 -0.0348609 0.01349598 0.007403433 -0.03477603 0.01369124 0.007669508 -0.03488671 0.01394313 0.007570326 -0.034774 0.01402246 0.007729291 -0.03490269 0.01438802 0.007667601 -0.03491836 0.01443624 0.007486879 -0.03482311 0.01472187 0.007451295 -0.03492838 0.01479756 0.007107794 -0.03484779 0.01490885 0.007202923 -0.03494584 0.0150128 0.00687772 -0.03496158 0.01485341 0.006602883 -0.03484731 0.01497256 0.006427288 -0.03497397 0.0147323 0.006277024 -0.03488898 0.01476186 0.006072759 -0.03499931 0.01439446 0.005984365 -0.0349105 0.01444202 0.005849659 -0.03501129 0.01413166 0.005765795 -0.03501826 0.01393574 0.005910456 -0.03493291 0.01379096 0.005789339 -0.03503733 0.01352715 0.006077051 -0.03495365 0.01350057 0.005920886 -0.03505194 0.01318299 0.006234109 -0.03506731 0.01327645 0.006414771 -0.03494536 0.01304769 0.006723046 -0.0350908 0.01320111 0.006697475 -0.0349884 0.01313692 0.007157146 -0.03509992 0.01330554 0.007182776 -0.0350123 0.01337015 0.007478237 -0.03512245 0.01373159 0.007528305 -0.03503829 0.01394671 0.007739484 -0.03514695 0.01416414 0.007574975 -0.03505921 0.01439231 0.007670164 -0.03516548 0.01458764 0.007380068 -0.03508144 0.01476204 0.007411003 -0.03517907 0.01480305 0.007072627 -0.03509944 0.01494783 0.007121324 -0.03520047 0.01487445 0.006628215 -0.0351206 0.01502245 0.006640672 -0.03521603 0.01477569 0.00608915 -0.03524029 0.0147016 0.006248772 -0.03511792 0.01425361 0.005923032 -0.03516751 0.01440107 0.005829632 -0.03526401 0.01405245 0.005757868 -0.03527796 0.01365906 0.005826175 -0.03529292 0.01364666 0.00599277 -0.03519684 0.01325511 0.00612539 -0.03530251 0.01330685 0.006352961 -0.03519552 0.01319175 0.006751239 -0.03524047 0.01306992 0.006529867 -0.03533113 0.01307165 0.006983995 -0.03535693 0.01335442 0.007221519 -0.03523594 0.01324713 0.007339775 -0.03536576 0.01354634 0.007424116 -0.0352782 0.01345992 0.007542729 -0.03537434 0.01376116 0.007692694 -0.03539001 0.01401489 0.007594823 -0.03530156 0.01413768 0.007725954 -0.03540295 0.01451092 0.007608532 -0.03542482 0.01453906 0.007419228 -0.0353285 0.01477724 0.00739324 -0.03543657 0.01484686 0.006988763 -0.03535372 0.0149697 0.007061898 -0.03544533 0.01502442 0.006730258 -0.03546804 0.0148285 0.006465971 -0.03537905 0.01491856 0.00630474 -0.03548163 0.01460731 0.006137669 -0.03539794 0.01465255 0.005974352 -0.03550416 0.01420211 0.005911529 -0.0354197 0.01421016 0.00576514 -0.03552335 0.01394259 0.005766987 -0.03551489 0.01368671 0.005982697 -0.03544497 0.01361256 0.005851328 -0.035546 0.01338541 0.006216883 -0.03546375 0.013273 0.006116449 -0.03556013 0.01319271 0.006661474 -0.03548663 0.0131123 0.006396293 -0.03557735 0.01304954 0.006840229 -0.03559786 0.0133028 0.007154881 -0.03551059 0.01314651 0.007165312 -0.03560638 0.01334172 0.007446587 -0.03562009 0.01363408 0.00748676 -0.03553336 0.01371616 0.007685303 -0.03563964 0.014059 0.007575035 -0.03552472 0.01414048 0.007722735 -0.03565293 0.01440787 0.007503569 -0.03557121 0.01446688 0.00763148 -0.0356729 0.0147913 0.007385373 -0.03568869 0.01477873 0.007140278 -0.03559601 0.01497662 0.007048547 -0.03569728 0.0148704 0.006590306 -0.03562217 0.01501184 0.006590664 -0.03572028 0.01483386 0.006164908 -0.03573638 0.01465088 0.006191194 -0.03561663 0.01457196 0.00591439 -0.03575438 0.01433867 0.005966663 -0.03566336 0.0142073 0.005774438 -0.03577661 0.01390266 0.00592482 -0.03565597 0.01379078 0.00578463 -0.03578478 0.01361674 0.006028831 -0.03567701 0.01333862 0.006039917 -0.03580194 0.01334917 0.006263375 -0.03571611 0.01310348 0.006395339 -0.0358268 0.01319265 0.006698191 -0.03573834 0.01306182 0.006927907 -0.03584527 0.01333326 0.007215082 -0.03576368 0.01321762 0.007304608 -0.03586876 0.01361614 0.007643938 -0.03588026 0.01378309 0.007554113 -0.03579115 0.01412421 0.007734477 -0.03590434 0.0142979 0.00753194 -0.03578925 0.01466792 0.007501304 -0.035914 0.01461362 0.007349669 -0.03583341 0.01488959 0.007244467 -0.03594517 0.0148288 0.007020175 -0.03585225 0.01500689 0.00689882 -0.03595906 0.0148608 0.006609737 -0.03587204 0.01497948 0.006429195 -0.03597724 0.01466768 0.006181836 -0.03589457 0.01464444 0.005962848 -0.03600215 0.01412808 0.005899369 -0.03592395 0.01417601 0.005766451 -0.03601616 0.01386272 0.005772352 -0.03603476 0.01361715 0.006019115 -0.03594863 0.01354199 0.005890548 -0.03605085 0.01329791 0.006336271 -0.03597044 0.01324427 0.006157219 -0.03606212 0.01307362 0.006513237 -0.03608089 0.01321017 0.006846964 -0.03596776 0.0130828 0.007019042 -0.0361036 0.01331508 0.007191002 -0.0360127 0.01328575 0.007386267 -0.03611862 0.01364809 0.007660269 -0.03613162 0.01368832 0.007507264 -0.03603595 0.01407313 0.007583379 -0.0360549 0.01416057 0.007725656 -0.03615415 0.0145924 0.007390975 -0.03608125 0.01450777 0.007614254 -0.03617209 0.0148648 0.00729382 -0.03619432 0.01486015 0.006900608 -0.03610819 0.01502138 0.006793081 -0.03621375 0.01481306 0.006414532 -0.03613162 0.01492035 0.006289899 -0.0362277 0.01443231 0.00601226 -0.03612536 0.01466202 0.005980372 -0.03625333 0.01416313 0.005906462 -0.03617167 0.01426643 0.005785107 -0.0362693 0.01385051 0.005775988 -0.03628015 0.01361823 0.006012737 -0.03619855 0.01348698 0.005922794 -0.03630197 0.01334446 0.006291806 -0.03619039 0.01323044 0.006179809 -0.03631812 0.01305425 0.006588757 -0.03633129 0.01318442 0.006715893 -0.03623938 0.013103 0.007068276 -0.03635597 0.01334369 0.007218003 -0.03626447 0.01325732 0.007347702 -0.03636628 0.01349455 0.007574558 -0.03637677 0.01364248 0.007486283 -0.03628349 0.01383763 0.007709681 -0.03639483 0.014108 0.007586658 -0.03630602 0.01414555 0.007721841 -0.0364052 0.0144788 0.007626295 -0.03641682 0.01458489 0.007383644 -0.03633135 0.01473808 0.007433652 -0.03643316 0.01493656 0.007145941 -0.03644603 0.01486968 0.006902635 -0.03635823 0.01502037 0.00683242 -0.03646016 0.01499736 0.006503164 -0.0364747 0.01481014 0.006433486 -0.03638088 0.01451426 0.006041705 -0.03640413 0.0146889 0.006005167 -0.03648191 0.01422023 0.005776345 -0.03651249 0.01396209 0.005906522 -0.03643143 0.0138036 0.005785465 -0.03654122 0.01367026 0.005997419 -0.03641581 0.0134859 0.005924701 -0.03655058 0.01317858 0.006249904 -0.03656119 0.01329725 0.006340682 -0.03647017 0.01319664 0.006864964 -0.03649604 0.01305937 0.006578743 -0.03658342 0.01308077 0.007010459 -0.03659975 0.01338452 0.00726056 -0.03649026 0.01327848 0.007392406 -0.03662276 0.01367944 0.007495641 -0.03651106 0.01368814 0.007667541 -0.03664034 0.01399803 0.007730484 -0.03664863 0.01415991 0.007577896 -0.03655916 0.01438277 0.007671415 -0.03666663 0.0146197 0.007354855 -0.0365833 0.01471441 0.007457554 -0.03667819 0.01492041 0.007176518 -0.03669607 0.0148248 0.006995558 -0.03657424 0.01501518 0.00685817 -0.03671044 0.01485353 0.006534993 -0.03662508 0.01495218 0.006359159 -0.03672927 0.01458394 0.00612396 -0.03662312 0.01460695 0.005936205 -0.0367518 0.01429766 0.005952954 -0.03666555 0.01418381 0.005766868 -0.03676885 0.01386445 0.00591588 -0.03668588 0.01383298 0.005770981 -0.03679174 0.01343858 0.005965113 -0.0368027 0.01340186 0.006189942 -0.03671181 0.01321679 0.006195902 -0.03681355 0.01322579 0.006540477 -0.03673076 0.01305574 0.006596505 -0.03683561 0.01322543 0.006990015 -0.03675222 0.0131008 0.007061123 -0.036848 0.0132839 0.007386922 -0.03686994 0.0135138 0.007403731 -0.03677642 0.01357328 0.007610976 -0.03688114 0.01399183 0.007590949 -0.03680109 0.01387149 0.007717609 -0.03689599 0.01420444 0.00771439 -0.03691112 0.01447129 0.007460772 -0.03682452 0.01449823 0.007611572 -0.0369181 0.01474893 0.00742346 -0.03693383 0.01478058 0.007138311 -0.03684628 0.0149331 0.007153332 -0.03694558 0.01501011 0.006881535 -0.03696233 0.01487022 0.006607592 -0.03687167 0.01496267 0.006379127 -0.0369811 0.01467078 0.006202161 -0.03689402 0.01468366 0.006006479 -0.03699624 0.01444733 0.006029784 -0.03687983 0.01429677 0.005787074 -0.0370177 0.01409709 0.005916655 -0.03689819 0.01375573 0.005794227 -0.03703337 0.0137192 0.005981922 -0.03692013 0.01336818 0.006012678 -0.0370599 0.01336872 0.006229341 -0.03696435 0.01309871 0.006427526 -0.03707301 0.0131886 0.006740868 -0.03699034 0.01305162 0.006892561 -0.03709465 0.01334834 0.007213115 -0.03698688 0.01318264 0.007238686 -0.03711229 0.01340973 0.007505416 -0.03712451 0.01367664 0.007516801 -0.037036 0.01376438 0.007697224 -0.03714019 0.01420068 0.007566511 -0.03706073 0.01412576 0.007723689 -0.03715878 0.01446276 0.007632374 -0.03716731 0.01457566 0.007388234 -0.03708076 0.01473957 0.00743556 -0.03718709 0.01485162 0.00696659 -0.03710526 0.01498061 0.007042765 -0.03720337 0.01501715 0.006642639 -0.03721851 0.01483142 0.00648117 -0.03712809 0.01493412 0.006341874 -0.03722929 0.01452076 0.006046354 -0.03715413 0.01464307 0.005959868 -0.03724884 0.01414036 0.005759775 -0.03727644 0.01395994 0.005905508 -0.03718119 0.01367855 0.005822002 -0.0372864 0.01362305 0.006023764 -0.03717172 0.01336038 0.006029009 -0.03730857 0.01324546 0.00643593 -0.03722566 0.01310014 0.006410837 -0.03732335 0.01322942 0.006992518 -0.03725236 0.01305621 0.00688064 -0.03734552 0.01323872 0.00733608 -0.03736966 0.01352548 0.007401049 -0.03724992 0.01357334 0.007619857 -0.03738397 0.01398205 0.007588326 -0.03730005 0.0138517 0.007713258 -0.03739154 0.01421511 0.007713198 -0.03740781 0.01453542 0.007429957 -0.03732794 0.01456207 0.007580637 -0.03742825 0.01478564 0.007381737 -0.03743553 0.01496422 0.00708425 -0.0374493 0.01485913 0.006941556 -0.03735637 0.01502019 0.006643593 -0.03746908 0.01480793 0.006412029 -0.03738135 0.01486015 0.006200551 -0.037481 0.01441067 0.005978405 -0.03740888 0.01456528 0.005907535 -0.03750377 0.01422137 0.005771934 -0.03752028 0.0138123 0.005931437 -0.03743904 0.01380842 0.005783021 -0.03753584 0.01349979 0.005915641 -0.03755557 0.01340651 0.006204485 -0.03743892 0.01322466 0.006187796 -0.03756433 0.01308459 0.006481587 -0.0375759 0.01322621 0.006565332 -0.03745424 0.01305747 0.006865918 -0.03759622 0.01323354 0.00695765 -0.03747493 0.01322555 0.007321596 -0.03761315 0.01345348 0.007359325 -0.03752285 0.01359474 0.007626295 -0.03763353 0.01391124 0.007575809 -0.03754723 0.01398968 0.007731378 -0.03764718 0.01439464 0.007509648 -0.03757005 0.01431638 0.007691085 -0.03766739 0.01461517 0.007535874 -0.037678 0.01485222 0.007302045 -0.03768557 0.01477575 0.007148623 -0.03759568 0.01500058 0.00695306 -0.03771227 0.01487183 0.006696045 -0.03761762 0.01499754 0.006522893 -0.03772395 0.01471745 0.006268024 -0.03761339 0.01487761 0.00622797 -0.0377348 0.01456749 0.006099224 -0.03765094 0.0146203 0.005952358 -0.03775388 0.014364 0.005813419 -0.03776168 0.01416456 0.005911767 -0.03767156 0.01397728 0.005756616 -0.03777909 0.01360666 0.006011962 -0.0376985 0.0135793 0.005872607 -0.03779178 0.01324051 0.006152212 -0.03781938 0.013278 0.00638777 -0.03772306 0.01305931 0.006567895 -0.03783303 0.0132088 0.006741821 -0.03771185 0.01306515 0.006953477 -0.03784596 0.01328104 0.007092893 -0.03773123 0.01329189 0.007405042 -0.03786796 0.01352125 0.007392823 -0.03774857 0.01386272 0.007578372 -0.03779518 0.01375287 0.007696211 -0.0378865 0.01413136 0.007722258 -0.03790622 0.01441717 0.00748372 -0.03780055 0.01454919 0.007596731 -0.03792089 0.01477694 0.007158756 -0.03784501 0.01496088 0.007095158 -0.03793454 0.01485955 0.006663143 -0.03784209 0.0150004 0.006525099 -0.03797155 0.014696 0.006222069 -0.03789174 0.01479786 0.006115019 -0.03798896 0.01435375 0.005802571 -0.03801417 0.01428145 0.005951225 -0.03789138 0.01379668 0.005939602 -0.03793913 0.01386928 0.005774676 -0.03803437 0.01340651 0.005971252 -0.03805655 0.01332521 0.00627017 -0.03796637 0.01312845 0.006361901 -0.03807133 0.01305288 0.006688773 -0.03808432 0.0132066 0.006944298 -0.03799933 0.01308095 0.006991088 -0.0381031 0.01321995 0.007292449 -0.03811091 0.01353853 0.007408916 -0.0380004 0.01352035 0.007594943 -0.03812819 0.01387465 0.007560491 -0.03802138 0.01391136 0.00772041 -0.03814798 0.01428633 0.007546603 -0.03806501 0.01431047 0.007695257 -0.03816229 0.01464897 0.00751537 -0.03818136 0.01466768 0.007300436 -0.03808718 0.01492607 0.00717628 -0.03819674 0.01485025 0.006932675 -0.03810632 0.01502531 0.006689369 -0.03821629 0.01485443 0.006567656 -0.03812384 0.01488584 0.006248772 -0.03823679 0.01459711 0.006105899 -0.03814965 0.01468837 0.006007552 -0.03824818 0.01440888 0.005831956 -0.03825813 0.01415789 0.005920171 -0.03817218 0.01395064 0.005758404 -0.03827655 0.01375645 0.005948781 -0.03819143 0.01340621 0.00598073 -0.03828907 0.01341539 0.006193518 -0.03818213 0.01324355 0.00649631 -0.03820395 0.01309746 0.006434977 -0.03832477 0.01305568 0.006878197 -0.03834766 0.01322495 0.006977021 -0.03825157 0.0131905 0.007255375 -0.03835648 0.01340758 0.007285237 -0.03824162 0.01353204 0.007601141 -0.0383796 0.01368653 0.007500171 -0.03825891 0.01405239 0.007736921 -0.03840464 0.0142253 0.007573008 -0.03831219 0.01452159 0.007604718 -0.03842467 0.01473128 0.007230103 -0.03834104 0.01480478 0.007358491 -0.03843694 0.01496714 0.007072389 -0.03844761 0.01487737 0.006638288 -0.03837031 0.01501625 0.006614327 -0.03847098 0.01487338 0.006228208 -0.03848761 0.01466023 0.006186962 -0.03839427 0.01462364 0.005950927 -0.03850364 0.01432883 0.005961 -0.038414 0.01425188 0.005782008 -0.03851246 0.01393467 0.005911469 -0.03843283 0.01388275 0.005771338 -0.03853303 0.01344418 0.006134092 -0.03845834 0.01356005 0.005883157 -0.03855085 0.01323664 0.00616014 -0.03855824 0.01321065 0.006596565 -0.03848356 0.01307505 0.006507158 -0.03858345 0.01307272 0.00695765 -0.03859931 0.01326233 0.007052898 -0.03847873 0.01323723 0.007329046 -0.03860998 0.01341885 0.007324039 -0.03852075 0.01349431 0.007568418 -0.03863078 0.01388835 0.007575571 -0.03854572 0.0139473 0.007736444 -0.03864854 0.0142045 0.007557213 -0.03853219 0.0144158 0.007652759 -0.0386675 0.01468068 0.007303237 -0.03858703 0.01478195 0.00739926 -0.03868395 0.01501691 0.006860256 -0.038706 0.01487517 0.006767332 -0.03861409 0.01497048 0.006429553 -0.03872388 0.01473432 0.00626558 -0.0386396 0.01482796 0.006161272 -0.03874081 0.01452195 0.005883336 -0.03876042 0.01429212 0.005955576 -0.03864145 0.01417517 0.005770444 -0.03877115 0.01393699 0.00591576 -0.03868287 0.01381254 0.005785286 -0.0387811 0.01351147 0.006079554 -0.03870469 0.01343441 0.005955576 -0.03880137 0.01321059 0.006200134 -0.03881698 0.01319754 0.006598711 -0.03873366 0.01305949 0.006563901 -0.03883177 0.01307308 0.006974697 -0.03885358 0.01331973 0.007197678 -0.03876239 0.01328361 0.007384955 -0.03886896 0.01364189 0.007654786 -0.03887993 0.01375603 0.007542312 -0.03878968 0.01406472 0.007731914 -0.03890317 0.01417964 0.007559955 -0.03878223 0.01442116 0.007652342 -0.03892111 0.01456433 0.007403314 -0.03882968 0.01481354 0.007364392 -0.03894013 0.01483327 0.006970763 -0.0388264 0.01500159 0.006938099 -0.0389539 0.0148552 0.006611943 -0.03884798 0.01500958 0.006600618 -0.03897219 0.01487404 0.006223201 -0.03898781 0.01468503 0.006231427 -0.03886449 0.01462543 0.005953729 -0.03900068 0.01437556 0.005985856 -0.03888887 0.01429593 0.005791008 -0.03901457 0.01393985 0.005914449 -0.03893244 0.01376801 0.005789101 -0.03903955 0.01359492 0.006043434 -0.03892403 0.01338171 0.006002724 -0.03905749 0.01331853 0.006312429 -0.03896886 0.01319104 0.006238162 -0.03905212 0.01319098 0.006744801 -0.03899055 0.0130487 0.006732046 -0.0390734 0.01311749 0.007119894 -0.03910821 0.01338875 0.007298231 -0.03901857 0.01338571 0.007486939 -0.03912329 0.013709 0.007674753 -0.03914165 0.01382732 0.007549524 -0.0390191 0.01411068 0.007730782 -0.03915131 0.01433014 0.007535338 -0.03906726 0.01447665 0.007625102 -0.03917032 0.01479274 0.007379055 -0.0391891 0.01470679 0.007234513 -0.03906559 0.01499289 0.006990849 -0.03920519 0.01488012 0.00672841 -0.0391159 0.01500654 0.006565153 -0.0392211 0.01468521 0.006202161 -0.03914332 0.01485329 0.006195664 -0.039236 0.01459217 0.005930542 -0.03925704 0.01412016 0.005893528 -0.03917443 0.01419568 0.005764484 -0.03926742 0.01371794 0.005810797 -0.03928792 0.01351499 0.006079614 -0.039204 0.01339668 0.005997657 -0.03930377 0.01316469 0.006274759 -0.03931945 0.01320236 0.006577968 -0.03923207 0.01305097 0.006673753 -0.03933775 0.01311457 0.007102966 -0.03935152 0.0132851 0.007101118 -0.03923195 0.01326549 0.007364273 -0.03936785 0.01365536 0.007502675 -0.03928434 0.01351344 0.007576882 -0.0393806 0.01381701 0.007706165 -0.03939539 0.01412189 0.007571876 -0.03928041 0.01427853 0.007708668 -0.03941148 0.01449513 0.007432758 -0.03929978 0.01472985 0.00744754 -0.03943401 0.01480025 0.007102012 -0.03934818 0.01497554 0.00706017 -0.03944617 0.0148642 0.00660324 -0.0393719 0.0150184 0.006658196 -0.03946685 0.01494413 0.006346404 -0.03948265 0.0146594 0.006180346 -0.03939515 0.01461315 0.005938947 -0.03950083 0.01416707 0.005904436 -0.03942167 0.01414543 0.005756497 -0.03953188 0.01367926 0.005819559 -0.03954046 0.01363444 0.006020069 -0.03942477 0.01332139 0.006061494 -0.03955858 0.01324975 0.006417393 -0.03947389 0.01309102 0.006439387 -0.03957575 0.01306033 0.00688517 -0.03959453 0.01323056 0.0069983 -0.03950303 0.01319044 0.007261157 -0.03961086 0.01345771 0.007346868 -0.03952252 0.01358163 0.007628023 -0.03963488 0.01377958 0.007546961 -0.03954046 0.01406759 0.007737576 -0.03965538 0.01407116 0.00757277 -0.0395292 0.01436442 0.00767219 -0.03964942 0.01446878 0.007463097 -0.0395745 0.01465332 0.007521867 -0.03967869 0.01478189 0.007135987 -0.03959596 0.01497638 0.007040441 -0.03968614 0.01485931 0.006638586 -0.03959053 0.01500046 0.006532669 -0.03972268 0.01475054 0.006321966 -0.03961503 0.01485925 0.006204545 -0.03973484 0.01443457 0.006017506 -0.03962981 0.01459115 0.005932867 -0.03975176 0.01431459 0.005800604 -0.03976374 0.01402479 0.00591439 -0.03965282 0.01393252 0.005764424 -0.03978574 0.01357465 0.006032288 -0.03970098 0.01360547 0.00585699 -0.03979218 0.01332551 0.006063163 -0.03981131 0.01309412 0.006433367 -0.03981041 0.01322913 0.006493031 -0.03972846 0.01323539 0.006957352 -0.03972339 0.01308715 0.006997585 -0.03983306 0.01336795 0.007237911 -0.03973925 0.01325297 0.007334351 -0.03985023 0.01363325 0.007476449 -0.03978365 0.01401638 0.007586181 -0.03980284 0.01427078 0.005928099 -0.03410905 0.01377463 0.005936443 -0.03412067 0.01319444 0.00668323 -0.03418546 0.01327437 0.007086575 -0.03420484 0.01348727 0.007381141 -0.03422272 0.01387119 0.007568061 -0.03424274 0.01430666 0.007540225 -0.03426378 0.01472002 0.006251692 -0.03433859 0.01430761 0.005947768 -0.03436255 0.01374018 0.005947887 -0.03438949 0.0133301 0.006289899 -0.0344153 0.01319134 0.006744205 -0.03443878 0.01391643 0.007576107 -0.03449493 0.01428735 0.007542014 -0.03451287 0.01477867 0.006347179 -0.03458267 0.01451683 0.006065666 -0.03460103 0.0141471 0.005907595 -0.03462028 0.01356917 0.006033241 -0.03464925 0.01325088 0.006450176 -0.03467381 0.01346087 0.007364153 -0.03472095 0.01427876 0.007546186 -0.03476256 0.01459306 0.007368385 -0.03477984 0.01483768 0.007008314 -0.03480058 0.01457571 0.006086647 -0.03484839 0.01408153 0.005908966 -0.03487366 0.01357358 0.00603038 -0.03489845 0.01320427 0.006923198 -0.03494638 0.01348376 0.007378101 -0.03497213 0.01386117 0.007565677 -0.03499263 0.01431572 0.007538497 -0.03501409 0.01471954 0.007239997 -0.03503865 0.0148794 0.006731688 -0.03506374 0.014521 0.006056964 -0.03510159 0.01405417 0.005903601 -0.03512465 0.01356196 0.006045162 -0.03514927 0.01319348 0.006789326 -0.03519022 0.01376354 0.007544755 -0.03523802 0.01417845 0.007568061 -0.03525745 0.0145815 0.007391929 -0.03527903 0.01487863 0.006855368 -0.03530848 0.01476317 0.006325662 -0.03533399 0.01444089 0.006008565 -0.03535586 0.01403665 0.005907595 -0.03537547 0.01361256 0.006016075 -0.03539687 0.01324349 0.006438791 -0.03542375 0.01322561 0.006967961 -0.03544878 0.01351577 0.007418811 -0.03547531 0.01458579 0.007392585 -0.03552883 0.0148586 0.006916105 -0.03555524 0.01484006 0.006517529 -0.03557401 0.01430827 0.005945503 -0.03561282 0.01327526 0.006381273 -0.03567034 0.01320123 0.00684601 -0.03569298 0.01337599 0.007267296 -0.03571504 0.01381206 0.00756222 -0.03574037 0.01469826 0.007265388 -0.03578662 0.01487463 0.006806492 -0.03581023 0.01472812 0.006246268 -0.03583878 0.01424294 0.005930781 -0.03586602 0.01367378 0.005972623 -0.03589302 0.01324379 0.006439983 -0.03592336 0.0133711 0.007253646 -0.03596442 0.01374834 0.007543683 -0.03598713 0.01432007 0.007540166 -0.03601461 0.01467895 0.007277846 -0.03603553 0.01486599 0.006895482 -0.03605598 0.01477277 0.00632286 -0.03608399 0.01402622 0.005908906 -0.03612613 0.01364225 0.006001651 -0.03614491 0.01319789 0.006674945 -0.03618508 0.01333981 0.007242441 -0.0362128 0.013848 0.007566809 -0.03624165 0.01427358 0.00754702 -0.03626209 0.01465004 0.007321059 -0.03628343 0.01488769 0.006785213 -0.03631222 0.0147022 0.006232142 -0.03633922 0.01423597 0.005918264 -0.03636574 0.01331031 0.006307661 -0.03641688 0.0131976 0.006823956 -0.0364418 0.01398307 0.00758326 -0.03649818 0.01452261 0.007444322 -0.03652483 0.01484936 0.006509125 -0.03657466 0.01411402 0.005900919 -0.03662246 0.0136258 0.006013154 -0.036646 0.01328992 0.006347477 -0.03666865 0.01319915 0.006817042 -0.0366916 0.01331877 0.007172405 -0.03670942 0.01357054 0.007445871 -0.03672772 0.01394933 0.007575809 -0.03674638 0.0143122 0.007536828 -0.03676408 0.01467353 0.007292628 -0.03678482 0.01485896 0.006902933 -0.03680568 0.01480323 0.006378948 -0.03683185 0.01340925 0.006180286 -0.03690886 0.01318848 0.006695806 -0.0369367 0.0137661 0.007546126 -0.03698772 0.01433199 0.007538318 -0.03701531 0.01474112 0.007203459 -0.03704023 0.01486545 0.006830453 -0.03705924 0.01480692 0.006400763 -0.03707969 0.01452708 0.006070315 -0.03710049 0.01412445 0.005904912 -0.03712129 0.01337885 0.006219267 -0.03716164 0.0132268 0.006545364 -0.03717851 0.01322364 0.007000625 -0.03719991 0.01402288 0.007594525 -0.03725039 0.01463639 0.007352292 -0.03728163 0.0148645 0.006860196 -0.0373075 0.01479637 0.006368577 -0.03733187 0.01433032 0.005947232 -0.0373612 0.01371634 0.005959928 -0.03739166 0.01340574 0.007291615 -0.03746652 0.01372814 0.007532477 -0.03748619 0.01424074 0.00756061 -0.03751069 0.01466745 0.007305085 -0.03753435 0.01486766 0.006859064 -0.03755778 0.01482182 0.006460964 -0.03757679 0.01434326 0.005963027 -0.03761136 0.01382166 0.005925655 -0.03763562 0.01333355 0.006266415 -0.03766441 0.0138424 0.007556796 -0.03774124 0.01420241 0.00756824 -0.0377587 0.01479101 0.007122933 -0.03779458 0.01471036 0.006231188 -0.03783881 0.013929 0.005910873 -0.03788071 0.01343059 0.006147384 -0.03790736 0.0132094 0.006607949 -0.03793185 0.01326638 0.007104516 -0.03795528 0.01439911 0.007507562 -0.0380184 0.01478725 0.007129609 -0.03804469 0.01486706 0.006607413 -0.0380699 0.014674 0.006203114 -0.03809106 0.01427036 0.005931675 -0.03811424 0.01377791 0.00594753 -0.03813791 0.01321047 0.006903409 -0.03819578 0.01421844 0.007573783 -0.03825974 0.01470476 0.007260024 -0.03828746 0.01488184 0.006731986 -0.03831362 0.01465296 0.006157636 -0.03834372 0.01416248 0.005916237 -0.03836983 0.01362186 0.005999445 -0.0383954 0.01328021 0.006385743 -0.03842037 0.01319426 0.006783366 -0.03843992 0.01363939 0.007500708 -0.03848189 0.01455444 0.007400751 -0.03852719 0.01484268 0.007006525 -0.03855079 0.01483255 0.006483018 -0.038576 0.01458084 0.006103754 -0.03859764 0.01378434 0.005937576 -0.03863757 0.01341372 0.006187379 -0.03865897 0.01320654 0.006572723 -0.03868037 0.01330065 0.007174253 -0.03870922 0.01373624 0.007532 -0.0387361 0.01462405 0.007353067 -0.0387811 0.01402318 0.005901515 -0.03887617 0.01325601 0.006410777 -0.03892254 0.01321333 0.00691241 -0.03894621 0.01340693 0.007303953 -0.03896731 0.01427531 0.007558882 -0.03901296 0.01485258 0.006927251 -0.03905433 0.01484501 0.006520152 -0.039074 0.01465976 0.00619322 -0.03909188 0.01433026 0.005952119 -0.03911137 0.01376706 0.005943 -0.03913867 0.01340728 0.006194531 -0.03915947 0.01320028 0.006604611 -0.03918129 0.01357161 0.007457256 -0.03922826 0.0148248 0.007061541 -0.03929769 0.01483833 0.006489634 -0.03932571 0.01455754 0.00608474 -0.03934943 0.01404505 0.005896985 -0.03937506 0.01336175 0.006244957 -0.03941267 0.01319211 0.006691336 -0.03943562 0.01331681 0.007182359 -0.03946018 0.01364129 0.007486104 -0.0394811 0.01445847 0.007483124 -0.03952217 0.01481413 0.007062137 -0.03954786 0.01349729 0.006089448 -0.03965288 0.01321488 0.006555974 -0.03967946 0.01374411 0.007540225 -0.03973644 0.01422792 0.007560372 -0.03975975 0.01458162 0.007380962 -0.03977924 0.01479446 0.007092952 -0.03979599 0.01487565 0.006676793 -0.03981631 0.01306575 0.006878256 -0.03410762 0.01317006 0.006316781 -0.03410619 0.0132206 0.007310092 -0.03411889 0.01369971 0.007672727 -0.03415369 0.01367586 0.007663071 -0.03515231 0.0149244 0.006334722 -0.03524696 0.01450222 0.007612764 -0.03593754 0.01483958 0.006180584 -0.0365042 0.01448953 0.005871713 -0.03652358 0.0148704 0.007269799 -0.03795814 0.01501643 0.006793141 -0.03797775 0.01371914 0.005814075 -0.03830575 0.01331162 0.00607568 -0.03832507 0.01493656 0.007124245 -0.03871417 0.01307523 0.006499826 -0.03909486 0.01486498 0.007273435 -0.03970772 0.01501876 0.006798446 -0.03972756 0.01494193 0.006816625 -0.04003131 0.01481139 0.007051229 -0.04008865 0.01461344 0.007309556 -0.04009866 0.01493322 0.007094085 -0.03994947 0.01498317 0.006997108 -0.03985524 0.01483112 0.007202565 -0.0400207 0.01473295 0.00739634 -0.0399689 0.01418602 0.00752753 -0.04010093 0.0145201 0.007503926 -0.0400421 0.01423025 0.007630527 -0.04003429 0.01430106 0.007665634 -0.03996396 0.01365119 0.007415771 -0.04010391 0.01392763 0.007585644 -0.04007732 0.01406681 0.007705211 -0.03995221 0.01390779 0.007659137 -0.04001891 0.01382005 0.007702469 -0.03986817 0.01357227 0.007515609 -0.04004633 0.01356595 0.007587194 -0.0399481 0.01339864 0.00733006 -0.04006838 0.01328665 0.007053732 -0.04009896 0.01329785 0.007362723 -0.03995317 0.01315546 0.007103323 -0.03998506 0.01316112 0.006795525 -0.04006105 0.01307809 0.006835103 -0.0399602 0.0132656 0.006512999 -0.04009914 0.01316618 0.006470084 -0.04003059 0.01317244 0.006299197 -0.03993505 0.01353478 0.006089746 -0.04009264 0.0137676 0.005986332 -0.04010027 0.01329022 0.00624305 -0.04004299 0.01338142 0.006045877 -0.03996497 0.01361924 0.005892038 -0.03997868 0.01385837 0.005856633 -0.04003334 0.01420313 0.005936443 -0.04009211 0.01438379 0.006036281 -0.04010289 0.01395356 0.005784451 -0.03994983 0.01419186 0.005808651 -0.03998559 0.0144335 0.005940914 -0.0400418 0.01459676 0.006126761 -0.04008364 0.01451575 0.005882203 -0.03986907 0.01482093 0.006602883 -0.0401017 0.01464664 0.006012678 -0.03996849 0.0148403 0.006341278 -0.04004883 0.0148366 0.006172776 -0.03988009 0.01493149 0.006420314 -0.0399692 0.01499247 0.006700634 -0.03996759 0.01444607 0.006033539 -0.03293633 0.01487255 0.006767153 -0.03293454 0.01362472 0.006031394 -0.03293508 0.0132113 0.006743848 -0.0329343 0.0136227 0.007457554 -0.03293544 0.01447278 0.00745958 -0.0329343 0.01447576 0.005981385 -0.0322166 0.0135951 0.005979478 -0.03221619 0.01447498 0.007510721 -0.03221619 0.01491636 0.006742298 -0.03221672 0.01359218 0.007509231 -0.03221595 0.0131523 0.00674349 -0.03221642 0.01249086 0.005692183 -0.03220498 0.01304906 0.005159795 -0.03220498 0.01387971 0.004873633 -0.03220498 0.01221954 0.006330609 -0.03220498 0.01218372 0.00697714 -0.03220498 0.01471668 0.005008995 -0.03220498 0.01527971 0.005357205 -0.03220498 0.01249802 0.007831394 -0.03220498 0.01570343 0.005906641 -0.03220498 0.01321178 0.008420705 -0.03220498 0.01588177 0.006513714 -0.03220498 0.01388132 0.008602917 -0.03220498 0.01584321 0.00723803 -0.03220498 0.01472187 0.008494555 -0.03220498 0.01544493 0.007969319 -0.03220498 0.0121712 0.006759822 -0.034105 0.01233345 0.007529616 -0.034105 0.01284664 0.00818485 -0.034105 0.01358759 0.00856477 -0.034105 0.01440501 0.008574128 -0.034105 0.01524621 0.008188247 -0.034105 0.01575225 0.007468879 -0.034105 0.01589632 0.006852686 -0.034105 0.01579785 0.006119608 -0.034105 0.01541173 0.005487978 -0.034105 0.01473557 0.005002617 -0.034105 0.01367735 0.004897117 -0.034105 0.01284664 0.005305349 -0.034105 0.012326 0.005973875 -0.034105 0.00668919 0.006783425 -0.03440499 0.006667852 0.006650984 -0.034105 0.006583988 0.007177293 -0.034105 0.006332099 0.007575631 -0.03440499 0.006189525 0.007687985 -0.034105 0.005723237 0.0078637 -0.03440499 0.005516111 0.007883846 -0.034105 0.00521928 0.007834494 -0.03440499 0.004825055 0.007650852 -0.034105 0.004711568 0.007535517 -0.03440499 0.004415392 0.006981074 -0.034105 0.004452347 0.007069826 -0.03440499 0.004415392 0.006509184 -0.03440499 0.004474043 0.006338477 -0.034105 0.004825055 0.005839407 -0.03440499 0.004817962 0.005860507 -0.034105 0.005525767 0.005590617 -0.034105 0.005516111 0.005606353 -0.03440499 0.006060838 0.005739986 -0.03440499 0.006148934 0.005794942 -0.034105 0.006463348 0.00608921 -0.03440499 0.006489336 0.006128907 -0.034105 0.003211438 0.007214903 -0.03440499 0.003357708 0.007643878 -0.034105 0.003564059 0.008039951 -0.03440499 0.003822445 0.008388876 -0.034105 0.004167675 0.008679986 -0.03440499 0.004655182 0.008936583 -0.034105 0.004970967 0.00903505 -0.03440499 0.005653679 0.009117782 -0.034105 0.005848824 0.009093642 -0.03440499 0.00650382 0.008891701 -0.034105 0.006609678 0.008840739 -0.03440499 0.007175922 0.008454501 -0.034105 0.007229387 0.008397519 -0.03440499 0.007658481 0.007767617 -0.034105 0.007692396 0.007698476 -0.03440499 0.007891476 0.006980895 -0.034105 0.007906913 0.006804287 -0.03440499 0.007822453 0.006180942 -0.034105 0.007737278 0.005900502 -0.03440499 0.007532298 0.005477786 -0.034105 0.007171452 0.005010366 -0.03440499 0.006676673 0.004649162 -0.034105 0.006024479 0.004422068 -0.03440499 0.005416989 0.004375696 -0.034105 0.005085825 0.004429876 -0.03440499 0.004296541 0.004718005 -0.034105 0.004213929 0.004772841 -0.03440499 0.003514707 0.005510389 -0.034105 0.003529906 0.005497872 -0.03440499 0.003224253 0.006258964 -0.03440499 0.003151953 0.006666183 -0.034105 0.006667852 -0.001848936 -0.034105 0.006533801 -0.001189172 -0.034105 0.006546854 -0.001225769 -0.03440499 0.006024718 -7.16842e-4 -0.03440499 0.006060838 -7.49701e-4 -0.034105 0.00560075 -6.24458e-4 -0.034105 0.005271494 -6.4119e-4 -0.03440499 0.005102336 -7.04079e-4 -0.034105 0.004652559 -0.001026391 -0.03440499 0.004692316 -9.98883e-4 -0.034105 0.004415392 -0.001518845 -0.034105 0.004401147 -0.001650631 -0.03440499 0.004530668 -0.002323865 -0.034105 0.004558145 -0.002363026 -0.03440499 0.005214452 -0.002860188 -0.034105 0.005232632 -0.002865314 -0.03440499 0.005951702 -0.002815842 -0.034105 0.005987286 -0.002803087 -0.03440499 0.006461441 -0.002420663 -0.034105 0.006444931 -0.002432405 -0.03440499 0.006669104 -0.0018875 -0.03440499 0.003255307 -0.001093387 -0.03440499 0.003265619 -0.001074671 -0.034105 0.00368005 -2.9869e-4 -0.034105 0.003702819 -2.70187e-4 -0.03440499 0.004285871 2.53469e-4 -0.034105 0.004318118 2.73155e-4 -0.03440499 0.005106866 5.67551e-4 -0.034105 0.005259573 5.98413e-4 -0.03440499 0.006102383 5.50378e-4 -0.034105 0.006250441 4.9966e-4 -0.03440499 0.006944715 1.36077e-4 -0.034105 0.007164001 -2.77469e-5 -0.03440499 0.007558286 -5.18622e-4 -0.034105 0.007814288 -0.001072108 -0.03440499 0.007891476 -0.001519083 -0.034105 0.007861196 -0.002184092 -0.03440499 0.007822453 -0.002319037 -0.034105 0.007532298 -0.003022193 -0.034105 0.007595658 -0.002896964 -0.03440499 0.007143199 -0.003487765 -0.03440499 0.006959915 -0.003635585 -0.034105 0.006361961 -0.003970921 -0.03440499 0.00615859 -0.004040718 -0.034105 0.005495011 -0.004116058 -0.03440499 0.005164086 -0.004090726 -0.034105 0.004467189 -0.003880679 -0.03440499 0.004338383 -0.003790676 -0.034105 0.003521621 -0.003032207 -0.034105 0.003588438 -0.003105223 -0.03440499 0.003204703 -0.002165794 -0.03440499 0.003186523 -0.001989841 -0.034105 0.006176292 -0.002304613 -0.0398491 0.005913794 -0.002659916 -0.03985506 0.005712091 -0.002593815 -0.0398547 0.006503462 -0.001903653 -0.03985506 0.006351768 -0.001928389 -0.03983795 0.00543791 -0.002733707 -0.03985476 0.00527364 -0.002612113 -0.039855 0.006482124 -0.001492917 -0.03985565 0.00633341 -0.001499235 -0.03985524 0.005016922 -0.002588212 -0.03985518 0.006197035 -0.001232564 -0.03984731 0.006329596 -0.001174628 -0.03985536 0.004810452 -0.002398788 -0.03984147 0.004738986 -0.002332925 -0.03986245 0.005892276 -9.17592e-4 -0.03985482 0.006038427 -9.06999e-4 -0.03986418 0.005627691 -7.76288e-4 -0.03986465 0.005380094 -7.91729e-4 -0.03986245 0.004952251 -9.56662e-4 -0.03411471 0.005311727 -7.97157e-4 -0.03414177 0.005676805 -7.74925e-4 -0.03415679 0.005526483 -8.26946e-4 -0.03410494 0.006369531 -0.001706302 -0.03410851 0.006009459 -8.86114e-4 -0.03417921 0.00595647 -9.63675e-4 -0.03410494 0.006340265 -0.001184999 -0.03419017 0.006253302 -0.001286208 -0.03410524 0.006495535 -0.001514613 -0.03420031 0.006503701 -0.001920223 -0.03421854 0.006276547 -0.002153992 -0.03411692 0.006411492 -0.002209007 -0.03423422 0.00593996 -0.002500891 -0.03415763 0.006196558 -0.002484798 -0.03424918 0.005782902 -0.002717196 -0.03426623 0.00543034 -0.002578854 -0.03415447 0.005223631 -0.002696454 -0.0342881 0.004980385 -0.002394676 -0.03420597 0.004847168 -0.002462029 -0.03431028 0.004612207 -0.002107203 -0.03432232 0.004707217 -0.001915454 -0.03423291 0.004552662 -0.001772522 -0.03434181 0.004792511 -0.001339495 -0.03426069 0.004619002 -0.001384794 -0.03435617 0.004849016 -0.001043438 -0.03437018 0.005245268 -9.62068e-4 -0.03428936 0.005309939 -7.87195e-4 -0.03439223 0.005712389 -9.35136e-4 -0.03431135 0.005736291 -7.92188e-4 -0.03441029 0.006127595 -9.60913e-4 -0.03442937 0.006003737 -0.001068174 -0.03429794 0.006431877 -0.001328706 -0.03444868 0.00630027 -0.001427531 -0.03432613 0.006525456 -0.001745283 -0.03446274 0.006350994 -0.001991808 -0.03437697 0.006400585 -0.002251386 -0.03448736 0.006227672 -0.002449989 -0.03448039 0.006081581 -0.002386331 -0.03439974 0.005869686 -0.002691745 -0.0345112 0.005626916 -0.002602934 -0.03442353 0.005491971 -0.002746641 -0.03452998 0.004998207 -0.002414703 -0.03445547 0.005021095 -0.002604365 -0.03454774 0.004639625 -0.002164006 -0.0345568 0.004739582 -0.001986265 -0.03445547 0.004553437 -0.001858651 -0.03458523 0.004711687 -0.001613318 -0.03449749 0.004579424 -0.001490354 -0.03460347 0.004850208 -0.001269638 -0.03451484 0.00478363 -0.00112152 -0.03461945 0.005089998 -8.71143e-4 -0.03463542 0.005185663 -0.001005411 -0.03450965 0.005394756 -7.74655e-4 -0.03464716 0.005549132 -9.1197e-4 -0.0345537 0.005716443 -7.89135e-4 -0.03464347 0.006017565 -0.001065015 -0.03457725 0.006166458 -9.91002e-4 -0.03467899 0.006418287 -0.001300811 -0.03468984 0.006332635 -0.001473724 -0.03460192 0.006523311 -0.00182414 -0.03472083 0.006348967 -0.001960635 -0.03462547 0.006379604 -0.002270221 -0.03473347 0.006206989 -0.002238929 -0.03461188 0.006065964 -0.002586364 -0.03475224 0.00588876 -0.002507209 -0.03463488 0.005733191 -0.002722203 -0.03476876 0.005393743 -0.002584457 -0.03468441 0.005297303 -0.002715468 -0.03479331 0.004891693 -0.002512216 -0.03480577 0.004972696 -0.002379775 -0.03470754 0.004619896 -0.002131938 -0.03482383 0.004731595 -0.001963734 -0.03470653 0.004539132 -0.001741111 -0.03483021 0.00473541 -0.001531362 -0.03472661 0.004658818 -0.001302063 -0.03486031 0.004949808 -0.001167297 -0.03474867 0.004881799 -0.001018643 -0.03487396 0.005188405 -8.30463e-4 -0.03488731 0.005366206 -9.29224e-4 -0.03479498 0.005551815 -7.72463e-4 -0.03490114 0.005856335 -9.76429e-4 -0.03481853 0.005912542 -8.38222e-4 -0.03492295 0.006272435 -0.001096904 -0.03493309 0.006050765 -0.001098036 -0.03479915 0.006343662 -0.001520514 -0.03485393 0.006484389 -0.00148344 -0.03495323 0.006516218 -0.001819312 -0.03496718 0.006353616 -0.001888155 -0.03484362 0.006395339 -0.002251446 -0.03498649 0.006232261 -0.002222955 -0.03488898 0.006039857 -0.002606093 -0.03500145 0.005909919 -0.002506315 -0.03490972 0.00558573 -0.002743244 -0.03502219 0.005417406 -0.002592206 -0.03493368 0.005010545 -0.002597033 -0.0350492 0.005179226 -0.002507448 -0.03491437 0.004772245 -0.002126812 -0.03497225 0.004690349 -0.002266228 -0.03506207 0.004552841 -0.001864254 -0.03508591 0.004706799 -0.001639902 -0.03499609 0.004591464 -0.001481056 -0.0350998 0.004868745 -0.001238346 -0.03501677 0.004797518 -0.00108546 -0.03512549 0.005187451 -8.27619e-4 -0.03513562 0.005074083 -0.001061558 -0.03499954 0.005578994 -9.10905e-4 -0.0350548 0.005597651 -7.70406e-4 -0.03515338 0.006000816 -8.82275e-4 -0.03517103 0.006120979 -0.001139223 -0.03508287 0.006366133 -0.001215875 -0.03519457 0.006508827 -0.001568019 -0.03520059 0.006367564 -0.001633048 -0.03510981 0.00625354 -0.00222063 -0.03513866 0.00647962 -0.00204432 -0.03522729 0.006311416 -0.002359747 -0.0352413 0.006016433 -0.002617001 -0.03525727 0.005752921 -0.002569079 -0.03516757 0.005626916 -0.002736866 -0.03527307 0.005179226 -0.002527773 -0.03519433 0.005307257 -0.00271058 -0.03528666 0.004916131 -0.002530097 -0.03530216 0.004786252 -0.00213623 -0.03522157 0.004638671 -0.002165019 -0.03532034 0.004698991 -0.001623749 -0.03524678 0.004544377 -0.001757144 -0.03533881 0.004673063 -0.001253783 -0.03535979 0.004941225 -0.001158714 -0.03527188 0.005181133 -8.28939e-4 -0.03537935 0.005358576 -9.31998e-4 -0.03529459 0.005666553 -7.70944e-4 -0.03540647 0.005731761 -9.45535e-4 -0.03531259 0.006042718 -0.001099348 -0.0353024 0.006036102 -8.99535e-4 -0.03542309 0.006425201 -0.001320064 -0.03544533 0.006344795 -0.001506745 -0.03535312 0.00652498 -0.001759469 -0.03546005 0.006305217 -0.002115845 -0.03538316 0.006419003 -0.002194344 -0.03548157 0.006135284 -0.002542078 -0.03550398 0.005926668 -0.002498209 -0.03540837 0.005665719 -0.002737879 -0.03551888 0.005555272 -0.002582311 -0.03540146 0.00517857 -0.002502977 -0.03541809 0.005180835 -0.002677679 -0.03554254 0.004849851 -0.002462387 -0.0355618 0.004814624 -0.002200603 -0.03546857 0.004670917 -0.002218842 -0.03555411 0.004578649 -0.002020359 -0.03557968 0.004696726 -0.001703798 -0.03549259 0.00456953 -0.001517474 -0.03560054 0.004899501 -0.001187682 -0.03551948 0.004791676 -0.001109182 -0.03561812 0.005122303 -8.54011e-4 -0.03563392 0.005404412 -9.23965e-4 -0.03554654 0.005505263 -7.70599e-4 -0.03565424 0.005940735 -0.001009225 -0.03557264 0.005887508 -8.3383e-4 -0.03566783 0.006173789 -0.001004219 -0.03567546 0.006274044 -0.001363813 -0.03559637 0.006390213 -0.001269578 -0.03569841 0.0065158 -0.001620471 -0.03570908 0.006376504 -0.001747846 -0.03561526 0.006474256 -0.002067983 -0.03573018 0.006257653 -0.002180218 -0.03563666 0.00635159 -0.002304315 -0.03572189 0.006111562 -0.002354562 -0.0356155 0.006145119 -0.002535939 -0.03575551 0.005665302 -0.002585768 -0.03567188 0.005736768 -0.002718746 -0.03576433 0.005362212 -0.002731561 -0.03578531 0.00525254 -0.002542972 -0.03569161 0.004864811 -0.002488613 -0.03581053 0.004935741 -0.002338707 -0.03571009 0.004705846 -0.001925408 -0.0357322 0.004606723 -0.002088725 -0.03582519 0.00454849 -0.001640975 -0.03584384 0.004801213 -0.001325428 -0.03576135 0.004710912 -0.00121659 -0.03586137 0.004917562 -9.87663e-4 -0.03587263 0.005245208 -9.63606e-4 -0.03578901 0.005213856 -8.2578e-4 -0.03589272 0.00566399 -7.66899e-4 -0.03590381 0.005783021 -9.5301e-4 -0.03579962 0.006079018 -9.37259e-4 -0.03592544 0.006168842 -0.001197814 -0.03583675 0.006329476 -0.001171112 -0.03593844 0.006366074 -0.001692473 -0.03583317 0.006500422 -0.001539707 -0.03595632 0.006343305 -0.001997768 -0.0358771 0.006477177 -0.002072215 -0.03597581 0.006076276 -0.002397239 -0.03589993 0.006193399 -0.002492308 -0.03600454 0.005841076 -0.002698957 -0.03601354 0.005598127 -0.002599954 -0.03592556 0.005426824 -0.002739727 -0.03601604 0.005207538 -0.002519071 -0.03591895 0.004871487 -0.002489924 -0.03605359 0.00482577 -0.002207636 -0.03596758 0.004631936 -0.002148747 -0.03607183 0.004697859 -0.001782894 -0.03598928 0.004545748 -0.001699805 -0.03609007 0.004788875 -0.001397371 -0.03597968 0.004670083 -0.001281261 -0.0361095 0.005013287 -0.001109719 -0.03600019 0.004951596 -9.55516e-4 -0.03612381 0.005326747 -9.54252e-4 -0.03601831 0.005485296 -7.63704e-4 -0.03615081 0.005770564 -9.45585e-4 -0.03606396 0.00574243 -7.95571e-4 -0.03614479 0.00607866 -9.23492e-4 -0.03617399 0.006089866 -0.001138687 -0.03605121 0.006310224 -0.001459896 -0.03607678 0.006355106 -0.001198649 -0.03619599 0.006526112 -0.001706182 -0.03621411 0.006362795 -0.001935005 -0.03612416 0.00641936 -0.002210736 -0.03623592 0.006202518 -0.002485811 -0.0362457 0.006219923 -0.002226829 -0.03610962 0.005812346 -0.002555191 -0.03616452 0.005858361 -0.002688765 -0.03626394 0.005528986 -0.002743244 -0.03627717 0.005437791 -0.002579867 -0.03615546 0.005188882 -0.002675294 -0.03629106 0.004930198 -0.002535223 -0.03630006 0.004910707 -0.002335488 -0.03621083 0.004666745 -0.002222239 -0.03631919 0.004692316 -0.001784086 -0.03623908 0.00454998 -0.001809835 -0.03634065 0.004581809 -0.001492083 -0.03635042 0.004844546 -0.001290738 -0.03623712 0.004723846 -0.001200139 -0.03636336 0.004945755 -9.6156e-4 -0.03637671 0.005097031 -0.001034438 -0.03628122 0.00520575 -8.21402e-4 -0.03638833 0.005539774 -9.26521e-4 -0.03627961 0.005645394 -7.68e-4 -0.03640639 0.005901694 -0.001013278 -0.03629219 0.006071805 -9.21409e-4 -0.03642481 0.006164669 -0.001218557 -0.0363146 0.006337106 -0.001177728 -0.03642427 0.006362557 -0.001599729 -0.03635835 0.006520748 -0.00168389 -0.03646111 0.006459474 -0.002117872 -0.03647804 0.006310403 -0.002085626 -0.03638154 0.006145358 -0.002533853 -0.03650224 0.006035208 -0.002426862 -0.03640246 0.005801439 -0.002708494 -0.0365144 0.005627572 -0.002592504 -0.03642332 0.005259692 -0.002709567 -0.03653901 0.005118012 -0.002489089 -0.03644859 0.004838824 -0.002458631 -0.03655397 0.004814863 -0.002176523 -0.03646957 0.004599571 -0.002068161 -0.03657388 0.004696071 -0.001814663 -0.03648746 0.004544019 -0.001738548 -0.03659021 0.004809498 -0.001324594 -0.03651177 0.004615247 -0.001398384 -0.03660452 0.004807412 -0.001082897 -0.03662252 0.005137503 -0.001025557 -0.03650462 0.005220651 -8.17156e-4 -0.03664058 0.005553066 -9.06964e-4 -0.03655356 0.005679488 -7.77352e-4 -0.03665906 0.005970239 -8.68593e-4 -0.03666961 0.00610423 -0.001127004 -0.03658246 0.006230294 -0.00106132 -0.03668308 0.006421625 -0.001319706 -0.03669625 0.00635904 -0.00163573 -0.03658485 0.006523728 -0.001695513 -0.0367127 0.006304323 -0.002122581 -0.03663343 0.006448984 -0.002129316 -0.03672367 0.006222188 -0.002465903 -0.03674858 0.005953192 -0.002478063 -0.03665727 0.005892038 -0.002670288 -0.03676515 0.005538284 -0.002585351 -0.03665333 0.005537331 -0.002744197 -0.03677767 0.005289435 -0.002705693 -0.03677147 0.005035221 -0.002435564 -0.0367031 0.00499171 -0.002583444 -0.03680258 0.004627525 -0.002162218 -0.036825 0.004740834 -0.002030909 -0.03672695 0.004554748 -0.00175935 -0.03683769 0.004725456 -0.001509904 -0.03675222 0.004611372 -0.001399695 -0.03684985 0.004997253 -0.001112282 -0.03677511 0.004766643 -0.001131534 -0.03686964 0.005032062 -9.13294e-4 -0.03688162 0.005523502 -8.98647e-4 -0.03680288 0.005347728 -7.85085e-4 -0.03689557 0.005849897 -8.11366e-4 -0.03690838 0.006146609 -0.001163244 -0.03683519 0.006302833 -0.001140356 -0.03692167 0.00645262 -0.001387774 -0.03695416 0.00636053 -0.00161904 -0.03685909 0.006516218 -0.001743376 -0.03696358 0.006308972 -0.002103805 -0.03688216 0.006471097 -0.002070665 -0.03697592 0.006218969 -0.002472341 -0.0369997 0.005919516 -0.002504646 -0.0369091 0.005870223 -0.002680122 -0.03700953 0.005513131 -0.002590656 -0.03692919 0.005540132 -0.002741098 -0.03702694 0.005053162 -0.002624332 -0.03704649 0.005050003 -0.002450704 -0.03695237 0.004646658 -0.002200067 -0.0370742 0.004766643 -0.002081811 -0.03697466 0.004697382 -0.001677393 -0.0369938 0.004549801 -0.001742482 -0.03708952 0.004606783 -0.001422762 -0.0371015 0.004834413 -0.0012995 -0.03701382 0.004823803 -0.001070499 -0.03712421 0.005009889 -9.2529e-4 -0.03711354 0.005088031 -0.001055419 -0.03700345 0.005255579 -8.06518e-4 -0.03714263 0.005591869 -9.12049e-4 -0.03705561 0.005642712 -7.76637e-4 -0.03715837 0.005994141 -8.83216e-4 -0.03717082 0.006005048 -0.00106275 -0.03707659 0.006339609 -0.001172304 -0.03719174 0.006267547 -0.001344501 -0.03709501 0.006522893 -0.001671195 -0.03721094 0.006361067 -0.001705229 -0.03708165 0.006316423 -0.002034842 -0.03710627 0.006443858 -0.002155542 -0.03722816 0.006103336 -0.002356469 -0.03711807 0.006153106 -0.002521395 -0.03724855 0.005826056 -0.002530395 -0.03714168 0.005796372 -0.002710998 -0.03726989 0.005279839 -0.002568364 -0.03719037 0.005329847 -0.002719163 -0.03728622 0.005041897 -0.002608835 -0.03729557 0.00469315 -0.002283334 -0.03731638 0.004772484 -0.00213468 -0.03722184 0.004542648 -0.001729011 -0.03734081 0.004711627 -0.001597046 -0.03724789 0.004678964 -0.001267194 -0.03735774 0.004961848 -0.00112617 -0.03727388 0.00498259 -9.3046e-4 -0.03737944 0.005461096 -9.28203e-4 -0.03727442 0.005396246 -7.8148e-4 -0.03739434 0.005791544 -7.98171e-4 -0.03741836 0.005847692 -9.88912e-4 -0.03728854 0.006196081 -0.00101304 -0.03742825 0.00615406 -0.001199901 -0.03730952 0.006335198 -0.0015316 -0.0373311 0.006479382 -0.001460015 -0.03745275 0.006516754 -0.001816689 -0.03746843 0.006314933 -0.002091467 -0.03738123 0.006421208 -0.00219655 -0.03747957 0.006165266 -0.002511799 -0.03749924 0.005967199 -0.002473652 -0.03740662 0.005792498 -0.002710521 -0.03751361 0.005484044 -0.002599954 -0.03743052 0.005414366 -0.002736091 -0.03753131 0.005026936 -0.002421379 -0.037454 0.005043983 -0.002618491 -0.03754752 0.004596948 -0.002094447 -0.0375697 0.004711806 -0.001976966 -0.03747981 0.004561126 -0.00163573 -0.03759318 0.004799723 -0.001326978 -0.03751176 0.00464946 -0.001320838 -0.03760558 0.004866242 -0.001024186 -0.03762561 0.005249083 -9.61861e-4 -0.03753888 0.005306601 -7.93527e-4 -0.03764009 0.005824387 -9.5543e-4 -0.03756654 0.005670785 -7.78116e-4 -0.03765863 0.006040275 -9.07246e-4 -0.03767526 0.006288826 -0.001364052 -0.0375967 0.006326973 -0.001169383 -0.03768664 0.006481707 -0.001474976 -0.03770196 0.006364941 -0.001875817 -0.03762096 0.006517767 -0.00178802 -0.03771603 0.006442487 -0.002150237 -0.03773516 0.006208658 -0.002255737 -0.03764098 0.006208896 -0.002474546 -0.03774929 0.005930125 -0.002659142 -0.03775542 0.005769252 -0.002573251 -0.03766721 0.005536019 -0.002741456 -0.03778111 0.005165636 -0.002671301 -0.03778958 0.005209863 -0.002530276 -0.03769385 0.004742681 -0.002354919 -0.03780996 0.004857063 -0.002250611 -0.03771537 0.004743158 -0.002006292 -0.03770041 0.004584431 -0.002005279 -0.03783059 0.004554748 -0.001621007 -0.03784328 0.004729986 -0.001504361 -0.0377525 0.004665613 -0.001289248 -0.03786027 0.004962861 -0.001146316 -0.03777325 0.004937887 -9.66253e-4 -0.03787577 0.005313456 -9.42877e-4 -0.03779208 0.005329608 -7.8809e-4 -0.03789317 0.005756139 -9.46701e-4 -0.03781372 0.00575 -7.88009e-4 -0.03791111 0.006144523 -0.001172006 -0.03783518 0.006142675 -9.7692e-4 -0.03792738 0.006379067 -0.001237869 -0.03794175 0.006366193 -0.001620888 -0.03785878 0.00652641 -0.001797378 -0.03796339 0.006324172 -0.002034246 -0.03787934 0.006364345 -0.002302825 -0.03798615 0.006042182 -0.002434551 -0.03790253 0.005913138 -0.002674281 -0.03801029 0.005586028 -0.00259006 -0.03792548 0.00544095 -0.002735078 -0.03803014 0.005086123 -0.002477705 -0.03795045 0.004990518 -0.002586722 -0.03804796 0.004680156 -0.002248585 -0.03806859 0.004740297 -0.002030611 -0.03797692 0.004560291 -0.001902163 -0.03808271 0.004711747 -0.00159806 -0.03799831 0.004560232 -0.001599907 -0.03809881 0.004694283 -0.001244783 -0.03810709 0.004869639 -0.001249969 -0.03801631 0.004882991 -0.00100857 -0.0381236 0.005155622 -0.001005649 -0.03803437 0.005315601 -7.85686e-4 -0.03814536 0.005521714 -9.21013e-4 -0.03805243 0.005920946 -8.35926e-4 -0.03817164 0.005911886 -0.001000285 -0.03807145 0.006342709 -0.001179218 -0.0381897 0.006178617 -0.001234948 -0.03806102 0.006344079 -0.001574456 -0.03808158 0.006504356 -0.0015679 -0.03820669 0.006500124 -0.001993 -0.03822225 0.006327211 -0.002037703 -0.03812885 0.006254613 -0.002429842 -0.03824079 0.006088674 -0.00238353 -0.03814923 0.005910515 -0.002672612 -0.03826087 0.005754888 -0.002553403 -0.03814232 0.005318582 -0.002559483 -0.03816521 0.005501866 -0.00274223 -0.03827726 0.005140244 -0.002668619 -0.0382936 0.004932105 -0.002332925 -0.03821039 0.004798173 -0.002418756 -0.03831064 0.004731893 -0.002000868 -0.03822833 0.004593074 -0.002054512 -0.0383321 0.004555046 -0.001663088 -0.03834152 0.004714369 -0.001594841 -0.0382483 0.00468713 -0.001245141 -0.03836381 0.004923999 -0.001187503 -0.03824818 0.004909515 -9.93326e-4 -0.03837597 0.005191862 -8.27735e-4 -0.03838634 0.005324602 -9.51424e-4 -0.03826647 0.005711734 -7.74876e-4 -0.0384112 0.005810201 -9.4956e-4 -0.03831607 0.006053745 -9.13712e-4 -0.03841888 0.006275057 -0.001342713 -0.03834503 0.006381332 -0.00124371 -0.03844022 0.006524503 -0.001672089 -0.03845959 0.006362378 -0.001796305 -0.03834044 0.006275534 -0.00212568 -0.03835946 0.006424009 -0.002180039 -0.03847777 0.006175458 -0.002509355 -0.03849703 0.005922317 -0.002510249 -0.03840851 0.005817115 -0.002699732 -0.03851634 0.005386173 -0.002582788 -0.03843545 0.005356311 -0.002731382 -0.03853863 0.004915356 -0.002522945 -0.03854757 0.004908978 -0.002327203 -0.03846079 0.004667401 -0.002230226 -0.03857076 0.004713237 -0.001902461 -0.03848361 0.004552006 -0.001830518 -0.038585 0.00472784 -0.001528918 -0.03850126 0.004581153 -0.001502454 -0.03860348 0.004741787 -0.00117135 -0.03861486 0.004956007 -0.001142501 -0.03852283 0.005059778 -8.88045e-4 -0.03863531 0.005485653 -9.04825e-4 -0.03855085 0.005440711 -7.65907e-4 -0.03864061 0.005938351 -8.50402e-4 -0.03866821 0.00609523 -0.001114308 -0.03858143 0.006396412 -0.001260876 -0.03869259 0.006362915 -0.001605272 -0.03860843 0.006522357 -0.001734077 -0.03870713 0.006300091 -0.002075135 -0.03860461 0.006468296 -0.002078115 -0.03872978 0.006121098 -0.002354443 -0.03864753 0.006248295 -0.002438008 -0.03874766 0.005893588 -0.002674579 -0.03875958 0.005741477 -0.002570748 -0.03866785 0.005554258 -0.002738237 -0.03877776 0.005187988 -0.002530455 -0.03869479 0.005109786 -0.00265181 -0.03879362 0.004724979 -0.002321243 -0.03881764 0.004827857 -0.002184629 -0.03869462 0.004577457 -0.001976668 -0.03883075 0.004718899 -0.001873612 -0.03870689 0.004550635 -0.00165373 -0.03884458 0.004743337 -0.001502275 -0.03872513 0.004654943 -0.00129652 -0.03885924 0.004937231 -0.001182019 -0.03874379 0.004906713 -9.92542e-4 -0.03887075 0.005193948 -9.99974e-4 -0.03876006 0.005340814 -7.81619e-4 -0.03889381 0.00556761 -9.2502e-4 -0.03877937 0.005833685 -8.14668e-4 -0.03890979 0.005934 -0.001015245 -0.03882265 0.006146967 -9.77275e-4 -0.03892982 0.006282985 -0.001361787 -0.03884619 0.006404757 -0.001292347 -0.03895074 0.00651127 -0.001612126 -0.03895717 0.006370484 -0.001771628 -0.0388664 0.006493687 -0.00199908 -0.03897494 0.006283462 -0.002112865 -0.03885811 0.006240487 -0.002456188 -0.03899455 0.005921185 -0.002515316 -0.03890901 0.005826652 -0.002698421 -0.03901761 0.005556583 -0.002739191 -0.03902459 0.005316972 -0.002570927 -0.0389381 0.005231916 -0.002695202 -0.0390371 0.004859328 -0.002475619 -0.03905445 0.004932761 -0.002335071 -0.03896015 0.004697918 -0.001898348 -0.038984 0.004628121 -0.002137601 -0.03907197 0.004545211 -0.00177747 -0.03908866 0.004766047 -0.001445055 -0.03898364 0.004625141 -0.001375436 -0.03910845 0.00486052 -0.001034021 -0.03911978 0.005018889 -0.001092493 -0.03902667 0.005205512 -8.24929e-4 -0.03913712 0.005523383 -9.04974e-4 -0.03905212 0.005576014 -7.69078e-4 -0.03915613 0.006056368 -9.0772e-4 -0.03917294 0.006064891 -0.001098513 -0.03908032 0.006415367 -0.001302897 -0.03919219 0.006293714 -0.00143069 -0.03907233 0.006365954 -0.001784443 -0.03909158 0.006520867 -0.001831531 -0.03921401 0.006239056 -0.002192974 -0.03911298 0.006402432 -0.002219319 -0.03923326 0.006141781 -0.002539932 -0.03925335 0.005901753 -0.002511799 -0.03915977 0.005650162 -0.002740144 -0.03926783 0.00541979 -0.00259006 -0.03918349 0.005158722 -0.002670109 -0.0392903 0.0048936 -0.002317011 -0.03921204 0.004884123 -0.002498567 -0.03930813 0.004621565 -0.002133488 -0.03932762 0.004702091 -0.001829683 -0.03923708 0.004549622 -0.001716613 -0.03933638 0.0047791 -0.001377582 -0.03925865 0.004672527 -0.001263856 -0.03936547 0.004929125 -9.8494e-4 -0.0393598 0.005092322 -0.001045405 -0.03928095 0.005117297 -8.56907e-4 -0.03938698 0.005562901 -9.05963e-4 -0.03930449 0.005549192 -7.67659e-4 -0.03940171 0.005938172 -8.5322e-4 -0.03941744 0.006004869 -0.001065075 -0.0393269 0.006227135 -0.001049995 -0.03943216 0.006264686 -0.00133562 -0.03934448 0.006440281 -0.001346588 -0.03944808 0.006376326 -0.001862585 -0.03937065 0.006516695 -0.001682341 -0.03946793 0.006476044 -0.002050399 -0.03947085 0.00607419 -0.002414464 -0.03940027 0.00630784 -0.002374827 -0.03949099 0.006062507 -0.002590119 -0.0395078 0.005660116 -0.002734541 -0.03952014 0.005562305 -0.002593696 -0.0394265 0.005200982 -0.002688705 -0.03953939 0.005044102 -0.002449154 -0.03945273 0.004810094 -0.002431452 -0.0395677 0.004742383 -0.002025544 -0.03947728 0.00457555 -0.002009451 -0.03957939 0.004712164 -0.001679897 -0.03946572 0.004562675 -0.001572191 -0.03959608 0.004699647 -0.00122404 -0.03961354 0.004818201 -0.001340448 -0.03948783 0.004877448 -0.00102812 -0.0396068 0.005082488 -0.001051366 -0.03953015 0.005100429 -8.6819e-4 -0.03963768 0.005453228 -9.18638e-4 -0.03954923 0.005519688 -7.67093e-4 -0.03965365 0.005939245 -8.54267e-4 -0.03966331 0.005990862 -0.001036107 -0.03957539 0.006222963 -0.001048505 -0.03968393 0.006346404 -0.001517593 -0.03960418 0.006418764 -0.001323521 -0.03969645 0.006509721 -0.001623153 -0.03970938 0.006344556 -0.001967489 -0.039626 0.006501972 -0.001952826 -0.03972285 0.006328225 -0.002342939 -0.03973597 0.006131708 -0.002349019 -0.03964626 0.006056368 -0.002599239 -0.03976088 0.005742907 -0.00256741 -0.0396682 0.005650222 -0.002730965 -0.0397734 0.005243718 -0.002549648 -0.0396921 0.005336046 -0.002717733 -0.03978353 0.005008757 -0.002590596 -0.03979456 0.004906177 -0.002295315 -0.03968727 0.004662811 -0.002216994 -0.03981828 0.004720628 -0.001942515 -0.03973162 0.004564762 -0.001929461 -0.03984534 0.004717707 -0.001560091 -0.03974992 0.004581272 -0.001499414 -0.03985863 0.004975795 -0.001121938 -0.0397734 0.00526309 -9.67239e-4 -0.03975892 0.00579071 -9.5115e-4 -0.03981572 0.005878329 -0.002520799 -0.03410571 0.004921793 -0.002344846 -0.03415644 0.004694402 -0.001816749 -0.0341854 0.004780769 -0.001396715 -0.03420561 0.005075156 -0.001042902 -0.03422802 0.005567967 -9.16883e-4 -0.03425204 0.006371796 -0.001708507 -0.03431099 0.00630182 -0.002089262 -0.03432965 0.006005644 -0.002459824 -0.0343526 0.00543797 -0.002595961 -0.03438001 0.004966676 -0.00237447 -0.03440511 0.004712879 -0.001555502 -0.03444802 0.004956185 -0.001149654 -0.03447037 0.005653083 -9.16648e-4 -0.03450608 0.006204843 -0.001224219 -0.03453701 0.006376862 -0.001801609 -0.03456532 0.005387485 -0.002595782 -0.03463304 0.004869997 -0.002274692 -0.03466206 0.005170106 -9.99059e-4 -0.03473269 0.005588591 -9.16923e-4 -0.03475344 0.006296634 -0.001389265 -0.0347957 0.006102859 -0.002389609 -0.03484684 0.005617201 -0.00258851 -0.03487199 0.004871129 -0.002277076 -0.03491204 0.004703164 -0.001846849 -0.03493356 0.004755437 -0.001439809 -0.03495371 0.005525648 -9.07026e-4 -0.0350008 0.006025195 -0.001071751 -0.03502547 0.006304144 -0.001419603 -0.03504663 0.006371557 -0.001820981 -0.0350663 0.006175935 -0.002313137 -0.03509223 0.005679786 -0.002585053 -0.03511875 0.005202353 -0.002527296 -0.03514188 0.004800379 -0.002177655 -0.03516727 0.004699647 -0.001692593 -0.03519105 0.004818141 -0.001324355 -0.03520989 0.005099475 -0.001035273 -0.03522896 0.005613923 -9.11717e-4 -0.03525447 0.006272554 -0.001360058 -0.03529351 0.006370902 -0.001700937 -0.0353108 0.006305396 -0.002082526 -0.0353291 0.006020784 -0.00244832 -0.03535181 0.004776239 -0.002141475 -0.03541952 0.004712343 -0.001582145 -0.03544628 0.004974782 -0.001117706 -0.03547257 0.005523025 -9.08785e-4 -0.03549998 0.00607264 -0.001099169 -0.0355286 0.006344497 -0.001532495 -0.03555244 0.006347715 -0.00196892 -0.03557348 0.005821108 -0.002542018 -0.03561168 0.005425214 -0.002586841 -0.03563106 0.004969596 -0.002383947 -0.03565508 0.00472927 -0.00197941 -0.03567719 0.004729926 -0.001483678 -0.03570091 0.005085349 -0.001041889 -0.03572815 0.005583941 -9.12388e-4 -0.0357536 0.0062415 -0.001295328 -0.0357905 0.006223738 -0.002252042 -0.03583818 0.005743503 -0.002572715 -0.03586608 0.004951119 -0.002353429 -0.03590637 0.004694044 -0.001895844 -0.03593146 0.00570631 -9.32304e-4 -0.03600883 0.006366252 -0.001837193 -0.03606694 0.005904436 -0.002508461 -0.03610742 0.005129575 -0.002483367 -0.03614574 0.004785835 -0.002157628 -0.03616857 0.004705309 -0.001641929 -0.03619366 0.005198955 -9.88539e-4 -0.03623408 0.006347715 -0.001540064 -0.03630316 0.006306052 -0.002125024 -0.03633087 0.005861639 -0.002531647 -0.03635972 0.005457699 -0.002586781 -0.03637933 0.005068898 -0.002454459 -0.036399 0.00475502 -0.002076208 -0.03642296 0.004733622 -0.001458108 -0.03645223 0.0056988 -9.20671e-4 -0.03650957 0.006216049 -0.001250922 -0.03653782 0.006301522 -0.002090513 -0.03657954 0.00597608 -0.002482533 -0.03660356 0.005122363 -0.00249195 -0.03664582 0.004805743 -0.002164125 -0.03666764 0.004693984 -0.001767098 -0.03668761 0.00481534 -0.001322686 -0.03670984 0.005146205 -0.00100845 -0.03673195 0.005684614 -9.1966e-4 -0.03675746 0.006177067 -0.001205921 -0.036785 0.006384909 -0.00175172 -0.03681331 0.006155371 -0.002336263 -0.03684318 0.005694448 -0.002577722 -0.03686785 0.005301117 -0.00255984 -0.03688699 0.004964113 -0.002365946 -0.0369054 0.004711568 -0.00195688 -0.03692877 0.004766166 -0.001412212 -0.03695505 0.005392014 -9.31817e-4 -0.0369938 0.00581634 -9.57959e-4 -0.03701412 0.00623387 -0.001282691 -0.03703945 0.005469441 -0.00259447 -0.0371291 0.00506699 -0.002447247 -0.03714901 0.004783928 -0.002137422 -0.03717011 0.004708051 -0.001546561 -0.03719747 0.005038797 -0.001075625 -0.03722542 0.006355047 -0.00196588 -0.03732299 0.006089031 -0.002384483 -0.03734683 0.005759656 -0.002561032 -0.03736495 0.005264282 -0.002559483 -0.03738933 0.004814326 -0.002194464 -0.03741639 0.004695832 -0.001721978 -0.03743976 0.004853546 -0.001255691 -0.0374633 0.005236685 -9.70758e-4 -0.03748619 0.005730926 -9.32339e-4 -0.03751057 0.006204843 -0.001237034 -0.03753709 0.006379604 -0.001758933 -0.03756326 0.006170511 -0.002323806 -0.03759229 0.005648255 -0.002589404 -0.03762054 0.005080997 -0.002475023 -0.03764843 0.004706799 -0.001591324 -0.03769594 0.005016088 -0.001080274 -0.03772526 0.005639076 -9.10349e-4 -0.03775513 0.006218373 -0.001241087 -0.03778779 0.006372809 -0.001770615 -0.03781378 0.006209611 -0.002275407 -0.03783935 0.005748629 -0.002566277 -0.03786528 0.005341768 -0.002570807 -0.03788495 0.004895508 -0.002312183 -0.0379098 0.004691839 -0.001782894 -0.03793716 0.004847645 -0.001262664 -0.03796279 0.005281805 -9.50988e-4 -0.03798872 0.005799293 -9.52727e-4 -0.03801333 0.00636357 -0.001894772 -0.03806984 0.006153643 -0.002329885 -0.03809303 0.005029916 -0.002429127 -0.03815156 0.004714906 -0.001973688 -0.03817796 0.004759728 -0.001428425 -0.03820401 0.005887985 -9.81569e-4 -0.0382682 0.006281137 -0.001366317 -0.03829395 0.005977988 -0.002481222 -0.0383535 0.00542736 -0.002589344 -0.03838098 0.004906833 -0.002331674 -0.03840953 0.004691302 -0.001767635 -0.03843748 0.004851996 -0.00125879 -0.03846305 0.005214035 -9.81569e-4 -0.03848522 0.005613803 -9.20176e-4 -0.03850436 0.005999505 -0.001055419 -0.03852391 0.006253898 -0.001330673 -0.03854191 0.006376862 -0.001700997 -0.03856056 0.00597459 -0.002477705 -0.03860473 0.005449652 -0.002593696 -0.03862971 0.005059123 -0.002440869 -0.03864967 0.006102561 -0.00112152 -0.03877955 0.006370842 -0.001637578 -0.03880834 0.00599569 -0.002459049 -0.03885251 0.005447268 -0.002601504 -0.03888034 0.00491774 -0.002331435 -0.03890818 0.004707276 -0.001890957 -0.03893184 0.00489813 -0.001208603 -0.03896629 0.005224347 -9.77174e-4 -0.03898537 0.005656421 -9.20985e-4 -0.03900671 0.006090164 -0.00112313 -0.03902971 0.00600773 -0.002453148 -0.03910189 0.005652725 -0.00257951 -0.03911995 0.005282938 -0.002556502 -0.03913801 0.004941046 -0.002343952 -0.03915709 0.004743576 -0.00202459 -0.03917497 0.004705965 -0.001601636 -0.03919541 0.004972159 -0.001122415 -0.03922188 0.005380809 -9.34264e-4 -0.03924292 0.005827069 -9.60665e-4 -0.03926527 0.006269216 -0.001330971 -0.03929227 0.006367921 -0.001907408 -0.03932088 0.006115913 -0.00236386 -0.03934538 0.005731761 -0.00256884 -0.03936636 0.005240797 -0.002550005 -0.03938966 0.004787266 -0.002155661 -0.03941828 0.005081772 -0.001040875 -0.03947854 0.00558573 -9.14805e-4 -0.03950339 0.006063222 -0.001095056 -0.03952753 0.006337881 -0.001506268 -0.03955119 0.006332099 -0.002050578 -0.03957742 0.005976319 -0.00247091 -0.03960388 0.00540632 -0.002599 -0.03963166 0.004703104 -0.00190562 -0.03968191 0.004806756 -0.001317739 -0.03970956 0.0056957 -9.29481e-4 -0.0397582 0.006059825 -0.00110346 -0.03977769 0.006326496 -0.00145781 -0.03979957 0.004546046 -0.0017879 -0.03410583 0.005338728 -0.002639651 -0.03410512 0.004835963 -0.002363801 -0.03410542 0.004668056 -0.001290977 -0.03411436 0.004735767 -0.002331554 -0.03458046 0.005933523 -8.53528e-4 -0.0346837 0.005353152 -0.002720832 -0.03505009 0.004857361 -0.001043498 -0.03538727 0.006291747 -0.001124858 -0.0354526 0.00526297 -0.002702593 -0.03605407 0.00522232 -8.21494e-4 -0.03615432 0.006420612 -0.00132519 -0.036462 0.006129026 -9.67091e-4 -0.03694295 0.004787027 -0.002397298 -0.03757655 0.006482779 -0.001495063 -0.03796935 0.006506502 -0.001893043 -0.03848558 0.006222367 -0.001055896 -0.03869819 0.006495177 -0.00154227 -0.03922176 0.006388366 -0.00165975 -0.0400756 0.006497025 -0.001749634 -0.03995114 0.00644809 -0.001491844 -0.03997951 0.006233453 -0.001168847 -0.04003721 0.006144165 -0.001230001 -0.0400983 0.006309449 -0.001174509 -0.03994435 0.005971968 -0.00104922 -0.04008591 0.005652964 -9.69717e-4 -0.04010111 0.005919516 -9.22352e-4 -0.04002404 0.005671024 -8.52733e-4 -0.04002839 0.005821645 -8.33744e-4 -0.039936 0.005091905 -0.001081109 -0.04009836 0.005424261 -9.06654e-4 -0.04007381 0.005421817 -8.34246e-4 -0.04000878 0.005306482 -8.16835e-4 -0.0399416 0.005133092 -9.38095e-4 -0.04002946 0.005074679 -8.86142e-4 -0.03986358 0.004860818 -0.001109898 -0.04000943 0.004889249 -0.001282989 -0.04010015 0.004778027 -0.001118659 -0.03985631 0.004777729 -0.0015468 -0.04010182 0.004693806 -0.001382887 -0.04002076 0.004636764 -0.001642823 -0.04003721 0.004857718 -0.002201318 -0.0400989 0.004674017 -0.001967549 -0.04005879 0.00456804 -0.001820683 -0.03993695 0.005247652 -0.00246948 -0.04010421 0.004682898 -0.002190291 -0.0399664 0.004912257 -0.002459764 -0.0399968 0.005173623 -0.002562344 -0.04005783 0.005400717 -0.002608478 -0.04007023 0.005111753 -0.0026201 -0.03994464 0.005414307 -0.002706706 -0.03996366 0.00576961 -0.002519369 -0.04009997 0.005749583 -0.002620697 -0.04004681 0.005720317 -0.002698123 -0.03995198 0.006162941 -0.002207636 -0.04010337 0.006097197 -0.002420723 -0.04006689 0.005947589 -0.002615451 -0.03996872 0.006206452 -0.002424478 -0.03998148 0.00612992 -0.002538502 -0.03986501 0.006356 -0.002056837 -0.04006439 0.006327271 -0.001686394 -0.04010319 0.006435334 -0.002096772 -0.03996157 0.006388425 -0.002244055 -0.03985756 0.005947649 -0.00246632 -0.03293645 0.006371378 -0.00173074 -0.03293567 0.00512439 -0.002469062 -0.0329343 0.004711866 -0.001756131 -0.03293508 0.005122423 -0.001041948 -0.03293466 0.005972743 -0.001040339 -0.0329343 0.005977749 -0.002518773 -0.03221625 0.005095183 -0.002520322 -0.03221642 0.005974888 -9.89393e-4 -0.03221642 0.006415426 -0.001756191 -0.03221684 0.005092263 -9.90857e-4 -0.03221619 0.004651963 -0.001756489 -0.03221595 0.004298448 -0.003156304 -0.03220498 0.004941284 -0.003522753 -0.03220498 0.005581736 -0.003617525 -0.03220498 0.003817737 -0.002495169 -0.03220498 0.003937005 -7.95397e-4 -0.03220498 0.003665208 -0.001583039 -0.03220498 0.006348907 -0.003444314 -0.03220498 0.007035195 -0.002872049 -0.03220498 0.004431307 -2.4514e-4 -0.03220498 0.007367372 -0.002125203 -0.03220498 0.005031466 3.58018e-5 -0.03220498 0.005674958 1.09083e-4 -0.03220498 0.007331132 -0.001200854 -0.03220498 0.006330013 -7.13691e-5 -0.03220498 0.006861388 -4.40607e-4 -0.03220498 0.003711044 -0.001371085 -0.034105 0.004073202 -5.69254e-4 -0.034105 0.004908621 1.11902e-5 -0.034105 0.005954861 8.33686e-5 -0.034105 0.006732404 -3.28155e-4 -0.034105 0.007201731 -9.00522e-4 -0.034105 0.007405519 -0.001739799 -0.034105 0.00728327 -0.00239104 -0.034105 0.006967127 -0.00295633 -0.034105 0.006179571 -0.003525078 -0.034105 0.005210697 -0.00359559 -0.034105 0.004536271 -0.00332868 -0.034105 0.004028081 -0.002856731 -0.034105 0.003700911 -0.00212562 -0.034105 0.01508516 -0.001291394 -0.034105 0.01504236 -0.001228153 -0.03440499 0.01455193 -7.26363e-4 -0.03440499 0.01465833 -8.07033e-4 -0.034105 0.01401603 -6.04049e-4 -0.034105 0.01377147 -6.41189e-4 -0.03440499 0.01326161 -9.07212e-4 -0.034105 0.01323676 -9.49269e-4 -0.03440499 0.01293385 -0.001454651 -0.03440499 0.01289778 -0.001602768 -0.034105 0.01293838 -0.002043545 -0.03440499 0.01303064 -0.002291381 -0.034105 0.01326161 -0.002602458 -0.03440499 0.01338994 -0.002685248 -0.034105 0.01385676 -0.002877175 -0.034105 0.01376515 -0.002851068 -0.03440499 0.01428973 -0.002869665 -0.03440499 0.01450639 -0.002798974 -0.034105 0.01482778 -0.002567291 -0.03440499 0.01498931 -0.002371013 -0.034105 0.01517391 -0.001945972 -0.03440499 0.01515763 -0.001904606 -0.034105 0.01167029 -0.001872897 -0.034105 0.01182264 -8.65547e-4 -0.03440499 0.01182669 -9.08355e-4 -0.034105 0.01248759 5.93076e-5 -0.034105 0.01261723 1.49067e-4 -0.03440499 0.01354813 5.59669e-4 -0.034105 0.01358515 5.67149e-4 -0.03440499 0.01473873 5.25717e-4 -0.034105 0.01438665 5.76321e-4 -0.03440499 0.01511317 3.4767e-4 -0.03440499 0.01572757 -1.04231e-4 -0.034105 0.01589006 -2.75684e-4 -0.03440499 0.01620411 -8.20434e-4 -0.034105 0.01628714 -0.001060247 -0.03440499 0.01641017 -0.001814007 -0.034105 0.01640027 -0.001872897 -0.03440499 0.0161252 -0.002871155 -0.03440499 0.01605516 -0.003011822 -0.034105 0.01556515 -0.003549695 -0.03440499 0.01539605 -0.003677785 -0.034105 0.01491534 -0.003946304 -0.03440499 0.01473206 -0.004013776 -0.034105 0.01387679 -0.004128634 -0.03440499 0.01370048 -0.004105091 -0.034105 0.0127139 -0.003727078 -0.03440499 0.01255083 -0.003616273 -0.034105 0.01202988 -0.003002047 -0.03440499 0.01189953 -0.002762615 -0.034105 0.01169091 -0.002108156 -0.03440499 0.01462334 -0.002352654 -0.03985071 0.01497811 -0.002052962 -0.03985971 0.01484626 -0.001965582 -0.03984516 0.01422125 -0.002590298 -0.0398547 0.0137881 -0.002616286 -0.03985506 0.01479476 -0.001370549 -0.03985327 0.01492577 -0.001348674 -0.039855 0.01329922 -0.002391755 -0.03984773 0.01446151 -0.0010221 -0.03984057 0.01313018 -0.00212264 -0.03984797 0.01409399 -7.83384e-4 -0.03986465 0.01306653 -0.00192666 -0.03985387 0.01370936 -8.29095e-4 -0.03985929 0.01329499 -0.001104891 -0.03985345 0.01330143 -0.001098752 -0.03410911 0.0135014 -9.24321e-4 -0.03412109 0.0138396 -7.92081e-4 -0.03414225 0.0142048 -7.81566e-4 -0.03415632 0.01402646 -8.26949e-4 -0.03410494 0.01486951 -0.001706361 -0.03410851 0.01450443 -8.86583e-4 -0.0341764 0.01446962 -9.70938e-4 -0.03410488 0.01476627 -0.001100599 -0.03418737 0.01495814 -0.001394093 -0.03419995 0.01475727 -0.001295089 -0.03410524 0.01501744 -0.001678466 -0.03419339 0.01482248 -0.002024412 -0.03411585 0.0149157 -0.002196073 -0.03421676 0.01464551 -0.002324998 -0.0341227 0.01452177 -0.00262165 -0.03425687 0.01427006 -0.00255692 -0.03416693 0.01408922 -0.002744674 -0.03427314 0.01380151 -0.002570152 -0.03418874 0.0137192 -0.002688646 -0.03428882 0.01336628 -0.002480447 -0.03430891 0.01332849 -0.002221226 -0.03421741 0.01316499 -0.002227008 -0.03431302 0.01319521 -0.001714527 -0.03424215 0.01305133 -0.001811861 -0.03433686 0.01311337 -0.001395642 -0.03435516 0.0133019 -0.001371979 -0.03423339 0.01332569 -0.001073122 -0.03437149 0.01350635 -0.00111401 -0.03425049 0.01371133 -8.15598e-4 -0.03438884 0.01400321 -9.08519e-4 -0.03430163 0.01418775 -7.79833e-4 -0.03440767 0.01453459 -0.001087903 -0.03429681 0.01466798 -9.86239e-4 -0.0344277 0.01471352 -0.001253664 -0.0343402 0.01497727 -0.001449704 -0.0344516 0.01487582 -0.001721739 -0.03436362 0.01500952 -0.001908302 -0.03447282 0.01473033 -0.002241253 -0.03439009 0.01486086 -0.002298951 -0.03448271 0.0145967 -0.002566516 -0.0345056 0.014256 -0.002556741 -0.03439307 0.01419967 -0.002728939 -0.03451871 0.01378804 -0.00255531 -0.03444004 0.01375526 -0.002705752 -0.034536 0.01344811 -0.002340257 -0.03443437 0.01345616 -0.002560257 -0.03455322 0.0131579 -0.002211153 -0.03457093 0.0132541 -0.002039909 -0.03444749 0.01304566 -0.001750648 -0.03459352 0.01319825 -0.001680076 -0.03449422 0.0131691 -0.001271009 -0.03460502 0.01331502 -0.001333475 -0.03451168 0.01362705 -0.001013219 -0.03453266 0.01350945 -9.16064e-4 -0.03463137 0.01395779 -7.69597e-4 -0.03464686 0.01402539 -9.26674e-4 -0.03452867 0.01433527 -8.16247e-4 -0.03466379 0.01452273 -0.00105983 -0.03457719 0.01466476 -9.90288e-4 -0.03468376 0.01493513 -0.001350522 -0.03470057 0.01484102 -0.001510858 -0.03460413 0.01502531 -0.001694142 -0.03471136 0.01485186 -0.00194323 -0.03462457 0.01498579 -0.002025723 -0.03472095 0.01465153 -0.002307653 -0.03461658 0.01480269 -0.002368092 -0.03474199 0.01454144 -0.002602398 -0.03475546 0.01439034 -0.002519547 -0.03466075 0.01418936 -0.002727091 -0.03476816 0.01391291 -0.002575039 -0.03465878 0.01386451 -0.002723276 -0.03478336 0.01355117 -0.002616047 -0.03479903 0.01351839 -0.002405405 -0.03467726 0.0132277 -0.002323031 -0.0348199 0.01329046 -0.00211203 -0.03469759 0.01311177 -0.002083003 -0.03481 0.01320487 -0.001737236 -0.0347135 0.01303994 -0.001744389 -0.03484153 0.01327842 -0.001427233 -0.03473174 0.01315611 -0.001314759 -0.03486186 0.01345729 -0.001158893 -0.03474622 0.01335 -0.001047611 -0.03487098 0.01364493 -8.48295e-4 -0.03488075 0.01376008 -9.77105e-4 -0.03476464 0.01410657 -9.28643e-4 -0.03478151 0.01417911 -7.75967e-4 -0.03490185 0.01460123 -0.001124024 -0.03483188 0.0146678 -9.88332e-4 -0.03492707 0.01493108 -0.001339733 -0.0349493 0.01487785 -0.001653671 -0.0348609 0.01502043 -0.001717686 -0.03496247 0.01496219 -0.002086102 -0.03498178 0.014723 -0.002227306 -0.03485947 0.01478344 -0.002398908 -0.03499162 0.0144813 -0.002480685 -0.03490543 0.01441746 -0.002669394 -0.03501439 0.01405549 -0.00273931 -0.03500998 0.0138942 -0.002574563 -0.03491002 0.01380473 -0.002721011 -0.0350387 0.01351189 -0.002413034 -0.03495442 0.01337349 -0.002489507 -0.03505522 0.01326924 -0.002090692 -0.03497397 0.01312601 -0.002144694 -0.03507667 0.01319772 -0.001730382 -0.0349918 0.0130499 -0.001646041 -0.03509616 0.01334577 -0.001263082 -0.03501528 0.01321369 -0.001199722 -0.03511434 0.01344192 -9.59965e-4 -0.0351265 0.01381641 -9.49644e-4 -0.03500956 0.01387685 -7.75426e-4 -0.03514319 0.01404511 -9.13196e-4 -0.03505313 0.01430702 -8.06756e-4 -0.03516173 0.01458048 -0.001100718 -0.03508049 0.01460504 -9.56287e-4 -0.03517675 0.01490247 -0.001265168 -0.03519004 0.01485109 -0.001561343 -0.03510612 0.01502239 -0.00173217 -0.03521412 0.01482534 -0.002059519 -0.03513026 0.01493275 -0.002173483 -0.03523522 0.0146172 -0.002555787 -0.03524857 0.01451551 -0.002441823 -0.03515404 0.01413655 -0.002587556 -0.03517282 0.01421689 -0.002724885 -0.03526788 0.01371324 -0.002691566 -0.03528809 0.01382434 -0.002553284 -0.03516227 0.0134871 -0.002390742 -0.03520596 0.01334917 -0.002464354 -0.0353049 0.01324748 -0.002016186 -0.03519928 0.01310086 -0.002083718 -0.03532648 0.01319521 -0.001749098 -0.03524047 0.01307016 -0.001504361 -0.03535336 0.01333171 -0.001312255 -0.03523987 0.01322937 -0.001175582 -0.03536343 0.01364558 -9.94075e-4 -0.03528398 0.01355445 -8.94028e-4 -0.03537714 0.01389825 -7.78951e-4 -0.03539603 0.01423424 -9.47922e-4 -0.03528803 0.01422303 -7.8996e-4 -0.03541177 0.01461231 -9.50116e-4 -0.03542232 0.01460969 -0.001156866 -0.03530853 0.01487618 -0.001236915 -0.03544312 0.01483684 -0.001514256 -0.03535425 0.0150128 -0.001615703 -0.03546285 0.01485782 -0.001932919 -0.03537368 0.01495611 -0.002133667 -0.03547871 0.0146808 -0.002282738 -0.03539305 0.01463043 -0.002541184 -0.03550332 0.01439702 -0.00251317 -0.03540992 0.0142042 -0.002734959 -0.03551328 0.01398235 -0.002590954 -0.03543066 0.01383775 -0.002724945 -0.03553575 0.0135079 -0.002419769 -0.03545445 0.0134378 -0.002545356 -0.03555637 0.01315945 -0.002204418 -0.03556954 0.01319283 -0.001877129 -0.03548544 0.01304292 -0.00175935 -0.03559255 0.01312911 -0.001368343 -0.03560203 0.0133028 -0.001345038 -0.03551059 0.01340007 -9.94478e-4 -0.03562122 0.01363408 -0.001013219 -0.03553336 0.01375913 -8.05999e-4 -0.0356425 0.01414364 -9.18359e-4 -0.0355578 0.01416617 -7.79477e-4 -0.03565967 0.01448899 -8.79673e-4 -0.03566807 0.01461052 -0.001152753 -0.0355612 0.0148006 -0.001129865 -0.03568476 0.01486688 -0.001594662 -0.03560769 0.01497024 -0.001433134 -0.03570419 0.0150178 -0.001826286 -0.03571999 0.01482397 -0.002009689 -0.03560155 0.01494097 -0.002134144 -0.03572833 0.01475489 -0.002429902 -0.03574335 0.0146088 -0.002354204 -0.03562432 0.01445513 -0.002646267 -0.03576296 0.01437163 -0.002513229 -0.03563231 0.01402395 -0.002747595 -0.03577923 0.0139873 -0.002581 -0.03565639 0.01382803 -0.002715826 -0.03576946 0.0135886 -0.002465128 -0.03570073 0.01349472 -0.002582252 -0.03579854 0.01335597 -0.002233505 -0.03568738 0.01326268 -0.00237298 -0.03581291 0.01309961 -0.002070188 -0.03582644 0.01319861 -0.001818835 -0.03573757 0.01304727 -0.001712858 -0.03584736 0.01326006 -0.00144577 -0.03575557 0.01316702 -0.001284956 -0.03585648 0.01345682 -0.001146018 -0.0357728 0.01345479 -9.54199e-4 -0.03588026 0.01396197 -9.0486e-4 -0.0357998 0.0138204 -7.91317e-4 -0.03589475 0.01418071 -7.68309e-4 -0.03590625 0.01451838 -0.001079142 -0.03580433 0.01461279 -9.5569e-4 -0.03592693 0.0148639 -0.001218259 -0.03594076 0.01476931 -0.001370549 -0.03581982 0.01499909 -0.001538872 -0.03595179 0.01487272 -0.001726031 -0.03586399 0.01499736 -0.001970529 -0.03597652 0.01478719 -0.002126276 -0.03588366 0.01478976 -0.002403676 -0.0359857 0.01449978 -0.002456665 -0.03590512 0.01446586 -0.002645671 -0.0360105 0.01399207 -0.00260055 -0.03592985 0.01398897 -0.002746164 -0.0360291 0.01356488 -0.00262022 -0.03605228 0.01355618 -0.0024392 -0.03595232 0.01329863 -0.002410352 -0.03605896 0.01325505 -0.002087473 -0.0359745 0.01313048 -0.002145171 -0.0360741 0.01304614 -0.001752376 -0.03608918 0.01322466 -0.001516997 -0.03600156 0.01317048 -0.001264452 -0.03611248 0.01343911 -9.61965e-4 -0.03612488 0.01348495 -0.001134932 -0.03599864 0.01389926 -9.18894e-4 -0.03604638 0.01390147 -7.71758e-4 -0.03614002 0.01420134 -9.39342e-4 -0.03603047 0.01434189 -8.16315e-4 -0.0361641 0.01464664 -0.001173973 -0.03608494 0.01471823 -0.0010342 -0.03618961 0.01495158 -0.001385092 -0.03619563 0.01487404 -0.001652896 -0.03611063 0.01501804 -0.001772344 -0.03621339 0.01476687 -0.002144813 -0.036107 0.01496368 -0.002091348 -0.03622841 0.01475739 -0.002425074 -0.03624206 0.01452815 -0.002441525 -0.03615278 0.0144996 -0.002626001 -0.03626227 0.01412439 -0.002585291 -0.03617388 0.01416021 -0.002731502 -0.03627276 0.01379853 -0.002711415 -0.03628641 0.01371365 -0.00253278 -0.0361936 0.01347303 -0.002563416 -0.03630113 0.01348084 -0.002376675 -0.0361759 0.01321989 -0.002315461 -0.03631848 0.01306217 -0.001957535 -0.0363295 0.01321041 -0.001924753 -0.0362327 0.01306891 -0.001546621 -0.03634852 0.0132395 -0.001493096 -0.03625297 0.01323902 -0.001161754 -0.0363596 0.01343834 -0.001170098 -0.03627133 0.01372069 -9.91662e-4 -0.03626018 0.0136041 -8.67767e-4 -0.03638243 0.01407372 -9.24913e-4 -0.0362792 0.01398539 -7.6671e-4 -0.03640061 0.01443862 -8.51863e-4 -0.03641694 0.01453542 -0.001066625 -0.03632819 0.01471322 -0.001036345 -0.0364378 0.0149371 -0.001362621 -0.03644359 0.01481783 -0.00146389 -0.03635144 0.01502603 -0.001737833 -0.03646284 0.01486861 -0.001911401 -0.03637248 0.01495534 -0.002108216 -0.03647899 0.01459038 -0.00238943 -0.03639942 0.01475459 -0.002436995 -0.03649657 0.01438015 -0.002678155 -0.0365166 0.01417768 -0.002570271 -0.0363993 0.01395088 -0.002741277 -0.03652387 0.01381546 -0.002552986 -0.03640925 0.01352846 -0.002606153 -0.03655028 0.01349782 -0.002384364 -0.03643161 0.01320803 -0.002290189 -0.0365653 0.01325386 -0.002061545 -0.03647553 0.01305645 -0.001906633 -0.03658705 0.01320672 -0.001599192 -0.03649789 0.01307398 -0.001559197 -0.03659659 0.01318734 -0.001253068 -0.03661304 0.01341557 -0.001189589 -0.03651982 0.01337492 -0.001022219 -0.03662049 0.01379901 -9.45901e-4 -0.03654134 0.01364177 -8.54184e-4 -0.03663599 0.01395171 -7.74925e-4 -0.03665018 0.01436388 -8.1382e-4 -0.03666293 0.01428884 -9.61657e-4 -0.03653359 0.01454335 -0.001085877 -0.03657925 0.014759 -0.001090049 -0.03668153 0.01484334 -0.001501202 -0.03660321 0.0149787 -0.001441001 -0.03670144 0.01501244 -0.00186485 -0.03672313 0.01481342 -0.002048969 -0.03660637 0.01490586 -0.002218127 -0.03673148 0.01450824 -0.002462923 -0.03665381 0.01464861 -0.002529382 -0.03674989 0.01418465 -0.002736628 -0.03677028 0.01386713 -0.002589523 -0.03668612 0.0137456 -0.002696573 -0.03679102 0.01336687 -0.002483963 -0.03680521 0.01335477 -0.0022583 -0.03671526 0.01308172 -0.002036213 -0.0368306 0.01322132 -0.001929342 -0.03670626 0.01307433 -0.001532137 -0.03684306 0.01328086 -0.001365542 -0.03675931 0.01320326 -0.001223325 -0.0368638 0.01352053 -9.09512e-4 -0.03688204 0.0137003 -9.80397e-4 -0.03678703 0.01394677 -7.72535e-4 -0.03690075 0.01423674 -9.33893e-4 -0.03681218 0.01432663 -8.07683e-4 -0.03691536 0.01461124 -9.61e-4 -0.03691107 0.01464909 -0.00118345 -0.03683555 0.01481956 -0.001148343 -0.03694033 0.01486027 -0.001582562 -0.036857 0.01500838 -0.001583993 -0.0369572 0.01499605 -0.001973628 -0.03697264 0.01479619 -0.002087533 -0.03685539 0.0148487 -0.002318382 -0.03699582 0.01458358 -0.002379179 -0.03687345 0.01450794 -0.002627491 -0.03700637 0.01431816 -0.002545595 -0.03691422 0.01407867 -0.002745985 -0.03702676 0.0138877 -0.002581298 -0.03693515 0.01367956 -0.002682387 -0.03704041 0.01345175 -0.002349019 -0.03693503 0.01330453 -0.002425134 -0.03706073 0.01314717 -0.002187609 -0.03706848 0.01324987 -0.002014517 -0.03694963 0.01319611 -0.001764714 -0.03698998 0.01304405 -0.001692891 -0.03709328 0.01316052 -0.001293122 -0.03710985 0.01333349 -0.001279592 -0.03701394 0.01339519 -0.001004278 -0.03711885 0.01377308 -9.53378e-4 -0.03704047 0.0137434 -8.12412e-4 -0.03714108 0.01419275 -7.77406e-4 -0.03716003 0.01429027 -9.50996e-4 -0.03706485 0.01462292 -9.58385e-4 -0.03717881 0.01476216 -0.001310408 -0.03709316 0.01484745 -0.001191139 -0.03718614 0.01500153 -0.001571953 -0.03720426 0.01486235 -0.001952588 -0.03712451 0.0150147 -0.001879513 -0.03722047 0.01484614 -0.002327084 -0.03723961 0.01454383 -0.002427101 -0.03715223 0.01446813 -0.00264281 -0.03725993 0.01417744 -0.002576947 -0.03717136 0.01413643 -0.002731502 -0.03727459 0.01374965 -0.002549767 -0.03719174 0.01381087 -0.002713978 -0.03728705 0.013466 -0.002567052 -0.03730225 0.01333582 -0.002225935 -0.03721684 0.01322776 -0.002317428 -0.03731423 0.01307821 -0.002001225 -0.03732818 0.01319545 -0.001773595 -0.03723961 0.01305705 -0.00162959 -0.03734415 0.01327699 -0.001407921 -0.03725767 0.01315319 -0.001325249 -0.03735733 0.01335263 -0.001039981 -0.03736644 0.01351785 -0.001088857 -0.03727674 0.01365637 -8.43231e-4 -0.0373916 0.01398223 -9.15332e-4 -0.03730022 0.01403707 -7.71313e-4 -0.03740149 0.01444107 -8.49863e-4 -0.03741884 0.01440405 -0.001002073 -0.03732109 0.01480257 -0.001136541 -0.03743261 0.01469719 -0.001244843 -0.03733968 0.01485955 -0.001592278 -0.03735774 0.01496046 -0.001415491 -0.03745102 0.01502132 -0.001726627 -0.03746438 0.01481407 -0.002044618 -0.03734791 0.0149284 -0.002184867 -0.03748476 0.0147196 -0.002241671 -0.03739005 0.01462125 -0.002550542 -0.03749829 0.01441913 -0.002498388 -0.03740918 0.01427972 -0.002707779 -0.03751611 0.01394528 -0.002597451 -0.03743237 0.0138958 -0.002738237 -0.03753089 0.01342123 -0.002338171 -0.03746014 0.01334589 -0.002466619 -0.03755146 0.01308655 -0.002040624 -0.03758466 0.0132156 -0.001880288 -0.03745931 0.01305925 -0.00156939 -0.03759735 0.01327747 -0.001373112 -0.03750926 0.01320093 -0.001215875 -0.03761202 0.0133661 -0.001030385 -0.03760683 0.01362848 -0.00102967 -0.03750896 0.01385283 -7.82239e-4 -0.03764241 0.01417154 -9.17269e-4 -0.03755956 0.01425474 -7.90137e-4 -0.03765881 0.0146054 -9.55583e-4 -0.03767633 0.01457047 -0.001119256 -0.03755104 0.0148546 -0.001203536 -0.03769254 0.0147925 -0.001414716 -0.03757506 0.01501679 -0.001615285 -0.03770637 0.0148645 -0.00193125 -0.03762346 0.0149495 -0.002135634 -0.03773051 0.01451772 -0.002456665 -0.03765356 0.01470065 -0.002481043 -0.0377506 0.01438629 -0.002677917 -0.03775584 0.01392066 -0.002592742 -0.03768306 0.01390981 -0.002741158 -0.03778094 0.01337409 -0.002488911 -0.03780227 0.0134254 -0.002323031 -0.03767842 0.01330131 -0.00216192 -0.03772014 0.01314485 -0.002176523 -0.03782397 0.01305961 -0.001872718 -0.0378344 0.01319456 -0.001705706 -0.03774279 0.01308995 -0.00144273 -0.03785371 0.01335966 -0.001273512 -0.03773921 0.01331949 -0.001070201 -0.03787004 0.01368635 -9.85791e-4 -0.0377857 0.01359802 -8.74048e-4 -0.03786754 0.01385337 -7.78435e-4 -0.03789782 0.01412302 -9.32413e-4 -0.03778225 0.01435548 -8.20085e-4 -0.03791391 0.01453191 -0.001071333 -0.03782808 0.01469302 -0.001019477 -0.03793299 0.01494592 -0.00136888 -0.03794968 0.01477247 -0.001380681 -0.03782099 0.01487886 -0.001835882 -0.03786951 0.01501905 -0.001773715 -0.03796446 0.01494443 -0.002144753 -0.03798019 0.01469987 -0.002260386 -0.0378915 0.01469486 -0.002484738 -0.03799813 0.01436209 -0.002534151 -0.0379123 0.01430642 -0.002710998 -0.03801733 0.01388257 -0.002568125 -0.03791064 0.01374202 -0.00270307 -0.03803837 0.01353502 -0.002433598 -0.03795331 0.01333647 -0.002452731 -0.03806012 0.01308822 -0.002056241 -0.03807777 0.01326203 -0.002075314 -0.03797489 0.01321256 -0.001625299 -0.03796827 0.01305037 -0.001628577 -0.03809499 0.01327395 -0.001404941 -0.03800749 0.01316553 -0.001280665 -0.03810739 0.01354098 -0.001075446 -0.03802794 0.01348412 -9.33048e-4 -0.03812903 0.0138787 -7.79403e-4 -0.03812992 0.0139842 -9.13663e-4 -0.03805059 0.01441931 -8.43958e-4 -0.03816682 0.01444017 -0.001018881 -0.038073 0.01471018 -0.001039981 -0.03818255 0.01477307 -0.001365602 -0.03807592 0.0149421 -0.001360356 -0.03820008 0.01487761 -0.001718878 -0.03811389 0.01502847 -0.001728534 -0.03821271 0.01495271 -0.002107858 -0.03822761 0.01477819 -0.002136766 -0.03813439 0.01477414 -0.00240761 -0.03823941 0.01451182 -0.002450168 -0.03815418 0.01448541 -0.002632677 -0.0382623 0.01410108 -0.002739131 -0.03827375 0.01413226 -0.002581 -0.03814995 0.01367628 -0.002679944 -0.03829497 0.01361179 -0.002485394 -0.0381993 0.01348561 -0.002572357 -0.03828501 0.01325583 -0.002080738 -0.03822445 0.01322406 -0.002324223 -0.03831428 0.01308637 -0.002049088 -0.03833061 0.01322788 -0.00148493 -0.03825306 0.01306962 -0.001541435 -0.03834897 0.01332163 -0.001061499 -0.0383718 0.01354473 -0.001076102 -0.03827792 0.01375848 -8.07993e-4 -0.03839123 0.01394802 -9.1879e-4 -0.03829884 0.01420134 -7.77698e-4 -0.03840345 0.01434046 -9.7599e-4 -0.03831821 0.0146436 -9.72131e-4 -0.03843247 0.0146926 -0.001245737 -0.03831475 0.01494216 -0.001360893 -0.03844916 0.01488476 -0.001805126 -0.03836697 0.01502168 -0.001752138 -0.03846454 0.01490467 -0.002241671 -0.03848326 0.0146408 -0.00234282 -0.03839588 0.01455342 -0.002592921 -0.03850597 0.0140751 -0.002610266 -0.03842675 0.01423162 -0.00271964 -0.03851902 0.01391673 -0.002736926 -0.03853243 0.01350587 -0.00259304 -0.03854048 0.01347404 -0.002387464 -0.03845685 0.01320159 -0.002293229 -0.03856819 0.01324295 -0.002000868 -0.03845143 0.01304596 -0.001806616 -0.03859257 0.01320958 -0.00159657 -0.03849768 0.01314097 -0.001324236 -0.0386039 0.0134564 -0.001135945 -0.03852319 0.01347815 -9.38731e-4 -0.03862565 0.01392138 -9.32942e-4 -0.03852051 0.01389944 -7.71772e-4 -0.03865003 0.01435106 -8.22466e-4 -0.03866732 0.01428574 -9.67539e-4 -0.03853696 0.01458722 -0.00113362 -0.03855615 0.01463693 -9.73855e-4 -0.03867554 0.01485252 -0.001206278 -0.03869062 0.01481926 -0.001485466 -0.03857874 0.01499634 -0.001537024 -0.03870815 0.01500993 -0.001923799 -0.03871476 0.01484912 -0.001989126 -0.03862679 0.01486599 -0.002285361 -0.03874152 0.01447129 -0.002488136 -0.03865683 0.01462703 -0.002539038 -0.03874891 0.01431787 -0.002701163 -0.0387625 0.01386535 -0.002582192 -0.03868561 0.01395314 -0.002739131 -0.03878068 0.01351201 -0.002597987 -0.03880292 0.01346671 -0.002369582 -0.03870767 0.01315832 -0.002215087 -0.03882056 0.01321977 -0.001976072 -0.03872954 0.013049 -0.001771926 -0.03883892 0.01323056 -0.001524507 -0.0387519 0.01311087 -0.00140506 -0.03885608 0.01331502 -0.001072943 -0.03886866 0.01342827 -0.001176774 -0.03877079 0.01366859 -8.35126e-4 -0.03888183 0.01380711 -9.43871e-4 -0.03879219 0.01409059 -7.72123e-4 -0.03890806 0.01432758 -9.75945e-4 -0.03878748 0.01447361 -8.6803e-4 -0.03891956 0.01460313 -0.001146733 -0.03881204 0.01476669 -0.001095235 -0.0389328 0.01482385 -0.001500904 -0.03882032 0.01499617 -0.001507461 -0.03895449 0.01487821 -0.001777231 -0.03886634 0.01498568 -0.002033352 -0.03897356 0.01467657 -0.002312719 -0.03889405 0.01477533 -0.002405345 -0.03899198 0.01451826 -0.002618253 -0.03900623 0.01423245 -0.002560794 -0.03889346 0.01422244 -0.002721548 -0.03902292 0.0138399 -0.002720534 -0.03903478 0.01390272 -0.002567648 -0.03890717 0.01360183 -0.002461671 -0.03892308 0.01352697 -0.002598583 -0.03904825 0.01321083 -0.002302467 -0.03906285 0.01333892 -0.002199769 -0.03894209 0.01319694 -0.001826405 -0.03898686 0.01305437 -0.001903295 -0.03908407 0.01309514 -0.001448035 -0.03910553 0.01328462 -0.001407027 -0.03898137 0.01334351 -0.001048684 -0.03912073 0.01355618 -0.001054704 -0.03902924 0.01379323 -7.90588e-4 -0.03914105 0.01409298 -9.14046e-4 -0.03905534 0.01430666 -8.0479e-4 -0.03916198 0.01445561 -0.001034736 -0.03907436 0.01461315 -9.60219e-4 -0.03917729 0.01479053 -0.001363515 -0.03909671 0.01488757 -0.001250922 -0.03919005 0.01500612 -0.001560568 -0.03921079 0.01486361 -0.001880288 -0.03912132 0.01498222 -0.002034068 -0.03922361 0.0146417 -0.002351403 -0.0391466 0.01482594 -0.002341151 -0.03924375 0.01455563 -0.002595484 -0.0392583 0.01421189 -0.00272721 -0.03926116 0.01419353 -0.002575814 -0.03917032 0.01383733 -0.002561748 -0.03916424 0.01381576 -0.002719342 -0.03928524 0.01344263 -0.002547442 -0.03931063 0.01335847 -0.002269983 -0.03921484 0.0131722 -0.002238631 -0.03931814 0.01304972 -0.001837253 -0.03933018 0.01319319 -0.001720428 -0.03924179 0.01309961 -0.001443862 -0.03935146 0.01333558 -0.001292645 -0.03926372 0.01325649 -0.001144707 -0.03936785 0.01359623 -0.001056075 -0.03925478 0.01362049 -8.5846e-4 -0.03938704 0.01393455 -9.30728e-4 -0.03926908 0.01413971 -7.64627e-4 -0.03940153 0.0143311 -9.63627e-4 -0.03931713 0.01456016 -9.20038e-4 -0.03942817 0.01471775 -0.00126475 -0.03934043 0.01491469 -0.001288712 -0.03944182 0.01486378 -0.001699924 -0.03933882 0.01502025 -0.001731693 -0.03946465 0.01482701 -0.002045214 -0.03937953 0.01496899 -0.002066731 -0.03947794 0.01478463 -0.002399444 -0.03949797 0.01453101 -0.002419054 -0.03937846 0.01452219 -0.002613604 -0.03950417 0.01413059 -0.002581 -0.03939747 0.01409363 -0.002745509 -0.03952461 0.01364308 -0.002657711 -0.03953796 0.01370203 -0.002514958 -0.03942322 0.01338583 -0.002496719 -0.03955644 0.01336878 -0.002263128 -0.03946465 0.01314896 -0.002191066 -0.03957653 0.01319158 -0.001811802 -0.03948783 0.01304626 -0.001767039 -0.03958165 0.01329863 -0.001356363 -0.03951036 0.01311606 -0.001393735 -0.03960847 0.0133056 -0.001098752 -0.03961735 0.01362371 -0.001017212 -0.03953278 0.0135613 -8.90436e-4 -0.03963518 0.01394164 -7.67141e-4 -0.03964251 0.01415157 -9.28346e-4 -0.03953802 0.01439583 -8.35883e-4 -0.03966671 0.01462805 -0.001138389 -0.03958314 0.01468789 -0.001016736 -0.0396853 0.01490455 -0.001292765 -0.03969126 0.01487278 -0.001675784 -0.03961139 0.01501888 -0.001663327 -0.03971183 0.01495242 -0.002129614 -0.03973048 0.01479107 -0.002121508 -0.03963387 0.01465219 -0.002526044 -0.03975212 0.01443809 -0.002483308 -0.03962981 0.01434022 -0.00269109 -0.03976404 0.01404553 -0.002605736 -0.03967666 0.01391339 -0.00273776 -0.03977972 0.01357662 -0.002445042 -0.03967559 0.01353251 -0.002600908 -0.03979831 0.01328504 -0.002393782 -0.03981053 0.01324522 -0.00205785 -0.03972595 0.01305145 -0.001887798 -0.03981727 0.01322001 -0.001600682 -0.03972089 0.01310122 -0.001454055 -0.03984141 0.01335728 -0.001283347 -0.03973543 0.01358395 -0.001040458 -0.03978145 0.01405048 -9.25186e-4 -0.03977686 0.01426529 -0.002567648 -0.03410863 0.01379644 -0.002571403 -0.03411936 0.01342183 -0.002344846 -0.03415644 0.01319444 -0.001816749 -0.0341854 0.01374971 -9.6977e-4 -0.0342366 0.01417553 -9.23882e-4 -0.03425753 0.01486831 -0.001571297 -0.03430402 0.01480752 -0.002072215 -0.03432875 0.01458489 -0.002391695 -0.03434735 0.01383978 -0.00257498 -0.0343849 0.0132324 -0.001485526 -0.03445142 0.01356476 -0.001055657 -0.03447741 0.01435756 -9.77939e-4 -0.03451657 0.01477724 -0.001340091 -0.03454297 0.01486325 -0.001927375 -0.03457123 0.01429688 -0.00255227 -0.03461295 0.01447629 -0.001037538 -0.03477281 0.01480257 -0.00140661 -0.03479653 0.01486426 -0.001908957 -0.03482043 0.01427501 -0.002567827 -0.03486448 0.01345884 -0.00236684 -0.03490579 0.01320499 -0.0019176 -0.03493028 0.01324743 -0.001476883 -0.03495162 0.01345825 -0.001145362 -0.03497046 0.01431697 -9.61923e-4 -0.03501451 0.01470774 -0.001247107 -0.03503739 0.01487493 -0.001700699 -0.03506064 0.01474022 -0.002227902 -0.03508704 0.01426964 -0.002566099 -0.03511488 0.01344799 -0.002361655 -0.0351566 0.01321965 -0.0015527 -0.03519809 0.01374596 -9.59381e-4 -0.03523725 0.01481449 -0.001432776 -0.03529757 0.01485037 -0.001992046 -0.03532487 0.01447588 -0.00247997 -0.03535455 0.01390075 -0.00259006 -0.03538191 0.01335561 -0.002272725 -0.03541266 0.01319617 -0.001724421 -0.03543949 0.01336246 -0.001239657 -0.0354641 0.01382207 -9.39166e-4 -0.03549039 0.01432418 -9.63317e-4 -0.03551489 0.01485329 -0.001567363 -0.03555411 0.01370507 -0.00252521 -0.0356419 0.01319074 -0.001770794 -0.03568726 0.01333379 -0.001291215 -0.03571164 0.01370495 -9.79192e-4 -0.03573465 0.01421016 -9.3049e-4 -0.03575921 0.01487648 -0.001846492 -0.03581738 0.01466149 -0.00231558 -0.03584212 0.01418995 -0.002590596 -0.03586947 0.01355314 -0.002457261 -0.0358994 0.01321589 -0.001960992 -0.03592818 0.01324421 -0.001474559 -0.03595185 0.01380473 -9.53547e-4 -0.03598922 0.01466912 -0.00118339 -0.03603488 0.01487827 -0.001746892 -0.03606271 0.01446843 -0.002473771 -0.03610402 0.01397603 -0.002599596 -0.03612822 0.01326119 -0.002077043 -0.03617233 0.01320159 -0.001660704 -0.03619307 0.0133906 -0.001207351 -0.03621613 0.01453417 -0.001078963 -0.03627586 0.01483744 -0.001485347 -0.03630065 0.01484066 -0.001993656 -0.03632462 0.01456469 -0.002415359 -0.03634929 0.0132389 -0.002029955 -0.03642487 0.01321554 -0.001577079 -0.03644669 0.01342493 -0.001173734 -0.03646838 0.01382559 -9.41742e-4 -0.03649067 0.01471269 -0.001252889 -0.03653782 0.01487827 -0.00173825 -0.03656226 0.01450049 -0.002457976 -0.03660231 0.01405876 -0.002593159 -0.03662472 0.0135324 -0.002443134 -0.03665083 0.01320356 -0.001645505 -0.03669345 0.01342338 -0.001165091 -0.03671884 0.01391369 -9.22819e-4 -0.03674477 0.0143277 -9.70095e-4 -0.03676491 0.01468688 -0.001220464 -0.03678578 0.01488018 -0.001715779 -0.03681159 0.01412308 -0.002592086 -0.03687167 0.01368641 -0.002517461 -0.03689283 0.01321017 -0.00160402 -0.03694552 0.01347678 -0.001108705 -0.03697264 0.0141099 -9.07417e-4 -0.03700375 0.01463526 -0.001161336 -0.03703236 0.01486092 -0.001597344 -0.03705596 0.01482552 -0.00203514 -0.03707671 0.01454746 -0.00242865 -0.03709989 0.01402336 -0.002599179 -0.03712612 0.0134499 -0.002377092 -0.03715622 0.01319229 -0.001812279 -0.03718543 0.01335209 -0.001250803 -0.03721392 0.01377308 -9.58168e-4 -0.03723806 0.0141502 -9.26397e-4 -0.03725606 0.01458197 -0.001109004 -0.03727883 0.01486331 -0.001586437 -0.03730517 0.01453548 -0.002432525 -0.03735059 0.01401752 -0.002602458 -0.03737705 0.01343286 -0.002357363 -0.03740715 0.01326251 -0.00141406 -0.03745472 0.01405113 -9.0696e-4 -0.03750193 0.01487213 -0.001793205 -0.03756505 0.01471138 -0.002266705 -0.03758919 0.01422131 -0.002579808 -0.03761732 0.01371181 -0.002531349 -0.0376414 0.0131815 -0.001775026 -0.03768759 0.01372128 -9.74848e-4 -0.0377354 0.01451116 -0.001063585 -0.03777456 0.01487857 -0.001819431 -0.0378167 0.01464146 -0.00234723 -0.03784388 0.01418113 -0.002581655 -0.03786867 0.01344776 -0.002360999 -0.03790616 0.01321303 -0.001928746 -0.03793042 0.0134077 -0.00119704 -0.03796702 0.01382917 -9.35513e-4 -0.03799104 0.01427817 -9.54614e-4 -0.03801226 0.01464873 -0.001177132 -0.03803342 0.0148679 -0.001876235 -0.03806918 0.01464319 -0.002343833 -0.03809392 0.01379281 -0.002562105 -0.03813719 0.01343464 -0.002337157 -0.03815788 0.01323634 -0.002007544 -0.03817582 0.01321059 -0.001595914 -0.03819578 0.01338458 -0.001229226 -0.03821504 0.01374185 -9.6291e-4 -0.03823643 0.01430463 -9.51476e-4 -0.03826379 0.01487326 -0.001633942 -0.0383076 0.01479965 -0.002094149 -0.03832972 0.01451778 -0.002448439 -0.03835135 0.01396262 -0.002600491 -0.03837954 0.01348352 -0.002387583 -0.03840416 0.0132339 -0.001482248 -0.03845167 0.01352941 -0.001085281 -0.03847527 0.01486814 -0.001882493 -0.0385695 0.01467198 -0.00230199 -0.0385918 0.01426237 -0.002568781 -0.0386148 0.01375085 -0.002546966 -0.03863936 0.01334095 -0.002235949 -0.03866392 0.01319336 -0.001743853 -0.03868931 0.01334476 -0.001271605 -0.0387125 0.0138185 -9.30345e-4 -0.03874021 0.01485264 -0.001968622 -0.03882318 0.01460963 -0.002364635 -0.03884547 0.01319497 -0.001808583 -0.03893548 0.0136249 -0.001009762 -0.03898036 0.01417273 -9.25257e-4 -0.03900742 0.01462924 -0.001153111 -0.03903198 0.01488369 -0.001693129 -0.03905993 0.01475733 -0.002176702 -0.03908407 0.01439541 -0.002525448 -0.03910827 0.01357406 -0.002458393 -0.03914886 0.01332342 -0.002187192 -0.03916615 0.01319837 -0.001843929 -0.03918391 0.01329636 -0.001345396 -0.03920865 0.01444596 -0.001015305 -0.03927075 0.01480442 -0.001410663 -0.03929632 0.01476341 -0.002174735 -0.03933387 0.01348501 -0.00238651 -0.03940403 0.01326191 -0.002076268 -0.03942257 0.0132001 -0.001642823 -0.03944379 0.01341706 -0.001180708 -0.03946828 0.01387977 -9.25135e-4 -0.03949314 0.01469236 -0.001214802 -0.03953552 0.01487517 -0.001730442 -0.03956222 0.01473921 -0.002224445 -0.03958684 0.01397943 -0.002592086 -0.03962838 0.0132761 -0.00213474 -0.0396704 0.01365345 -0.001007378 -0.0397318 0.01461994 -0.001128435 -0.03978085 0.01487511 -0.001685976 -0.03980952 0.01308703 -0.001480221 -0.03411018 0.01317006 -0.002183198 -0.03410619 0.01500463 -0.001915752 -0.03423666 0.01479625 -0.002384483 -0.03425759 0.01391094 -7.84307e-4 -0.03491264 0.01391476 -0.002731084 -0.03529769 0.01369374 -0.002676486 -0.03755676 0.01358622 -8.80778e-4 -0.03764873 0.01362311 -0.002643585 -0.03780978 0.01399117 -7.69996e-4 -0.03816556 0.01496732 -0.001815617 -0.04000258 0.01501834 -0.001695573 -0.03986424 0.01495909 -0.00152564 -0.03997367 0.01480716 -0.001372873 -0.04007083 0.01450914 -0.001099169 -0.04010003 0.01488101 -0.001288115 -0.03994178 0.0146963 -0.001127302 -0.04003161 0.01470404 -0.001029551 -0.03986233 0.01437807 -9.23513e-4 -0.04004442 0.01447427 -8.95831e-4 -0.03993928 0.01391744 -9.99285e-4 -0.04010546 0.01402145 -9.08094e-4 -0.04007804 0.01414561 -8.28189e-4 -0.04000633 0.01428908 -8.06434e-4 -0.03985941 0.01400482 -7.88664e-4 -0.03993117 0.01376008 -8.39927e-4 -0.03996866 0.01368618 -9.62641e-4 -0.04007178 0.01352971 -0.001092731 -0.04009217 0.01343828 -9.95315e-4 -0.03994852 0.01338422 -0.001112282 -0.04002475 0.01323926 -0.001379251 -0.04005706 0.01326066 -0.001665472 -0.04010403 0.01321697 -0.001247107 -0.03994768 0.01315754 -0.001751422 -0.04006165 0.01312118 -0.00152266 -0.03998744 0.01307374 -0.001693367 -0.03995102 0.01329821 -0.002068877 -0.04010182 0.01314669 -0.00209856 -0.03997826 0.01334261 -0.002322971 -0.04004961 0.01328665 -0.002373993 -0.03992038 0.0137338 -0.002510309 -0.04009479 0.01362413 -0.002561509 -0.04004162 0.01420944 -0.002538681 -0.04010158 0.01350796 -0.002561211 -0.03994983 0.01397323 -0.002677798 -0.04002094 0.0137127 -0.002686798 -0.03986126 0.01414322 -0.002700924 -0.03997123 0.01393955 -0.002734005 -0.03985536 0.01442772 -0.002625882 -0.03997415 0.01456648 -0.0024423 -0.04007136 0.01476156 -0.002096295 -0.04009956 0.01438385 -0.002673268 -0.03985512 0.01484417 -0.001738071 -0.04010039 0.01475471 -0.002349674 -0.04000741 0.01470118 -0.002476513 -0.03985786 0.01488113 -0.002223193 -0.03993546 0.01490026 -0.002044856 -0.04002749 0.0144481 -0.002467215 -0.03293508 0.01487082 -0.001729846 -0.03293699 0.01362299 -0.002468883 -0.03293454 0.0132125 -0.00175482 -0.0329349 0.01362293 -0.001042842 -0.03293609 0.01447218 -0.001039326 -0.03293251 0.01447772 -0.002518773 -0.03221625 0.01359307 -0.00252074 -0.03221577 0.01447498 -9.89229e-4 -0.03221619 0.01491528 -0.001756191 -0.03221708 0.01359218 -9.90711e-4 -0.03221595 0.01315355 -0.00175482 -0.03221684 0.01279848 -0.003156304 -0.03220498 0.01351422 -0.003551065 -0.03220498 0.01422071 -0.003607988 -0.03220498 0.01226925 -0.002397596 -0.03220498 0.01218372 -0.001522779 -0.03220498 0.01490187 -0.003412246 -0.03220498 0.01562476 -0.002763152 -0.03220498 0.01249802 -6.68565e-4 -0.03220498 0.01330685 -2.6895e-5 -0.03220498 0.01591181 -0.00175482 -0.03220498 0.01408171 1.07854e-4 -0.03220498 0.01493626 -1.00383e-4 -0.03220498 0.0156657 -8.31087e-4 -0.03220498 0.0121712 -0.001740157 -0.034105 0.01233345 -9.70344e-4 -0.034105 0.01295149 -2.21208e-4 -0.034105 0.01381766 1.02724e-4 -0.034105 0.01455432 3.55826e-5 -0.034105 0.0152893 -3.56977e-4 -0.034105 0.01575225 -0.001031041 -0.034105 0.01589632 -0.001647233 -0.034105 0.01579785 -0.002380371 -0.034105 0.01541173 -0.003012001 -0.034105 0.01476365 -0.003482818 -0.034105 0.01370787 -0.003611683 -0.034105 0.01284664 -0.00319457 -0.034105 0.012326 -0.002526044 -0.034105 0.006302535 0.006119787 -0.03986138 0.006156682 0.006174564 -0.03985136 0.00647962 0.006470859 -0.03986316 0.005712151 0.005906164 -0.0398547 0.006389021 0.00676006 -0.0398541 0.006521821 0.006837785 -0.03985631 0.00527364 0.005887866 -0.039855 0.004985868 0.005939126 -0.03984701 0.006191909 0.007275402 -0.03984713 0.006138861 0.007518529 -0.03985506 0.005731999 0.007649898 -0.0398547 0.005823194 0.007683277 -0.03985548 0.005097746 0.007626593 -0.03985744 0.004860758 0.007467031 -0.0341143 0.005186855 0.007665991 -0.03412348 0.0055027 0.007728278 -0.03414809 0.006376862 0.006684362 -0.03411096 0.005801677 0.007692873 -0.03416371 0.005739986 0.007636427 -0.03410494 0.006150364 0.007518112 -0.0341776 0.006459653 0.007107317 -0.03419947 0.006201684 0.007315099 -0.03410476 0.006508409 0.006556987 -0.03422141 0.006218075 0.006257116 -0.03414034 0.006262362 0.006064653 -0.03424471 0.005839765 0.005957186 -0.03416299 0.005856573 0.005814015 -0.03426349 0.005518913 0.005759418 -0.03427743 0.005345582 0.005938887 -0.03416246 0.005120873 0.005843639 -0.03429239 0.005037486 0.006086409 -0.03417754 0.004699885 0.006221473 -0.0343011 0.004809081 0.006325244 -0.03421956 0.004578888 0.006500363 -0.03433138 0.004692792 0.006767153 -0.03424119 0.004558384 0.006863057 -0.03434318 0.004890382 0.007274389 -0.03423869 0.004646658 0.007177472 -0.03435695 0.00491172 0.007517814 -0.034379 0.005054593 0.007430136 -0.03427881 0.005363166 0.007716476 -0.03439164 0.005311727 0.007543683 -0.03426122 0.005736947 0.007551133 -0.03428703 0.005786657 0.007704377 -0.03441202 0.006102383 0.007349967 -0.03430461 0.006205201 0.007472574 -0.03443741 0.006338715 0.007013916 -0.03435254 0.006419181 0.007183253 -0.03444629 0.006510436 0.006878316 -0.03445625 0.006330251 0.006462097 -0.03437912 0.006475687 0.006429791 -0.0344811 0.006342113 0.006181538 -0.03447324 0.006055653 0.006102263 -0.03437566 0.006152093 0.005972862 -0.03450298 0.005696773 0.005929231 -0.03438943 0.005674362 0.005760192 -0.03452759 0.005320847 0.005923867 -0.03443783 0.005289494 0.005789577 -0.03453415 0.004929125 0.005967378 -0.03455191 0.004898607 0.006199359 -0.03446227 0.004664361 0.00627768 -0.03457432 0.004704773 0.006607234 -0.0344839 0.004561662 0.006586968 -0.03457742 0.004591107 0.007046759 -0.03460723 0.00479263 0.007157683 -0.03451007 0.004750788 0.007349193 -0.03461176 0.005235731 0.007535338 -0.03453868 0.005135297 0.007649362 -0.03463667 0.005520939 0.007731616 -0.03465032 0.005657732 0.007569968 -0.03455895 0.005896151 0.007659792 -0.03466516 0.006032109 0.007426559 -0.03457808 0.006184935 0.007487714 -0.03468137 0.006289422 0.00708723 -0.03457224 0.006444156 0.007134616 -0.03469949 0.006374776 0.006709933 -0.03461682 0.006521701 0.006702184 -0.03471636 0.006454825 0.006396114 -0.03472769 0.006218075 0.006272315 -0.03461623 0.006215989 0.006023883 -0.03474527 0.005879759 0.005989432 -0.03463512 0.005856215 0.005814552 -0.03476381 0.005433678 0.005760371 -0.03477847 0.005321264 0.005922436 -0.03468781 0.005060672 0.005879163 -0.03479671 0.004971385 0.00613439 -0.0346812 0.00482434 0.006063342 -0.03481018 0.004602074 0.006415367 -0.03482687 0.004710674 0.006569921 -0.0347318 0.004554986 0.00686115 -0.03484928 0.004776298 0.007125139 -0.03475874 0.004662394 0.007205843 -0.03485023 0.004905462 0.007509768 -0.03487461 0.005145847 0.007488608 -0.0347836 0.005321264 0.007713437 -0.0348978 0.005604445 0.007584393 -0.03480625 0.005815625 0.007692873 -0.0349155 0.006117582 0.007543265 -0.03492206 0.006031274 0.007412075 -0.03479719 0.006227672 0.007205247 -0.03482019 0.006374835 0.007255911 -0.03494215 0.006381094 0.006756961 -0.03486466 0.00649923 0.006955027 -0.03496026 0.006499826 0.006513357 -0.03497439 0.006179332 0.006188869 -0.03489416 0.006286919 0.006101965 -0.03499233 0.006017565 0.00588566 -0.03500443 0.005715548 0.005926251 -0.03491944 0.005675792 0.005772531 -0.03501963 0.005283832 0.005787014 -0.03503572 0.005281507 0.005943 -0.03494024 0.004935741 0.005964994 -0.03505313 0.004819512 0.006281912 -0.03496748 0.004643976 0.006305277 -0.03507626 0.004545927 0.006795048 -0.03509098 0.004708528 0.006815075 -0.03496962 0.004672706 0.007224977 -0.03510707 0.004908323 0.007319927 -0.03501975 0.004969179 0.007556915 -0.03512728 0.005286753 0.007536172 -0.03501403 0.005384624 0.007718861 -0.03514409 0.005750834 0.00755757 -0.03506344 0.005736172 0.007711172 -0.03515923 0.006100654 0.007556736 -0.03517711 0.006095767 0.007363617 -0.03508222 0.006405055 0.007215321 -0.03519272 0.00631535 0.007059514 -0.03510034 0.006509065 0.006905078 -0.03521263 0.006364524 0.006631314 -0.0351209 0.006485939 0.006485223 -0.03522133 0.006240963 0.006294906 -0.03513801 0.006318271 0.00613892 -0.03523975 0.00592339 0.005998075 -0.03515887 0.005887329 0.005826056 -0.03524625 0.005498826 0.005907833 -0.03517979 0.005544364 0.005758643 -0.03527909 0.005112469 0.005850911 -0.03529924 0.005070507 0.006043314 -0.03520125 0.004859805 0.006023406 -0.0353021 0.004798412 0.006349205 -0.03522092 0.004603326 0.006411612 -0.03532272 0.004706978 0.006699144 -0.03521257 0.004552364 0.006845295 -0.0353443 0.004807233 0.007169723 -0.03526192 0.004657864 0.007192492 -0.03535902 0.00491321 0.00751394 -0.03537714 0.005196034 0.007518589 -0.03528654 0.005399763 0.007730364 -0.03539168 0.005659878 0.007573723 -0.03530883 0.006012082 0.007610142 -0.03540593 0.006067931 0.007381319 -0.03530031 0.006225526 0.007219314 -0.03534138 0.006290972 0.007383942 -0.03543823 0.006471455 0.007047057 -0.0354548 0.006376981 0.006790578 -0.03536367 0.006518781 0.006652534 -0.0354638 0.006307542 0.006443679 -0.03535223 0.00641644 0.006296813 -0.03548371 0.006003379 0.006037652 -0.0354045 0.006138265 0.005961954 -0.03550672 0.00583148 0.005804538 -0.03551548 0.005554676 0.005910038 -0.03542727 0.005494117 0.005758583 -0.03552877 0.005161166 0.006005048 -0.03541815 0.00505948 0.00587511 -0.03553855 0.004799067 0.006312191 -0.03546863 0.004730641 0.00616616 -0.03556638 0.004547834 0.006650328 -0.03558313 0.004716575 0.006882548 -0.03547161 0.00459516 0.007067143 -0.03561037 0.004897236 0.007277905 -0.03548979 0.004895567 0.007501244 -0.03562539 0.005211889 0.007525086 -0.03553742 0.005144596 0.007655739 -0.03563487 0.005483448 0.007726788 -0.03565019 0.005695402 0.007568717 -0.0355603 0.005780935 0.007700204 -0.03565841 0.006149768 0.007518887 -0.03567516 0.005953311 0.007461845 -0.03554564 0.006265878 0.007153749 -0.03559517 0.006436228 0.007166087 -0.03569555 0.006374716 0.006769478 -0.03561437 0.006529569 0.006771326 -0.03571355 0.006250202 0.00632286 -0.03561192 0.006474554 0.006440222 -0.03573131 0.006250798 0.00606513 -0.03574132 0.006043314 0.006074249 -0.03565222 0.006020188 0.005886971 -0.03575873 0.005640149 0.005925357 -0.0356462 0.005616366 0.005759835 -0.03577667 0.005331218 0.005928516 -0.03568768 0.00517714 0.005822658 -0.03579354 0.004866003 0.006019115 -0.03580236 0.005004584 0.006102561 -0.0357058 0.004743397 0.006444931 -0.03572583 0.004575908 0.006476521 -0.03583151 0.004714429 0.00689876 -0.035748 0.004581093 0.007004499 -0.03585112 0.004866898 0.007254242 -0.03576636 0.004743814 0.007336914 -0.03586208 0.005014121 0.007580161 -0.03588086 0.005247712 0.007524967 -0.03576511 0.005412757 0.007729411 -0.03589838 0.00561732 0.007565855 -0.03577989 0.005797743 0.007703721 -0.03590589 0.005985915 0.007455289 -0.03582555 0.006211638 0.007462203 -0.03593546 0.006315052 0.00707072 -0.03584951 0.006451606 0.007116496 -0.03594422 0.006524384 0.006689608 -0.03596556 0.006363332 0.006686866 -0.03584098 0.006256997 0.006345689 -0.03585851 0.006423294 0.006296336 -0.03598368 0.005985498 0.00603193 -0.03590589 0.006148457 0.005972385 -0.03599983 0.005892515 0.005825221 -0.03601312 0.005492568 0.005903005 -0.03592973 0.005473077 0.005756378 -0.0360291 0.004944562 0.00595498 -0.03603631 0.004947602 0.006127715 -0.0359584 0.004708349 0.006200075 -0.03606992 0.004684209 0.006733775 -0.03598916 0.004557967 0.006617486 -0.03608191 0.004572868 0.006959378 -0.0360974 0.004880964 0.00727564 -0.03601765 0.004726767 0.007320821 -0.03612196 0.005041897 0.007599353 -0.03612953 0.005247831 0.00752139 -0.03601187 0.005412697 0.007726192 -0.03614896 0.005735933 0.007567822 -0.036062 0.005770087 0.007709085 -0.03616088 0.006134331 0.007526695 -0.03617537 0.006191611 0.007274448 -0.03608858 0.006367981 0.007274448 -0.03619444 0.006514191 0.006894052 -0.03620809 0.006340146 0.006944954 -0.03608208 0.006338715 0.006498038 -0.03612762 0.006493926 0.006516098 -0.03621923 0.00632435 0.006150603 -0.03623962 0.00601679 0.00604242 -0.03615361 0.005973577 0.005859315 -0.03625881 0.005463004 0.005907058 -0.0361815 0.005613267 0.005763888 -0.03627574 0.005145072 0.005831003 -0.03629511 0.004963696 0.006117582 -0.03620719 0.004801154 0.006082236 -0.03631043 0.004623234 0.006376266 -0.03632414 0.004683017 0.006698429 -0.03623867 0.004550814 0.00668466 -0.03633344 0.004593729 0.007034063 -0.03635382 0.004843771 0.007218062 -0.03626447 0.004735291 0.007317483 -0.03636115 0.005134165 0.007470726 -0.03625512 0.005016326 0.007584929 -0.03637665 0.005395174 0.007727444 -0.03639853 0.005553126 0.007584273 -0.03630363 0.005912899 0.00766009 -0.0364176 0.005927443 0.007483899 -0.03632235 0.006228208 0.007443368 -0.03643393 0.006209373 0.007243692 -0.03634059 0.006467938 0.007081091 -0.03644931 0.00638628 0.006744384 -0.03636544 0.006513833 0.006602227 -0.03646844 0.006186008 0.006210923 -0.0363928 0.00641483 0.006303369 -0.03648328 0.006197154 0.006008744 -0.03649657 0.005837619 0.005964159 -0.03641343 0.005720555 0.005778491 -0.03650403 0.005364596 0.005926668 -0.03641676 0.005292773 0.005786478 -0.03653508 0.004953026 0.006151676 -0.03643232 0.005004346 0.005912065 -0.03655022 0.004712343 0.006196558 -0.03656625 0.004778385 0.006414949 -0.03644841 0.004704117 0.006754577 -0.03646504 0.004570364 0.006546497 -0.03658199 0.004562854 0.006919026 -0.03660082 0.004787981 0.00712502 -0.03650921 0.004767537 0.007376015 -0.03661304 0.005043089 0.007423579 -0.03652805 0.00519067 0.007671475 -0.03663843 0.005480289 0.007586836 -0.0365504 0.005668759 0.007725536 -0.03665852 0.005948781 0.007463395 -0.03654706 0.006114065 0.00754863 -0.03667527 0.006176233 0.007282912 -0.03658765 0.00643742 0.007153332 -0.0366978 0.006359219 0.006914675 -0.0366072 0.006521761 0.006700694 -0.03672057 0.00630033 0.006379187 -0.03663337 0.006419599 0.00628829 -0.03673106 0.0060817 0.005919694 -0.03675353 0.005984067 0.006040453 -0.03665554 0.005671322 0.005768537 -0.036767 0.00562191 0.005921542 -0.03664565 0.005211889 0.005966186 -0.03669333 0.005273342 0.00579214 -0.03679203 0.004831075 0.006042838 -0.03680586 0.00488156 0.006237566 -0.03668528 0.004732429 0.006546378 -0.0367074 0.004559278 0.006560742 -0.03683423 0.00473231 0.007006168 -0.03675299 0.004600584 0.007073044 -0.03685462 0.004705727 0.007278025 -0.03684639 0.004936635 0.007320106 -0.03674799 0.004910111 0.007512032 -0.03687512 0.00535351 0.007568597 -0.0367943 0.005221605 0.007686078 -0.03689044 0.00573939 0.007716953 -0.03691178 0.005912244 0.007505536 -0.03682065 0.006185233 0.007487714 -0.03693455 0.006403386 0.007216572 -0.0369448 0.006277859 0.007136702 -0.03684628 0.006528377 0.006772816 -0.03696316 0.006363272 0.00678569 -0.03683906 0.006410658 0.006278336 -0.03698068 0.006317138 0.006474614 -0.03684926 0.006125152 0.006162285 -0.03687089 0.006082713 0.005925238 -0.03699994 0.005821883 0.005970656 -0.03688663 0.005689442 0.00576055 -0.03702628 0.005483984 0.005917966 -0.03690385 0.005083143 0.005859375 -0.0370413 0.005022048 0.006069302 -0.03695404 0.004721283 0.006184637 -0.03706783 0.004756987 0.006458103 -0.03695297 0.004578173 0.006526589 -0.03708034 0.004560649 0.006931364 -0.03709262 0.004708051 0.006799161 -0.03696221 0.00482124 0.007164895 -0.03698927 0.004675209 0.007236957 -0.03711134 0.005222618 0.007539033 -0.0370385 0.004985451 0.007570624 -0.03712898 0.00536406 0.007715702 -0.03714603 0.005877077 0.007523536 -0.03706914 0.005778133 0.007702946 -0.03716361 0.006198763 0.007480144 -0.03718435 0.006267547 0.007155478 -0.03709501 0.006406068 0.007200121 -0.03717988 0.00650084 0.006975889 -0.03720653 0.006378054 0.006638288 -0.03712117 0.00649929 0.006528317 -0.03722453 0.006134808 0.006156504 -0.03714603 0.006276845 0.006085991 -0.037243 0.005900382 0.005828499 -0.03726494 0.005732417 0.005926728 -0.03716868 0.005426287 0.005758464 -0.03728276 0.005151927 0.005982875 -0.03719651 0.004936575 0.005951046 -0.03730052 0.004804432 0.00634247 -0.03722071 0.00462079 0.006372511 -0.03732144 0.004692256 0.006726503 -0.03723967 0.004550039 0.006734311 -0.03733915 0.004606187 0.007070541 -0.0373581 0.004849314 0.00723946 -0.03726494 0.00475353 0.007343113 -0.03736287 0.005021929 0.007589519 -0.03738218 0.005202233 0.007511913 -0.03728681 0.005308568 0.007701754 -0.03739291 0.005645751 0.007582128 -0.03730821 0.00570476 0.007723152 -0.03739988 0.005937814 0.007473289 -0.03729951 0.006040215 0.007595598 -0.03742551 0.006282567 0.007133364 -0.03734636 0.006297945 0.007363617 -0.03743815 0.006483137 0.007030427 -0.03745698 0.006366491 0.006782829 -0.03733909 0.006514132 0.00659877 -0.03746908 0.006271719 0.006349205 -0.0373851 0.006305515 0.006118834 -0.03749394 0.006018102 0.00607115 -0.03737598 0.006064474 0.005906939 -0.03750532 0.005782961 0.005792617 -0.03750121 0.005677878 0.005917549 -0.03742122 0.005470395 0.005751848 -0.03752928 0.005161046 0.005983948 -0.03744608 0.00510329 0.005855321 -0.03754889 0.00468713 0.006222903 -0.03756487 0.004757225 0.006410479 -0.03747451 0.004543185 0.006764948 -0.03759211 0.004714131 0.00682038 -0.03746914 0.004824638 0.00717765 -0.03748768 0.004722893 0.007320284 -0.03761219 0.005167126 0.007497668 -0.03753477 0.005110681 0.007636666 -0.03763329 0.005615234 0.007585108 -0.03755718 0.005542099 0.007739901 -0.03765171 0.005954146 0.00763899 -0.03767478 0.00604248 0.007400155 -0.0375511 0.006288766 0.007381439 -0.03768408 0.006304323 0.007104039 -0.03759795 0.006488621 0.00700879 -0.03770339 0.006348192 0.006590247 -0.03759771 0.006508409 0.006602168 -0.03771799 0.006192266 0.006212413 -0.03764265 0.006421983 0.00630784 -0.03773176 0.006171345 0.005981504 -0.03774923 0.005758285 0.005945622 -0.03763967 0.005553245 0.005750536 -0.03777414 0.005260765 0.005944192 -0.03769057 0.005021274 0.005895793 -0.03780013 0.004752099 0.006137073 -0.0378108 0.004857063 0.006249368 -0.03771537 0.004557311 0.006587564 -0.03783297 0.004738032 0.006521999 -0.0377019 0.004725098 0.006926655 -0.03772312 0.00458455 0.007006406 -0.03785002 0.004785954 0.007398128 -0.03786653 0.00499624 0.007398962 -0.03777539 0.00527507 0.007703602 -0.03789108 0.005372643 0.007560551 -0.03777146 0.005716741 0.007711708 -0.03791177 0.005947411 0.007491171 -0.03782278 0.006015181 0.007604479 -0.03792107 0.006339311 0.00733143 -0.03794276 0.006285727 0.007101774 -0.03782147 0.006460666 0.00707072 -0.03793519 0.006375014 0.006630659 -0.03787106 0.006521761 0.006776094 -0.03796464 0.006450116 0.006370604 -0.03797829 0.006177306 0.006211161 -0.03789317 0.006261289 0.006078958 -0.03799921 0.005765795 0.005924046 -0.03791683 0.005952417 0.005851268 -0.03800952 0.00555849 0.005757093 -0.038028 0.00511527 0.006005048 -0.03794884 0.005191445 0.005821704 -0.03803998 0.004870116 0.006008982 -0.03805822 0.004679083 0.00625503 -0.0380634 0.004774332 0.006417989 -0.03795009 0.004558324 0.006623566 -0.03808486 0.004710376 0.006749391 -0.03796297 0.004580616 0.00700134 -0.03810048 0.004782915 0.007096648 -0.03798323 0.004845321 0.007460772 -0.03811979 0.004998981 0.007371783 -0.03799521 0.005355775 0.007570862 -0.03804409 0.005314528 0.007709264 -0.03814035 0.005720317 0.007717311 -0.03815805 0.005832076 0.007519304 -0.03804075 0.006225228 0.007456123 -0.03817993 0.00612533 0.007324218 -0.03805875 0.006346642 0.006969392 -0.03810501 0.006499052 0.006982922 -0.03820669 0.006494879 0.006496667 -0.03822368 0.006338834 0.006496846 -0.03812718 0.006281495 0.006101787 -0.03824257 0.006041824 0.00606656 -0.03815263 0.005990028 0.00586611 -0.03825604 0.005514025 0.005914211 -0.0381537 0.005452394 0.005754649 -0.03828418 0.005062997 0.006038248 -0.03820157 0.005062341 0.005874574 -0.0382936 0.004669606 0.006258249 -0.03831613 0.004762411 0.006439566 -0.03820204 0.004545152 0.006767451 -0.03833913 0.004726648 0.006943047 -0.03822612 0.004866421 0.007261574 -0.03826677 0.004653632 0.007196009 -0.03836131 0.004945397 0.007535874 -0.03837889 0.005269587 0.007541298 -0.03829026 0.00537759 0.007725656 -0.03839504 0.005495071 0.007577598 -0.03826975 0.005913436 0.00766313 -0.03841531 0.005986154 0.007453739 -0.0383259 0.006290256 0.007377147 -0.03843504 0.006277263 0.007114827 -0.03831732 0.006453216 0.007103085 -0.0384491 0.006366968 0.006756722 -0.03833979 0.006525099 0.00671637 -0.03846752 0.006292641 0.006411433 -0.03835761 0.006383299 0.006235063 -0.03848844 0.006050825 0.006094157 -0.03837507 0.00610125 0.005936145 -0.03850525 0.005881845 0.005826532 -0.03849691 0.005608916 0.005896627 -0.03842496 0.005629599 0.005761206 -0.0385251 0.00514996 0.005830168 -0.03854447 0.005250453 0.005965352 -0.0384165 0.004882574 0.006216287 -0.03846305 0.004757344 0.006137192 -0.03855973 0.004763007 0.006439626 -0.0384491 0.004605591 0.006415188 -0.03857874 0.004556298 0.006916642 -0.03859478 0.004709541 0.006903409 -0.03849768 0.004956483 0.007364094 -0.03852325 0.00476402 0.00736171 -0.03862076 0.005055665 0.00760442 -0.03862822 0.005472242 0.007587611 -0.03854978 0.005366146 0.007715106 -0.03864586 0.005773305 0.007706284 -0.03866589 0.005929172 0.007472157 -0.03854554 0.006044447 0.007582187 -0.03865784 0.006211936 0.007260918 -0.03858983 0.006306648 0.007372438 -0.03868955 0.006497085 0.006952822 -0.03870785 0.006361365 0.006800055 -0.0385887 0.006497025 0.00650072 -0.03871959 0.00631088 0.006433725 -0.03863066 0.006028771 0.006055474 -0.03865325 0.006273508 0.006077349 -0.03874331 0.005998909 0.005861639 -0.03875809 0.00549221 0.005903124 -0.03867971 0.005484163 0.005755603 -0.0387879 0.005120456 0.005849659 -0.03878933 0.004957139 0.006120741 -0.03870797 0.004808068 0.006078898 -0.03880965 0.004592061 0.006450772 -0.03882706 0.004715144 0.006577312 -0.0387324 0.004555165 0.006837368 -0.03884059 0.004735052 0.007009744 -0.03875327 0.004640877 0.007166624 -0.03885751 0.005071282 0.007455706 -0.03877979 0.004978656 0.007570326 -0.03888028 0.005484759 0.007731497 -0.03889697 0.005465567 0.007571935 -0.03877294 0.005849778 0.00751084 -0.03878915 0.00589323 0.007666528 -0.03891754 0.00622791 0.007235765 -0.03884023 0.006273984 0.007404744 -0.03893703 0.006492197 0.006984829 -0.03895676 0.006376504 0.006709635 -0.03886723 0.006516218 0.006645619 -0.03896796 0.006389796 0.006248652 -0.03898543 0.006233036 0.006280899 -0.03888887 0.006111264 0.00594449 -0.03900235 0.005836427 0.00595045 -0.03891307 0.005717992 0.005770027 -0.03901636 0.005284368 0.005941748 -0.03894001 0.005275607 0.005795419 -0.03903687 0.004902899 0.00598067 -0.03905302 0.004850506 0.00624603 -0.03896528 0.004646658 0.006313323 -0.03907072 0.004694461 0.0067451 -0.03899061 0.0045529 0.006614506 -0.03908532 0.004575073 0.006957828 -0.03909975 0.004849314 0.007240831 -0.03901547 0.004704236 0.007272601 -0.03911066 0.004982471 0.00757128 -0.03912651 0.00519365 0.007501959 -0.03900998 0.005535304 0.00773251 -0.03915172 0.005542635 0.007569551 -0.0390262 0.005878329 0.007673859 -0.03916341 0.005960166 0.007476687 -0.03907388 0.006199121 0.007467925 -0.03918254 0.006410241 0.007202088 -0.03919154 0.006228804 0.007202804 -0.03906619 0.006365478 0.006737232 -0.0390926 0.006520092 0.006816685 -0.0392161 0.006327211 0.006478428 -0.03912842 0.006441056 0.006339013 -0.03922939 0.006111145 0.00612998 -0.03914815 0.00617206 0.005993366 -0.03924781 0.00574243 0.005773007 -0.03926777 0.005657613 0.005911707 -0.03917187 0.005269885 0.005795478 -0.03928929 0.00512588 0.006003201 -0.03919821 0.004976153 0.005938768 -0.03930324 0.004745483 0.006152868 -0.03931015 0.004796922 0.006349623 -0.0392208 0.004570424 0.00653398 -0.03933596 0.004704773 0.006785035 -0.039218 0.004556536 0.006848275 -0.03934204 0.004640102 0.007157921 -0.03935647 0.004791498 0.007135927 -0.03925973 0.004833519 0.007441461 -0.03936421 0.005167365 0.007510364 -0.03928458 0.005221188 0.007686913 -0.03938823 0.005792796 0.007554948 -0.03931534 0.005687654 0.007725656 -0.03941661 0.006049811 0.007580935 -0.03940826 0.006239414 0.007209002 -0.03934204 0.006229162 0.007452547 -0.03943431 0.006462633 0.007087826 -0.03945273 0.006379842 0.006672978 -0.03936892 0.006512939 0.006582438 -0.03947293 0.006365537 0.006214737 -0.039487 0.006194472 0.0062294 -0.03939181 0.006109237 0.005944371 -0.03950428 0.00585854 0.00598216 -0.03938555 0.005859494 0.005814194 -0.03950917 0.00551778 0.005919754 -0.03940224 0.005500137 0.005759775 -0.03952729 0.005187213 0.005993962 -0.03942042 0.00515145 0.005840063 -0.03954076 0.004813194 0.006059646 -0.0395599 0.004925489 0.006188809 -0.03943425 0.00474441 0.006490886 -0.03945165 0.004575312 0.006513833 -0.03958636 0.004560053 0.006927073 -0.03959625 0.004719495 0.006979286 -0.03950178 0.004694163 0.007259786 -0.03960943 0.005062043 0.007430136 -0.03950643 0.004949569 0.007535934 -0.03962683 0.005239069 0.007686972 -0.03963899 0.005430817 0.007564246 -0.03952127 0.005684554 0.007723391 -0.03965628 0.005758404 0.007542431 -0.03953909 0.00614053 0.007528722 -0.03967988 0.006171047 0.007303059 -0.0395869 0.006406903 0.007203459 -0.0396924 0.006353914 0.006897687 -0.0395857 0.006517887 0.006831109 -0.03970891 0.006492018 0.006498157 -0.03972941 0.006294131 0.006376743 -0.03963381 0.006331384 0.006170153 -0.03974014 0.006104111 0.005939126 -0.03975069 0.005925953 0.00599581 -0.03965866 0.005737125 0.005777239 -0.03977018 0.005488991 0.005911231 -0.0396803 0.005329728 0.005783021 -0.03978276 0.005122959 0.006013095 -0.03969836 0.004993021 0.005919575 -0.03980153 0.004728972 0.006182432 -0.03981584 0.004767835 0.006386458 -0.03972303 0.004567801 0.006554186 -0.03984242 0.004725694 0.007003247 -0.03975009 0.00454396 0.006771326 -0.03983813 0.004711627 0.007283508 -0.03984922 0.005083858 0.007459461 -0.03978145 0.005552172 0.00758326 -0.03980416 0.005795121 0.007532238 -0.03978419 0.006120979 0.006130993 -0.03410553 0.005710899 0.005925357 -0.03411132 0.004764974 0.006401956 -0.03417068 0.004709362 0.006922781 -0.0342009 0.006375372 0.006878495 -0.03430652 0.006280124 0.006360888 -0.03433227 0.005175471 0.005980134 -0.03439348 0.00475502 0.00640583 -0.03442144 0.004736661 0.007033348 -0.03445273 0.005024909 0.007406651 -0.03447437 0.005450785 0.007587373 -0.03449684 0.005989015 0.007457375 -0.03452324 0.006370246 0.006626248 -0.03456866 0.005460977 0.005902588 -0.03462904 0.004736125 0.006465315 -0.03467518 0.00473082 0.006992518 -0.03470003 0.005056679 0.007449328 -0.03472715 0.00560677 0.0075832 -0.03475433 0.006380259 0.006691277 -0.03481584 0.006117641 0.00612086 -0.03484612 0.005544126 0.005901277 -0.03487592 0.005092501 0.006032705 -0.03489786 0.004784405 0.006362676 -0.03491938 0.004859447 0.007252275 -0.03496378 0.005718886 0.007573068 -0.03500962 0.006198167 0.007268249 -0.03503662 0.006374955 0.006799221 -0.03506064 0.006240189 0.006271958 -0.03508704 0.005786597 0.005940854 -0.03511393 0.005312681 0.005935013 -0.0351364 0.004883646 0.006204426 -0.03516072 0.004793345 0.007150352 -0.03520828 0.005147576 0.007489502 -0.03523147 0.005680561 0.007583379 -0.03525751 0.006354808 0.006959795 -0.03530323 0.006100237 0.006127536 -0.03534621 0.005637943 0.005900621 -0.03537094 0.004770755 0.006374716 -0.03542041 0.005402982 0.00758779 -0.03549438 0.006261944 0.007184386 -0.03554177 0.006369948 0.006614506 -0.03556919 0.005930304 0.006006002 -0.03560608 0.00522089 0.005966663 -0.03564113 0.004848182 0.006256163 -0.03566354 0.004690587 0.006763279 -0.03568887 0.004883408 0.007285356 -0.03571617 0.005947113 0.007477402 -0.03577107 0.006268143 0.007157444 -0.035793 0.006060719 0.006091475 -0.03584879 0.005706548 0.005925655 -0.03586769 0.00520575 0.005962967 -0.03589159 0.004802942 0.00633043 -0.03591758 0.004695594 0.006777167 -0.03593969 0.004864275 0.007259905 -0.03596442 0.005690395 0.00757569 -0.03600782 0.006120562 0.00734663 -0.03603154 0.006365358 0.006593704 -0.03607106 0.006077349 0.006090819 -0.036098 0.005509316 0.005898714 -0.03612667 0.005082726 0.006043374 -0.0361483 0.004812121 0.006317555 -0.03616696 0.004703521 0.006675481 -0.03618496 0.004777073 0.007122218 -0.0362063 0.00554949 0.007587969 -0.03625166 0.006052255 0.007414162 -0.03627675 0.006363511 0.006926238 -0.03630512 0.006306707 0.006412625 -0.03632938 0.006018102 0.006056308 -0.03635156 0.005581438 0.005905508 -0.03637355 0.004874467 0.007274091 -0.0364651 0.005262613 0.007536947 -0.03648757 0.005646049 0.007575452 -0.03650575 0.006278514 0.007138252 -0.03654372 0.006370723 0.006575524 -0.0365712 0.006042718 0.006069898 -0.03659987 0.005199015 0.005975306 -0.03664201 0.00471121 0.006907224 -0.03669589 0.005145847 0.00749129 -0.03673189 0.005577504 0.007581353 -0.03675258 0.005920529 0.007487952 -0.03676962 0.006228566 0.007218897 -0.03678947 0.005044102 0.006060421 -0.0369004 0.005070924 0.00745058 -0.03697752 0.005543529 0.007585227 -0.03700107 0.005945026 0.007475733 -0.03702086 0.006278157 0.007147431 -0.03704327 0.006370365 0.00670433 -0.03706514 0.006249666 0.006297886 -0.03708541 0.005935549 0.006011903 -0.03710561 0.005523025 0.0059008 -0.03712618 0.004989087 0.006096184 -0.03715372 0.00470674 0.006585359 -0.03718096 0.004757106 0.007061123 -0.03720355 0.005052149 0.007436215 -0.03722631 0.005487918 0.007582724 -0.03724843 0.006167113 0.007310152 -0.03728431 0.006321966 0.006434977 -0.03732842 0.005548298 0.005900621 -0.03737503 0.00499624 0.006088197 -0.0374031 0.004734516 0.00650525 -0.03742641 0.005068063 0.00744915 -0.03747719 0.005605816 0.007588565 -0.03750437 0.006351649 0.006976425 -0.03755229 0.00615102 0.006169319 -0.037593 0.005354762 0.005927324 -0.03763437 0.004969596 0.006120622 -0.03765493 0.004905641 0.007310271 -0.03771752 0.005621552 0.007582306 -0.03775471 0.006009638 0.007433831 -0.03777456 0.006367921 0.006730377 -0.03781378 0.006288945 0.006372213 -0.03783178 0.005980312 0.006031751 -0.03785341 0.005426883 0.005899548 -0.03788036 0.004952132 0.006143569 -0.03790622 0.005363166 0.007572352 -0.03799235 0.006339013 0.006990015 -0.03805166 0.006334006 0.006458818 -0.03807657 0.005928695 0.00599116 -0.03810667 0.005044758 0.006061911 -0.03815078 0.004696726 0.006702482 -0.03818607 0.005006253 0.007402956 -0.03822356 0.005933821 0.007498383 -0.03827047 0.005661487 0.00591886 -0.03836977 0.005025327 0.006079614 -0.03840172 0.00470072 0.006664216 -0.03843438 0.004792273 0.007152378 -0.0384581 0.005212247 0.007524788 -0.03848576 0.005682349 0.007570862 -0.03850775 0.006239175 0.007201731 -0.03854012 0.006313621 0.006411015 -0.03857958 0.006005764 0.006053268 -0.03860193 0.005501389 0.005892753 -0.03862714 0.004956245 0.006131947 -0.03865569 0.004689395 0.006652057 -0.03868442 0.00482881 0.007204055 -0.03871142 0.005110144 0.007461249 -0.03872907 0.006188809 0.007273018 -0.03878617 0.006367325 0.006862521 -0.0388081 0.006293118 0.006372272 -0.03883129 0.005979061 0.006035566 -0.03885328 0.005574405 0.005903601 -0.03887379 0.005107879 0.006021499 -0.03889679 0.004764735 0.006395995 -0.03892165 0.004711031 0.00691539 -0.03894656 0.004877805 0.007257938 -0.03896427 0.005878567 0.00751084 -0.03901737 0.006344139 0.00696063 -0.03905266 0.00620377 0.006225347 -0.03908991 0.005654871 0.005900204 -0.03912085 0.005083799 0.006033897 -0.0391485 0.004755854 0.006422579 -0.03917247 0.004929184 0.007345139 -0.03921884 0.005356252 0.00755912 -0.03924214 0.005723774 0.00756365 -0.03925961 0.006087899 0.007374763 -0.03927922 0.006376743 0.006897628 -0.03930586 0.006232261 0.006261467 -0.03933709 0.004712343 0.006873309 -0.03944402 0.004843413 0.007226169 -0.03946262 0.006126284 0.007342636 -0.03953158 0.006366312 0.006604075 -0.03957009 0.006086826 0.006097316 -0.03959786 0.00546205 0.00589621 -0.03962928 0.004922986 0.006162941 -0.03965777 0.004726052 0.006540834 -0.03967845 0.004724919 0.006990969 -0.03969967 0.00500369 0.007392883 -0.03972315 0.00537604 0.007569789 -0.03974312 0.006136178 0.007338047 -0.03978282 0.006374835 0.006848037 -0.03980803 0.006281316 0.006360292 -0.03983217 0.005284786 0.005876779 -0.034105 0.004593074 0.007048726 -0.03410947 0.004670083 0.006316721 -0.03410619 0.004841268 0.006041646 -0.03432327 0.006033122 0.005892157 -0.03527116 0.005846202 0.007680594 -0.03542995 0.005100846 0.005863547 -0.03606081 0.005859732 0.005810022 -0.03653001 0.005834877 0.005806088 -0.03777986 0.005940258 0.007640779 -0.03818458 0.005202174 0.007667124 -0.03915375 0.006338298 0.006933689 -0.0400967 0.006260752 0.007130146 -0.04009145 0.006487071 0.006968379 -0.03993278 0.006304562 0.007240891 -0.04002714 0.005816817 0.007480084 -0.04010373 0.00634396 0.007308423 -0.03986334 0.006088316 0.007428884 -0.04005634 0.006069481 0.007549107 -0.03995364 0.005835711 0.007583558 -0.04004871 0.005712807 0.007696866 -0.03993588 0.005631625 0.007673799 -0.04000025 0.005466163 0.007606208 -0.04007005 0.005182385 0.007457196 -0.04010152 0.005467474 0.007725894 -0.03986483 0.005324661 0.007655143 -0.0400002 0.005040645 0.007497787 -0.04004585 0.004954934 0.007293522 -0.04010337 0.005174636 0.007630586 -0.03996455 0.004956603 0.007524788 -0.03991866 0.004772961 0.007288157 -0.04000484 0.004724204 0.006965517 -0.04008376 0.004613041 0.00701934 -0.03995883 0.004806399 0.006415307 -0.04010242 0.004630506 0.006758332 -0.04003721 0.004703223 0.006437063 -0.04005068 0.004600226 0.006536066 -0.03995734 0.004681408 0.006313741 -0.039963 0.004875183 0.006129145 -0.04003947 0.005153894 0.006031334 -0.04009753 0.004718065 0.006186604 -0.03986173 0.005018591 0.005931138 -0.0399506 0.00552082 0.005943655 -0.04010027 0.005208075 0.005891919 -0.04002863 0.005265414 0.005800008 -0.03986352 0.005560278 0.005824983 -0.04002159 0.005498588 0.005758523 -0.03986138 0.005932271 0.005968093 -0.0400657 0.005726814 0.005804359 -0.03995376 0.006020009 0.005927264 -0.03997904 0.005979895 0.006098806 -0.04010117 0.005931556 0.005846619 -0.03985798 0.006253659 0.00641632 -0.04010134 0.006211757 0.006153404 -0.04004347 0.006337344 0.00642091 -0.04007148 0.006372094 0.006305098 -0.03997963 0.006462156 0.006637394 -0.04000657 0.005945861 0.006033957 -0.03293699 0.00637257 0.006767153 -0.03293454 0.00512439 0.006030917 -0.0329343 0.004711866 0.006743788 -0.03293508 0.005122423 0.007458031 -0.03293466 0.005972743 0.00745958 -0.0329343 0.005975723 0.005981504 -0.03221684 0.005095124 0.005979478 -0.03221619 0.005974948 0.007510721 -0.03221619 0.00641638 0.006742298 -0.03221672 0.005092263 0.007509112 -0.03221619 0.004651963 0.00674349 -0.03221595 0.004212677 0.005434989 -0.03220498 0.004948914 0.004951417 -0.03220498 0.005951225 0.004922807 -0.03220498 0.003817737 0.00600475 -0.03220498 0.003760755 0.007325589 -0.03220498 0.003674626 0.006684303 -0.03220498 0.006702125 0.005281984 -0.03220498 0.004590511 0.0083521 -0.03220498 0.004097878 0.007932066 -0.03220498 0.007219314 0.005934119 -0.03220498 0.005287766 0.008598923 -0.03220498 0.007405519 0.006730079 -0.03220498 0.00629729 0.008471548 -0.03220498 0.007166743 0.007687091 -0.03220498 0.003735542 0.007267236 -0.034105 0.004204452 0.008064389 -0.034105 0.00513041 0.008588314 -0.034105 0.006130576 0.008516967 -0.034105 0.006732404 0.008171796 -0.034105 0.007201731 0.007599472 -0.034105 0.007405519 0.006760179 -0.034105 0.00728327 0.00610888 -0.034105 0.006967127 0.005543649 -0.034105 0.006465375 0.005134165 -0.034105 0.005814373 0.004893362 -0.034105 0.004773259 0.005018711 -0.034105 0.004028081 0.005643188 -0.034105 0.003700911 0.006374299 -0.034105 0.01516598 0.006915509 -0.034105 0.01490998 0.00746721 -0.034105 0.01488125 0.007503986 -0.03440499 0.01445996 0.00780189 -0.034105 0.01433622 0.007849335 -0.03440499 0.01373267 0.007855594 -0.034105 0.01366376 0.007821738 -0.03440499 0.0132184 0.007529258 -0.03440499 0.01317226 0.007481217 -0.034105 0.01293385 0.007045328 -0.03440499 0.01293838 0.007033824 -0.034105 0.01293385 0.006444931 -0.034105 0.01293838 0.006456375 -0.03440499 0.01326161 0.005897462 -0.03440499 0.01335573 0.005816161 -0.034105 0.01379239 0.005640983 -0.03440499 0.01411145 0.005603194 -0.034105 0.01431673 0.005639731 -0.03440499 0.01476192 0.00586462 -0.034105 0.01482778 0.005932629 -0.03440499 0.01508986 0.006331205 -0.034105 0.01508873 0.006331682 -0.03440499 0.01516801 0.006915807 -0.03440499 0.01167029 0.006627082 -0.034105 0.01175135 0.007345855 -0.03440499 0.01177901 0.007422566 -0.034105 0.01210391 0.008110404 -0.034105 0.01222532 0.008289158 -0.03440499 0.0127384 0.008718788 -0.034105 0.0131874 0.008957564 -0.03440499 0.01354813 0.009059667 -0.034105 0.01421225 0.009106457 -0.03440499 0.01473873 0.009025692 -0.034105 0.01511317 0.008847653 -0.03440499 0.01572757 0.008395731 -0.034105 0.01589006 0.008224308 -0.03440499 0.01620411 0.007679522 -0.034105 0.01628714 0.007439672 -0.03440499 0.01641017 0.006685912 -0.034105 0.01640027 0.006627082 -0.03440499 0.0161252 0.005628764 -0.03440499 0.01605516 0.005488097 -0.034105 0.01556515 0.004950225 -0.03440499 0.01539605 0.004822134 -0.034105 0.01491534 0.004553616 -0.03440499 0.01454579 0.004421472 -0.034105 0.01387679 0.004371345 -0.03440499 0.01343339 0.004457771 -0.034105 0.0127139 0.004772901 -0.03440499 0.01249462 0.00493896 -0.034105 0.01202988 0.005497872 -0.03440499 0.01189953 0.005737304 -0.034105 0.01169091 0.006391763 -0.03440499 0.01069372 0.003447115 -0.05699998 0.01031625 0.003718495 -0.05099999 0.01019328 0.0037539 -0.05699998 0.009529709 0.003867328 -0.05699998 0.009543597 0.003858566 -0.05099999 0.008968472 0.003694474 -0.05099999 0.008792519 0.003595769 -0.05699998 0.008469402 0.003299891 -0.05099999 0.008402168 0.003192067 -0.05699998 0.008174061 0.002680003 -0.05699998 0.008179605 0.00269252 -0.05099999 0.008158385 0.002132117 -0.05099999 0.008205533 0.001857757 -0.05699998 0.008373498 0.001533389 -0.05099999 0.008738279 0.001135528 -0.05699998 0.008951365 0.001001656 -0.05099999 0.009480178 8.43189e-4 -0.05699998 0.009718894 8.36265e-4 -0.05099999 0.01018458 9.36254e-4 -0.05699998 0.01055777 0.001119971 -0.05099999 0.0108202 0.001376628 -0.05699998 0.01106542 0.001814723 -0.05099999 0.01112437 0.002032756 -0.05699998 0.01115435 0.002531826 -0.05099999 0.01111698 0.00275588 -0.05699998 0.01090329 0.003196418 -0.05099999 0.001414716 -0.004525899 -0.05099999 -9.02897e-4 -0.006594836 -0.05099999 -0.00243771 -0.004330515 -0.05099999 0.001528561 -0.003824174 -0.05099999 0.00179553 -0.005379557 -0.05099999 -0.003298401 -0.00245434 -0.05099999 0.001935303 -0.003208756 -0.05099999 -0.004018843 2.20084e-4 -0.05099999 8.6255e-4 -0.008295595 -0.05099999 0.002492129 -0.005817413 -0.05099999 0.002750575 -0.002863109 -0.05099999 0.002512276 0.007610023 -0.05099999 -0.002769649 0.008413851 -0.05099999 -0.001122593 0.01102894 -0.05099999 0.002543926 0.008421719 -0.05099999 -0.003724932 0.005832731 -0.05099999 0.002821803 0.008965015 -0.05099999 0.00250703 -0.009482026 -0.05099999 0.002997398 0.006868481 -0.05099999 0.003352046 -0.005834639 -0.05099999 -0.004140675 0.003210723 -0.05099999 0.001091301 0.01320207 -0.05099999 0.003421187 0.009412348 -0.05099999 0.003771483 0.006492793 -0.05099999 0.004339933 0.009497165 -0.05099999 0.003411352 0.01468276 -0.05099999 0.004684329 -0.01053738 -0.05099999 0.006303191 0.01577281 -0.05099999 0.004054546 -0.005382895 -0.05099999 0.005108416 0.009032666 -0.05099999 0.006660521 -0.01113355 -0.05099999 0.004373073 -0.004818975 -0.05099999 0.009035587 -0.01145726 -0.05099999 0.003431379 -0.002941668 -0.05099999 0.004621207 0.006631076 -0.05099999 0.004031896 -0.003321588 -0.05099999 0.009047389 0.01614779 -0.05099999 0.005084216 0.006968796 -0.05099999 0.005398452 0.007448077 -0.05099999 0.004425644 -0.004072308 -0.05099999 0.005497038 0.008265376 -0.05099999 0.01381343 -0.003050267 -0.05099999 0.01384776 -0.003685474 -0.05099999 0.01409071 -0.002409279 -0.05099999 0.01414781 -0.004287958 -0.05099999 0.0111351 -0.01137375 -0.05099999 0.01313269 -0.01102495 -0.05099999 0.01465386 -0.001935839 -0.05099999 0.0146932 -0.004683673 -0.05099999 0.01571381 -0.01006966 -0.05099999 0.01485806 0.00909841 -0.05099999 0.01495337 0.008545398 -0.05099999 0.01503074 0.009787917 -0.05099999 0.01144254 0.01605421 -0.05099999 0.01526343 0.008033931 -0.05099999 0.01546454 -0.001796483 -0.05099999 0.01380288 0.01552176 -0.05099999 0.01563376 0.01040107 -0.05099999 0.01602154 0.01461464 -0.05099999 0.0159251 0.007611095 -0.05099999 0.01661485 0.01058048 -0.05099999 0.01663601 0.007584214 -0.05099999 0.01832896 -0.008422613 -0.05099999 0.01531344 -0.004822134 -0.05099999 0.01805746 0.01330709 -0.05099999 0.01596796 -0.004664063 -0.05099999 0.01745915 0.01012307 -0.05099999 0.02006781 0.01145178 -0.05099999 0.01654648 -0.004190027 -0.05099999 0.02056521 -0.006134092 -0.05099999 0.01782923 0.009459197 -0.05099999 0.01681232 -0.003450751 -0.05099999 0.02169823 0.009107112 -0.05099999 0.01786208 0.00888735 -0.05099999 0.02206969 -0.003713786 -0.05099999 0.01768827 0.008326768 -0.05099999 0.01669156 -0.002674818 -0.05099999 0.0225659 0.007234215 -0.05099999 0.02299666 -0.001226186 -0.05099999 0.01720434 0.007806599 -0.05099999 0.02321147 0.005015313 -0.05099999 0.01617485 -0.002067208 -0.05099999 0.02347886 0.001832485 -0.05099999 0.003707528 -0.005672097 -0.04899996 0.003075659 -0.005868077 -0.04899996 0.002480328 -0.005810678 -0.04899996 0.001898884 -0.005471587 -0.04899996 0.001448035 -0.004738748 -0.04899996 0.001510798 -0.003843009 -0.04899996 0.001943349 -0.003218114 -0.04899996 0.002541899 -0.002909958 -0.04899996 0.00320208 -0.002876341 -0.04899996 0.0038926 -0.003193855 -0.04899996 0.004323482 -0.003773868 -0.04899996 0.004441857 -0.004398345 -0.04899996 0.004269242 -0.005087971 -0.04899996 0.004745006 0.006691217 -0.04899996 0.004024267 0.006491839 -0.04899996 0.003226399 0.006691932 -0.04899996 0.002574443 0.00742954 -0.04899996 0.002501547 0.008224666 -0.04899996 0.00271666 0.008823394 -0.04899996 0.003381788 0.009407997 -0.04899996 0.004199624 0.009503185 -0.04899996 0.004808008 0.00928086 -0.04899996 0.005257606 0.00883162 -0.04899996 0.005503475 0.008164584 -0.04899996 0.005341112 0.007294416 -0.04899996 0.01592689 -0.004696905 -0.04899996 0.01495999 -0.00479716 -0.04899996 0.01419156 -0.004332661 -0.04899996 0.01379948 -0.003553271 -0.04899996 0.01392292 -0.002689659 -0.04899996 0.01441502 -0.002077698 -0.04899996 0.01511216 -0.001807034 -0.04899996 0.0159285 -0.001913189 -0.04899996 0.01662176 -0.002540111 -0.04899996 0.0168159 -0.00326246 -0.04899996 0.01664018 -0.004054605 -0.04899996 0.01694875 0.007671296 -0.04899996 0.01628541 0.007557332 -0.04899996 0.01574188 0.007698237 -0.04899996 0.01528018 0.008016288 -0.04899996 0.01486641 0.008770704 -0.04899996 0.0149511 0.009590208 -0.04899996 0.01532232 0.0101661 -0.04899996 0.01605951 0.01055812 -0.04899996 0.01687955 0.01049363 -0.04899996 0.01744347 0.01012647 -0.04899996 0.01775383 0.009659349 -0.04899996 0.01787984 0.009074211 -0.04899996 0.01764488 0.008219718 -0.04899996 0.01975816 -0.007075607 -0.03900068 0.01769006 -0.008891642 -0.03900068 0.01530319 -0.01026183 -0.03900068 0.01334506 -0.01095002 -0.03900068 0.01133459 -0.01136785 -0.03900068 0.008583068 -0.01142966 -0.03900068 0.005873858 -0.01094502 -0.03900068 0.003931522 -0.01021355 -0.03900068 0.002122819 -0.009241342 -0.03900068 4.82408e-4 -0.007969856 -0.03900068 -9.59377e-4 -0.006507694 -0.03900068 -0.00250411 -0.004229843 -0.03900068 -0.00356692 -0.001691102 -0.03900068 -0.004016578 3.95315e-4 -0.0390011 -0.004167377 0.002443075 -0.03899943 -0.003802061 0.005597293 -0.03899896 -0.002664387 0.008624792 -0.03900068 -0.001176893 0.01094043 -0.03900068 2.2797e-4 0.01243805 -0.03900068 0.001836121 0.01375007 -0.03900068 0.00424993 0.01507228 -0.03900068 0.006877839 0.01589 -0.03900068 0.009615719 0.01617085 -0.03900068 0.01229661 0.01591181 -0.03899943 0.01427388 0.01535826 -0.0390011 0.0162298 0.01450413 -0.03900068 0.01794862 0.0133807 -0.03900068 0.01952004 0.0120247 -0.03900068 0.02135956 0.009707629 -0.03900223 0.02257066 0.007236063 -0.03899967 0.02314954 0.005254566 -0.03900158 0.02343684 0.003210425 -0.03899967 0.02340596 0.001146435 -0.03900158 0.02307796 -8.91503e-4 -0.03899967 0.02226185 -0.00330317 -0.03900068 0.02115517 -0.005285799 -0.03900158 0.00370419 0.003197729 -0.03799998 0.003974318 0.003257691 -0.04499995 0.004344642 0.003193795 -0.03799998 0.004517972 0.003073334 -0.04499995 0.004862427 0.002622127 -0.03799998 0.00487101 0.00259298 -0.04499995 0.004797935 0.00194168 -0.03799998 0.004756212 0.001852512 -0.04499995 0.00440514 0.001554727 -0.03799998 0.004253387 0.001492977 -0.04499995 0.003952443 0.001457154 -0.03799998 0.003635764 0.00151205 -0.04499995 0.003457725 0.001624524 -0.03799998 0.003194332 0.001944839 -0.04499995 0.00316137 0.00202775 -0.03799998 0.003103971 0.002533614 -0.04499995 0.003108024 0.002517461 -0.03799998 0.003336548 0.002953767 -0.03799998 0.003420412 0.003038585 -0.04499995 0.01492142 0.00317651 -0.03799998 0.01508718 0.003228068 -0.04499995 0.01558983 0.003204345 -0.03799998 0.01563698 0.003180503 -0.04499995 0.01609766 0.002802073 -0.04499995 0.01610499 0.00278902 -0.03799998 0.01618999 0.002212941 -0.04499995 0.01618766 0.002198636 -0.03799998 0.01596575 0.001733303 -0.04499995 0.01589733 0.001652181 -0.03799998 0.01550185 0.001477777 -0.04499995 0.0153107 0.00145626 -0.03799998 0.01503914 0.001495242 -0.04499995 0.01484203 0.001581907 -0.03799998 0.01456969 0.001824736 -0.04499995 0.01445764 0.00203675 -0.03799998 0.01441115 0.00238347 -0.04499995 0.01446348 0.002668917 -0.03799998 0.01458328 0.00288397 -0.04499995 0.009226858 0.008792042 -0.04499995 0.009676218 0.008904159 -0.04499995 0.009801685 0.008889555 -0.03799998 0.01013815 0.008755445 -0.04499995 0.01027566 0.008653819 -0.03799998 0.01047194 0.008373498 -0.04499995 0.01055508 0.008078515 -0.03799998 0.01052653 0.007802784 -0.04499995 0.01030707 0.007371306 -0.03799998 0.01029998 0.007398247 -0.04499995 0.009848237 0.007120788 -0.04499995 0.009653806 0.007104337 -0.03799998 0.009278833 0.007193803 -0.04499995 0.009035229 0.007338643 -0.03799998 0.00892049 0.007487177 -0.04499995 0.008754789 0.00791341 -0.03799998 0.008749246 0.007995605 -0.04499995 0.008829116 0.008348405 -0.03799998 0.008904278 0.008501708 -0.04499995 0.009170055 0.00878483 -0.03799998 0.009170234 -0.002556681 -0.04499995 0.00927627 -0.002488017 -0.03799998 0.009586751 -0.002411305 -0.04499995 0.009801685 -0.00242412 -0.03799998 0.01001983 -0.002496838 -0.04499995 0.01027566 -0.002659857 -0.03799998 0.01044076 -0.002854704 -0.04499995 0.01055508 -0.003235161 -0.03799998 0.01052653 -0.003510892 -0.04499995 0.01039218 -0.00380814 -0.03799998 0.0101934 -0.004030644 -0.04499995 0.01004123 -0.004110336 -0.03799998 0.009510397 -0.004207015 -0.04499995 0.009519279 -0.004199802 -0.03799998 0.008942544 -0.003875911 -0.03799998 0.00895977 -0.003880918 -0.04499995 0.008760809 -0.003414332 -0.04499995 0.008756637 -0.003332972 -0.03799998 0.008850812 -0.002892792 -0.04499995 0.008870601 -0.00286132 -0.03799998 0.0174902 -0.005179047 -0.03799986 0.01325935 -0.007964909 -0.03799974 0.008434414 -0.008438289 -0.03799992 0.004325509 -0.007143616 -0.03799986 0.001441955 -0.004713535 -0.03799998 -4.37441e-4 -0.001699805 -0.03799992 -0.001199424 0.002214729 -0.03799992 -6.81201e-4 0.005628407 -0.03799992 9.14852e-4 0.008796811 -0.03799992 0.004543602 0.0120117 -0.03799974 0.009463489 0.0132184 -0.03799992 0.01267236 0.01273578 -0.03799998 0.01542598 0.01154249 -0.03799992 0.0180692 0.009176254 -0.03799992 0.02001047 0.005687773 -0.03799986 0.02046525 0.001403808 -0.03799992 0.0195654 -0.002027809 -0.03799992 + + + + + + + + + + 0.9615321 -0.1973574 0.1910659 0.9612456 -0.1989444 0.1908617 0.9185168 -0.3491172 0.1855912 0.8975646 -0.4041656 0.1761481 0.8037685 -0.5736363 0.1577896 0.8049806 -0.5717886 0.1583165 0.6397531 -0.7585768 0.123602 0.5941013 -0.7954109 0.1198553 0.4264742 -0.9007965 0.08176589 0.3919323 -0.9166605 0.0782473 0.2372556 -0.9705001 0.04289007 0.0774011 -0.9967917 0.02037942 0.9516117 -0.1393593 0.2738874 0.9617605 -3.80291e-4 0.2738921 0.9147138 -0.2224183 0.3373851 0.8893823 -0.2190518 0.4012675 0.9658716 0.02154213 0.2581239 0.1991714 0.1555866 0.9675348 0.7758606 0.1494107 0.6129574 0.5219336 0.3204053 0.7905225 0.9718697 0.03141182 0.2334153 0.2432659 0.292281 0.9248749 0.7929642 0.2268286 0.5654703 0.9681056 0.05112612 0.2452704 0.4325726 0.4056382 0.8051947 0.1685774 0.5396295 0.8248526 0.485879 0.4719109 0.7356778 0.9706406 0.04864722 0.2355637 0.4963391 0.6503376 0.5750728 0.2301514 -0.813044 0.5347803 0.804443 -0.3608562 0.4718627 0.2652344 -0.7540548 0.6008762 0.878849 -0.1879024 0.4385399 0.2503326 -0.6810299 0.6881366 0.3438202 -0.6457314 0.6817762 0.1814904 -0.6767574 0.7134848 0.881479 -0.187419 0.4334384 0.1988378 -0.5849677 0.7863055 0.2580503 -0.5550569 0.790773 0.9171319 -0.08927989 0.3884565 0.901121 -0.09086877 0.4239385 0.4553829 -0.396578 0.7970899 0.2421282 -0.4685528 0.8496071 0.9088771 -0.05946749 0.4128027 0.900354 -0.05034464 0.4322361 0.1546087 -0.3480815 0.9246273 0.9177167 -0.02151006 0.3966528 0.2107626 -0.1972983 0.9574198 0.8959749 0.02810931 0.4432141 0.9027864 0.02278637 0.4294853 0.4729 0.009235322 0.8810677 0.9200975 0.04483824 0.3891146 0.2491192 0.01302284 0.9683853 0.5489743 0.1566453 0.8210296 0.7557172 0.106656 0.6461549 0.6535548 0.110938 0.7487049 0.5392181 0.1568647 0.8274282 0.8166715 0.1499643 0.5572777 0.9013805 0.0929355 0.4229378 0.9162281 0.09129184 0.3901178 0.2905447 0.2340595 0.9277932 0.6041671 0.2450004 0.7582592 0.9147627 0.1236087 0.3846171 0.8226371 0.2190232 0.5246875 0.9105446 0.1255488 0.3938859 0.2601662 0.3095605 0.914596 0.7256649 0.275048 0.6306815 0.9179242 0.1625102 0.3619471 0.9075158 0.1859593 0.3766088 0.2823263 0.4446908 0.8500247 0.8029093 0.2959809 0.5174282 0.6800311 0.3960667 0.6169999 0.2574 0.5720134 0.7788106 0.2654019 0.6532593 0.7090939 0.5866437 0.5831183 0.5619808 0.7081195 0.4564774 0.5386977 0.2733725 0.743607 0.6101772 0.2124973 0.8202353 0.5310923 0.7994818 -0.3646075 0.4773784 0.9643089 -0.05401664 0.2592115 0.9116052 -0.1317884 0.3893683 0.6178668 -0.4776639 0.6245622 0.8273744 -0.2404657 0.5075706 0.4582563 -0.5175765 0.7225758 0.5943679 -0.4001908 0.6975486 0.7961454 -0.244283 0.5536048 0.5395389 -0.4242202 0.7272792 0.6791865 -0.3127483 0.6639986 0.8175999 -0.1588253 0.5534482 0.2174401 -0.4844688 0.8473547 0.7859842 -0.1651681 0.5957754 0.7702262 -0.07138586 0.6337631 0.7752701 -0.07672399 0.626953 0.5118649 -0.10637 0.8524551 0.8056198 0.01554173 0.5922291 0.8389859 0.0331645 0.5431417 0.5996565 0.005437612 0.8002391 0.6552457 0.03349673 0.7546729 0.4323677 0.0275132 0.9012775 0.4107841 0.08999234 0.9072805 0.1886298 0.05170291 0.9806863 0.5637467 0.2980583 0.7702929 0.1677976 0.4079262 0.8974632 0.6633641 0.4027493 0.6306673 0.5664671 0.4603402 0.6835218 0.8439187 0.2749623 0.4606485 0.8003462 0.3661817 0.4747179 0.2116898 0.6271939 0.7495435 0.502119 0.5705867 0.6498518 0.6139174 0.5182389 0.5954277 0.1921257 0.726776 0.6594577 0.2400211 -0.8147029 0.5278722 0.3162471 -0.8044557 0.5028309 0.8661183 -0.2745316 0.4176979 0.9093615 -0.2179532 0.3543419 0.8116714 -0.3877864 0.4368196 0.5941185 -0.5653968 0.5721449 0.5162957 -0.6208636 0.5898874 0.4813171 -0.6576979 0.5794545 0.6239489 -0.531199 0.5731627 0.2051935 -0.7438777 0.636036 0.7594079 -0.3529902 0.5465324 0.3699352 -0.5615006 0.7401791 0.6740695 -0.4144498 0.6114423 0.6193431 -0.2835819 0.7321172 0.5249298 -0.3168405 0.7899753 0.4880794 -0.3378954 0.8047392 0.5275575 -0.1805887 0.830103 0.4804732 -0.2059034 0.8524959 0.418031 -0.0789932 0.9049918 0.2354588 0.1261781 0.9636588 0.2414314 0.8192153 0.5201898 0.6904888 -0.5527839 0.4665356 0.6931579 -0.5462901 0.4702122 0.5035581 -0.7040629 0.5007241 0.6560068 -0.2485612 0.7126517 0.2544335 -0.362313 0.8966565 0.3169069 -0.3453988 0.8833287 0.608617 -0.1723324 0.7745237 0.7367148 -0.1209493 0.6652989 0.3831508 -0.2293028 0.8947713 0.2715618 -0.226188 0.9354643 0.634588 -0.05308216 0.7710256 0.1941549 -0.07376074 0.9781939 0.2450949 -0.09957748 0.9643718 0.5151866 0.6950262 0.501519 0.7514286 -0.5245898 0.400201 0.5243474 -0.6955151 0.491242 0.7084086 0.5272861 0.4691766 0.6844996 0.5604344 0.4662333 0.5171995 0.6943818 0.5003386 0.8616082 -0.3340218 0.3821789 0.8611199 -0.3396127 0.3783329 0.8490532 0.3495843 0.3961055 0.8360306 0.3796421 0.3961375 0.9793823 -0.01043021 0.2017464 0.9484506 -0.1453721 0.2816174 0.9148336 0.2241616 0.3359036 0.9407477 0.1729707 0.2916759 0.4716498 -0.8806403 0.04493612 0.63291 -0.7721419 0.05676019 0.6791936 -0.7329093 0.03924548 0.8077192 -0.5843759 0.07806777 0.9503437 -0.2974946 0.09134578 0.9725603 -0.1856862 0.1401685 0.8581013 -0.5108197 0.05220556 0.9482098 -0.3108077 0.06555062 0.9567136 -0.2782813 0.08519858 0.9604191 -0.2785277 0.004177331 0.9317878 -0.3629969 -0.00220108 0.8538569 -0.5205078 4.75489e-4 0.8242756 -0.5661853 -0.002033829 0.6829737 -0.7304408 0.001833319 0.6513224 -0.7588009 -6.45695e-4 0.4144849 -0.9100553 0.00135678 0.4568814 -0.889526 -0.00172609 0.2279027 -0.9736828 0.001565217 0.1464439 -0.9892164 -0.00229007 0.1909967 -0.9814848 -0.01442223 0.3991327 -0.9160224 -0.03995215 0.4584453 -0.8882296 -0.02960377 0.6015396 -0.7968823 -0.05593711 0.9512864 -0.3068251 -0.03020888 0.6631447 -0.7470342 -0.0466808 0.7762238 -0.6273574 -0.06244474 0.8144088 -0.5782864 -0.0482009 0.9210484 -0.3813621 -0.07894885 0.9488447 -0.3117624 -0.04998058 0.8075203 -0.5787366 -0.1139081 0.3895729 -0.9181836 -0.07191622 0.4101735 -0.9092372 -0.07103127 0.9184132 -0.3810908 -0.1062404 0.5942764 -0.7972765 -0.1057631 0.5990496 -0.7933998 -0.1079648 0.9407542 -0.311797 -0.1332833 0.2248179 -0.973185 -0.04866266 0.7857938 -0.6042669 -0.1318702 0.9424402 -0.2975345 -0.1525774 0.189725 -0.9805713 -0.04984337 0.8289715 -0.5285663 -0.1828225 0.6086802 -0.7768263 -0.1613986 0.9233788 -0.3355194 -0.1865432 0.105372 -0.9938192 -0.03493165 0.9425443 -0.2438217 -0.2283888 0.7090761 -0.6742575 -0.2063688 0.8181093 -0.5397146 -0.1985076 0.4184384 -0.8977833 -0.137457 0.4262304 -0.8934408 -0.1417443 0.4748012 -0.8660843 -0.1564031 0.8811295 -0.3854086 -0.2739908 0.941269 -0.2437325 -0.2336817 0.715934 -0.656161 -0.2385191 0.8501589 -0.4391487 -0.2904796 0.8786892 -0.3851854 -0.2820242 0.614191 -0.7520983 -0.2389931 0.6715687 -0.6968993 -0.2516483 0.1833374 -0.9796203 -0.08204686 0.9209845 -0.2158958 -0.3243095 0.3624783 -0.9194523 -0.1523711 0.3945955 -0.8991566 -0.1892403 0.7701916 -0.5395507 -0.3401323 0.8233421 -0.4523228 -0.3428003 0.4994898 -0.8287683 -0.2522959 0.5623151 -0.7806342 -0.2727856 0.8714131 -0.2990965 -0.3888196 0.1964396 -0.9739757 -0.1130617 0.9029657 -0.2020972 -0.3792225 0.6468101 -0.6860616 -0.3331009 0.2842025 -0.944887 -0.162535 0.7454593 -0.5591444 -0.3628332 0.7840209 -0.4661267 -0.4099236 0.8545302 -0.3011097 -0.4232153 0.8670515 -0.2060738 -0.4536026 0.4130934 -0.8678481 -0.2760317 0.4808943 -0.8271694 -0.2907433 0.1270608 -0.9881246 -0.08640217 0.6250184 -0.6828999 -0.3781532 0.6591336 -0.6206608 -0.4246448 0.7502079 -0.4754009 -0.4595458 0.4134718 -0.8679904 -0.2750161 0.7875198 -0.3478468 -0.5087388 0.505657 -0.7767502 -0.3754602 0.1544005 -0.9810483 -0.1170675 0.8403755 -0.1995382 -0.5039381 0.6478599 -0.6273896 -0.4320415 0.2949585 -0.92693 -0.2319495 0.3269407 -0.9104284 -0.2534364 0.7770758 -0.325571 -0.5386621 0.5073637 -0.7629105 -0.4006868 0.6284369 -0.5977997 -0.4976975 0.6477907 -0.5738224 -0.5010939 0.4206056 -0.8299831 -0.3663594 0.7374955 -0.36618 -0.5674616 0.7384193 -0.3520407 -0.5751559 0.4565886 -0.7995703 -0.3901466 0.13891 -0.9816108 -0.1309359 0.2176132 -0.9511895 -0.2188217 0.7182603 -0.3052669 -0.6252314 0.5733696 -0.6108997 -0.5459385 0.5786137 -0.6041138 -0.5479531 0.238421 -0.9385127 -0.2496985 0.3553113 -0.8607965 -0.3643946 0.3410603 -0.8710547 -0.353471 0.6793327 -0.3546924 -0.6424176 0.6967509 -0.323075 -0.640438 0.4520854 -0.7457926 -0.4892976 0.5634182 -0.6183543 -0.5479034 0.6539322 -0.3108913 -0.689724 0.4530361 -0.727375 -0.5154453 0.4794525 -0.6667675 -0.5705667 0.5538341 -0.5483525 -0.62656 0.5773494 -0.4656011 -0.6707335 0.6376896 -0.3252419 -0.6982619 0.6340693 -0.1800426 -0.7520245 0.5889948 -0.1955693 -0.7841159 0.5901277 -0.1832379 -0.7862399 0.5395389 -0.4377323 -0.7192276 0.5345917 -0.4559319 -0.7115741 0.4463868 -0.6674684 -0.5960074 0.4493338 -0.6622905 -0.5995586 0.3575129 -0.803469 -0.4760486 0.3206537 -0.8447821 -0.4283977 0.3078976 -0.8584126 -0.4102766 0.190672 -0.9487337 -0.2520885 0.1454849 -0.9699202 -0.1951643 0.02434223 -0.9991647 -0.03282725 0.008938491 -0.9999065 -0.01035356 0.08604013 -0.2004677 -0.9759149 0.1243711 -0.1332035 -0.9832542 0.08225208 -0.3924013 -0.9161092 0.0467745 -0.4454154 -0.8941015 0.08525156 -0.6260918 -0.775075 0.06324023 -0.6650698 -0.7440987 0.2166477 -0.2311966 -0.9484788 0.1585414 -0.4385823 -0.8845962 0.2572299 -0.1620283 -0.9526698 0.1285257 -0.6042043 -0.7863958 0.1994544 -0.3954584 -0.8965661 0.1563529 -0.6311669 -0.7597249 0.2627141 -0.4887399 -0.8319344 0.08234655 -0.8289304 -0.553257 0.09389287 -0.8395468 -0.5351126 0.2558323 -0.487238 -0.8349545 0.05862748 -0.9192997 -0.3891673 0.3427454 -0.2853111 -0.8950549 0.3897901 -0.1980596 -0.8993532 0.174606 -0.7388468 -0.6508595 0.06453192 -0.9422428 -0.3286551 0.3242222 -0.4177831 -0.8487269 0.1483017 -0.8075233 -0.5708877 0.260485 -0.6542497 -0.7100034 0.03366291 -0.9800183 -0.1960384 0.4243371 -0.1968935 -0.8838389 0.3551036 -0.4509547 -0.8188658 0.3529722 -0.5609834 -0.7488046 0.4493732 -0.3393017 -0.8264007 0.1641893 -0.8379976 -0.5203863 0.2911334 -0.6627416 -0.6899384 0.1341299 -0.9249715 -0.3555797 0.4839577 -0.3674774 -0.7941948 0.549467 -0.1856984 -0.8146178 0.2785866 -0.7678385 -0.5769 0.4008094 -0.5507144 -0.732165 0.1349885 -0.9262012 -0.3520362 0.462292 -0.3800418 -0.8011583 0.2823309 -0.7735376 -0.5673877 0.05559164 -0.9897191 -0.1317794 0.3026529 -0.768154 -0.5642169 0.4027109 -0.6657254 -0.6281988 0.1920677 -0.9110288 -0.3648789 0.1924272 -0.9112628 -0.3641046 0.3113892 -0.8467558 -0.4313251 0.0555067 -0.9897986 -0.1312172 0.1409786 -0.9686574 -0.204519 0.002181887 -0.9906522 -0.1363952 -0.002005696 -0.954734 -0.2974541 0.001404762 -0.9171812 -0.3984681 -6.47873e-4 -0.8070887 -0.59043 6.61166e-4 -0.8288675 -0.5594446 0.002076745 -0.6956105 -0.7184161 -0.001612246 -0.590324 -0.8071648 0.002249598 -0.4477443 -0.8941588 -0.001799106 -0.2825502 -0.9592508 0.001567423 -0.1613526 -0.9868956 -0.2815272 -0.9595528 -0.001010775 -0.3279005 -0.9442684 0.02895945 -0.3736473 -0.9275584 -0.004820346 -0.4657796 -0.8848437 0.01006019 -0.4840068 -0.8750607 -0.002488195 -0.5692898 -0.8220739 0.01017665 -0.5963056 -0.8027274 -0.006959736 -0.6855496 -0.727967 0.009259819 -0.7095733 -0.7045714 -0.009213984 -0.7768338 -0.6293008 0.02257883 -0.8378363 -0.5458862 -0.006213366 -0.8484852 -0.5287078 -0.0232585 -0.8985509 -0.438308 0.02219426 -0.9479205 -0.3184977 -0.002463638 -0.9498609 -0.3126026 -0.006632208 -0.9631405 -0.2687237 0.01216888 -0.9919663 -0.1264472 0.0037418 -0.9934283 -0.1144134 -0.003135144 -0.9960306 -0.08866608 0.007844686 -0.9997602 0.01464432 0.01628619 -0.9946693 0.1007342 -0.02203673 -0.9900795 0.1399121 0.01292794 -0.9550839 0.2957018 0.01937413 -0.9327901 0.3589898 -0.03207963 -0.9035733 0.4280772 0.01747161 -0.8304014 0.5571412 0.005229473 -0.8168609 0.5767274 -0.01113098 -0.7904603 0.6125041 0.003368914 -0.7106527 0.7034979 0.007971405 -0.6920582 0.7218067 -0.007108926 -0.6139681 0.7892783 0.009111583 -0.5800242 0.8145831 -0.005148112 -0.5322848 0.8464556 0.01363605 -0.4367716 0.8995142 -0.01023066 -0.41598 0.9093398 0.007873415 -0.3006358 0.9537248 0.005225658 -0.3014059 0.9534875 0.004040122 -0.2237446 0.9745497 0.01382797 4.72849e-4 -0.9999998 5.78271e-4 0.006183624 -0.9999809 -1.09311e-4 -9.19014e-4 -0.9999947 0.003144443 -2.23681e-4 -0.9999996 -9.65765e-4 -0.00280708 -0.9999918 0.002955496 -0.001212537 -0.9999993 1.13959e-4 -0.001871466 -0.9999982 4.62595e-4 -0.001103579 -0.9999991 7.65108e-4 -0.001510977 -0.9999979 0.001477599 -0.001022934 -0.9999985 0.001430809 -0.001197695 -0.9999979 0.001698374 -0.001365661 0.9017091 0.4323412 0.01233547 0.8622637 0.5063096 0.02327102 0.8536473 0.5203315 -0.004088342 0.8174812 0.5759409 0.004089951 0.7682085 0.6401867 0.01508659 0.7541515 0.6565274 -0.01050072 0.6874736 0.7261335 0.01677829 0.6594719 0.751542 0.01934403 0.5572162 0.8301421 -0.0247997 0.5167341 0.8557868 0.02918094 0.4226193 0.9058375 -0.009905636 0.3433696 0.9391482 0.01666414 0.3092633 0.9508305 -0.009393632 0.1816431 0.9833196 0.009103417 0.1649361 0.9862623 0.02027946 0.05494266 0.9982836 -0.02080196 -0.008724868 0.9997456 0.02523839 -0.06506133 0.9975621 -0.0254383 -0.1998354 0.9794993 0.005827486 -0.2252376 0.9742864 -0.01131248 -0.3879761 0.9216001 0.01883405 -0.3610576 0.9323533 -0.01343494 -0.5572543 0.8302332 0.02330517 -0.5100088 0.8598535 0.01926922 -0.6066979 0.794699 0.001763641 -0.69878 0.7153345 -0.002814054 -0.7027724 0.7114092 0.01117569 -0.7820775 0.623081 1.59669e-4 -0.7958096 0.6055471 0.01141619 -0.8447031 0.5351133 -0.004105389 -0.8610149 0.5085632 0.008307695 -0.8929926 0.4499947 0.005245923 -0.8982821 0.4393879 0.08070039 0.9965603 0.01884216 0.2560243 0.9655076 0.04739862 0.323772 0.9438991 0.06500905 0.414409 0.9067792 0.07756906 0.6007705 0.7900977 0.121739 0.6293047 0.7672678 0.1235951 0.7666108 0.6240532 0.1512141 0.7842222 0.6014294 0.1525727 0.8802417 0.4407449 0.1758363 0.8937286 0.412905 0.1753823 0.950957 0.2473486 0.185741 0.960791 0.200747 0.1912626 0.9744013 0.1176275 0.1915875 0.970627 0.2281022 0.07650303 0.9557824 0.2880848 0.05905157 0.8976786 0.4327333 0.08315658 0.8483855 0.525846 0.06106001 0.7939139 0.603495 0.07412636 0.6974416 0.7151724 0.04586631 0.6276924 0.7759655 0.06228846 0.5140059 0.8569977 0.0367816 0.1048763 0.9944845 -0.001316368 0.2297153 0.9732562 0.001834273 0.3268526 0.945074 -0.001573204 0.4821979 0.8760606 0.001759648 0.5656419 0.8246468 -0.002612531 0.6976839 0.7164058 -2.30085e-4 0.7492727 0.6622523 -0.003538489 0.861491 0.5077708 -0.00142914 0.8594294 0.5112519 -0.001714408 0.950245 0.3115005 0.001419186 0.9574767 0.2885109 8.05627e-6 0.3078835 0.8840116 -0.3517548 0.3023884 0.8872121 -0.3484481 0.4547417 0.737553 -0.4992249 0.1580472 0.9734879 -0.1653555 0.4805546 0.6748096 -0.5600887 0.5720266 0.5168617 -0.6368984 0.5860803 0.4362396 -0.682792 0.6424465 0.2405509 -0.7275973 0.6423372 0.2206295 -0.7339793 0.3553688 0.8702031 -0.3412619 0.4588044 0.7795468 -0.4263865 0.4837828 0.7428223 -0.4627844 0.175165 0.9717987 -0.1578755 0.5883532 0.6019583 -0.5398951 0.299744 0.9185433 -0.2577434 0.6242756 0.4961835 -0.6033921 0.6847065 0.3510729 -0.6386899 0.1093312 0.9906353 -0.08178228 0.6897162 0.2575988 -0.6767086 0.3625205 0.8900352 -0.2764348 0.3901232 0.8730221 -0.2926368 0.7162154 0.3250057 -0.6175814 0.4844731 0.7847551 -0.3865815 0.6047898 0.6566595 -0.450586 0.6302019 0.5898303 -0.5049214 0.7310081 0.359515 -0.5799795 0.7588522 0.3182823 -0.56819 0.2169746 0.966845 -0.1346582 0.2139125 0.9677715 -0.1328909 0.6324867 0.6398477 -0.4365267 0.4574527 0.8446414 -0.2780612 0.746514 0.4310913 -0.5068306 0.7600392 0.3198217 -0.5657339 0.627788 0.6592789 -0.4138041 0.3287292 0.9270414 -0.1803649 0.4523889 0.8505902 -0.2680313 0.805471 0.357111 -0.4729568 0.8205425 0.2046304 -0.5337008 0.6850785 0.6117737 -0.3954749 0.7904216 0.4194386 -0.4464358 0.803963 0.3538302 -0.4779622 0.594548 0.7506522 -0.2881565 0.6663146 0.6639809 -0.3393439 0.8650506 0.1837925 -0.466806 0.3391083 0.9278698 -0.1551238 0.7631649 0.5338482 -0.364123 0.4666154 0.8618292 -0.1987983 0.8025736 0.4195644 -0.4240772 0.5848741 0.7656353 -0.2678151 0.1495286 0.9869 -0.06057733 0.8735171 0.2463321 -0.4198671 0.2695608 0.9569227 -0.1078706 0.8110314 0.4815548 -0.3321644 0.8917824 0.2199005 -0.3954338 0.6903479 0.6801475 -0.2466157 0.8969137 0.2017548 -0.3934982 0.3462485 0.9320184 -0.1070225 0.8071224 0.4982866 -0.3166451 0.4860535 0.8584613 -0.1636957 0.07738935 0.9966785 -0.02535849 0.5804581 0.7941508 -0.17998 0.6862549 0.6873177 -0.2380098 0.8892416 0.3621186 -0.2794988 0.2626581 0.9633662 -0.05419057 0.329798 0.9405028 -0.0817793 0.9256511 0.1905984 -0.3268676 0.7537684 0.6204966 -0.2163732 0.8907588 0.3755569 -0.2559414 0.8766925 0.415101 -0.2431077 0.5919806 0.7939803 -0.1384001 0.5428716 0.8318544 -0.1153629 0.7229018 0.6720082 -0.1606798 0.7074486 0.6897416 -0.1541847 0.9487036 0.2066315 -0.2393009 0.8555826 0.4877994 -0.1732927 0.2782999 0.9597296 -0.0383169 0.3271102 0.9443364 -0.03504008 0.8821414 0.4461296 -0.1509799 0.5466447 0.8348823 -0.06443035 0.5537645 0.82995 -0.06728988 0.9440875 0.2897216 -0.1573541 0.7081271 0.7005395 -0.08831989 0.9632465 0.1957951 -0.1839032 0.7441451 0.6627084 -0.08405792 0.8479818 0.5200485 -0.1023547 0.971933 0.2105618 -0.1049296 0.896326 0.4374908 -0.07212191 0.961409 0.2646448 -0.07520622 0.9781528 0.2045051 -0.03734701 0.07848757 0.9915602 -0.1031899 0.1019746 0.9853692 -0.1365609 0.2233897 0.9276748 -0.2991932 0.2828522 0.8829658 -0.3746548 0.3318613 0.8324966 -0.4436412 0.4232342 0.7084398 -0.5647885 0.4394337 0.682458 -0.5840798 0.5391009 0.4397763 -0.7183085 0.5408406 0.4330704 -0.7210698 0.5726313 0.2957683 -0.7646009 0.5863661 0.2191652 -0.7798343 0.5032784 0.2274392 -0.833656 0.4869247 0.2416011 -0.8393648 0.458038 0.4946542 -0.7385922 0.4503873 0.2068221 -0.8685483 0.4414309 0.4782829 -0.7591997 0.40368 0.6775026 -0.6148436 0.3850064 0.2696399 -0.8826463 0.398899 0.5053333 -0.7651916 0.3536842 0.2190459 -0.9093551 0.3595289 0.4445679 -0.8204256 0.3289455 0.656771 -0.6785623 0.3284677 0.7087776 -0.6242942 0.3012164 0.5060639 -0.8081881 0.2643551 0.8091154 -0.5248323 0.2570031 0.8422042 -0.4739637 0.2908898 0.6446478 -0.7069741 0.1792458 0.9201903 -0.3480243 0.164114 0.9273735 -0.3362218 0.2612109 0.3015932 -0.9169572 0.2426843 0.4810415 -0.8424389 0.236136 0.2553148 -0.937579 0.09873706 0.9725404 -0.2107518 0.2428229 0.481729 -0.8420061 0.21208 0.823791 -0.5257287 0.1933606 0.7391244 -0.6452184 0.1564786 0.8978767 -0.4114998 0.1579359 0.2811375 -0.9465823 0.1941292 0.6279057 -0.7536898 0.1287067 0.2222858 -0.966449 0.2053054 0.7415085 -0.6387605 0.1610731 0.4420528 -0.8824085 0.1341046 0.2506105 -0.9587547 0.06204986 0.9826292 -0.1748993 0.0698226 0.1377344 -0.9880051 0.1411318 0.7904289 -0.5960739 0.1098465 0.6597456 -0.7434175 0.090366 0.5465867 -0.8325124 0.1133882 0.8331645 -0.5412764 0.05691468 0.4027917 -0.9135205 0.08781063 0.9109904 -0.4029716 0.1112506 0.6606849 -0.7423738 0.08493542 0.5419125 -0.8361321 0.05608934 0.9626802 -0.2647659 0.07849407 0.9199589 -0.3840761 0.03494477 0.768861 -0.6384603 -0.001353979 0.9941148 -0.1083245 0.001354753 0.982552 -0.1859835 8.68443e-4 0.910731 -0.4129995 -0.001580834 0.8846379 -0.466276 0.003235399 0.779895 -0.6259021 -0.001959204 0.6409967 -0.7675411 8.50106e-4 0.5785697 -0.8156327 0.001637697 0.3774201 -0.9260408 -0.001360237 0.2841795 -0.9587701 0.001136183 0.183191 -0.9830767 0.5206195 6.30771e-4 -0.8537886 0.5436828 -9.56518e-4 -0.8392903 0.4692162 -0.001052916 -0.8830828 0.4510299 3.85785e-4 -0.8925088 0.3643169 3.29527e-4 -0.931275 0.3517469 0.001082718 -0.9360945 0.2763896 -0.001157701 -0.961045 0.2519435 6.8572e-4 -0.9677418 0.1295339 -0.001479148 -0.9915739 0.1686184 7.66922e-4 -0.9856811 0.0239703 2.10018e-4 -0.9997127 0.03009492 5.42764e-4 -0.999547 0.05757123 0.00183779 -0.9983397 0.009378492 -0.001476466 -0.9999549 0.0307452 -3.01606e-5 -0.9995273 0.07850813 5.37188e-5 -0.9969135 0.03152573 -2.67999e-5 -0.999503 0.02627301 8.2911e-5 -0.9996548 0.07356154 0.001198589 -0.99729 0.02619796 -4.91689e-5 -0.9996568 0.009165287 -1.63342e-4 -0.999958 0.004514515 8.22396e-5 -0.9999899 0.00415492 6.91532e-4 -0.9999912 0.6002327 7.33893e-4 -0.7998252 0.6000082 3.99191e-4 -0.7999938 0.6602839 2.36772e-4 -0.7510161 0.6591619 4.73143e-4 -0.752001 0.7256703 1.56183e-4 -0.6880427 0.696331 -0.001705229 -0.7177187 0.7603567 4.19243e-4 -0.6495056 0.7244895 2.95705e-4 -0.6892859 0.7905785 1.87964e-4 -0.6123607 0.763038 7.58974e-5 -0.6463536 0.7920363 -9.17076e-5 -0.6104741 0.8421367 6.87536e-4 -0.5392639 0.8191966 -0.001537919 -0.5735108 0.8720264 0.002164244 -0.489454 0.8470296 -6.8674e-5 -0.5315456 0.9148178 2.84885e-4 -0.4038667 0.8933959 -0.001814484 -0.4492666 0.9171663 -4.62469e-4 -0.3985046 0.9500892 1.85547e-4 -0.3119785 0.9637759 -2.3008e-4 -0.2667131 0.9514349 -3.4932e-4 -0.30785 0.960241 0.00140506 -0.2791688 0.978352 -0.001698136 -0.2069411 0.9848294 -9.37561e-5 -0.1735256 0.9849522 -1.5191e-4 -0.1728271 0.9928175 3.34323e-5 -0.1196385 0.9938817 -0.001102924 -0.1104453 0.9966356 -0.002158522 -0.08193188 0.9994999 3.67149e-4 -0.03162014 0.9997149 -4.24228e-4 -0.0238797 0.9999716 -0.005714118 0.004926145 0.9999684 -0.007234752 0.003326535 0.9999253 -0.01218646 0.001005709 0.9999988 1.65408e-4 -0.001621127 0.9999992 -3.2902e-4 -0.001269459 0.9999992 -6.40637e-4 -0.001096427 0.999999 -0.001116454 -9.27653e-4 0.9999974 -0.002176821 -6.94838e-4 1 0 0 1 -1.46879e-5 -1.62217e-4 1 1.16409e-6 0 1 -4.08609e-6 0 1 3.81642e-6 0 1 -1.61433e-6 0 0.9999943 5.95928e-4 0.003344237 0.9999769 -8.96297e-4 0.006747961 0.9999947 0.001204073 0.003052175 1 1.42678e-6 0 0.9999955 0.002064168 0.002201676 0.9999992 -1.93413e-4 -0.0012905 0.9999998 -3.89424e-4 -5.24898e-4 0.999993 0.003456115 0.001471877 0.9999701 0.007724463 2.37861e-4 0.9999995 4.05554e-4 -8.86285e-4 0.9999994 1.23565e-4 -0.00118786 0.9999988 0.001493036 -4.14078e-4 0.9999806 0.006210744 5.99546e-4 0.9999977 -5.2191e-4 -0.002076506 0.9999995 8.15123e-4 -6.33712e-4 0.9999988 -1.83176e-4 -0.001538157 0.9999164 -0.01291286 8.03751e-4 0.9999786 4.6174e-4 0.006528377 0.9996934 3.25281e-4 0.02476191 0.9998527 -0.002160131 0.01703584 0.9993924 -0.001081347 0.03483992 0.9416054 0.002702236 0.3367076 0.9973177 4.44004e-4 0.07319438 0.9967191 0.001031696 0.08093243 0.9927324 -4.61108e-4 0.1203428 0.9927052 -4.53443e-4 0.1205672 0.9805956 -0.002634406 0.1960241 0.9807266 -4.94754e-4 0.1953844 0.981984 -0.00626713 0.18886 0.9807767 -7.00046e-5 0.1951337 0.9808856 5.03742e-4 0.1945853 0.9740114 0.008254587 0.2263485 0.9766147 -0.01484966 0.214484 0.9799966 0.001894891 0.1990052 0.9807471 -1.50725e-4 0.1952822 0.9805818 -4.18866e-6 0.1961109 0.9806503 -2.54971e-4 0.1957676 0.9805811 0 0.1961143 0.9807085 -2.04384e-4 0.1954756 0.98058 2.45367e-6 0.1961197 0.9805803 -3.63026e-6 0.1961183 0.9800972 0.003357946 0.1984899 0.9805809 1.66394e-6 0.196115 0.980581 0 0.1961145 0.9800747 0.001143753 0.1986261 0.9808171 1.26717e-4 0.1949303 0.9808915 -8.41621e-5 0.1945555 0.9807424 4.2562e-4 0.1953058 0.98071 6.60043e-4 0.1954677 0.9803706 0.00391072 0.1971252 0.9800389 -6.75475e-4 0.1988047 0.9802414 2.15862e-4 0.1978055 0.9806787 0.001024425 0.1956228 0.9803375 -0.001222491 0.1973245 0.9800246 0.001342654 0.1988719 0.9805953 0.005270063 0.1959727 0.9805237 0.004604339 0.1963468 0.979926 -0.001361131 0.1993572 0.9802475 0.004081308 0.1977327 0.9807159 0.003328382 0.1954107 0.9799302 -0.002118825 0.1993302 0.9820398 8.78126e-4 0.188672 0.9810303 -0.00204277 0.193844 0.9811359 -8.64445e-4 0.1933177 -0.9739382 0.2268137 -1.00662e-4 -0.9638928 0.2662889 9.53461e-4 -0.8669475 0.4983993 4.11682e-4 -0.8510477 0.5250872 0.001144409 -0.7131354 0.7010263 -7.37851e-5 -0.5959968 0.8029841 0.002101957 -0.575228 0.8179922 0.001237034 -0.3824797 0.9239633 -0.00111854 -0.1881124 0.9821458 0.001855313 -0.2625063 0.9649303 1.84966e-4 -4.16598e-6 0.00123012 -0.9999993 7.53312e-5 9.05465e-4 -0.9999996 -3.16544e-4 6.0927e-4 -0.9999998 0.001122653 0.001505434 -0.9999982 2.43734e-6 0 -1 0 0 -1 9.40816e-7 0 -1 -5.83072e-6 0 -1 -2.40183e-5 4.8634e-5 -1 -1.45532e-5 -0.003418326 -0.9999942 -1.54787e-7 0 -1 -2.35332e-6 0 -1 -4.15638e-7 0 -1 -9.68516e-7 0 -1 -3.96579e-7 0 -1 5.06524e-4 -0.001284539 -0.9999991 -3.85965e-4 -6.13689e-4 -0.9999998 0.001025497 -0.001463472 -0.9999985 -0.001339316 0.9999991 3.61338e-4 0.005763173 0.9999833 -4.74615e-4 -0.001916348 0.9999975 0.001144051 -0.0018332 0.9999978 0.001100242 -0.00183916 0.9999978 0.001099348 -0.001614332 0.9999985 6.16554e-4 -5.9708e-4 0.9999999 2.88258e-4 -0.002222061 0.9999932 0.002957522 0.001705884 0.9999973 0.001603066 -0.001476883 0.9999967 -0.002077162 0.001254439 0.9999962 -0.002501845 -0.6480562 0.3290419 0.686844 -0.7156854 0.2278126 0.6602241 -0.4981237 0.7131333 0.4932685 -0.6183428 0.4954847 0.6100386 -0.5967694 0.5755616 0.5591022 -0.7175735 0.27666 0.6391773 -0.4149969 0.8021908 0.429264 -0.5491313 0.6526978 0.5219583 -0.2647815 0.9359574 0.232109 -0.7041953 0.4369552 0.5596241 -0.4956185 0.7521355 0.4343437 -0.7961477 0.2058318 0.5690187 -0.3731389 0.8653181 0.3346521 -0.785278 0.2378178 0.5716478 -0.54253 0.7240828 0.4258701 -0.702096 0.5057712 0.5012552 -0.8069229 0.2891367 0.515049 -0.5749225 0.7010225 0.421938 -0.7532202 0.4510672 0.4787461 -0.4077231 0.8568062 0.315666 -0.4441663 0.8404152 0.3105134 -0.3626588 0.8901169 0.2759901 -0.8190608 0.269487 0.5064744 -0.6084685 0.6947156 0.3835836 -0.5651306 0.7560885 0.3300872 -0.7342624 0.5590783 0.3850849 -0.8617554 0.2589561 0.4362562 -0.2795609 0.9339583 0.222638 -0.1208426 0.9890596 0.08460724 -0.8535026 0.329069 0.4040384 -0.5087352 0.804023 0.3077913 -0.7344315 0.5590484 0.3848057 -0.4258788 0.8738182 0.2346682 -0.3267182 0.9263456 0.1874543 -0.7950838 0.4818505 0.368323 -0.1474596 0.9865902 0.06996905 -0.9010103 0.2557571 0.3503839 -0.9004061 0.2603983 0.3485136 -0.646337 0.7045531 0.2930076 -0.6332452 0.7170121 0.2913662 -0.7874437 0.5289539 0.3164495 -0.4641245 0.8614179 0.2062709 -0.843093 0.4652937 0.2696218 -0.9521823 0.1896556 0.2395408 -0.5644236 0.8003854 0.2020131 -0.6615237 0.7158827 0.2233794 -0.2879451 0.9483855 0.1328634 -0.8450046 0.456032 0.2792889 -0.6112247 0.7572674 0.2301096 -0.9205802 0.3525054 0.1681434 -0.8126521 0.5476852 0.1990923 -0.949522 0.261053 0.1739526 -0.2795515 0.9559223 0.08979815 -0.91101 0.3908817 0.131424 -0.4490304 0.8849183 0.1236582 -0.6699329 0.7294192 0.1383386 -0.6202136 0.771018 0.1444523 -0.2582545 0.962608 0.08179712 -0.4030416 0.9109428 0.08798152 -0.8942706 0.4258609 0.1375602 -0.8209457 0.5637477 0.09075647 -0.9699683 0.227244 0.08672797 -0.961525 0.2654304 0.07082825 -0.6214498 0.7775876 0.09569627 -0.433475 0.8973618 0.08271241 -0.8455879 0.5308065 0.05679672 -0.1758363 0.9842234 0.01964539 -0.7341395 0.6779213 0.0382362 -0.3544951 0.9344849 0.03273081 -0.5309963 0.8447835 0.06621152 -0.1366742 0.9760167 0.1694453 -0.1819195 0.9574718 0.2239488 -0.2743901 0.8990832 0.3411151 -0.3217148 0.85922 0.3977947 -0.4386209 0.714667 0.5448513 -0.4196812 0.744561 0.5191308 -0.5495662 0.485415 0.6799627 -0.534865 0.5237116 0.6630578 -0.6086025 0.2363867 0.7574459 -0.6008363 0.2889617 0.7453168 -0.1393759 0.9667174 0.2145501 -0.2897328 0.8663835 0.4067365 -0.3840593 0.7155624 0.5834972 -0.4165996 0.6816069 0.6015454 -0.1464372 0.9336816 0.326795 -0.294704 0.8147574 0.4993197 -0.4957879 0.4494116 0.7431176 -0.1051629 0.9715676 0.2121255 -0.330675 0.6832135 0.6510556 -0.4433914 0.5098798 0.7371749 -0.2021651 0.8710873 0.4475893 -0.5130679 0.2662113 0.8160227 -0.04464977 0.9889337 0.1414801 -0.3305276 0.6906535 0.6432335 -0.5111394 0.2491508 0.8225938 -0.1872496 0.9109028 0.3676869 -0.424416 0.4697581 0.7740792 -0.1980752 0.7831321 0.5894661 -0.3169329 0.5511174 0.7718958 -0.439664 0.3119465 0.8422501 -0.3774143 0.4138252 0.8284366 -0.3199518 0.5744264 0.7534356 -0.1176294 0.9220595 0.3687405 -0.1182971 0.8966243 0.4266973 -0.3800303 0.2007594 0.9029245 -0.1805538 0.7512021 0.6348983 -0.2088212 0.6521068 0.7288007 -0.2855606 0.4927976 0.8219525 -0.2214071 0.68761 0.6914994 -0.2704877 0.4163029 0.8680601 -0.3618096 0.2250196 0.9046878 -0.1531437 0.7360157 0.6594148 -0.3098441 0.1571636 0.937708 -0.1817411 0.4903351 0.8523742 -0.2063946 0.4601837 0.8635001 -0.2439469 0.2242009 0.9435168 -0.2195934 0.1871381 0.9574748 -0.1473392 0.1225484 0.9814648 -0.1426196 0.2217629 0.9646145 -0.1385636 0.3573361 0.9236401 -0.128951 0.4620801 0.8774131 -0.1227496 0.5646274 0.8161669 -0.1001141 0.7229388 0.6836203 -0.09724944 0.7508166 0.6533123 -0.07105004 0.8819113 0.4660307 -0.06076353 0.9090973 0.4121285 -0.03049916 0.9796617 0.1983256 -0.02570241 0.9871966 0.1574242 -0.1812224 -0.9834421 -4.35435e-4 -0.2887437 -0.9574046 0.001935958 -0.4151946 -0.9097322 -9.82009e-4 -0.6322568 -0.7747589 4.41885e-4 -0.6822201 -0.7311427 0.002498924 -0.7802744 -0.6254373 3.25549e-4 -0.8953654 -0.4453314 8.37593e-4 -0.9249264 -0.3801409 0.002083301 -0.9544667 -0.2983175 -7.05775e-5 -0.9515115 -0.2959367 0.08394825 -0.8959941 -0.444066 -2.86725e-4 -0.9447172 -0.3090468 0.109542 -0.9235506 -0.3592265 0.1342046 -0.646483 -0.7596283 0.07088506 -0.8222231 -0.5619544 0.09031295 -0.7721449 -0.6278932 0.09768646 -0.6459724 -0.760044 0.07108503 -0.1813353 -0.9831897 0.02134603 -0.6200829 -0.7819439 0.06372708 -0.9250691 -0.30853 0.2214873 -0.4025746 -0.9135133 0.0585435 -0.9017127 -0.393874 0.1782623 -0.7086209 -0.6915251 0.1401773 -0.3327993 -0.9422503 0.03753733 -0.5079526 -0.8571913 0.08489626 -0.1468342 -0.9888553 0.02459585 -0.8049493 -0.5621177 0.1899485 -0.7283903 -0.6717922 0.1346959 -0.8873846 -0.3691332 0.276205 -0.8901557 -0.3646996 0.2731611 -0.8537713 -0.4401272 0.2781418 -0.7849937 -0.5796461 0.2186215 -0.7243529 -0.6508008 0.2275331 -0.5383669 -0.8325022 0.1307722 -0.8787934 -0.3687912 0.3028452 -0.8807979 -0.3413028 0.3281883 -0.328414 -0.9397797 0.09464937 -0.6593438 -0.7262787 0.1943838 -0.2986349 -0.950878 0.08153808 -0.8970174 -0.2151686 0.3860858 -0.1534258 -0.987116 0.04541558 -0.7191244 -0.6310627 0.2908951 -0.4380409 -0.8859508 0.1523526 -0.8194153 -0.3985647 0.4119526 -0.4629392 -0.8663882 0.1872403 -0.6464359 -0.728266 0.2274848 -0.723238 -0.6233454 0.2972663 -0.5697917 -0.7797051 0.2596101 -0.2356767 -0.9671447 0.09532982 -0.8465429 -0.2166119 0.4862555 -0.8133596 -0.4290841 0.3928524 -0.4547411 -0.8705874 0.1878514 -0.8465027 -0.2068293 0.4905657 -0.6338323 -0.69707 0.3351867 -0.7636478 -0.48909 0.4214655 -0.4725713 -0.844951 0.2504682 -0.6450206 -0.6652984 0.3759343 -0.7579914 -0.4086767 0.5083626 -0.7928017 -0.2023977 0.574892 -0.4409726 -0.8616729 0.2511236 -0.2324815 -0.9682262 0.09214359 -0.7914398 -0.2395798 0.5623385 -0.6310289 -0.6765152 0.3796443 -0.7080946 -0.4728835 0.5243886 -0.1870009 -0.9773585 0.09900099 -0.6359755 -0.6259052 0.4514178 -0.7180899 -0.427506 0.5491681 -0.7218509 -0.3048005 0.6213116 -0.5775416 -0.6667749 0.4710168 -0.4303824 -0.8513739 0.2998893 -0.4150719 -0.860023 0.2967756 -0.2108515 -0.9657617 0.1511489 -0.2154302 -0.9643963 0.1533936 -0.7016402 -0.180864 0.6891947 -0.5803566 -0.6269107 0.5197781 -0.6591181 -0.4169531 0.6258702 -0.6137032 -0.5104286 0.6023547 -0.6625313 -0.2601273 0.7024145 -0.4641595 -0.7952444 0.3900541 -0.5523872 -0.6522542 0.5190694 -0.3570158 -0.8700384 0.3399603 -0.5509844 -0.5620768 0.6168355 -0.4119371 -0.7933495 0.4482238 -0.4667912 -0.7462495 0.4745711 -0.3194658 -0.9037204 0.2850106 -0.125363 -0.9834277 0.1309738 -0.258226 -0.9289442 0.2652962 -0.1618435 -0.9664503 0.1994503 -0.1251415 -0.9799079 0.1553068 -0.2493923 -0.9172311 0.3106294 -0.2640414 -0.907046 0.3279478 -0.3362678 -0.8446244 0.4165739 -0.4100437 -0.7557169 0.5106428 -0.4602997 -0.6807313 0.56985 -0.5045022 -0.5945393 0.6260996 -0.5726178 -0.41439 0.7073824 -0.5498144 -0.4815896 0.6824776 -0.6173313 -0.192205 0.7628626 -0.6033369 -0.2738788 0.7489827 -0.5273609 -0.3290071 0.783355 -0.5684221 -0.2763842 0.7749247 -0.4800546 -0.4849604 0.731 -0.4660359 -0.6036446 0.6468569 -0.3578987 -0.7284303 0.5842071 -0.4526038 -0.3335189 0.8269916 -0.4606701 -0.3210611 0.8274677 -0.4200648 -0.5435627 0.7266948 -0.3778699 -0.5997377 0.7053575 -0.4239651 -0.1399274 0.8948038 -0.3645678 -0.8610811 0.3544427 -0.3299203 -0.7519597 0.5707096 -0.3672069 -0.3244432 0.87172 -0.3578119 -0.7231329 0.5908042 -0.3764904 -0.4084728 0.8315076 -0.3244854 -0.5441887 0.7736718 -0.2019702 -0.8981726 0.3905051 -0.329487 -0.63485 0.698859 -0.2956757 -0.2210857 0.929353 -0.07241952 -0.986502 0.1468646 -0.2265407 -0.7763975 0.5881211 -0.3121399 -0.3020762 0.9007323 -0.1948031 -0.9149491 0.3534401 -0.2334667 -0.6229969 0.746571 -0.2731304 -0.4072227 0.8715329 -0.2770056 -0.5567946 0.7831013 -0.2306586 -0.8025576 0.5501798 -0.1230314 -0.9243889 0.3610659 -0.08859229 -0.9720602 0.2173714 -0.2382808 -0.6701819 0.7029073 -0.2185914 -0.3073506 0.9261498 -0.2130445 -0.3148401 0.9249259 -0.1240428 -0.8822873 0.4540734 -0.1774516 -0.5069769 0.8434959 -0.08873486 -0.9719891 0.2176314 -0.1948454 -0.5887205 0.7845022 -0.1416887 -0.7595906 0.6347807 -0.1449038 -0.2258332 0.9633288 -0.1375406 -0.3243348 0.9358898 -0.1310962 -0.47205 0.8717698 -0.1180747 -0.5835373 0.8034568 -0.1055932 -0.7034497 0.7028576 -0.1031224 -0.7170691 0.6893314 -0.07619416 -0.8599069 0.5047324 -0.07554793 -0.863592 0.4984991 -0.03878551 -0.9649966 0.2593788 -0.03392916 -0.9753596 0.2179964 0.001278638 -0.9999683 -0.007862448 -0.1686978 0.9777321 0.1248245 -0.5289317 0.8377572 0.1356253 -0.2810694 0.2477347 0.927161 -0.7150586 0.6855455 0.1368163 -0.2915949 0.1660547 0.9420182 -0.3029299 0.1878661 0.9343126 -0.8344596 0.5222821 0.1757796 -0.8986794 0.4210637 0.1228039 -0.3334677 0.1433891 0.9317934 -0.346833 0.1614563 0.9239257 -0.3553115 0.101656 0.9292039 -0.3524813 0.09947013 0.9305174 -0.3762116 0.04722762 0.9253294 -0.3708176 0.04300045 0.9277098 -0.9613959 -0.1577287 0.2254766 -0.8406332 -0.5163894 0.1633332 -0.3660179 -0.1595308 0.916832 -0.6029263 -0.7640664 0.2295268 -0.5760907 -0.8036554 0.1491899 -0.3441454 -0.1980296 0.9177953 -0.2961803 -0.2410255 0.9242208 -0.2671532 -0.9441283 0.1930055 -0.2437955 0.5562694 0.7944358 -0.3515378 0.6819648 0.6413621 -0.438136 0.856767 0.2720062 -0.1992545 0.13271 0.97092 -0.5881363 0.7476632 0.3083757 -0.5980535 0.3639754 0.7140406 -0.1869437 0.02384746 0.9820812 -0.9526943 0.1618424 0.257256 -0.6214222 0.1133775 0.7752292 -0.9654408 0.0217747 0.2597114 -0.9602465 0.01565045 0.2787148 -0.6396874 0.009686112 0.7685741 -0.9064897 -0.3380107 0.2530322 -0.2550914 -0.02007842 0.9667085 -0.2744606 -0.07905036 0.9583437 -0.7025191 -0.6542211 0.2801101 -0.1744629 -0.02287554 0.9843981 -0.5923318 -0.7314723 0.3377743 -0.4567762 -0.4864097 0.7448229 -0.4813011 -0.8503146 0.2128723 -0.4471859 -0.4733374 0.7589312 -0.3222335 -0.9444566 -0.06455498 -0.3797631 -0.6289024 0.678426 -0.3478327 -0.4932241 0.7973346 -0.3454959 -0.7758756 0.5278728 -0.3135679 0.929417 0.194575 -0.2974585 0.8732557 0.3859316 -0.2952207 0.9192243 0.2605213 -0.2943619 0.7179794 0.6307588 -0.2871078 0.7114493 0.6414119 -0.2289588 0.3526701 0.9073047 -0.2712878 0.433119 0.8595411 -0.4483436 0.8671163 0.2170192 -0.4375764 0.8449417 0.3075716 -0.4031656 0.8091436 0.4274858 -0.4009567 0.7457579 0.5320515 -0.2865808 0.4384862 0.8518224 -0.195941 0.159446 0.9675661 -0.3503016 0.5546262 0.7547706 -0.4820886 0.6764562 0.5567744 -0.5199103 0.7383716 0.4295354 -0.4377048 0.5448786 0.7152076 -0.4736171 0.593062 0.6511255 -0.6212693 0.7592879 0.193666 -0.5897239 0.7525523 0.2930713 -0.2977865 0.2867016 0.9105632 -0.6297927 0.6216063 0.4657971 -0.3932977 0.3915714 0.8318587 -0.5385733 0.4413381 0.7177461 -0.5644987 0.5583049 0.6079777 -0.729048 0.6251046 0.2788069 -0.7316448 0.638838 0.2378697 -0.4334232 0.3487419 0.8309774 -0.4100717 0.3060742 0.8591623 -0.6700496 0.4890754 0.5584254 -0.7627165 0.5558472 0.3306018 -0.7500291 0.4985824 0.4345942 -0.7890097 0.4350336 0.4338314 -0.4389215 0.2263231 0.8695549 -0.7121381 0.3483397 0.6095234 -0.5119355 0.2603794 0.8186115 -0.8987325 0.3568607 0.2548143 -0.4907017 0.1669624 0.8551816 -0.9305217 0.2678281 0.2497951 -0.5384032 0.1610097 0.8271626 -0.7024518 0.143409 0.6971337 -0.7395275 0.1450912 0.6573033 -0.9761974 0.1352233 0.1695684 -0.5457957 0.1127992 0.8302913 -0.8697658 0.06483668 0.4891868 -0.8192452 0.05001842 0.5712578 -0.9553025 -0.03443163 0.2936182 -0.5846376 0.03206002 0.8106609 -0.4132831 0.02457535 0.9102709 -0.792532 0.02406269 0.6093556 -0.9156148 -0.09443002 0.3908103 -0.9132427 -0.05665236 0.4034581 -0.81507 -0.03485667 0.5783131 -0.9461985 -0.2095884 0.2465384 -0.7150532 -0.08381831 0.694027 -0.3830343 -0.01036679 0.923676 -0.5010739 -0.04874682 0.8640305 -0.709643 -0.1199342 0.6942785 -0.8990101 -0.237453 0.3679633 -0.8662583 -0.2222397 0.447444 -0.7329254 -0.1456788 0.6645285 -0.5101947 -0.07374864 0.8568913 -0.6731723 -0.1863961 0.7156085 -0.8927735 -0.3609601 0.2695618 -0.4514539 -0.09593278 0.8871226 -0.8835361 -0.4316985 0.1816611 -0.8715252 -0.4480164 0.1993116 -0.512362 -0.145929 0.84628 -0.3413308 -0.06319123 0.9378167 -0.783479 -0.3306195 0.5261667 -0.7669845 -0.3334717 0.5482075 -0.6261878 -0.2758331 0.7292496 -0.7902421 -0.5382472 0.2929293 -0.7719962 -0.6090399 0.1819134 -0.4433915 -0.1986711 0.874033 -0.6933358 -0.5462457 0.4700012 -0.5439066 -0.3890828 0.743492 -0.6804417 -0.7199734 0.136519 -0.5985999 -0.595179 0.5361345 -0.5769828 -0.4916889 0.6521755 -0.4332879 -0.3189185 0.8429429 -0.531935 -0.6382263 0.5565181 -0.5450378 -0.7069973 0.4506536 -0.2925114 -0.1663944 0.9416741 -0.4829462 -0.8511182 0.2058175 -0.4079643 -0.3680679 0.8355186 -0.4942024 -0.599379 0.6296895 -0.3240677 -0.2800566 0.9036308 -0.3690496 -0.8983919 0.2381059 -0.3917932 -0.8811165 0.2648242 -0.3295208 -0.9003281 0.284298 -0.247114 -0.2109324 0.9457497 -0.3352826 -0.6957768 0.6352009 -0.309106 -0.6757377 0.6692026 -0.2673939 -0.4549642 0.8494163 -0.2791667 0.8570389 0.4330708 -0.6074089 0.4264398 0.6702265 -0.8420047 0.4916539 0.2220469 -0.7871348 0.4190287 0.4525856 -0.6988674 0.3022699 0.6482416 -0.5307068 0.2332336 0.8148326 -0.9334929 0.2866927 0.2154026 -0.7249547 0.2713811 0.6330822 -0.7976963 0.2847717 0.531588 -0.6811836 0.2177143 0.6989917 -0.8498516 0.2139527 0.4816395 -0.6235013 -0.02361041 0.7814658 -0.7123144 -0.295026 0.6368422 -0.5175235 -0.2025043 0.8313612 -0.6998124 -0.4477785 0.5565583 -0.7163218 -0.5209811 0.4641787 -0.5752307 -0.3635721 0.7327516 -0.5740857 -0.359673 0.7355685 -0.5694421 -0.4810234 0.6665976 -0.6454683 -0.6297232 0.4322261 -0.3820123 -0.459079 0.8020681 -0.4250429 -0.6620193 0.6173079 -0.4055898 -0.7977311 0.4462311 -0.3083007 -0.8339716 0.4576483 -0.2847268 -0.416539 0.8633806 -0.2485691 -0.2764402 0.9283287 -0.6710585 0.6061931 0.4268612 -0.8370922 0.3529938 0.4179378 -0.8491685 0.2139952 0.482824 -0.909577 0.1484138 0.3881278 -0.7930389 -0.4440501 0.4170237 -0.7706078 -0.4092842 0.4885182 -0.7856783 -0.5315745 0.3164464 -0.6785264 -0.6234967 0.3883991 -0.4764408 -0.7767896 0.4118281 -0.4490894 -0.7663015 0.4594573 -0.8276038 -0.1759822 0.5330124 -0.1506102 -0.002742409 0.9885895 -0.1484063 -0.003183662 0.9889214 -0.1488267 -0.002745568 0.9888595 -0.146895 -0.0042997 0.9891427 -0.148132 -3.14568e-4 0.9889675 -0.1480932 2.0934e-4 0.9889734 -0.1481762 7.41147e-4 0.9889607 -0.1480907 8.44099e-4 0.9889734 -0.1478088 0.001284837 0.9890152 -0.1488454 7.27491e-4 0.9888603 -0.1484702 -1.26736e-4 0.9889169 -0.1492168 -0.001800835 0.988803 -0.1465559 3.94216e-7 0.9892024 -0.1465544 -1.87911e-7 0.9892027 -0.1492735 -4.38458e-4 0.9887958 -0.1499105 0.001539587 0.9886984 -0.1502058 0.001356601 0.9886539 -0.1490551 0.003173589 0.9888238 -0.1487249 0.004930555 0.9888664 -0.1480118 0.005224585 0.9889718 -0.1503608 0.003276765 0.9886258 -0.1464616 -0.004141926 0.9892077 -0.1471051 -0.001255214 0.9891201 -0.1464617 4.5288e-6 0.9892164 -0.1465486 4.14878e-4 0.9892035 -0.1497331 7.11076e-4 0.9887262 -0.1465486 0.00151354 0.9892024 -0.1503119 -8.08311e-4 0.9886384 -0.147257 -0.001820623 0.9890966 -0.2020789 0.004767715 0.9793577 -0.1781163 -0.002343475 0.9840067 -0.2047897 0.001278638 0.9788052 -0.2557049 -0.001417577 0.9667539 -0.260569 -0.002333104 0.9654524 -0.176566 -0.005707919 0.9842723 -0.2741432 -4.78093e-4 0.9616888 -0.2400002 -7.81261e-4 0.9707726 -0.2529963 1.37345e-4 0.9674673 -0.2376202 -0.002614736 0.9713546 -0.226413 -6.2309e-4 0.9740313 -0.2716932 6.02597e-5 0.962384 -0.2741473 -3.18354e-6 0.9616877 -0.279379 -3.07147e-6 0.960181 -0.2585005 -0.002829372 0.9660071 -0.3219109 -0.001453697 0.9467689 -0.3511668 -8.69811e-4 0.9363126 -0.3117072 0.00119543 0.9501774 -0.4380075 7.96047e-4 0.898971 -0.4024835 -0.002411365 0.9154242 -0.4922524 6.32893e-4 0.8704524 -0.5366584 -0.001149833 0.8437989 -0.5716196 6.10975e-4 0.8205186 -0.6278142 -5.16109e-4 0.7783631 -0.6272937 3.41511e-4 0.7787827 -0.998288 -3.81204e-4 0.05848902 -0.989942 1.87727e-4 0.1414737 -0.997368 -0.001170754 0.07249677 -0.977087 0.001371383 0.2128365 -0.9867922 -7.24568e-4 0.1619904 -0.9634921 -8.42263e-4 0.2677357 -0.947443 8.96924e-4 0.3199233 -0.9070066 8.84353e-4 0.4211157 -0.9351352 -0.001554727 0.3542877 -0.867908 0.001454114 0.496723 -0.8914539 -7.28397e-4 0.4531109 -0.8170852 9.59595e-4 0.5765164 -0.8477399 -2.11991e-4 0.5304123 -0.8061918 -2.49092e-4 0.5916544 -0.7511228 -1.33733e-4 0.6601626 -0.7545423 3.11681e-4 0.6562514 -0.6866215 3.39867e-4 0.7270151 -0.6866679 3.44978e-4 0.7269713 -0.999997 -0.002280652 -0.001038968 -1 0 0 -0.9999986 -0.001586079 6.05963e-4 -0.9999971 -0.002397418 -4.44394e-4 -1 -1.35521e-6 0 -1 1.84796e-6 0 -1 4.48741e-7 0 -1 -2.12899e-6 0 -1 -8.9828e-6 0 -1 1.01188e-5 0 -1 -2.44972e-6 0 -1 -5.50203e-6 0 -1 -5.77954e-6 0 -1 5.3684e-6 0 -1 6.06608e-6 0 -1 -1.02014e-6 0 -1 4.7317e-6 0 -1 2.02306e-5 0 -0.999998 -0.001977145 -2.58893e-5 -0.9999998 -6.23768e-4 2.61658e-4 -1 -8.65276e-6 0 -1 2.60486e-6 0 -1 -1.29758e-5 0 -1 2.46743e-6 0 -1 6.09356e-6 0 -1 8.9473e-7 0 -1 -7.88883e-6 0 -1 3.94924e-6 0 -0.9999997 8.60264e-4 -2.42743e-4 -1 -3.55579e-6 0 -1 3.36621e-4 2.41019e-4 -1 -3.71921e-6 0 -1 3.72092e-6 0 -0.9999999 4.92502e-4 1.27281e-4 -1 1.11781e-5 0 -0.9999994 0.001134395 -2.66432e-4 -1 -2.718e-6 0 -1 -7.47009e-6 0 -1 1.23933e-6 0 -0.9999986 -0.001746535 5.91542e-5 -0.9999998 -7.73269e-4 -1.53116e-4 -1 -3.63554e-4 -2.54546e-4 -1 -1.52079e-4 -3.1035e-4 -1 -2.01691e-6 -3.60767e-4 -1 1.99927e-4 -4.41744e-4 -1 -2.40011e-6 0 -1 1.08527e-5 0 -1 -2.94558e-6 0 -1 -1.29436e-5 0 -1 2.78151e-6 0 -1 1.06322e-5 0 -1 2.50469e-6 0 -1 -9.7142e-7 0 -1 -2.28653e-6 0 -1 -6.74017e-5 -3.25523e-4 -1 -6.92599e-6 0 -1 2.32434e-5 0 -0.9999999 6.51648e-4 6.98003e-6 -1 1.38829e-4 9.25362e-5 -1 1.8359e-5 7.92924e-5 -1 -6.68295e-5 3.94734e-5 -1 -1.47985e-4 9.43424e-6 -1 -4.49318e-6 6.07618e-5 -1 -3.22822e-5 5.22072e-5 -1 -2.14545e-4 -6.27806e-5 -6.72941e-4 0.9999647 0.008378028 0.001814961 0.9999904 -0.003991603 -0.3242025 0.9459342 -0.01006221 -0.5869138 0.8095682 0.01146179 -0.7703105 0.6375566 -0.01197856 -0.904205 0.4269995 0.009206235 -0.9997263 0.02331686 0.001924574 -0.9955768 0.09377682 -0.00573641 -0.9268363 -0.3754529 -0.003078877 -0.9122769 -0.4095702 0.001776099 -0.6063663 -0.7951842 0.001486003 -0.5821495 -0.8130741 -0.003554701 0.2521398 0.9672597 0.02888351 0.515596 0.8563522 -0.02866357 0.5736113 0.8191136 0.004803478 0.8075578 0.589757 0.006100177 0.8355125 0.5491928 -0.01750046 0.9691644 0.2458027 0.01735919 0.9815192 0.1911464 -0.009130299 0.9912018 -0.1323527 0.001293897 0.9927059 -0.120452 -0.005144476 0.910902 -0.4123646 0.01460266 0.882066 -0.4709503 -0.01285785 0.7072181 -0.7069924 0.002115428 0.6833462 -0.7298706 0.01808148 0.3942526 -0.9187188 -0.02282071 0.308502 -0.9510946 0.01567053 -9.20011e-4 -0.9999822 -0.005886673 2.94592e-4 -0.9999867 0.005171835 -0.230171 -0.9731121 -0.008611798 -0.4073607 -0.9131831 0.0124045 -0.59564 -0.803161 -0.0120657 -0.7350644 -0.6779194 0.01027858 -0.8701544 -0.4927129 -0.008090138 -0.9445011 -0.3283638 0.009751379 -0.9800468 -0.1986454 -0.00694704 -0.9858208 0.1677395 0.004587829 -0.9937622 0.1111161 -0.009488165 -0.9106105 0.4131555 0.009554147 -0.7994561 0.6006 -0.01222938 -0.7080229 0.7061526 0.007215559 -0.4538206 0.8910737 -0.005869209 -0.4213231 0.9069094 0.001513659 -0.001427948 -0.9999982 0.001316249 7.13272e-4 -0.9999276 0.01201307 8.8136e-4 0.9999983 -0.001643121 -0.001538157 0.9997031 -0.02432078 0.345091 -0.9384937 -0.01191675 0.6609239 -0.7503843 0.01015108 0.7552645 -0.6553949 -0.00577408 0.9582729 -0.285759 0.007412254 0.9834333 -0.1811046 -0.007761299 0.9281202 0.3722361 0.005759835 0.9184151 0.3956155 0.001488864 0.5969563 0.8022602 -0.004690527 0.5371128 0.8434865 0.006372809 -3.7365e-6 0 1 5.03639e-6 0 1 -3.49128e-6 0 1 0 0 1 4.01267e-7 0 1 5.73173e-6 0 1 -1.25008e-5 0 1 2.9957e-6 0 1 2.9462e-7 0 1 -1.80706e-7 0 1 9.10729e-6 0 1 -6.06227e-6 0 1 4.47176e-6 0 1 -2.9042e-6 0 1 -4.2745e-6 0 1 9.14544e-6 0 1 0.4507628 -0.8926433 -9.95436e-4 0.4644361 -0.8856061 0.001111388 0.8264331 -0.5630339 -0.001155436 0.8386071 -0.5447329 0.002032339 0.9958045 -0.09147143 -0.00256282 0.9996715 0.02311223 0.01108705 0.9476251 0.3191845 -0.01132398 0.7182456 0.6956642 0.01321738 0.6425741 0.7662076 -0.004946589 0.001260697 0.9999785 0.006442427 0.002144336 0.9999957 0.002018034 -9.19938e-4 -0.9999979 0.001892685 -5.57344e-4 -0.9999868 0.005120813 -0.2302042 -0.9731042 -0.008613705 -0.4073616 -0.9131827 0.01240432 -0.5956945 -0.8031205 -0.01206582 -0.7350623 -0.6779217 0.01027756 -0.8701782 -0.4926708 -0.008086383 -0.9445015 -0.3283625 0.0097512 -0.9800469 -0.1986449 -0.006946742 -0.9858192 0.1677483 0.004587829 -0.993762 0.111117 -0.009490907 -0.910609 0.4131587 0.009554028 -0.7994407 0.6006206 -0.01223099 -0.7080188 0.7061569 0.007213354 -0.4538894 0.8910387 -0.005860626 -0.4213224 0.9069097 0.00153464 -0.3242124 0.9459437 -0.008766889 -0.5220326 0.8528751 0.009277284 -0.7703337 0.637577 -0.009028553 -0.8357831 0.5490424 0.004379153 -0.9997155 0.02284485 0.006864368 -0.9955878 0.09379208 -0.002839863 -0.9267995 -0.3754308 -0.009716331 -0.8387693 -0.5443953 0.009991645 -0.5821326 -0.813049 -0.008558332 -0.5006873 -0.8656207 0.00363636 -9.45334e-4 -0.999996 -0.002660989 -2.39274e-4 -0.9999997 8.67432e-4 8.78899e-4 0.9999983 -0.001666188 -2.0509e-4 0.99993 -0.01182663 -2.49269e-6 0 1 -6.62015e-7 0 1 5.84902e-6 0 1 0 0 1 -5.63866e-6 0 1 0 0 1 -7.58962e-6 0 1 2.06705e-6 0 1 4.47201e-6 0 1 0 0 1 -3.26759e-6 0 1 6.56459e-6 0 1 0.403977 0.9144633 0.0236575 0.5160022 0.8559505 -0.03302258 0.7446164 0.6667525 0.03142702 0.8358309 0.5481463 -0.03037053 0.9648466 0.261613 0.02509522 0.9876733 0.1542169 -0.02680993 0.9923573 -0.1204094 0.02699208 0.9401479 -0.3387767 -0.03677517 0.9109926 -0.4124064 0.003667294 0.6833347 -0.7298545 0.01913666 0.6298267 -0.7763954 -0.02299457 0.2767831 -0.9609292 -0.002546787 0.3085222 -0.95115 0.01131457 1 -1.00192e-5 0 1 1.30938e-5 0 1 -3.27311e-6 0 1 2.34062e-6 0 1 -1.0742e-5 0 1 6.73053e-6 0 1 9.00298e-6 0 1 5.71639e-6 0 1 7.92915e-6 0 1 -9.48875e-6 0 1 -2.47664e-6 0 1 1.92353e-5 0 -0.01937437 -0.8414304 0.5400182 0.01780438 -0.932586 0.3605086 -0.01364517 -0.9874821 0.1571403 0.01364994 -0.9982329 -0.05783516 -0.0136432 -0.971064 -0.2384297 0.01364648 -0.8974555 -0.4408941 -0.01310557 -0.8045538 -0.5937352 0.01183676 -0.6636713 -0.7479307 -0.009230554 -0.5391224 -0.8421769 0.007452428 -0.3824834 -0.9239323 -0.009147703 -0.2413433 -0.9703968 0.01031273 -0.0973646 -0.9951954 -0.01063328 0.1287413 -0.9916213 0.01235711 0.2768289 -0.9608399 -0.0118702 0.4413741 -0.8972447 0.01287227 0.6504147 -0.7594704 -0.008005261 0.72863 -0.6848609 0.005234777 0.8941211 -0.4477948 -0.001769244 0.908411 -0.4180746 0.001951754 0.9951502 -0.09834748 -0.002062261 0.9966186 -0.08214151 0.002245962 0.9552418 0.2958179 2.09511e-5 0.9528727 0.3033706 -0.002298891 0.7657396 0.6431467 0.0104016 0.732327 0.6808738 -0.01137548 0.5070499 0.8618417 0.011684 0.3492562 0.9369545 -0.005683422 0.2465302 0.9691184 0.006805896 -0.02590352 0.9996413 -0.008995771 -0.1000194 0.9949448 0.009322881 -0.3815159 0.9243153 -0.01431745 -0.5122333 0.8587271 0.01469522 -0.6585013 0.7524361 -0.02002382 0.325024 -0.9454938 0.01662659 0.1305589 -0.9913012 -0.01247864 -0.1487801 -0.9887917 0.009519875 -0.3697118 -0.9290978 -0.008240938 -0.5072532 -0.8617578 0.01155167 -0.696209 -0.7177462 -0.01533406 -0.826106 -0.563306 0.01289039 -0.9466339 -0.322053 -0.01263314 -0.9940667 -0.108036 0.01472592 -0.9951378 0.09738671 -0.01656597 -0.933901 0.3571477 -0.002820611 -0.7254607 0.6882579 0.01321274 -0.7807385 0.6247181 -0.01127099 -0.323365 0.9462073 0.002378404 -0.3838472 0.9233936 0.01574134 0.02983433 0.999431 -0.02076578 0.3074191 0.9513477 0.008671104 0.4386258 0.8986281 -0.003311991 0.8033941 0.5954385 -0.005855858 0.809527 0.5870534 0.008190572 0.980332 0.1971852 -0.01450788 0.9949609 0.09920936 0.01402872 0.925061 -0.3795596 -0.02335083 0.8459085 -0.5328166 0.02110469 0.6402214 -0.7679005 1 8.67384e-6 0 1 2.60783e-6 0 1 6.20228e-6 0 1 3.52199e-6 0 1 4.82702e-6 0 1 -4.89398e-6 0 1 -7.9826e-6 0 1 4.23531e-6 0 1 -6.52786e-6 0 1 3.20614e-6 0 1 1.26469e-5 0 1 -3.9715e-6 0 1 1.55498e-5 0 1 -1.02994e-5 0 0.01580613 -0.7492345 0.6621163 -0.02256441 -0.8195621 0.572546 0.02311223 -0.9652238 0.2604014 -0.02196145 -0.9904507 0.1361078 0.02223575 -0.9858605 -0.1660871 -0.01671898 -0.9646865 -0.2628697 0.006354987 -0.8057037 -0.5922847 0.007173836 -0.8048957 -0.593373 -0.005926191 -0.5330723 -0.846049 0.005417108 -0.513634 -0.8579924 0.01879537 -0.1811918 -0.9832682 -0.004161536 -0.2321336 -0.972675 -0.02847796 0.07551229 -0.9967381 0.02980887 0.2447558 -0.9691265 -0.02075219 0.4170842 -0.908631 0.02101624 0.5569756 -0.830263 -0.02307218 0.6826292 -0.7304006 0.02571946 0.8230546 -0.5673797 -0.0239855 0.8948222 -0.4457778 0.02550017 0.9805884 -0.1944121 -0.002435326 0.9930216 -0.1179081 -0.01343488 0.991918 0.1261677 0.02656966 0.9697351 0.2427095 -0.02275985 0.8484062 0.5288565 0.01780986 0.7713055 0.636216 -0.01986157 0.5436574 0.8390722 0.02248537 0.4349018 0.9001972 -0.02196699 0.07067996 0.9972572 0.01871931 -0.0499463 0.9985765 -0.01187372 -0.3083214 0.9512082 0.01248681 -0.4467431 0.8945752 -0.009587764 -0.5434805 0.8393671 0.01439279 0.6114192 -0.791176 -0.008989632 0.3006801 -0.9536828 0.00160247 0.2473081 -0.9689356 -0.002070963 -0.2069896 -0.9783411 -0.007030844 -0.1894881 -0.981858 0.01317077 -0.6228273 -0.7822486 -0.01603621 -0.7321482 -0.6809566 0.00985527 -0.8931081 -0.4497341 -0.009983241 -0.9669051 -0.2549414 0.008195877 -0.9931369 -0.1166704 -0.01124078 -0.9760305 0.2173432 0.002950847 -0.958999 0.283394 0.007612824 -0.7903997 0.6125443 -0.01868462 -0.6945402 0.7192113 0.02083027 -0.4256479 0.9046492 -0.02155739 -0.185364 0.9824334 0.01976406 0.2084318 0.9778372 -5.42883e-4 0.2915041 0.9565694 -0.01137638 0.6660368 0.7458322 0.01688295 0.7525575 0.6583102 -0.01215642 0.9681259 0.2501694 0.004870414 0.9832356 0.1822748 -0.003174066 0.9542136 -0.2991094 0.01033872 0.9339693 -0.3572037 -0.01475834 0.7366542 -0.6761086 1 5.10249e-6 0 1 -4.1672e-6 0 1 3.14665e-6 0 1 -3.11544e-6 0 1 5.51674e-6 0 1 -2.72798e-6 0 1 7.14339e-6 0 1 7.43729e-6 0 1 -3.44828e-6 0 -0.004614233 -0.6952182 0.718784 0.01804661 -0.7491597 0.6621437 -0.01705455 -0.8982375 0.4391794 0.01971346 -0.9544786 0.2976273 -0.01881742 -0.9995114 0.02496129 0.01709991 -0.9948736 -0.09967076 -0.01992201 -0.9228859 -0.384558 0.005840182 -0.8940795 -0.4478703 0.01435685 -0.7240439 -0.6896045 -0.02633583 -0.6493663 -0.7600197 0.0197016 -0.317452 -0.9480698 0.00216329 -0.2865693 -0.9580571 -0.009720802 0.1135539 -0.9934843 0.02315127 0.1990858 -0.9797086 -0.0150116 0.3757151 -0.9266136 0.02357274 0.6042562 -0.7964414 -0.02600061 0.6929528 -0.7205139 0.02606952 0.912068 -0.4092097 -0.02063184 0.9542643 -0.2982517 0.01682579 0.999858 0.001025199 -0.01860117 0.9918304 0.1262005 0.01719325 0.9258552 0.3774873 -0.01679921 0.8439497 0.5361592 0.01251477 0.7537363 0.6570578 -0.01237589 0.5812466 0.8136335 0.01414459 0.4572293 0.8892364 -0.01424932 0.2886719 0.9573221 0.01670163 0.07227951 0.9972446 -0.01628333 -0.09870535 0.9949836 0.01949465 -0.3425237 0.939307 -0.01122987 -0.4539384 0.8909623 -0.006574094 0.2610133 -0.9653128 -0.004053235 0.2505069 -0.9681064 0.00657761 -0.1072736 -0.9942078 -0.006575107 -0.1897532 -0.9818099 0.00429964 -0.5312269 -0.8472188 -0.002749204 -0.5065892 -0.8621832 0.006129205 -0.8161247 -0.5778434 -0.01276385 -0.8764598 -0.4813059 0.01218241 -0.9682642 -0.2496317 -0.02026814 -0.9986629 0.04755789 0.0161693 -0.9736868 0.2273163 0.01587831 -0.7793357 0.6264054 -0.01002526 -0.7306645 0.6826632 -0.01863259 -0.4213685 0.9066981 0.01930165 -0.1887449 0.9818364 -0.01476001 0.073969 0.9971514 0.01180738 0.2707611 0.9625742 -0.01050746 0.5276057 0.8494244 0.009416937 0.6489127 0.7608046 -0.009434401 0.8099929 0.5863639 0.009276092 0.8935384 0.448891 -0.01033359 0.9822568 0.1872559 0.009521365 0.9971842 0.0743857 -0.009661793 0.9524319 -0.3045984 0.009164214 0.9150783 -0.4031721 -0.01038247 0.7308989 -0.6824068 0.01022189 0.6532823 -0.7570456 1 -1.37796e-5 0 1 9.25216e-6 0 1 -2.0672e-6 0 1 3.24224e-6 0 1 -1.3495e-6 0 1 5.08218e-6 0 1 6.26364e-6 0 1 -5.093e-6 0 0.004315376 -0.7519274 0.6592318 -0.01016062 -0.7868131 0.6171077 0.01123946 -0.9482451 0.3173406 -0.002800226 -0.9647573 0.2631268 -0.00987035 -0.9994815 -0.03064852 0.01887291 -0.9840986 -0.1766177 -0.01601576 -0.9200031 -0.3915839 0.0136578 -0.8101945 -0.586002 -0.01051348 -0.6839381 -0.7294643 0.009361088 -0.5718716 -0.8202898 -0.01471024 -0.3671172 -0.9300584 0.01113069 -0.2415621 -0.9703215 0.001177012 0.04716968 -0.9988862 -0.01909953 0.1328147 -0.9909569 0.01520204 0.3631892 -0.9315915 -0.01081824 0.5947016 -0.8038738 0.01135367 0.6846029 -0.7288278 -0.01287013 0.8281513 -0.560357 0.01383161 0.9386972 -0.3444652 -0.01162558 0.9732197 -0.229583 0.01358598 0.996656 0.08057457 -0.0145868 0.974722 0.2229447 0.01087993 0.9021044 0.4313807 -0.00879842 0.8148638 0.5795858 0.007079541 0.7274729 0.6861001 -0.009193301 0.594416 0.8041053 0.01274901 0.4706769 0.8822137 -0.01389002 0.2435678 0.9697844 0.01647955 0.05782639 0.9981907 -0.01030367 -0.1028995 0.9946384 0.004833281 -0.4171097 0.9088433 0.001875162 -0.408881 0.9125859 -0.0162779 0.601915 -0.7983943 0.01243233 0.3894926 -0.9209457 -0.01182168 0.1736768 -0.9847318 0.01282852 -0.01637792 -0.9997836 -0.01259982 -0.2784214 -0.9603765 0.01163089 -0.4919476 -0.8705472 -0.007792949 -0.6040523 -0.7969066 0.01246339 -0.8534071 -0.5210959 -0.002849817 -0.8858524 -0.4639587 -0.01100856 -0.9960152 -0.08850246 0.01565015 -0.9982824 0.05645847 -0.01045012 -0.9417303 0.3362064 0.01297754 -0.8589792 0.5118461 -0.01609849 -0.7176458 0.6962222 0.01346939 -0.5125409 0.8585572 -0.00912398 -0.2984995 0.9543662 0.005702853 -0.1895229 0.9818598 -0.00959444 0.0905717 0.9958438 0.01812738 0.2952162 0.9552586 -0.01786035 0.4926377 0.8700513 0.01556676 0.7928382 0.6092333 -0.008253812 0.8611231 0.5083296 0.005596399 0.9806014 0.1959333 -0.008423149 0.9941077 0.1080698 0.0123887 0.9790275 -0.2033513 -0.01662945 0.9194073 -0.3929553 0.01658779 0.7836156 -0.6210246 -0.4645099 -0.03845 0.8847329 -0.8500873 -0.02491098 0.5260525 -0.4507899 -0.1895421 0.8722743 -0.5953654 -0.2212973 0.7723779 -0.6758027 -0.2037425 0.7083641 -0.9548543 -0.06773334 0.2892503 -0.8518438 -0.1819932 0.4911626 -0.415839 -0.3589116 0.8356198 -0.8550001 -0.2103236 0.4740662 -0.4538253 -0.430878 0.7799916 -0.5675857 -0.4382278 0.6969956 -0.6419959 -0.4041051 0.6515676 -0.4807946 -0.5383484 0.692111 -0.9574776 -0.1681984 0.2344054 -0.4968078 -0.5814896 0.6442453 -0.9133715 -0.2615766 0.3119781 -0.5847968 -0.5785263 0.5686125 -0.50937 -0.6683424 0.5420894 -0.8619701 -0.3678667 0.348829 -0.5908886 -0.6930599 0.4129391 -0.8837695 -0.3683242 0.2885982 -0.5227152 -0.7171385 0.460957 -0.8062034 -0.5039571 0.3099409 -0.5131559 -0.7900453 0.3354094 -0.2631381 -0.9060888 0.3313025 -0.7229068 -0.6487041 0.2378843 -0.8371818 -0.5010611 0.2192366 -0.3490722 -0.9224764 0.1648812 -0.7121533 -0.6881597 0.1388306 -0.9652147 -0.2508821 0.0736128 -0.5148464 -0.8488989 0.1195998 -0.8936851 -0.4452751 0.05529302 -0.5046209 -0.8633303 -0.004333615 -0.5538995 -0.8320518 -0.0297507 -0.9016869 -0.4322507 0.01096129 -0.6798471 -0.7324027 -0.03733986 -0.9562404 -0.2914782 -0.02539259 -0.388532 -0.9025794 -0.185455 -0.5112547 -0.8270029 -0.2338484 -0.7904933 -0.5983641 -0.1306935 -0.8793699 -0.4618277 -0.1158614 -0.5026636 -0.8239136 -0.2617171 -0.2488979 -0.888553 -0.3853872 -0.8891554 -0.4303371 -0.1556047 -0.6903424 -0.657796 -0.3012174 -0.480122 -0.7601522 -0.4377801 -0.6443682 -0.6653093 -0.3770321 -0.7573553 -0.545683 -0.3586685 -0.2282359 -0.7760296 -0.5879512 -0.9289783 -0.310964 -0.2007508 -0.9577044 -0.251275 -0.140226 -0.5443537 -0.5951543 -0.5911603 -0.652498 -0.5441281 -0.5274193 -0.3602548 -0.582707 -0.7284703 -0.3793476 -0.5809148 -0.7201622 -0.9177373 -0.2638661 -0.2968723 -0.8624084 -0.3271006 -0.3863379 -0.361182 -0.4494878 -0.8170118 -0.7716684 -0.3169672 -0.5514162 -0.7758195 -0.3150989 -0.5466414 -0.9942634 -0.05697154 -0.09052455 -0.6110546 -0.3324207 -0.718407 -0.6305178 -0.3751122 -0.6795132 -0.9531342 -0.123114 -0.2763661 -0.4400297 -0.2952131 -0.8480702 -0.5717508 -0.1663015 -0.8033959 -0.7494176 -0.1638291 -0.6415087 -0.5567778 -0.1580609 -0.8154847 -0.547784 -0.1201773 -0.8279433 -0.3292348 -0.06721299 -0.941853 -0.8867068 -0.100225 -0.451338 -0.3491007 0.03447729 -0.9364508 -0.7107294 -0.01355957 -0.7033348 -0.9184798 -0.04272347 -0.3931537 -0.1989907 0.08311378 -0.9764707 -0.6672028 0.03734004 -0.7439397 -0.7051777 0.08102732 -0.7043856 -0.9757081 0.003624677 -0.2190449 -0.870608 0.09412997 -0.4828886 -0.4632586 0.2021445 -0.8628611 -0.3012819 0.3026595 -0.904227 -0.4318399 0.2618839 -0.8630939 -0.8628501 0.1637254 -0.4782087 -0.6667809 0.2694575 -0.6948352 -0.297927 0.4554767 -0.8389164 -0.3556487 0.4568235 -0.8153688 -0.9332248 0.1582284 -0.3225762 -0.6236935 0.3805223 -0.6827953 -0.6713556 0.379437 -0.6366389 -0.8753827 0.2544835 -0.4110271 -0.3868291 0.5727294 -0.722734 -0.5277747 0.5490546 -0.6480687 -0.8741003 0.3098658 -0.3740746 -0.5804607 0.5608447 -0.5903547 -0.6752392 0.5188509 -0.5242576 -0.3794389 0.6873916 -0.6192891 -0.4257764 0.762645 -0.4869159 -0.7640166 0.4984699 -0.4096417 -0.9265113 0.30462 -0.2208701 -0.4701387 0.7508571 -0.4638784 -0.9616047 0.2126919 -0.1734322 -0.6027714 0.6809552 -0.4158928 -0.7677654 0.5778527 -0.2768081 -0.2383236 0.9017114 -0.3607197 -0.9027976 0.3706887 -0.2180516 -0.7634224 0.5873994 -0.2686043 -0.4624689 0.8438903 -0.2719777 -0.4959388 0.8421179 -0.2118543 -0.7654597 0.6286439 -0.137399 -0.8298766 0.5397464 -0.1413468 -0.3872037 0.9092181 -0.1529569 -0.9939416 0.1075471 -0.02266865 -0.4975845 0.8645025 -0.07103002 -0.9720476 0.2324741 -0.03285205 -0.7330119 0.6767009 -0.06906318 -0.4273551 0.9040483 0.008017778 -0.5020568 0.8629934 0.056405 -0.9253279 0.3791604 -0.002416312 -0.8468607 0.5317773 0.006320953 -0.7751397 0.6297463 0.05077642 -0.3671675 0.9134584 0.1754476 -0.4866427 0.8404369 0.238421 -0.7313838 0.6509215 0.2034181 -0.7872419 0.5916746 0.1736991 -0.2878298 0.8886149 0.357096 -0.9759392 0.2103446 0.05742782 -0.9142055 0.3824903 0.133901 -0.4521202 0.7881053 0.4177049 -0.3295603 0.8002972 0.5009137 -0.6504319 0.6717898 0.3544532 -0.7481115 0.566064 0.3462669 -0.8998378 0.3771318 0.2192345 -0.3998233 0.7290576 0.5555325 -0.2994397 0.7280876 0.6166234 -0.6809252 0.5832616 0.4428847 -0.9584038 0.2266903 0.1734173 -0.934956 0.2656825 0.235096 -0.7626873 0.4738265 0.4402233 -0.472582 0.5641217 0.6770768 -0.449436 0.5620226 0.6943616 -0.7148945 0.4727737 0.5151805 -0.9132629 0.2223779 0.3413195 -0.502761 0.4303057 0.7497123 -0.9160506 0.2143764 0.3389604 -0.5868943 0.3732054 0.7185213 -0.7974439 0.2702251 0.5395014 -0.4162591 0.282057 0.8643912 -0.9941997 0.04361617 0.09830844 -0.493007 0.2055919 0.8453852 -0.5369925 0.1848999 0.8230742 -0.8041264 0.1358889 0.5787185 -0.8553782 0.09797352 0.5086546 -0.493655 0.06897801 0.866918 -0.5641571 0.008971691 0.8256189 -0.8320788 0.001721143 0.5546549 -0.8611419 0.02482223 0.5077584 -0.03004032 -0.03647297 0.9988831 0.03218281 -0.2089473 0.9773973 0.0229631 -0.2204705 0.9751234 -0.02518773 -0.3665915 0.930041 -0.019584 -0.504949 0.862927 0.02152359 -0.5971516 0.8018397 0.01862066 -0.6014289 0.7987093 -0.0160433 -0.6973208 0.7165796 0.009613752 -0.8218221 0.5696631 -0.01238501 -0.7823721 0.6226882 -0.008785247 -0.8478568 0.5301526 0.02996009 -0.9600929 0.2780719 -0.01522231 -0.9325582 0.3606985 -0.02610409 -0.9882187 0.1508058 -0.02295917 -0.9997094 -0.007351696 0.02869373 -0.9918109 -0.1244506 -0.007344603 -0.9816498 -0.1905511 -0.01828408 -0.9192902 -0.3931553 0.03287661 -0.8762582 -0.480719 -0.03294599 -0.7940276 -0.6069882 0.01134443 -0.6324447 -0.7745226 0.01265466 -0.6310922 -0.7756046 -0.01822942 -0.4554251 -0.8900875 0.01433128 -0.3422833 -0.9394875 0.002521514 -0.3232505 -0.9463102 -0.02348977 -0.2147288 -0.9763912 -0.02088546 -0.1113729 -0.9935592 0.02272433 0.007568955 -0.9997132 -0.01447939 0.08874189 -0.9959495 0.01151049 0.2998017 -0.9539322 0.006357014 0.3070864 -0.9516605 -0.02229422 0.4890697 -0.8719598 0.02539592 0.6125531 -0.7900214 0.002067208 0.6432688 -0.7656376 -0.02377057 0.732821 -0.6800062 0.01192182 0.8490958 -0.5281044 0.0213744 0.8415032 -0.5398291 -0.02822482 0.9273791 -0.373057 0.0191766 0.9753977 -0.2196174 -0.01048493 0.9874119 -0.1578223 -0.01021432 0.9999181 0.00772345 0.008385658 0.9985862 0.05249112 -0.01638829 0.9844328 0.1749955 0.01898401 0.9519575 0.3056416 -0.01701372 0.9258255 0.3775684 -0.01274359 0.8554903 0.5176621 0.01638662 0.8149631 0.5792813 -0.01329809 0.7578234 0.6523243 0.01188081 0.6255078 0.7801274 0.007798612 0.6209411 0.7838185 -0.03158086 0.4696157 0.882306 -0.008060514 0.3419227 0.9396936 0.04380857 0.2572906 0.9653406 -0.002142488 0.1799706 0.9836698 -0.02940577 0.08854192 0.9956383 -0.9999926 0.002938985 -0.002498745 -0.9999976 -0.002192676 -3.09862e-4 -0.9999635 -0.00579065 -0.006291329 -0.9999591 0.004480779 0.007870376 -0.9999941 0.001594126 0.003060936 -0.9999673 0.007793307 0.002165853 -0.9999985 -0.001598119 -7.16503e-4 -0.9999994 -0.001207888 -6.50228e-5 -0.9999896 0.004361331 0.001380383 -0.9998484 -0.01682388 0.004498302 -0.9999964 -0.002683699 -8.28823e-5 -0.9999986 0.001232087 0.001110315 -0.9999928 0.003803074 -1.59115e-4 0.2319151 0.9680808 -0.0950523 0.3491947 0.9260616 -0.143084 0.3868035 0.9146324 -0.1176042 0.140838 0.9420134 -0.3045907 0.7065858 0.6907238 -0.1537439 0.2689146 0.856493 -0.4405732 0.5142918 0.7968314 -0.3171179 0.8977339 0.4373186 0.05316221 0.4961746 0.7933666 -0.3526758 0.2315142 0.8413643 -0.488372 0.8066767 0.5643374 -0.1754881 0.7095444 0.6882957 -0.1509832 0.3355252 0.6964715 -0.6343109 0.9073975 0.4116674 -0.08461523 0.9913062 0.1298042 -0.0215159 0.6009714 0.6339561 -0.4867579 0.7618924 0.546851 -0.3470937 0.3271122 0.6890487 -0.6466913 0.5892607 0.617469 -0.5210604 0.488043 0.406664 -0.7722944 0.3170725 0.5711473 -0.7571365 0.7759112 0.5377132 -0.3298885 0.9255752 0.3093992 -0.2181346 0.7242003 0.4034613 -0.5592433 0.8666337 0.3233201 -0.3800134 0.4678562 0.7580409 -0.4544059 0.3457765 0.3548963 -0.8686122 0.7198832 0.2980255 -0.6268565 0.3419567 0.3593647 -0.8682872 0.9042256 0.3404317 -0.257842 0.6834859 0.3385519 -0.6467068 0.9358068 0.2509201 -0.2475983 0.9610297 0.2119179 -0.1775185 0.9253063 0.1497843 -0.3483864 0.7238462 0.2989823 -0.6218169 0.6708897 0.1080643 -0.733641 0.3533192 0.2428188 -0.9034404 0.5937474 0.2119948 -0.7762231 0.1441546 0.1929056 -0.9705705 0.4954882 0.03334611 -0.8679745 0.9270111 0.1402592 -0.3478186 0.3199254 -0.02307224 -0.9471618 0.9092378 0.1360864 -0.3934047 0.2334201 -0.1301045 -0.9636327 0.8453856 0.093759 -0.5258638 0.5037519 0.04367464 -0.8627437 0.676342 -0.05013549 -0.7348795 0.7947731 0.1943055 -0.5749619 0.5826912 -0.1454071 -0.7995799 0.2963421 -0.2787148 -0.9135095 0.9037236 0.154006 -0.3994569 0.2756724 -0.3061164 -0.9112067 0.8307462 0.1760058 -0.5280936 0.8785672 0.01359212 -0.4774254 0.5276139 -0.2926332 -0.7974896 0.8141855 -0.07135254 -0.576204 0.6127024 -0.2080125 -0.7624479 0.3374322 -0.4494265 -0.8271369 0.9754157 0.01085728 -0.2201052 0.8313418 -0.1186981 -0.5429379 0.2805138 -0.5280971 -0.8015145 0.9456464 -0.06548357 -0.3185358 0.5364997 -0.4039826 -0.7409225 0.7808755 -0.2588682 -0.5685253 0.78636 -0.2632514 -0.5588709 0.4274948 -0.5026808 -0.7513722 0.3710172 -0.6193731 -0.6918984 0.6683791 -0.5080751 -0.543258 0.9556698 -0.08088386 -0.2831131 0.3006015 -0.7069703 -0.640181 0.3737084 -0.7684983 -0.519377 0.9284268 -0.2231189 -0.2970553 0.9109511 -0.22732 -0.3442292 0.7379993 -0.413972 -0.5329017 0.6409291 -0.6021892 -0.4760023 0.7976896 -0.4335814 -0.419164 0.3042215 -0.8712518 -0.3851878 0.2827969 -0.9065499 -0.313358 0.3691259 -0.8920543 -0.2607398 0.5846928 -0.7027875 -0.4052459 0.6017252 -0.7017055 -0.381492 0.745977 -0.5163875 -0.4205502 0.8980486 -0.3604573 -0.2521496 0.7831461 -0.5067186 -0.3604421 0.5566742 -0.7696242 -0.312718 0.4061591 -0.8731516 -0.2695205 -0.8041346 -0.4168549 -0.423792 0.9356424 -0.2741259 -0.222325 0.6644597 -0.739784 -0.1058914 0.1892302 -0.9754017 -0.1130641 0.763266 -0.60372 -0.230103 0.8265433 -0.5462478 -0.1357924 0.594047 -0.8044289 -0.001595258 0.4063243 -0.9074111 0.1072652 0.9645701 -0.2544584 -0.0696811 0.6234077 -0.7771055 -0.0864287 0.9193792 -0.3925238 -0.02582961 0.8519485 -0.5234816 0.01228183 0.8047383 -0.5837225 0.1080018 0.4875634 -0.8668319 0.1043291 0.1372619 -0.9467027 0.2913988 0.9307547 -0.3652139 -0.01773667 0.4260899 -0.9026144 0.06111228 0.4876798 -0.8051589 0.3374726 0.3535102 -0.7726368 0.5273168 0.8176183 -0.575539 -0.01597863 0.547873 -0.7476071 0.3753914 0.7491687 -0.6255642 0.2177518 0.7975319 -0.5507158 0.2462829 0.3479338 -0.7723183 0.5314759 0.9212535 -0.3886373 0.01591265 0.5090078 -0.6553203 0.5580917 0.7996938 -0.4449763 0.4030956 0.7126488 -0.5762016 0.4001543 0.960615 -0.2454428 0.1302952 0.2578629 -0.651917 0.7130995 0.4282954 -0.5345427 0.7285789 0.613256 -0.4995778 0.6118326 0.733359 -0.3802468 0.5635574 0.3756071 -0.4656599 0.801299 0.1937572 -0.3026313 0.9332056 0.9198241 -0.3096365 0.2409339 0.310678 -0.3353612 0.8893886 0.7479962 -0.3817592 0.5429195 0.9132122 -0.3239295 0.2472107 0.5749776 -0.2887562 0.7655199 0.5727539 -0.2904871 0.7665313 0.4865154 -0.09496253 0.8684958 0.8525075 -0.4106546 0.3234099 0.9501129 -0.1501133 0.2734073 0.3601756 -0.04114615 0.9319767 0.8316574 -0.181983 0.524622 0.643845 -0.0618422 0.7626528 0.9222686 -0.1542718 0.3544305 0.3311724 0.07163983 0.9408469 0.7670637 -0.1302335 0.6282138 0.3937777 0.1489447 0.9070583 0.9507605 -0.08006113 0.2994074 0.9964761 -0.04072362 0.07332879 0.5795667 0.04678642 0.8135808 0.56616 0.03929668 0.8233582 0.7480158 0.0228936 0.6632859 0.8360408 0.05856907 0.5455323 0.9676075 -0.03253263 0.2503545 0.8841177 0.004924476 0.4672384 0.9779509 -0.02216428 0.2076553 0.4687339 -0.3003629 0.8307051 0.9289645 0.03227865 0.3687589 0.451358 0.3856889 0.8046864 0.4322658 0.3695681 0.8225362 0.7042055 0.2432493 0.6670266 0.8139115 0.2373821 0.5302809 0.8136762 0.2032274 0.5446372 0.4123257 0.5733413 0.7080024 0.3362938 0.5331233 0.7763287 0.3815253 0.729632 0.5675169 0.8496841 0.194173 0.4902384 0.676994 0.4442491 0.5867895 0.682956 0.4440689 0.5799775 0.3384138 0.7127323 0.6144012 0.9745043 0.09286069 0.2042507 0.9250247 0.1238839 0.3591411 0.86834 0.3020932 0.3933515 0.2806161 0.8264681 0.4880627 0.4050598 0.8323702 0.3782678 0.8254621 0.3733153 0.4233771 0.7080758 0.5682255 0.4192235 0.9700798 0.1707089 0.172638 0.3552945 0.9023476 0.2439972 0.6250248 0.678416 0.3861293 0.8736745 0.4095662 0.2625806 0.6459091 0.6708018 0.3644536 0.3075793 0.9350589 0.1762381 0.8175544 0.5175689 0.2524429 0.9498304 0.2391016 0.2016251 0.3721151 0.9254872 0.07073873 0.6394457 0.7533972 0.1533042 0.6608231 0.7392082 0.1299389 0.9719208 0.198013 0.1271253 0.6613385 0.7434202 -0.09978967 0.834775 0.5463188 0.06845903 0.9399704 0.3378508 0.04808878 0.8949273 0.4366064 0.0920875 0.8839581 0.4647701 0.05105692 -0.001550257 0.9871948 -0.1595122 0.01240301 0.9580664 -0.2862778 -0.001549959 0.9082294 -0.41847 -0.002289593 0.7770175 -0.629475 0.008599996 0.6741698 -0.7385264 6.7982e-4 0.5888136 -0.8082686 0.009141445 0.3941414 -0.9190044 0.00276345 0.3415971 -0.9398425 -0.00127846 0.1933275 -0.9811335 0.005281209 -0.05485188 -0.9984806 0.005683183 -0.05862265 -0.998264 -0.002877652 -0.2779804 -0.9605824 0.003282964 -0.4632884 -0.8862016 0.006550371 -0.4927631 -0.870139 -0.001499354 -0.6594461 -0.7517505 0.007987201 -0.7924399 -0.6098979 0.00131458 -0.8365205 -0.5479341 -0.00255686 -0.9521203 -0.3057132 0.009979248 -0.9833198 -0.1816114 -0.002630472 -0.9999146 0.01280218 0.007838189 -0.9555314 0.2947851 0.005142331 -0.947754 0.3189609 -0.001569688 -0.8437091 0.5367985 0.009270787 -0.7438888 0.6682391 2.87994e-4 -0.6624771 0.7490822 -9.94015e-4 -0.4926416 0.8702318 0.007805645 -0.3652928 0.9308601 0.001934647 -0.2979595 0.9545766 -1.92933e-5 -0.08510899 0.9963717 0.009085476 0.06705611 0.9977079 0.002136826 0.1418395 0.9898874 -0.001893877 0.3851813 0.9228391 0.004529118 0.6266212 0.779311 0.0130999 0.563552 0.8259767 -0.003400743 0.7519747 0.6591834 1.32955e-4 0.8686202 0.4954787 0.01425385 0.9339969 0.3569968 0.004525184 0.9603371 0.278805 -0.004449188 0.9964092 0.0845521 0.9999802 0.003853619 -0.004980266 0.9999846 0.005413889 -0.001186311 0.9999961 0.00232768 -0.001562297 0.9999845 0.001237928 -0.005444943 0.9999867 0.001461982 -0.004971981 0.9999952 0.003045141 -7.03489e-4 0.9999846 -1.40352e-4 -0.0055601 0.9999972 0.002361416 4.54444e-4 0.9999751 0.002185225 -0.006719768 0.9999934 0.003654062 -1.12919e-4 0.9999638 -0.00261563 -0.008097052 0.9999933 0.003125011 0.001906335 0.9999687 -0.005252301 -0.005912721 0.9999815 0.006030797 7.65807e-4 0.9999818 -0.005043923 -0.003306329 0.9999753 0.004566311 0.005344927 0.9999746 -7.45766e-4 0.007099986 0.9999957 0.001018941 0.002810239 0.999976 -0.006502985 -0.002408921 0.9999848 -0.005514085 4.14231e-6 0.9999931 -0.001834452 0.003250479 0.9999995 -7.71533e-5 9.83485e-4 0.9999803 -0.006223797 7.94593e-4 0.9999994 -5.18299e-4 0.001044511 0.9999805 -0.005540251 0.002921223 0.9999879 -0.001031517 0.004806697 0.9999995 -7.25237e-4 7.34174e-4 1 1.04813e-5 -2.26519e-5 1 1.31708e-5 -8.65531e-6 1 1.51486e-5 -9.98177e-6 1 2.38329e-5 3.82481e-7 1 -9.3945e-6 -1.72332e-5 1 0 -2.13844e-5 1 5.35143e-5 1.65841e-5 1 -7.58438e-6 -5.80737e-6 1 0 -1.09539e-5 1 1.01749e-5 -9.13588e-6 1 1.9036e-5 -5.84564e-6 1 0 -9.27439e-6 1 -1.32285e-5 -2.5364e-5 1 -3.69937e-6 -2.98804e-7 1 1.85477e-5 -7.01536e-6 1 0 9.58825e-7 1 -8.45659e-6 -1.14756e-5 1 0 -1.30221e-5 1 3.72317e-5 -1.21183e-5 1 1.982e-5 1.34272e-5 1 2.02663e-5 6.74033e-6 1 0 2.17706e-5 1 -1.84567e-5 -1.08399e-5 1 -8.65136e-6 6.32532e-6 1 -1.975e-6 6.89819e-7 1 -1.41718e-6 1.08894e-5 1 -1.43696e-5 -3.89651e-6 1 2.27846e-6 0 1 -1.24032e-5 0 1 6.06899e-6 0 1 -6.25068e-6 0 1 -1.39469e-6 0 1 -7.15606e-6 -9.68111e-6 1 4.21244e-6 0 1 -7.31178e-7 0 1 4.81617e-6 0 1 9.00833e-6 -1.88736e-6 1 8.38158e-6 5.27239e-6 1 -9.60292e-7 0 1 -2.99825e-6 0 1 -7.1407e-6 0 1 -1.84206e-5 2.61828e-5 1 -1.75037e-6 -7.34359e-6 1 9.48339e-6 3.09136e-6 1 -2.86925e-5 3.56913e-5 1 -7.85253e-7 0 1 4.05014e-6 0 1 7.01167e-6 3.1894e-6 1 7.4782e-6 -1.88249e-6 1 7.92748e-6 2.52134e-6 1 -1.59437e-6 0 1 1.1059e-5 0 1 1.51716e-6 0 1 2.68864e-5 -2.73637e-5 1 -5.58711e-6 -6.40412e-6 1 -1.41844e-6 -7.50284e-6 1 1.5079e-5 -9.14937e-6 1 -1.09947e-5 -7.03727e-6 1 8.00072e-7 0 1 0 -1.23264e-5 1 2.44039e-6 0 1 -1.51665e-5 0 1 -1.56887e-6 0 1 0 1.50753e-6 1 7.53333e-6 -1.6094e-5 1 -2.43235e-5 3.80882e-6 1 8.49399e-6 7.61177e-7 1 1.25557e-6 2.95349e-6 1 -5.08967e-6 -1.3952e-7 1 -8.7614e-6 1.15047e-5 1 -3.51487e-6 -1.10659e-5 1 1.73928e-5 -1.35103e-6 1 -9.54367e-6 7.07016e-6 1 8.09006e-6 -8.73422e-6 1 -1.00084e-5 1.15875e-5 1 -7.12929e-6 1.36636e-5 1 7.38953e-6 -8.77156e-6 1 1.73285e-5 -3.1662e-6 1 8.53633e-6 2.08413e-5 1 -2.33995e-5 -3.65316e-5 1 -2.42355e-5 -3.97819e-6 1 0 1.66316e-6 1 -1.30593e-5 3.34559e-6 1 8.72003e-6 1.70415e-5 0.7281571 0.02369517 -0.6850006 0.6915127 -0.03782659 -0.7213733 0.7257759 -0.1249182 -0.6764945 0.7004724 -0.1562881 -0.6963566 0.7213701 -0.2592085 -0.642212 0.7133129 -0.2553396 -0.6526764 0.7339568 -0.3994169 -0.5493393 0.6877319 -0.3665073 -0.6266556 0.7023153 -0.4431461 -0.5571129 0.7397965 -0.5313497 -0.4127574 0.6871919 -0.5407757 -0.4851074 0.6878693 -0.618734 -0.3794788 0.6905335 -0.6708032 -0.2705302 0.7207838 -0.6273109 -0.294876 0.7271161 -0.6654866 -0.1686117 0.7079554 -0.688978 -0.1552694 0.6922038 -0.7192864 -0.05900114 0.7317322 -0.6814838 -0.01216351 0.6709415 -0.7386322 0.06526911 0.7481377 -0.6428697 0.1643435 0.7162139 -0.6706556 0.1930255 0.6788713 -0.6769437 0.2843958 0.7128594 -0.5912715 0.3771333 0.7267473 -0.5742648 0.3769062 0.7270816 -0.4725608 0.4980348 0.6998941 -0.5141645 0.4957653 0.68671 -0.4416572 0.5773807 0.7379598 -0.3303418 0.5884639 0.7040647 -0.325135 0.6313321 0.6761814 -0.2039381 0.7079463 0.7449322 -0.125741 0.6551834 0.6852397 -0.06502056 0.7254095 0.7197052 0.03923326 0.6931704 0.6987799 0.06185162 0.7126578 0.6766405 0.2039839 0.7074944 0.7136545 0.1573905 0.6825874 0.7360139 0.2776203 0.6174225 0.6765826 0.3659675 0.6389865 0.7287704 0.4033588 0.5533493 0.6865034 0.4803625 0.5458617 0.7282828 0.506805 0.4612516 0.6982504 0.5522122 0.4555308 0.7374468 0.5948735 0.3198402 0.6981499 0.6093834 0.3758172 0.6761848 0.6833155 0.275416 0.7243156 0.6717095 0.1554775 0.695752 0.7053855 0.1355014 0.7206975 0.6929037 0.02190124 0.6839161 0.7294839 -0.01058322 0.728988 0.6690216 -0.1448674 0.6970627 0.6960285 -0.1721863 0.6915186 0.6385895 -0.337647 0.7095806 0.6176391 -0.3391422 0.74408 0.479302 -0.4654189 0.6930404 0.5499809 -0.4660645 0.6692487 0.4634874 -0.5807631 0.7331933 0.3282191 -0.5955669 0.6942512 0.3178732 -0.6457336 0.7262749 0.1842918 -0.6622397 0.6930359 0.1669685 -0.7013008 0.7056906 0.05050462 -0.7067179 0.006904006 0.07111537 -0.9974442 -0.01265972 0.127896 -0.9917068 0.02037394 0.2300651 -0.972962 -0.02301156 0.3138074 -0.9492077 0.02104777 0.441897 -0.8968189 -0.01276677 0.4949443 -0.8688309 0.006458997 0.6215298 -0.783364 0.008544325 0.6237974 -0.7815394 -0.008181631 0.7360049 -0.6769267 0.01234972 0.7628093 -0.6465055 -0.01679319 0.8344782 -0.550785 0.02722185 0.88418 -0.4663528 -0.02789843 0.929287 -0.3683037 0.03071331 0.9694764 -0.2432536 -0.02778834 0.9915143 -0.1269934 0.01858651 0.9997779 -0.009936869 -0.01480096 0.9979076 0.06293928 0.01760536 0.9820965 0.1875542 -0.02199012 0.96487 0.2618057 0.02172493 0.9270215 0.3743784 -0.02189332 0.8755788 0.4825789 0.005986332 0.8519861 0.5235304 -0.01799547 0.7418515 0.6703228 0.00599128 0.7710198 0.6367831 0.01750177 0.6625257 0.7488347 -0.0196228 0.5893508 0.807639 0.02361136 0.4971432 0.8673473 -0.02818161 0.4079678 0.9125614 0.02801936 0.2755393 0.9608814 -0.02598005 0.1709731 0.9849331 0.01620912 0.08420997 0.9963163 -0.00941962 -0.04598987 0.9988976 0.01134401 -0.08969771 0.9959045 -0.01227843 -0.1842695 0.9827991 0.01888561 -0.2755898 0.9610898 -0.0242154 -0.3684546 0.9293303 0.02111321 -0.4554337 0.8900193 -0.02067261 -0.5877371 0.8087879 -6.04608e-4 -0.6093992 0.7928634 0.01403635 -0.7204852 0.6933283 -0.02866101 -0.7705211 0.63677 0.02301949 -0.8431801 0.5371385 -0.02277243 -0.9039586 0.4270132 0.004939436 -0.922384 0.3862427 0.009219229 -0.9684484 0.249044 -0.01458764 -0.9780881 0.2076799 0.01173245 -0.9958634 0.09010219 -0.01640015 -0.9994546 0.02866548 0.01763361 -0.9964403 -0.08243674 -0.0135135 -0.9840605 -0.1773201 0.005081653 -0.9757069 -0.2190216 -0.00979048 -0.9383198 -0.34563 0.009885251 -0.9265086 -0.3761438 -0.006521642 -0.850736 -0.5255527 -0.003448963 -0.8529126 -0.5220424 -0.002576172 -0.7341852 -0.6789444 0.006194293 -0.7432529 -0.6689819 0.002313733 -0.6256907 -0.7800679 -0.01093542 -0.6067519 -0.7948161 0.01552474 -0.502541 -0.864414 -0.02056723 -0.4211756 -0.9067459 0.01050031 -0.3631147 -0.9316853 -0.0041278 -0.2209311 -0.9752807 -0.006520807 -0.2177883 -0.9759743 0.005321264 -0.05240148 -0.998612 -0.007106363 -0.02851963 -0.9995681 1 4.33849e-6 0 1 -1.0877e-5 0 1 5.18274e-6 0 1 1.09198e-5 0 1 -6.28577e-6 0 1 -1.08868e-5 0 1 1.52778e-5 0 1 1.52051e-5 0 1 8.02646e-6 0 1 1.38132e-5 0 1 1.5896e-6 0 1 -7.21356e-6 0 1 3.33353e-6 0 1 1.31013e-5 0 -0.01318025 -0.9387592 0.3443219 0.09304076 -0.9402816 0.3274354 -0.01318216 -0.8035754 0.5950571 0.01875394 -0.8003299 0.5992665 0.008939385 -0.579825 0.814692 0.01875197 -0.5811088 0.8136098 -0.04160243 -0.365771 0.9297747 0.2009602 -0.3112421 0.9288399 -0.3349051 -0.06275177 0.94016 0.3349053 0.06275469 0.9401597 -0.2352218 0.3243291 0.9162322 0.05353659 0.3807591 0.9231233 9.45841e-4 0.6241092 0.7813367 -0.2044634 0.6413633 0.7394917 0.2278779 0.7668671 0.5999889 -0.2389808 0.8589587 0.4528557 0.2443578 0.905779 0.3461992 -0.271099 0.9474777 0.1696804 0.2762901 0.9610704 -0.002733409 -0.2365327 0.9626891 -0.1314616 0.2336612 0.9200642 -0.3144589 -0.2310364 0.8717399 -0.4320784 0.2580338 0.770322 -0.5831146 -0.3371291 0.6606903 -0.6706956 0.3995422 0.4717644 -0.7860054 -0.3648342 0.3307663 -0.8703389 0.2474406 0.1633662 -0.9550313 -0.1905977 0.01904708 -0.9814835 0.1528422 -0.09578549 -0.9835978 -0.1848332 -0.2609221 -0.9475001 0.1838998 -0.3486659 -0.9190283 -0.1904371 -0.548724 -0.8140243 0.0749787 -0.5995873 -0.7967894 0.03435236 -0.7849187 -0.6186459 -0.0769689 -0.7950711 -0.6016126 0.02155256 -0.9339191 -0.3568345 -0.01869803 -0.9316833 -0.36279 -0.1411079 -0.9897586 -0.02160507 0.08878445 -0.9945461 -0.05473107 -0.03971874 -0.01660883 -0.9990729 0.04221385 0.07426887 -0.9963445 -0.04497182 0.3265861 -0.9440971 0.04495221 0.4478154 -0.8929954 -0.03380608 0.6426535 -0.7654108 0.02230477 0.7035636 -0.7102822 -0.02073657 0.8446714 -0.5348836 0.02774918 0.8842908 -0.4661114 -0.03327596 0.9576656 -0.2859534 0.05793863 0.9902771 -0.1264697 -0.0513072 0.9981163 0.03363519 0.03606873 0.9360017 0.3501426 0.03154528 0.9373729 0.3468964 -0.046467 0.7243785 0.6878348 0.05085265 0.6631176 0.7467858 -0.03207916 0.3396266 0.9400132 0.00233227 0.30783 0.9514386 0.00865978 0.02418303 0.99967 -0.01446342 -0.005533516 0.9998801 0.01223516 -0.2819225 0.9593592 -0.01362574 -0.3080362 0.9512771 0.01974385 -0.6122905 0.7903864 -0.03646409 -0.6589608 0.7512929 0.03869372 -0.8288103 0.5581901 -0.05215543 -0.8974235 0.4380765 0.05822026 -0.9726561 0.2248345 -0.05673891 -0.9963715 0.06344044 0.04842627 -0.9807322 -0.1892597 -0.04970216 -0.9476327 -0.3154712 0.04952794 -0.8525334 -0.520321 -0.04652541 -0.739985 -0.6710124 0.03399968 -0.6490821 -0.7599583 -0.04544866 -0.4379981 -0.8978264 0.04880213 -0.3417583 -0.93852 0.004757225 0.05492669 -0.9984791 6.98389e-4 0.4470383 -0.8945146 -0.007571041 0.4953179 -0.8686788 0.006503701 0.8366067 -0.5477655 -0.006669759 0.892065 -0.4518579 0.007151186 0.9929698 -0.1181519 -0.007588386 0.9998348 0.01651465 0.005953669 0.9059265 0.4233933 -0.008644402 0.8542295 0.5198244 0.01133573 0.5839942 0.8116788 -0.01414448 0.3397356 0.9404146 0.004492342 0.1823371 0.9832258 0.002509653 -0.2228817 0.9748423 -0.01331973 -0.3269436 0.9449501 0.014593 -0.703982 0.7100679 -0.0135197 -0.8527078 0.5222133 0.009032547 -0.9747082 0.2232989 -0.006804466 -0.9996669 0.02489531 0.008189439 -0.9689018 -0.24731 -0.007854044 -0.917991 -0.3965237 0.004751145 -0.6991344 -0.7149745 -0.007153749 -0.616545 -0.7872872 0.008307456 -0.3730571 -0.9277712 -0.01098662 -0.08285886 -0.9965007 4.46648e-4 0.3910722 -0.9203599 -0.005698025 0.4328141 -0.9014652 0.004518449 0.7123863 -0.7017731 -0.004238784 0.7716907 -0.635984 0.004456102 0.9686316 -0.2484616 -0.003534674 0.9793511 -0.2021365 0.004461944 0.9048163 0.4257789 -0.007526814 0.8769725 0.4804817 0.007392644 0.5010961 0.8653601 -0.01002967 0.363579 0.9315094 0.0065822 0.1325963 0.9911483 -0.008771002 -0.1766844 0.9842285 0.008101403 -0.3261299 0.9452903 -0.00791651 -0.6720181 0.7404924 0.002381265 -0.7270299 0.6866017 0.002410173 -0.9451819 0.3265357 -0.008782386 -0.9703567 0.2415175 0.007855951 -0.9958411 -0.09076857 -0.007332682 -0.9523266 -0.3049926 0.007190823 -0.8780184 -0.4785727 -0.01048856 -0.7152633 -0.6987763 0.01191163 -0.5076096 -0.861505 -0.01387751 -0.2053842 -0.978583 0.007943093 -0.02798461 -0.9995769 0.01258939 -9.60071e-4 -0.9999204 -0.007641434 0.2304123 -0.9730631 0.0064767 0.5070055 -0.8619185 -0.00539112 0.6043878 -0.7966722 0.00720638 0.8617982 -0.5072002 -0.007206439 0.9148828 -0.4036555 0.006202459 0.9999808 -3.44895e-4 -0.004120051 0.9965308 0.0831229 0.003118276 0.8783928 0.4779295 -0.002080738 0.8574662 0.5145363 0.002247989 0.5632646 0.8262736 -0.003575086 0.5279446 0.8492713 0.004618048 0.08621531 0.9962658 -0.007902681 -0.01103442 0.9999079 0.008545577 -0.3706871 0.9287186 -0.009638249 -0.5376338 0.8431234 0.008817136 -0.769467 0.6386259 -0.005409121 -0.8589844 0.5119732 0.003679335 -0.9849323 0.1729017 0.001159965 -0.9817444 0.1902014 0.005341649 -0.9478622 -0.3186358 -0.001080453 -0.9626137 -0.2708761 -0.008465349 -0.7492154 -0.6622723 0.01427829 -0.6034662 -0.7972609 -0.01413124 -0.2867891 -0.9578896 0.00366801 0.358211 -0.9336335 -8.8243e-4 0.382582 -0.9239211 -0.005625903 0.7625738 -0.6468769 0.01078546 0.8425551 -0.5385023 -0.007437169 0.962639 -0.270686 0.006148636 0.99932 -0.03635448 -0.008166491 0.9885868 0.1504312 0.01005434 0.9287173 0.3706523 -0.009469747 0.7160778 0.6979563 0.003695309 0.649134 0.7606652 -0.007338523 0.198876 0.9799972 -0.002838134 0.1732901 0.9848667 0.008618414 -0.1979694 0.9801703 -0.01072376 -0.4284684 0.9034932 0.007571101 -0.5948658 0.8037895 -0.008621752 -0.8417218 0.5398427 0.009620845 -0.9106143 0.4131454 -0.009924829 -0.9998947 -0.01059222 0.006506681 -0.9885433 -0.1507977 0.004255771 -0.8412749 -0.5405909 -0.004092872 -0.8859487 -0.4637652 -0.006235539 -0.6231605 -0.7820692 0.005943894 -0.5171856 -0.8558526 -0.006009459 -0.1945202 -0.9808802 0.001146852 -0.1408109 -0.9900358 -1 -2.75227e-6 0 -1 1.29487e-5 0 -1 -1.78687e-6 0 -1 2.58185e-6 0 -1 -6.29768e-6 0 -1 1.72772e-6 0 -1 1.50993e-6 0 -1 -1.64386e-6 0 -1 1.55414e-6 0 -1 4.48758e-6 0 -1 2.77771e-6 0 -1 -4.247e-7 0 -1 -1.23465e-6 0 -1 -9.82578e-6 0 -1 2.99317e-6 0 -1 -9.72933e-6 0 -1 1.86023e-5 0 -1 -1.86509e-5 0 -1 1.66491e-5 0 -1 2.17117e-5 0 -1 -1.60345e-5 0 -1 4.11579e-6 0 -1 8.83613e-7 0 -1 -2.01504e-6 0 -1 -1.11633e-6 0 -1 2.00918e-6 0 -1 -5.77753e-6 0 -1 2.27454e-5 0 -1 1.31779e-6 0 -1 -9.50083e-6 0 -1 -1.45554e-5 0 -1 2.29579e-5 0 -1 5.78398e-7 0 -1 -1.77337e-6 0 -1 1.64514e-5 0 -1 1.98887e-6 0 -1 -1.61235e-7 0 -1 -9.32754e-7 0 -1 -9.95241e-6 0 -1 -7.71539e-6 0 -1 -1.19325e-5 0 -1 -3.23669e-6 0 -1 1.03181e-5 0 -1 -1.06763e-5 0 -1 1.48245e-6 0 -1 7.62276e-7 0 0.738 0.1823774 0.649688 0.5417674 0.2516986 0.8019576 0.5327939 0.8236865 0.1940909 0.5388676 0.820129 0.1923807 0.5472198 0.5724088 -0.6106543 0.5330136 0.5799936 -0.616039 0.5472395 -0.2397811 -0.801894 0.5284751 -0.2455691 -0.8126561 0.7501433 -0.6466876 -0.1381313 0.5308969 -0.8224543 -0.2042483 0.7465682 -0.4564651 0.4840204 0.7357861 -0.4633383 0.4938992 0.0206604 -0.9735532 -0.2275246 0.02508151 -0.9744605 -0.223154 0.02500844 -0.6855929 0.7275555 0.02547526 -0.6859361 0.7272157 0.02507197 0.2830558 0.9587758 0.02100563 0.2870168 0.9576953 0.999998 0.002007842 4.33219e-5 0.9999264 -0.005172133 -0.01097619 0.9999895 0.003451406 -0.003026843 0.9999633 0.008360505 -0.001872301 0.9999694 0.005578517 0.005489945 0.9999886 0.001810252 -0.004429638 0.9999687 0.007741391 0.001678943 0.9999656 0.008015871 0.002136051 0.9999574 0.006103932 0.006926357 0.9999871 0.005014181 -8.08889e-4 0.9999839 4.43265e-4 -0.005658149 0.9999834 0.004127979 -0.004030168 0.9999834 -1.24899e-4 -0.005756139 0.9999681 0.002559483 0.007574081 0.9999897 -0.002788305 0.003607749 0.9999784 0.006307065 -0.001878201 0.9999654 -0.007780313 0.002928614 0.9999941 -0.001439213 -0.00313133 0.9999922 -0.002468585 -0.003086447 0.9999899 -5.6965e-4 -0.004460155 0.9999676 -0.005276978 0.006086766 0.9999856 1.02434e-4 0.005378186 0.9999996 -6.21624e-4 -7.62996e-4 0.999948 -0.01018667 -4.99308e-4 0.9999719 0.005996286 -0.004495441 0.9999049 -0.006762921 0.01202845 0.9988875 -0.04337275 0.01851463 0.9982762 -0.05791282 0.009527146 0.9998891 -0.01183658 -0.00904715 0.9968877 -0.07297074 -0.02983891 0.9999872 0.00470364 -0.001902997 0.9975834 -0.06876164 0.009967684 0.9989835 -0.0282607 -0.03512245 0.9999933 -0.003076851 -0.002005875 0.9946858 -0.06039065 0.083386 0.9986165 -0.007641613 0.05202585 0.9999263 0.01207292 0.001299262 0.9993259 -0.01778149 0.03211641 0.9997541 0.005546331 0.02146989 0.9995574 0.002159357 0.02967214 0.9994356 0.01210039 0.03133815 0.9996188 0.01205092 0.02484619 0.9823317 0.1458489 0.1172717 0.9781615 0.1519999 0.1417614 0.9962217 0.07028365 0.0510143 0.8877804 0.3848688 0.2524326 0.7100954 0.6667147 0.2263979 0.8861299 0.4630305 0.01940459 0.7755472 0.6266555 -0.07635152 0.8748753 0.4419409 -0.1981964 0.8211338 0.4956238 -0.2830131 0.8488051 0.3464656 -0.3993641 0.8108634 0.3550437 -0.4652361 0.8310669 0.2146003 -0.5131028 0.7779847 0.1863201 -0.6000205 0.8064063 -0.07334679 -0.5867958 0.8778104 -0.0245276 -0.4783801 0.7953097 -0.233646 -0.5593675 0.8485566 -0.3404175 -0.4050528 0.8500731 -0.3380532 -0.4038512 0.8113816 -0.5073633 -0.2902456 0.8553399 -0.4812816 -0.1917338 0.8160809 -0.5572013 -0.1534229 0.8480717 -0.5291312 0.02819204 0.8409814 -0.5400196 0.03360325 0.8055095 -0.5307946 0.2634611 0.8627965 -0.4201178 0.2812176 0.8007099 -0.4075852 0.4390197 0.867573 -0.2601088 0.423864 0.7918542 -0.2307762 0.5654284 0.8614571 -0.009967029 0.5077328 0.8424351 0.004957377 0.5387752 0.803153 0.1635542 0.5728834 0.8709591 0.2202256 0.439239 0.779518 0.3777352 0.499668 0.8628334 0.4241757 0.2749425 0.8057644 0.5253928 0.2733247 0.8525169 0.514997 0.08940327 0.8043736 0.591323 0.05762267 0.8504434 0.5090916 -0.1325592 0.8027897 0.5642782 -0.1926627 0.8507742 0.4137794 -0.3239905 0.8178443 0.4357888 -0.375791 0.8235667 0.2614281 -0.503382 0.8773491 0.1700983 -0.4486928 0.7696065 0.06239181 -0.6354629 0.841838 -0.09725016 -0.5308967 0.8896468 -0.136413 -0.4357983 0.8011572 -0.2865476 -0.5253927 0.863331 -0.3865604 -0.324393 0.8174693 -0.4648539 -0.3400806 0.8438979 -0.5127437 -0.1578931 0.8148446 -0.5602588 -0.1487897 0.8328845 -0.5484091 0.07450389 0.828369 -0.5556336 0.07124829 0.8376379 -0.4715793 0.2756373 0.8269139 -0.4818835 0.2898306 0.8526494 -0.2718957 0.4461634 0.8628017 -0.2678155 0.4287751 0.7847653 -0.09070795 0.6131197 0.8618989 0.007666885 0.5070224 0.7784146 0.165983 0.6054095 0.8649355 0.2141559 0.4538988 0.800796 0.4149091 0.4319448 0.8772382 0.3920831 0.2769912 0.7746945 0.573946 0.2653949 0.8407621 0.5403441 0.03387272 0.8613463 0.5078647 0.01249176 0.8254766 0.5401044 -0.1639387 0.8616662 0.4664352 -0.1999238 0.7930267 0.4947898 -0.3553754 0.8611466 0.3280521 -0.3883407 0.8078248 0.3411031 -0.480695 0.8203126 0.114506 -0.5603352 0.8140317 0.1216085 -0.567947 0.757192 -0.1078169 -0.6442329 0.8510495 -0.1947903 -0.4876184 0.7886157 -0.350758 -0.5050288 0.8752944 -0.3545671 -0.3288493 0.7838731 -0.5190564 -0.3407691 0.8418208 -0.5262841 -0.1198455 0.8591639 -0.502877 -0.09461563 0.8139543 -0.5800265 0.03236889 0.8599408 -0.49621 0.1194889 0.79081 -0.5667246 0.231177 0.8647472 -0.398298 0.3058938 0.7873781 -0.4200506 0.4512133 0.8594207 -0.2335057 0.4548311 0.8235476 -0.2237669 0.5212463 0.8346483 -0.0729317 0.5459334 0.9059014 0.03010016 0.4224175 0.7957888 0.1758214 0.5794885 0.9079664 0.2738614 0.3171704 0.8481066 0.3756765 0.3736073 0.8271803 0.5269688 0.1951323 0.8679897 0.4840723 0.1107607 0.8042951 0.5918684 0.05292588 0.8595047 0.4977961 -0.1159781 0.8151871 0.5551245 -0.1652477 0.8192164 0.4336962 -0.3752229 0.8721432 0.3277654 -0.3632302 0.8077065 0.3321534 -0.4871184 0.8071024 0.1415593 -0.5731902 0.8765959 0.04644054 -0.4789812 0.8042491 -0.09438002 -0.5867504 0.8353669 -0.1331542 -0.5333219 0.7462826 -0.333844 -0.5758563 0.8532996 -0.3742144 -0.3631027 0.7961235 -0.5106803 -0.324643 0.8558752 -0.4673177 -0.2215666 0.8499852 -0.5257584 -0.03321659 0.8135577 -0.5748306 -0.08771359 0.7875751 -0.6054196 0.1148597 0.864714 -0.4678407 0.1827429 0.8346666 -0.4829716 0.2647079 0.8842393 -0.3029806 0.3554207 0.8593584 -0.3191207 0.3995814 0.7889502 -0.2602123 0.5566393 0.8593041 -0.08279204 0.5047197 0.8232131 -0.05596345 0.5649677 0.839321 0.1556965 0.5208635 0.8554688 0.1390529 0.4988363 0.7880718 0.353607 0.5038899 0.8768861 0.3610522 0.3173519 0.8167753 0.4856067 0.3115514 0.8287498 0.5376767 0.1551696 0.8519057 0.4985266 0.1603999 0.7961861 0.6039063 -0.03721719 0.876974 0.4677049 -0.1103127 0.7666422 0.5547651 -0.3232576 0.8705403 0.3393357 -0.3563858 0.8143734 0.3561376 -0.4582161 0.841834 0.1423834 -0.5206177 0.8362756 0.1412185 -0.5298117 0.7986683 -0.06441009 -0.5983145 0.8634555 -0.1204159 -0.4898414 0.7959079 -0.28726 -0.5329282 0.8685464 -0.3227611 -0.3761016 0.8224897 -0.415129 -0.3888169 0.8342639 -0.5181481 -0.1884842 0.8736581 -0.4681654 -0.1324495 0.7993237 -0.600864 0.006639659 0.8719581 -0.4651584 0.1526982 0.8130511 -0.5326748 0.2349588 0.8491527 -0.3961507 0.3492912 0.8199029 -0.412142 0.397364 0.8440464 -0.2183257 0.489816 0.8348901 -0.2331131 0.498615 0.8561205 -0.008616447 0.5167045 0.8263189 -0.04896509 0.5610699 0.7960491 0.1478016 0.5869076 0.8647422 0.2303712 0.4462625 0.8193863 0.3023189 0.4870415 0.822887 0.4650691 0.3264471 0.862816 0.4347209 0.2580045 0.8126787 0.5632894 0.1491928 0.8858124 0.4616336 0.0472325 0.8230958 0.5475151 -0.1508001 0.8765865 0.4424098 -0.189393 0.7814166 0.5168853 -0.3495967 0.8437345 0.3038941 -0.4424487 0.8568443 0.2812818 -0.4320861 0.8176971 0.1452211 -0.5570299 0.8560692 0.07988578 -0.5106505 0.8037476 -0.04880058 -0.5929658 0.8632992 -0.1396332 -0.4849917 0.833595 -0.1847545 -0.5205625 0.8527078 -0.4018661 -0.333756 0.8774017 -0.3830433 -0.2888671 0.7721555 -0.6039415 -0.197562 0.8754482 -0.4831964 0.01057028 0.816734 -0.5731869 0.06635051 0.8506191 -0.4699796 0.2357251 0.844286 -0.4811806 0.2358952 0.8889291 -0.289057 0.3553183 0.7964886 -0.3120538 0.5179077 0.858457 -0.1625484 0.486446 0.7933112 -0.09876912 0.6007512 0.8773244 0.05583608 0.4766387 0.7708247 0.1793956 0.6112663 0.8414832 0.3388787 0.4207935 0.7904061 0.3513082 0.5018373 0.7707848 0.5556114 0.3117479 0.8470847 0.4961624 0.1904482 0.7887822 0.6141088 0.02632391 0.8620222 0.5048648 -0.04505056 0.830816 0.5348607 -0.1538466 0.8963328 0.3832591 -0.2229351 0.8085343 0.4384325 -0.3924911 0.9058056 0.1997177 -0.3736696 0.8373876 0.2100018 -0.5046596 0.7833389 0.06009948 -0.6186828 0.8736031 -0.06107085 -0.4827921 0.7887706 -0.1866729 -0.5856571 0.8419802 -0.2529128 -0.4765549 0.752716 -0.4168922 -0.5095288 0.8285418 -0.4843063 -0.2810091 0.797407 -0.536794 -0.2756709 0.8506622 -0.5199726 -0.0774756 0.8269382 -0.5587747 -0.06280314 0.8365476 -0.5222772 0.1655745 0.8331887 -0.5266075 0.1687644 0.8165435 -0.3964945 0.419582 0.8673285 -0.3053142 0.3930962 0.8061253 -0.244988 0.5386492 0.9027611 -0.0726152 0.4239688 0.8184638 0.09714013 0.5662871 0.8574078 0.1285242 0.4983309 0.7848908 0.3166896 0.532592 0.8813346 0.3374689 0.3307027 0.7538818 0.5473064 0.3634806 0.854157 0.5137551 0.08044767 0.8748521 0.4810191 0.05704909 0.8097404 0.5753598 -0.1152456 0.8821421 0.4103823 -0.23111 0.8207753 0.4675501 -0.3282145 0.84622 0.3139805 -0.4304975 0.8318912 0.3189941 -0.4540922 0.8031107 0.1467251 -0.5774816 0.8688765 0.05144137 -0.4923491 0.8197596 -0.06057024 -0.5694957 0.8646202 -0.1489106 -0.4798517 0.7995747 -0.2553758 -0.5435656 0.8423299 -0.3804141 -0.3817924 0.847866 -0.3718166 -0.3779889 0.772037 -0.5815684 -0.2563925 0.8800755 -0.4704811 -0.06414741 0.8229228 -0.5677269 -0.02201044 0.8250912 -0.5392218 0.1687141 0.8668705 -0.4580351 0.196824 0.8104878 -0.4627269 0.3591564 0.8783833 -0.3236195 0.351729 0.7771569 -0.2726618 0.5671709 0.8676064 -0.1123055 0.4844035 0.7986839 -0.02172482 0.6013587 0.8615818 0.08864516 0.4998188 0.7795276 0.2188425 0.5868942 0.8544101 0.294932 0.4277835 0.8544489 0.2948433 0.4277669 0.8678374 0.4240146 0.2589787 0.8646444 0.4297126 0.2602643 0.7714263 0.6144537 0.1653731 0.8956356 0.4445237 0.01535236 0.8156792 0.5423567 -0.2012878 0.8279393 0.5222257 -0.204443 0.829603 0.4364359 -0.3482566 0.8998641 0.2733877 -0.3398587 0.8132061 0.2672798 -0.5169695 0.8045539 0.1837567 -0.5647358 0.8765488 0.07026213 -0.4761571 0.7812029 -0.02784848 -0.6236558 0.8441027 -0.2179228 -0.4898982 0.8547316 -0.2220537 -0.4691761 0.8097568 -0.3575052 -0.4652783 0.8593733 -0.391845 -0.3285346 0.8040546 -0.4961749 -0.3275771 0.8626372 -0.492232 -0.1164682 0.8223478 -0.5595104 -0.1034026 0.7980743 -0.5920435 0.1120808 0.8725489 -0.4577838 0.170565 0.7981372 -0.5109879 0.3191686 0.866472 -0.3546445 0.3513599 0.8001629 -0.3364045 0.4965595 0.8804294 -0.1562117 0.4477074 0.7900254 -0.09543704 0.6056002 0.862667 0.06021362 0.5021755 0.8122104 0.1308555 0.568499 0.8597417 0.2643297 0.4370058 0.8203058 0.3250317 0.4705878 0.8201355 0.4641799 0.3345368 0.8511804 0.443147 0.2812696 0.8090595 0.5729683 0.130882 0.8366405 0.540727 0.08744764 0.8039481 0.5942707 -0.0225833 0.8280813 0.5577023 -0.05700623 0.7570172 0.6048581 -0.2471271 0.8486745 0.4145919 -0.3284282 0.8008845 0.418861 -0.4279482 0.8734136 0.2608372 -0.4112331 0.8030785 0.1905393 -0.5645881 0.8718898 0.06947672 -0.4847485 0.7780724 -0.02827042 -0.6275382 0.8753468 -0.2294512 -0.4255819 0.844942 -0.2188555 -0.4880322 0.7815387 -0.4086739 -0.4713631 0.85676 -0.4402623 -0.2685734 0.8283687 -0.4941597 -0.26384 0.8362094 -0.5402444 -0.09428733 0.8564933 -0.5122329 -0.06353574 0.7874795 -0.6098316 0.08933949 0.8707386 -0.4571117 0.1812822 0.796448 -0.5215721 0.3059954 0.8448572 -0.3679589 0.3883591 0.7950539 -0.3799802 0.4727625 0.7921177 -0.1788595 0.5835742 0.822438 -0.1372476 0.5520498 0.8301731 -0.02842026 0.5567809 0.8853865 0.0492596 0.4622381 0.8358924 0.1872853 0.5159536 0.8627414 0.2310503 0.44977 0.7713576 0.3967252 0.497611 0.8668019 0.3770806 0.3262892 0.8139366 0.5405099 0.2129702 0.852466 0.5005322 0.1508954 0.8101004 0.586115 0.01437926 0.85821 0.5111402 -0.04702526 0.792918 0.5693083 -0.2171852 0.85695 0.4449882 -0.260043 0.8007663 0.4443729 -0.4016294 0.8713082 0.2833718 -0.4006528 0.7746412 0.2767484 -0.5686311 0.8352485 0.06540733 -0.5459687 0.8708986 0.0209347 -0.4910168 0.8207717 -0.1366128 -0.554681 0.8714081 -0.1900277 -0.4522582 0.7886913 -0.3415201 -0.5112046 0.8707562 -0.3901194 -0.2993172 0.802206 -0.5140594 -0.3036586 0.8561948 -0.5002143 -0.1292911 0.8035899 -0.5874259 -0.09578156 0.8547852 -0.5111532 0.0898053 0.8096992 -0.5685398 0.1454296 0.8491442 -0.4434328 0.2869173 0.8197901 -0.4669717 0.3314839 0.8275259 -0.3226173 0.4594768 0.8546639 -0.2695007 0.4437557 0.8108676 -0.2024815 0.5490858 0.8701038 -0.04558753 0.4907557 0.800921 0.01466178 0.5985904 0.845591 0.1958471 0.4966083 0.8382446 0.2054902 0.5050939 0.8512572 0.3714082 0.370698 0.7831992 0.4748106 0.4014398 0.8615542 0.4709104 0.189652 0.8174419 0.5504729 0.1696127 0.8463668 0.5319942 -0.02540981 0.8475331 0.5300655 -0.02680301 0.8161203 0.5510812 -0.1739461 0.8582512 0.4646264 -0.2180076 0.7969219 0.4869751 -0.3574506 0.8777207 0.3093492 -0.3659364 0.7854867 0.3047698 -0.5386335 0.8475631 0.1134599 -0.5184242 0.8027483 0.08792781 -0.5897998 0.7317767 -0.201704 -0.6510134 0.8225177 -0.1267818 -0.5544286 0.8420093 -0.3352605 -0.4226356 0.8285268 -0.3548398 -0.4331654 0.8156231 -0.5043798 -0.2834783 0.8699282 -0.454966 -0.1903442 0.7788531 -0.6206263 -0.09061437 0.8355162 -0.5450139 0.06980299 0.8511804 -0.5183493 0.0824989 0.8238732 -0.5071191 0.2531075 0.8486331 -0.460058 0.261091 0.8071814 -0.3850014 0.4474732 0.8542808 -0.2995245 0.4248407 0.8328762 -0.2259528 0.5052352 0.8967669 -0.07085567 0.4367938 0.8296807 -0.02891534 0.5574889 0.7893333 0.1453088 0.596522 0.8783281 0.213076 0.4279467 0.7673152 0.3906528 0.5085448 0.8643276 0.4243614 0.269917 0.846028 0.4582324 0.2725063 0.7975391 0.5853388 0.1459791 0.8640714 0.5033482 -0.004612982 0.8205667 0.5694435 -0.0490359 0.8393994 0.4991111 -0.2151671 0.8527151 0.4839813 -0.1965687 0.8243469 0.4086949 -0.3916898 0.8558191 0.3412797 -0.3887184 0.7898163 0.2786399 -0.5463974 0.8208263 0.2291978 -0.5231754 0.7560451 0.06339561 -0.6514422 0.8551099 -0.08104068 -0.5120739 0.8064165 -0.2247611 -0.546969 0.869487 -0.2421486 -0.4305304 0.7804711 -0.4323816 -0.4515652 0.8629816 -0.4596219 -0.2097867 0.8633906 -0.4591326 -0.2091745 0.8085327 -0.5879597 -0.02404743 0.8601051 -0.5086353 0.03885167 0.8046317 -0.563859 0.1860938 0.8504405 -0.4690843 0.2381408 0.8052031 -0.4887246 0.3358514 0.8584319 -0.3081484 0.4100478 0.8093848 -0.3228788 0.4905564 0.8246204 -0.1141821 0.5540431 0.855783 -0.07609486 0.5117081 0.8231949 0.1260077 0.5535994 0.8516627 0.1471776 0.5030004 0.8182518 0.3093464 0.4845295 0.8535476 0.3165041 0.4138618 0.8041067 0.4776504 0.3539244 0.8614488 0.4457687 0.2433031 0.7980325 0.5854462 0.1428175 0.8597026 0.5089586 0.04327327 0.7936696 0.6016687 -0.08990854 0.8619413 0.4836439 -0.1521371 0.798797 0.4897969 -0.3493171 0.8522824 0.3908489 -0.3476376 0.8065161 0.3131435 -0.5014709 0.851363 0.2335553 -0.469716 0.7947627 0.09452795 -0.5995138 0.8553695 0.01177859 -0.5178843 0.8070448 -0.1324976 -0.575433 0.8721734 -0.1925854 -0.4496938 0.7864893 -0.3416004 -0.5145326 0.8739718 -0.4168761 -0.249775 0.8551844 -0.4501101 -0.2570226 0.7721232 -0.6259489 -0.1096071 0.8700972 -0.4914187 0.0379275 0.8006712 -0.584882 0.1297644 0.8453654 -0.4546416 0.2804611 0.8621719 -0.4216862 0.2807856 0.7971229 -0.408552 0.4446128 0.8914977 -0.1460106 0.4288506 0.9045565 -0.1238604 0.4079662 0.7948809 0.01470559 0.6065873 0.847415 0.1855643 0.4974471 0.863062 0.1902685 0.4678911 0.7747065 0.411276 0.4802938 0.873411 0.41395 0.2565125 0.8760071 0.4085131 0.2563762 0.8387097 0.5365715 0.09304416 0.8662419 0.4995651 0.007735669 0.8176766 0.5749434 -0.02907174 0.7907476 0.5469086 -0.2749719 0.8655878 0.4149324 -0.2803369 0.7926177 0.3939116 -0.4653933 0.8668265 0.236531 -0.4389362 0.8041096 0.1644158 -0.5712927 0.860372 0.05671709 -0.5065011 0.8048096 -0.04310333 -0.591966 0.8823751 -0.1548473 -0.4443383 0.792451 -0.2829315 -0.5403438 0.8218265 -0.4238091 -0.3807716 0.8330466 -0.4186517 -0.3616133 0.7449486 -0.6182466 -0.2506449 0.8794597 -0.4739705 -0.0436182 0.8133347 -0.5711202 0.110943 0.875024 -0.4592536 0.1530336 0.792986 -0.524079 0.3106678 0.8521825 -0.3232897 0.411423 0.8550117 -0.3179087 0.4097428 0.8060752 -0.2243506 0.5476402 0.8757383 -0.09266197 0.4738104 0.7841753 0.001482307 0.6205377 0.8480281 0.1891533 0.4950448 0.830617 0.18401 0.5255623 0.8205287 0.3828037 0.4244927 0.8703736 0.3668017 0.328491 0.7694027 0.5697257 0.2888461 0.8610547 0.5052612 0.05741041 0.8709894 0.4892272 0.04510253 0.812993 0.5714098 -0.1119524 0.8778582 0.426062 -0.218715 0.8299893 0.4786211 -0.2864257 0.8049728 0.3318137 -0.4918522 0.8724002 0.2149878 -0.4389743 0.7897935 0.1445807 -0.5960896 0.8721959 -0.02345454 -0.4885942 0.80219 -0.1076061 -0.5872924 0.8554005 -0.2673699 -0.4436251 0.8551243 -0.2678018 -0.4438971 0.8066871 -0.4697456 -0.3586015 0.8577536 -0.3904153 -0.3344172 0.7794189 -0.5725232 -0.2544078 0.859282 -0.4984375 -0.1148677 0.7940912 -0.6076776 0.01214069 0.8777625 -0.4669973 0.1069896 0.8059508 -0.5460934 0.2285285 0.845079 -0.3748375 0.381233 0.8484801 -0.3686631 0.379696 0.8121533 -0.2565882 0.523994 0.8631911 -0.165682 0.4769179 0.8264791 -0.09394246 0.5550739 0.8905987 0.07910203 0.4478581 0.8527439 0.1266714 0.5067369 0.8238068 0.3021973 0.4796031 0.8272731 0.2977792 0.4763895 0.8845421 0.3847321 0.2637549 0.8234673 0.4981827 0.2715066 0.8384302 0.535966 0.09887039 0.8404678 0.5326083 0.09971171 0.8152884 0.572964 -0.08376818 0.8941214 0.4278976 -0.1321016 0.7976844 0.4879195 -0.3544493 0.874528 0.331954 -0.353564 0.7954944 0.3332056 -0.5061253 0.7894945 0.2001367 -0.5802101 0.8818746 0.05190819 -0.4686179 0.8599972 -0.005153477 -0.5102729 0.9258961 -0.1120924 -0.3607657 0.7980663 -0.3077972 -0.5180261 0.905079 -0.2735181 -0.3256068 0.7274765 -0.6014196 -0.3302611 -0.6489175 0.03284537 -0.7601495 0.5722712 -0.3246775 -0.7530539 -0.5407238 -0.4753367 -0.6940265 0.4729101 -0.7493733 -0.4634605 -0.2552393 -0.8643644 -0.4332751 0.07831096 -0.9968332 -0.01382642 -0.05086082 -0.9981501 -0.03331148 0.2462494 -0.8430594 0.478134 0.1499844 -0.8571492 0.4927474 -0.4828835 -0.5294318 0.6975138 0.4964202 -0.3693005 0.7856107 -0.2704724 -0.1049169 0.9569939 0.01469588 -0.04924511 0.9986787 -0.04879653 0.386588 0.9209607 0.0491293 0.3807148 0.9233865 -0.1022662 0.7882389 0.6068123 0.4568044 0.7588781 0.4641485 -0.4783516 0.8469229 0.2321664 0.5920191 0.8013359 -0.08587384 -0.09996885 0.9789651 -0.1778582 -0.387947 0.7731439 -0.5017428 0.580677 0.5777207 -0.5736315 -0.58184 0.3719124 -0.7232865 0.4788376 0.2037739 -0.8539267 -0.299444 -0.211506 -0.9303755 -0.09723246 -0.2113323 -0.972566 -0.0501371 -0.7122678 -0.700115 0.4227335 -0.6984632 -0.5774475 -0.443334 -0.8293137 -0.340138 0.4348348 -0.8932556 -0.1140751 -0.2728017 -0.9608643 0.04815739 0.4170895 -0.8631664 0.2845699 -0.4554142 -0.8054763 0.3792174 0.292618 -0.5451586 0.7856062 -0.2802561 -0.608816 0.7421587 0.4295221 -0.1760848 0.8857229 -0.4904257 -0.07217741 0.868489 0.3431265 0.3497098 0.8717611 -0.05475944 0.3122134 0.9484326 0.2204862 0.6741918 0.7048768 -0.5382463 0.6311897 0.5584716 0.6318809 0.7562903 0.1695629 -0.4046182 0.9080678 0.1081525 -0.08912014 0.943556 -0.3189982 0.3510565 0.8607801 -0.3685336 -0.3323202 0.6696244 -0.6642037 0.2719155 0.6037939 -0.7493296 -0.03940057 0.1877074 -0.9814345 -0.2323539 -0.1712046 -0.9574449 0.258257 -0.6067773 -0.7517477 -0.3595467 -0.6192245 -0.6980597 0.3763718 -0.8936081 -0.2445586 0.1592655 -0.9559044 -0.2467412 -0.3951066 -0.9093112 0.1305525 0.5060929 -0.8052415 0.3089599 -0.3755888 -0.7837887 0.494579 0.3848354 -0.592227 0.7079328 -0.4029887 -0.4919062 0.7717698 0.3497372 -0.2516044 0.9024296 -0.4425152 -0.04137313 0.8958062 0.1834701 0.08387947 0.9794402 0.1898146 0.4891911 0.8512711 -0.5999642 0.442447 0.6665461 0.6328465 0.7073584 0.31488 -0.3827244 0.8765134 0.29197 0.02789908 0.9875083 -0.1550774 0.1813257 0.9676896 -0.175208 0.04710799 0.7712194 -0.634824 -0.5018219 0.640812 -0.5809774 0.4703245 0.3723071 -0.800114 -0.3572871 0.1827808 -0.9159352 0.1206974 0.08892095 -0.9886987 -0.1043186 -0.2851225 -0.9527974 0.2014495 -0.5817299 -0.7880409 -0.1318217 -0.858376 -0.495796 0.2335623 -0.8779039 -0.4180115 -0.2985861 -0.9442611 -0.1386267 0.4741799 -0.8793192 0.04417377 -0.5169635 -0.8249726 0.228405 0.4959354 -0.6829654 0.5362895 -0.4112812 -0.6589586 0.6297789 0.4980046 -0.26412 0.8259735 -0.2223905 -0.2401303 0.9449233 -0.1523865 0.2138581 0.9649057 0.2005285 0.2640256 0.9434399 0.06030845 0.6983724 0.7131893 0.1094074 0.6933423 0.7122545 -0.3458296 0.8779803 0.3309873 0.3019329 0.9281306 0.2177388 -0.2147774 0.9667914 -0.1385103 0.08280301 0.9780761 -0.1910784 -0.01500976 0.7632458 -0.6459341 -0.2380407 0.7302252 -0.6403967 0.2881606 0.3846871 -0.8769147 -0.3078322 0.3253016 -0.894102 0.308502 -0.08749675 -0.9471911 -0.2856533 -0.1460293 -0.9471418 0.2447054 -0.5528745 -0.7965232 -0.0460866 -0.5876519 -0.8078004 0.02712804 -0.9391752 -0.3423656 0.05795258 -0.9374653 -0.3432209 -0.111145 -0.9670343 0.2291101 0.2729904 -0.9194638 0.2829532 -0.3176204 -0.7619864 0.5643529 0.2707158 -0.687218 0.674125 -0.1228778 -0.4704523 0.8738283 0.3002879 -0.3671352 0.880363 -0.4620161 -0.09860879 0.8813725 0.4056972 0.1136358 0.9069162 -0.3918392 0.3417354 0.8542125 0.3276703 0.4821372 0.812512 -0.2536316 0.7867609 0.5627417 0.3579145 0.8174915 0.4512259 -0.4277073 0.8847833 0.1850002 0.5091036 0.8586114 -0.06000238 -0.5647556 0.7899914 -0.2386726 0.5240097 0.7162446 -0.460877 -0.4115409 0.5659089 -0.7144097 0.3056734 0.4616157 -0.8327513 -0.2991657 0.2289981 -0.9263152 0.2579212 0.08588278 -0.9623413 -0.3720237 -0.1748721 -0.911602 0.3994477 -0.3128484 -0.8617236 -0.2993324 -0.7126984 -0.6343983 -0.1580318 -0.7332851 -0.6613009 0.2088328 -0.974107 -0.08662825 -0.1453043 -0.9872272 -0.06534081 0.01914077 -0.9280298 0.3720141 -0.08003485 -0.9209264 0.3814305 0.2133641 -0.6836361 0.697938 0.1024506 -0.6890177 0.7174668 -0.3869674 -0.3721342 0.8436661 0.3727848 -0.2061152 0.9047365 -0.3837896 0.0187475 0.9232303 0.3838738 0.1765691 0.9063467 -0.2331387 0.5729554 0.7857281 0.04045921 0.8621058 0.5051107 -0.1154601 0.9932603 -0.01014745 0.2468735 0.9665416 -0.06964915 -0.2977235 0.8698673 -0.3933084 0.3512588 0.7892406 -0.503703 -0.1995711 0.5801274 -0.7896984 -0.4583725 0.5082089 -0.7291217 0.5083858 0.1542624 -0.8471996 -0.4124706 -0.02489459 -0.9106307 0.1680455 -0.1702302 -0.9709699 -0.2936869 -0.4884811 -0.8216656 0.5429965 -0.6808977 -0.4914604 -0.5379423 -0.8175843 -0.2053629 0.5343714 -0.8439675 0.04654031 -0.458814 -0.8678408 0.1906359 0.556031 -0.6889873 0.4648935 -0.5347234 -0.5841257 0.6106294 0.4935734 -0.3943909 0.7751395 -0.4527421 -0.2502968 0.8557898 0.414087 0.1138945 0.9030837 -0.1296979 0.1712642 0.9766509 -0.4168549 0.5477319 0.7254115 0.02346748 0.654448 0.7557428 0.4786981 0.7768898 0.4090118 -0.6094765 0.7716096 0.182091 0.1578384 0.9850696 0.06873798 0.3044608 0.8943283 -0.3278425 -0.3454236 0.8587994 -0.3783468 0.197229 0.6378094 -0.7445132 0.04347306 0.641126 -0.7662033 -0.1017209 0.1851222 -0.9774368 0.4567846 0.07132399 -0.8867136 -0.4785307 -0.175491 -0.8603553 0.5919665 -0.4386072 -0.6761654 -0.5132053 -0.5475507 -0.6609149 0.4750923 -0.8240739 -0.308528 -0.5195553 -0.8284073 -0.2092936 0.4128202 -0.908035 0.07107716 -0.3038369 -0.9056138 0.2958831 0.2889633 -0.8523537 0.4358825 -0.4860398 -0.6549137 0.5786652 0.5081129 -0.4719136 0.720499 -0.3142054 -0.2991456 0.9009922 0.278519 -0.1593396 0.947121 -0.4433851 0.07118231 0.8935003 0.4349194 0.3016304 0.8484482 -0.2729287 0.4770762 0.8354091 0.3802134 0.6436014 0.6642402 -0.5078221 0.6851614 0.5221787 0.4580482 0.8600187 0.2248549 -0.2996993 0.9451777 0.1296897 0.3865018 0.9050139 -0.1776689 -0.4170793 0.8712272 -0.258859 0.2134546 0.6719958 -0.7091255 -0.07061392 0.7155873 -0.694945 0.2242279 0.3249059 -0.9187808 -0.542845 0.2126474 -0.8124656 0.6364977 -0.1888393 -0.7478038 -0.4049013 -0.3137151 -0.8588585 -0.08902227 -0.7108184 -0.6977195 0.350874 -0.7176591 -0.6015421 -0.3322643 -0.8951115 -0.2972809 0.2713723 -0.9413887 -0.2003609 -0.05506289 -0.9527911 0.2985924 0.2492036 -0.928357 0.2757732 -0.4330562 -0.6988345 0.5692914 0.5285328 -0.4942806 0.6901737 -0.4485369 -0.381469 0.8082673 0.3601159 -0.1433088 0.9218347 -0.2893522 0.03103363 0.9567196 0.4247654 0.228798 0.8759142 -0.4973291 0.3719618 0.7837781 0.4117404 0.652401 0.6362726 -0.3051632 0.7585846 0.5756952 0.3592259 0.8734234 0.3287679 -0.3051139 0.9244104 0.2288476 0.3039364 0.9421662 -0.1412292 0.1240706 0.8715839 -0.4742867 -0.3478235 0.5770259 -0.7389588 0.4562002 0.4013051 -0.7942516 -0.4871729 0.2117837 -0.8472369 0.5211693 -0.02316892 -0.8531388 -0.2582236 -0.3613646 -0.8959555 -0.4168445 -0.3512025 -0.8383899 0.3457862 -0.6923074 -0.633358 -0.2886855 -0.7708734 -0.5678159 0.3955746 -0.8730582 -0.2851143 -0.4209842 -0.8859387 -0.1946407 0.2229295 -0.9287274 0.2962564 0.1761293 -0.9399246 0.2924385 -0.1427369 -0.674516 0.7243303 -0.269843 -0.3933491 0.8788979 0.1752474 0.02728748 0.9841462 0.07513338 0.009425342 0.997129 -0.1353614 0.3821017 0.914153 0.3981963 0.4510399 0.7987508 -0.4825238 0.6014885 0.6366965 0.4961323 0.786845 0.3670528 -0.1201212 0.9253473 0.359588 -0.1674911 0.985818 -0.0104798 0.1528707 0.985677 -0.07121527 0.1523506 0.9017286 -0.4045675 -0.1388733 0.8919339 -0.4303118 -0.2316438 0.6300112 -0.7412336 0.08283287 0.6061125 -0.7910541 0.3831605 0.1992617 -0.9019328 -0.3977997 0.1270389 -0.9086344 0.1606926 -0.3181214 -0.9343322 -0.3130905 -0.2396144 -0.9189991 0.4542684 -0.565628 -0.6882624 -0.4386149 -0.6542028 -0.6161459 0.2377756 -0.8989612 -0.3678745 -0.1829942 -0.9287723 -0.3223277 0.2890237 -0.9558642 0.05280995 -0.1052827 -0.9897382 0.09661209 -0.1010032 -0.8732235 0.476738 0.2133505 -0.8297559 0.5157391 -0.2096571 -0.575262 0.7906438 0.4580042 -0.4136521 0.7868444 -0.5137121 -0.1660699 0.8417367 0.6256345 0.1198412 0.7708564 -0.3984196 0.259658 0.8796816 0.05671888 0.6557626 0.7528336 0.4792864 0.6302574 0.6107865 -0.4670057 0.7841097 0.4087513 0.6005972 0.7920762 0.1090802 -0.2664724 0.9633554 0.03064018 -0.2584077 0.9065865 -0.3336563 0.4361512 0.7912732 -0.4285547 -0.4094255 0.6545928 -0.6355148 0.484382 0.4791209 -0.7319954 -0.4932907 0.1678981 -0.8535072 0.5735857 -0.2049034 -0.7931041 -0.5141165 -0.4653376 -0.7205173 0.5104377 -0.6707957 -0.5380394 -0.5152216 -0.7528984 -0.4095007 0.6094247 -0.7855212 -0.1075087 -0.4929495 -0.8684723 0.05250597 0.3323143 -0.8447651 0.4194512 -0.09648263 -0.9199464 0.3799865 0.267844 -0.6544256 0.7070975 -0.1962279 -0.6277831 0.7532483 0.04872149 -0.2436009 0.9686511 0.08469283 -0.2379855 0.9675691 -0.01029425 0.3699758 0.9289845 -0.102423 0.355888 0.9288989 0.07675129 0.7506073 0.6562758 -0.4013596 0.7238723 0.561177 0.5467911 0.8028758 0.2375077 -0.5385134 0.8386725 0.08143639 0.403967 0.8797795 -0.2505971 -0.09606838 0.9393672 -0.329181 0.08244282 0.708401 -0.7009788 0.05940908 0.7124992 -0.6991534 -0.1409299 0.3528413 -0.9250091 0.1129502 0.03461849 -0.9929974 -0.1331306 -0.4072831 -0.9035468 -0.08410668 -0.4162889 -0.9053341 0.2513852 -0.823085 -0.509251 -0.2805166 -0.8344797 -0.4742934 0.2485658 -0.9672872 -0.05070042 -0.2057553 -0.9785906 -0.005031824 0.01419562 -0.9212386 0.3887391 0.3258071 -0.8475912 0.4188542 -0.3488034 -0.6278478 0.6958041 0.1143937 -0.5955989 0.795095 0.07950615 -0.2356854 0.9685717 -0.08215975 -0.2225748 0.9714475 -0.002859532 0.2118806 0.9772914 0.1980968 0.2441708 0.949283 -0.3040114 0.5126177 0.8029946 0.3275393 0.6285856 0.7054064 -0.2103049 0.8142944 0.5410145 0.2807167 0.8579366 0.4302827 -0.4242204 0.8914468 0.1592479 0.4786298 0.8750048 -0.07266479 -0.2907028 0.9344164 -0.2058109 0.2987292 0.7935417 -0.530144 -0.1953676 0.7833011 -0.5901448 0.03436857 0.5064464 -0.8615863 0.1819916 0.4756547 -0.8605996 -0.1506619 0.1006658 -0.9834468 0.3857828 -0.01399695 -0.9224835 -0.5280755 -0.2495957 -0.8116886 0.5199381 -0.4552305 -0.7227929 -0.4000041 -0.7523378 -0.5234355 -0.1191067 -0.8070375 -0.5783634 -0.02878791 -0.9995804 -0.003232598 0.4404456 -0.8952283 0.06763249 -0.5319374 -0.749103 0.3948258 0.5438131 -0.6362268 0.5472503 -0.413026 -0.3593413 0.8368294 -0.08902585 -0.345537 0.9341727 0.2073627 0.1958023 0.9584687 -0.539999 0.2317931 0.8091186 0.5073386 0.5097802 0.6947891 -0.5338616 0.6683164 0.5180204 0.2818204 0.8559862 0.4334338 -0.2234727 0.9697626 0.09808409 0.07102429 0.9961048 0.05225598 -0.01252788 0.8602491 -0.5097203 0.1911045 0.8491619 -0.4923447 -0.2887496 0.5277507 -0.7988134 0.3923741 0.3824911 -0.8365066 -0.3277063 0.1895246 -0.9255751 0.2882664 6.04172e-4 -0.9575501 -0.4444645 -0.2073451 -0.8714696 0.4766969 -0.3741351 -0.7954766 -0.3083918 -0.7313195 -0.6083307 0.200971 -0.9424056 -0.2673618 -0.3890067 -0.8984777 0.2034987 0.2736699 -0.9098636 0.3118541 0.04911071 -0.6571038 0.7521986 0.1688554 -0.6534808 0.7378691 -0.4273729 -0.2620167 0.8652744 0.3623365 -0.1279483 0.9232234 -0.01205825 0.2499524 0.9681831 -0.1579151 0.2582474 0.9530851 0.05861186 0.6183859 0.7836859 -0.4516394 0.6028307 0.6577363 0.4989914 0.751175 0.4321388 -0.3521427 0.919391 0.1752589 -0.08592802 0.986811 0.1371878 0.09960895 0.9297571 -0.354443 -0.2181307 0.9049218 -0.3654253 0.2778483 0.5334492 -0.7988944 -0.3050833 0.4947783 -0.8137068 0.2025616 0.107792 -0.973319 -0.2903308 0.04170519 -0.9560171 0.3833796 -0.247446 -0.8898262 -0.4125148 -0.395474 -0.820629 0.2424975 -0.5940644 -0.7669959 -0.2543923 -0.7254652 -0.6395192 0.4891186 -0.7728945 -0.4042245 -0.4622529 -0.8399516 -0.2842602 0.2773456 -0.9488638 0.1507877 -0.04972052 -0.9924263 0.1123298 0.295859 -0.7518683 0.5892043 -0.2893484 -0.7214923 0.6290678 0.1472184 -0.3877937 0.9099137 0.1379954 -0.3876503 0.911419 -0.2327967 0.07444155 0.9696723 0.4681505 0.1891693 0.8631629 -0.4314685 0.4152904 0.8008552 0.3866317 0.6486857 0.6555324 -0.202616 0.7519528 0.6273068 0.2798651 0.8891068 0.3621668 -0.3722298 0.8954207 0.2442678 0.304106 0.9526358 -0.002177894 -0.4711521 0.8666306 -0.1642167 0.5251278 0.7687422 -0.3650706 -0.4722082 0.5872923 -0.6573486 0.2451419 0.280397 -0.9280533 -0.3181838 -0.1675609 -0.9331037 0.265043 -0.2767393 -0.9236707 -0.2034027 -0.5490105 -0.810688 0.3538371 -0.6315441 -0.6898923 -0.3399019 -0.7781559 -0.5281478 0.3434594 -0.8682275 -0.3580736 -0.1465057 -0.9875226 -0.05775123 0.1560405 -0.9877361 -0.005384445 -0.1898261 -0.8539155 0.4845559 -0.9020484 -0.3296045 -0.2786927 -0.7737017 -0.6295028 -0.07149809 -0.830058 -0.5550506 -0.05405992 -0.9187885 -0.364717 0.151027 -0.5887249 -0.637884 0.4964949 -0.8965028 -0.2291208 0.3791917 -0.7928956 -0.1569659 0.5887942 -0.8500849 -0.06343525 0.5228115 -0.7864856 0.06906783 0.6137346 -0.8425865 0.1740009 0.5096782 -0.8339534 0.1879204 0.5188524 -0.8406355 0.4013282 0.3636865 -0.8822799 0.3739146 0.2859548 -0.7786699 0.5792059 0.241234 -0.8536769 0.5208003 0.001658141 -0.8574583 0.5145535 -4.18996e-4 -0.7735832 0.5784259 -0.2588295 -0.907181 0.3006079 -0.2943766 -0.822453 0.4391457 -0.3615552 -0.8273392 0.2327911 -0.5111929 -0.8760312 0.1608088 -0.4546536 -0.7987535 0.01333075 -0.6015108 -0.8669009 -0.0791704 -0.4921536 -0.8300822 -0.1387908 -0.5400933 -0.7861611 -0.3463148 -0.5118761 -0.8845895 -0.3272606 -0.3322677 -0.8253828 -0.4550432 -0.3341839 -0.8069129 -0.5517808 -0.2107834 -0.8653968 -0.4887437 -0.1105355 -0.7992797 -0.6006499 -0.01927888 -0.8660147 -0.48786 0.1095961 -0.8120567 -0.5517843 0.1899951 -0.8079295 -0.435622 0.396842 -0.8654877 -0.3410049 0.3669425 -0.8010023 -0.2790614 0.5296416 -0.8683969 -0.1448888 0.4742298 -0.8092377 -0.07968205 0.5820526 -0.8263195 0.1085897 0.5526342 -0.8609147 0.1244724 0.4932876 -0.8005111 0.3111086 0.5122435 -0.8675879 0.3107163 0.3882612 -0.7794192 0.5249456 0.3419618 -0.8803191 0.4475064 0.157406 -0.8121671 0.5715686 0.1170219 -0.805783 0.578443 -0.1269547 -0.8757154 0.4597147 -0.1475974 -0.799883 0.48655 -0.3513636 -0.8663752 0.3471423 -0.3590074 -0.7990092 0.3360725 -0.4986378 -0.8514539 0.1855905 -0.4904922 -0.780627 0.1233524 -0.6127038 -0.798206 -0.1261394 -0.5890297 -0.8520816 -0.06102937 -0.5198388 -0.7929235 -0.241372 -0.5594747 -0.8734816 -0.2684833 -0.4061363 -0.7715417 -0.4642419 -0.4349746 -0.8502553 -0.4881935 -0.1968078 -0.870639 -0.4606008 -0.1727271 -0.7830354 -0.6214205 0.02631092 -0.8766289 -0.4651743 0.1230234 -0.7764413 -0.563324 0.2824978 -0.8611057 -0.3364672 0.381165 -0.803448 -0.4164046 0.4255334 -0.8570232 -0.1486872 0.4933593 -0.7963734 -0.2048391 0.5690611 -0.8757385 -5.42981e-4 0.4827855 -0.7849337 0.1302409 0.6057363 -0.8712259 0.2051 0.4459814 -0.7715011 0.3868694 0.5050924 -0.8516087 0.4470264 0.2737336 -0.8699272 0.4261125 0.2483042 -0.7830466 0.6172491 0.0764302 -0.8690601 0.490467 -0.06462913 -0.8424651 0.5360118 -0.05426019 -0.8108295 0.5171988 -0.2739725 -0.8759996 0.3962736 -0.2749398 -0.8067286 0.3734604 -0.4579482 -0.8622476 0.2565759 -0.43669 -0.7988791 0.1727389 -0.576154 -0.8506097 0.08830046 -0.5183302 -0.7931065 -0.03196656 -0.6082436 -0.8265751 -0.06245797 -0.5593503 -0.7540267 -0.3265574 -0.5699158 -0.8431532 -0.3389014 -0.4174188 -0.7950302 -0.4710586 -0.3821399 -0.8679292 -0.4283001 -0.2515115 -0.8102415 -0.5570471 -0.1822285 -0.8506379 -0.5251495 -0.02516603 -0.8650212 -0.5002511 -0.03856384 -0.7600544 -0.6215347 0.1897683 -0.8802611 -0.4013307 0.2531283 -0.8207674 -0.4384983 0.3661423 -0.8451302 -0.2119831 0.4907323 -0.8939913 -0.2139813 0.3936895 -0.7497417 -0.05417484 0.6595093 -0.9055439 0.07293391 0.4179368 -0.8082517 0.2631927 0.5267437 -0.9043024 0.2687601 0.3316704 -0.7758368 0.5230774 0.3527994 -0.8715272 0.4648438 0.1560786 -0.8100616 0.5775493 0.1011782 -0.854062 0.5166304 -0.0605911 -0.8170294 0.5667323 -0.106195 -0.8210792 0.4852859 -0.3005436 -0.8693807 0.4005032 -0.2894383 -0.8242776 0.3430891 -0.4503959 -0.8687291 0.2389986 -0.4338082 -0.8018237 0.1963859 -0.5643682 -0.8533478 -0.002793788 -0.5213345 -0.8370797 -0.0201025 -0.5467118 -0.8146717 -0.2510242 -0.5227782 -0.8671277 -0.2478612 -0.4320355 -0.763773 -0.5054903 -0.4014106 -0.8848866 -0.4219878 -0.197236 -0.8120878 -0.5616024 -0.1584813 -0.7984646 -0.5997831 0.05210298 -0.8827476 -0.4599696 0.09583681 -0.7650818 -0.5280452 0.368535 -0.8425968 -0.413372 0.3451874 -0.8318304 -0.2909818 0.4726393 -0.8654994 -0.2338247 0.4429861 -0.7895923 -0.1209427 0.6015955 -0.8109067 0.09790116 0.5769279 -0.8651736 0.01577258 0.5012242 -0.8210811 0.2797738 0.4975467 -0.8538928 0.2246177 0.4694827 -0.8285125 0.4188629 0.3716462 -0.8822393 0.3874171 0.2675107 -0.7998954 0.5546668 0.2291554 -0.8306075 0.5562447 0.02613508 -0.8500282 0.5265512 0.01400113 -0.8197713 0.5209333 -0.2379153 -0.8528659 0.4648465 -0.2377766 -0.7885242 0.4216839 -0.4476743 -0.8652287 0.2812985 -0.4150308 -0.8029311 0.2307581 -0.5495929 -0.870047 0.08652591 -0.4853159 -0.7989107 -0.01828569 -0.6011716 -0.8640468 -0.1255197 -0.487512 -0.8127425 -0.2120423 -0.5426673 -0.8618915 -0.3575007 -0.3596337 -0.8889653 -0.3036978 -0.3427953 -0.7608633 -0.5833772 -0.28418 -0.8772932 -0.4722118 -0.08586543 -0.8302979 -0.5561294 -0.03640836 -0.8133317 -0.5581315 0.1642591 -0.8362461 -0.521299 0.1701169 -0.8262791 -0.4434537 0.3472921 -0.8576024 -0.3885418 0.3369774 -0.7808341 -0.3189716 0.5371735 -0.8606958 -0.1589389 0.4836747 -0.8177741 -0.118644 0.5631779 -0.847599 0.05473047 0.5278073 -0.841672 0.06219249 0.5363958 -0.8166922 0.2679949 0.51107 -0.8230938 0.268803 0.5002616 -0.7459245 0.5065128 0.4324827 -0.8391836 0.4752845 0.2643399 -0.8037919 0.5445685 0.2395073 -0.9011862 0.433234 0.01311171 -0.8089829 0.5817026 -0.08466964 -0.8406857 0.4764045 -0.2574614 -0.8331236 0.4890045 -0.2584181 -0.8273696 0.3662803 -0.4257915 -0.838807 0.3474531 -0.4191412 -0.8080933 0.2139993 -0.5488075 -0.8573101 0.1418421 -0.4948741 -0.8132373 0.02513462 -0.5813892 -0.8635366 -0.04503428 -0.5022714 -0.8036093 -0.1856821 -0.5654505 -0.8433676 -0.1954625 -0.5005253 -0.7663328 -0.5256732 -0.3693261 -0.8834817 -0.3477421 -0.3139038 -0.7750742 -0.5797657 -0.2512603 -0.8665988 -0.4984636 -0.0232523 -0.8414576 -0.5403232 1.20156e-4 -0.8028279 -0.5482611 0.2342593 -0.8818342 -0.4175484 0.2191385 -0.844507 -0.3077425 0.4382951 -0.8663402 -0.2714403 0.4192553 -0.7630062 -0.1589784 0.6265361 -0.878637 0.01304394 0.4773122 -0.8111042 0.09792578 0.576646 -0.8362178 0.3012874 0.4582204 -0.847122 0.2982223 0.4398269 -0.8147474 0.4720823 0.336638 -0.8456749 0.4468334 0.2918457 -0.8327838 0.5473877 0.08269166 -0.8262736 0.5577429 0.07870823 -0.845659 0.514616 -0.1415323 -0.8075271 0.5587403 -0.1889694 -0.9003555 0.3154652 -0.299736 -0.7731948 0.3662217 -0.517737 -0.8462148 0.1217321 -0.5187503 -0.8812195 0.08637875 -0.4647485 -0.7792031 -0.1429659 -0.6102487 -0.8828929 -0.2085194 -0.4207373 -0.812369 -0.3304618 -0.4804704 -0.7916904 -0.5051605 -0.3435684 -0.8773646 -0.4296754 -0.2135661 -0.7967726 -0.5933153 -0.1145885 -0.85354 -0.5209897 -0.006274998 -0.8448204 -0.5349372 0.01099503 -0.8795823 -0.4425377 0.1746294 -0.8581709 -0.4682496 0.2104399 -0.773081 -0.4862427 0.4073253 -0.8678227 -0.3127806 0.3860726 -0.8003062 -0.278162 0.5311647 -0.8986266 -0.1175471 0.4226735 -0.789278 0.04612749 0.6123011 -0.8653951 0.1221799 0.4859668 -0.7999199 0.2540001 0.5437023 -0.8714632 0.3053843 0.383787 -0.7753607 0.4846366 0.4048993 -0.8773166 0.4497972 0.167326 -0.8240537 0.5510504 0.1314495 -0.8643863 0.5004108 -0.04925 -0.8357321 0.54282 -0.08305656 -0.7514365 0.5893985 -0.2965683 -0.8715945 0.3757567 -0.3148491 -0.8147337 0.3848664 -0.43369 -0.8597154 0.21218 -0.4646174 -0.8080499 0.1896136 -0.5577652 -0.8112009 0.01316452 -0.5846194 -0.8856948 -0.05955994 -0.4604318 -0.82077 -0.1661431 -0.5465649 -0.8176784 -0.3648034 -0.445332 -0.8782362 -0.3357377 -0.3405603 -0.801488 -0.5259366 -0.2846187 -0.866879 -0.4762495 -0.1473345 -0.8093245 -0.5804106 -0.09009635 -0.8582511 -0.4994155 0.1182762 -0.8822417 -0.4628816 0.08596706 -0.7583976 -0.540971 0.3635705 -0.8675157 -0.3306689 0.3715838 -0.7938425 -0.3294314 0.5111644 -0.8554872 -0.1236352 0.502848 -0.8068779 -0.0778771 0.5855624 -0.8569042 0.08396571 0.5085912 -0.8269757 0.1232289 0.5485672 -0.8363202 0.3700913 0.4044763 -0.8059296 0.3890314 0.4462425 -0.8488432 0.4628369 0.2554357 -0.8776391 0.4299013 0.2119779 -0.8343512 0.5474667 0.06433081 -0.86177 0.5060009 0.03627461 -0.7694239 0.6065447 -0.2002256 -0.8540057 0.4496184 -0.2617586 -0.7531697 0.4784196 -0.4514977 -0.8852851 0.2523468 -0.3906297 -0.812476 0.216413 -0.5413392 -0.8410359 0.02955079 -0.5401718 -0.8327686 0.035829 -0.5524606 -0.8299608 -0.1492244 -0.5374917 -0.8552982 -0.1643318 -0.4913859 -0.8121471 -0.3148158 -0.4912314 -0.8608412 -0.3428977 -0.3759971 -0.8047266 -0.4632685 -0.3712109 -0.8641099 -0.4619016 -0.1999032 -0.8154484 -0.5504344 -0.1790701 -0.8201399 -0.569 0.0600813 -0.8804882 -0.4637416 0.09840935 -0.7914174 -0.5491793 0.2684412 -0.845753 -0.4296404 0.3164033 -0.7329438 -0.4191102 0.5358545 -0.8066549 -0.2006719 0.5559126 -0.7709918 -0.1655206 0.6149591 -0.8634983 -0.03437381 0.503179 -0.8016268 0.06896102 0.5938341 -0.8667489 0.201249 0.456339 -0.8299161 0.2611564 0.4929873 -0.7831743 0.465098 0.4127008 -0.8833435 0.401864 0.2412664 -0.8214231 0.5311643 0.2076742 -0.8477009 0.5304008 0.008847951 -0.8527652 0.5222787 0.004079163 -0.8175491 0.5404673 -0.1987676 -0.856722 0.494121 -0.1478915 -0.7815664 0.4714323 -0.4085409 -0.8586531 0.3419268 -0.3818387 -0.7919262 0.2671238 -0.5490881 -0.8678825 0.1521452 -0.4728973 -0.7825298 0.02057439 -0.6222732 -0.8683251 -0.1259531 -0.4797368 -0.8233922 -0.115534 -0.5555873 -0.8461567 -0.2987432 -0.441329 -0.836668 -0.3145695 -0.4483669 -0.8140269 -0.4897798 -0.3122113 -0.8582989 -0.4568817 -0.2336285 -0.8090616 -0.5611668 -0.1746749 -0.8561584 -0.5164721 -0.01579427 -0.8197047 -0.5722967 0.02368295 -0.8274999 -0.5117144 0.2310684 -0.8600153 -0.4545124 0.2319315 -0.7966139 -0.4185284 0.4361655 -0.8713521 -0.2700844 0.409634 -0.8054533 -0.2486109 0.5379943 -0.8613616 0.02071547 0.5075697 -0.8350101 0.04269146 0.548576 -0.8035857 0.2466507 0.5416767 -0.8484457 0.3828979 0.3654164 -0.9009296 0.2753844 0.3353945 -0.7706561 0.5584009 0.3070465 -0.8802808 0.4595169 0.1181097 -0.8179343 0.5709155 0.07098674 -0.7880926 0.5973901 -0.1484427 -0.8833268 0.4327153 -0.1802539 -0.7999314 0.4736611 -0.3684495 -0.8594114 0.321328 -0.3976938 -0.8161949 0.3183627 -0.4821525 -0.8516294 0.1665538 -0.4969781 -0.80045 0.1148 -0.5883034 -0.7728514 -0.1704006 -0.611281 -0.8791607 -0.06339955 -0.4722892 -0.769543 -0.3049172 -0.5610964 -0.8706514 -0.349812 -0.3458291 -0.8060623 -0.4716587 -0.3574937 -0.8394916 -0.524421 -0.142255 -0.8580316 -0.4987659 -0.1225336 -0.7821962 -0.61696 0.08677279 -0.8699786 -0.4684855 0.1538142 -0.8036487 -0.5158023 0.2968112 -0.8598701 -0.3780032 0.3431284 -0.8193428 -0.3823223 0.4272087 -0.8227391 -0.2422865 0.5141962 -0.8767973 -0.1536096 0.4556651 -0.769267 -0.04788923 0.6371302 -0.8404625 0.1521283 0.5200767 -0.85207 0.1535522 0.5003985 -0.8353328 0.2629102 0.4828017 -0.8835701 0.3255492 0.3366329 -0.832015 0.4348011 0.3445277 -0.8425038 0.4996169 0.2014214 -0.8516397 0.482936 0.2036732 -0.7919097 0.6089937 0.04478716 -0.8595115 0.5027794 -0.09194052 -0.8603974 0.501196 -0.09229862 -0.7859135 0.5268599 -0.3236643 -0.8644445 0.3853037 -0.3229194 -0.7896218 0.3545047 -0.5008233 -0.8269477 0.2836352 -0.4854982 -0.7561513 0.1728529 -0.6311555 -0.8387565 -0.00863409 -0.5444384 -0.7896679 -0.0820657 -0.6080212 -0.8757482 -0.1642729 -0.4539599 -0.7735507 -0.348582 -0.5292543 -0.8526449 -0.4218963 -0.308221 -0.8508819 -0.4236228 -0.3107151 -0.8186268 -0.5543594 -0.1501199 -0.8713898 -0.4855221 -0.07034325 -0.8134639 -0.5810021 0.02670133 -0.8437842 -0.4994037 0.1965304 -0.8535419 -0.4880491 0.1824125 -0.8002133 -0.4448809 0.4021688 -0.8677023 -0.3289692 0.3726553 -0.7934339 -0.180729 0.5812054 -0.8142668 -0.1843532 0.5504395 -0.8303648 0.05844944 0.5541462 -0.8705877 0.08119487 0.4852674 -0.7985613 0.319798 0.5099306 -0.8586761 0.3064497 0.4108088 -0.8247815 0.484582 0.2914031 -0.8663924 0.4098329 0.2853089 -0.7993046 0.5631992 0.2095685 -0.8435618 0.536661 0.019966 -0.8594627 0.5111319 0.008247852 -0.7917532 0.5774996 -0.1990509 -0.8627113 0.430903 -0.2646733 -0.8222106 0.4960415 -0.2791283 -0.8545413 0.2878805 -0.4323011 -0.8299158 0.2903072 -0.4764049 -0.8071563 0.09531831 -0.5825918 -0.8607134 0.03917568 -0.5075804 -0.8419127 -0.007087886 -0.5395674 -0.8569259 -0.2192562 -0.4664812 -0.8662358 -0.2228246 -0.4471965 -0.806506 -0.3736147 -0.4582141 -0.8608707 -0.4006387 -0.3136724 -0.8012643 -0.5100261 -0.312808 -0.8006 -0.5920924 -0.09201294 -0.8851286 -0.4651623 -0.01309531 -0.8103886 -0.5758588 0.1079674 -0.8356668 -0.4716733 0.2813989 -0.869414 -0.407482 0.2794239 -0.7851084 -0.4047974 0.4687686 -0.8833478 -0.1962985 0.4256334 -0.8107586 -0.1583714 0.5635504 -0.8300226 0.06368178 0.5540824 -0.8392337 0.06838905 0.5394534 -0.8140079 0.254294 0.5222315 -0.8578406 0.2605116 0.4429937 -0.7856691 0.4556573 0.4184501 -0.8666726 0.4233183 0.2639704 -0.7978969 0.5690466 0.1988636 -0.8669707 0.4941033 0.06499105 -0.7823173 0.6221337 -0.03048807 -0.8698807 0.4431788 -0.2165644 -0.8366786 0.4774162 -0.268408 -0.7856142 0.3824477 -0.486358 -0.8738504 0.2429026 -0.4211696 -0.801895 0.1530009 -0.5775424 -0.8668063 0.04392975 -0.4967063 -0.8015301 -0.08391308 -0.5920374 -0.8668441 -0.1651445 -0.4704347 -0.7944679 -0.2964347 -0.5300446 -0.8398398 -0.3655909 -0.4012635 -0.7539333 -0.5227441 -0.3978986 -0.8107934 -0.5665174 -0.1472144 -0.8270081 -0.5405372 -0.1545229 -0.8034297 -0.5922719 0.06094825 -0.8802262 -0.4613627 0.111114 -0.8082615 -0.5260757 0.2644956 -0.8567763 -0.3668811 0.3623988 -0.8402206 -0.3745203 0.3921278 -0.8648074 -0.08488905 0.4948757 -0.8162363 -0.1250234 0.5640279 -0.8436304 0.1036412 0.5268265 -0.8359809 0.1014192 0.5393053 -0.8563624 0.2883328 0.4283781 -0.833027 0.3307899 0.4434459 -0.8476739 0.4333467 0.3060388 -0.7798389 0.548278 0.302064 -0.8697048 0.4821658 0.1054977 -0.8058352 0.5913155 0.03123742 -0.8650206 0.4816816 -0.1404361 -0.8255805 0.5299413 -0.1938528 -0.8141689 0.4074136 -0.4136947 -0.8769434 0.3016884 -0.3741046 -0.7960112 0.2272809 -0.5609899 -0.8628998 0.0976327 -0.4958546 -0.7998569 0.003035128 -0.6001832 -0.8555848 -0.09210318 -0.5094035 -0.788995 -0.2254129 -0.5715558 -0.8522955 -0.2860402 -0.4379196 -0.8058567 -0.3920813 -0.4436972 -0.8634386 -0.420351 -0.2788892 -0.8810374 -0.3815693 -0.2796036 -0.8095622 -0.5741187 -0.122461 -0.9035285 -0.4284026 0.01036655 -0.8366976 -0.5382837 0.1009348 -0.8070104 -0.527695 0.2650893 -0.858945 -0.4287813 0.2799288 -0.8088385 -0.4351633 0.3954911 -0.8445087 -0.2406195 0.4784426 -0.8548038 -0.2414005 0.4593869 -0.7779881 -0.0759418 0.6236726 -0.8812048 0.05346935 0.4697011 -0.8273168 0.132506 0.5458838 -0.8315212 0.3358265 0.4424851 -0.8574097 0.3261547 0.3980852 -0.8103906 0.4908621 0.3198775 -0.8606504 0.4531361 0.2322685 -0.8215926 0.5556104 0.1276048 -0.8680052 0.4946473 0.04348665 -0.8098703 0.5825055 -0.06926333 -0.8520975 0.4924194 -0.1773504 -0.8098826 0.5336483 -0.2435364 -0.8363202 0.4099282 -0.3640432 -0.7675244 0.4179139 -0.48606 -0.7975466 0.1641074 -0.580507 -0.8398864 0.1773646 -0.5129646 -0.7933847 -0.0612958 -0.6056267 -0.8578512 -0.1057198 -0.5029063 -0.8107945 -0.2249841 -0.540365 -0.8617454 -0.3058523 -0.404783 -0.8423858 -0.3453392 -0.4136751 -0.8224444 -0.4946534 -0.2808973 -0.8520138 -0.4649585 -0.2405954 -0.8481968 -0.5278975 -0.0434345 -0.8370397 -0.5459993 -0.0353477 -0.8129219 -0.5538446 0.1800394 -0.8569701 -0.4738777 0.2025893 -0.7610012 -0.5129282 0.3972178 -0.8326035 -0.3095156 0.4593164 -0.8142549 -0.3070141 0.4926778 -0.8370712 -0.07419008 0.5420403 -0.7626028 -0.0381698 0.64574 -0.8526957 0.1816045 0.4898264 -0.8981699 0.1718562 0.4046683 -0.7920548 0.4722999 0.3867583 -0.9039227 0.3569059 0.2356733 0.07968455 0.9662094 0.2451328 -0.4829764 0.8739492 -0.05428355 -0.127862 0.4659028 0.875549 0.3127035 0.6970445 0.6452485 -0.7945213 -0.05677503 0.6045763 0.7139821 0.1955566 0.6723 -0.7396084 0.3070315 0.5989249 0.6651028 0.5155375 0.5402401 -0.6805053 0.6089315 0.4075721 -0.8746623 -0.4031109 0.2691978 0.4431196 0.8649754 0.2355054 -0.1267395 0.9803701 -0.1510351 -0.505544 -0.3105646 -0.8049689 0.6590409 -0.5537768 -0.5089169 -0.5485745 -0.7524902 0.3644514 0.3653137 -0.531104 0.7645094 -0.8158299 0.548297 -0.1838263 0.7163443 0.5259258 -0.4585334 -0.771825 0.3671956 -0.5190892 0.7916134 -0.5833261 0.1818763 -0.4853046 -0.3637133 0.7951052 0.1508354 0.08053529 0.985273 -0.8284947 0.3786007 0.4126237 0.7435523 0.645564 0.1742907 -0.6045739 0.7934958 0.06967657 0.7236419 0.6527524 -0.2241804 -0.8129338 0.4279906 -0.3949214 -0.8309052 0.04356276 0.5547062 0.8339663 0.3478383 0.4283792 0.8014495 0.458039 0.3845505 -0.8746078 -0.1599445 0.4576886 0.7791436 -0.2348647 -0.5811832 -0.6862819 -0.4800567 0.546409 0.5944746 -0.2952047 0.7479667 -0.6714074 -0.1210683 0.7311324 -0.8224032 0.4960365 0.2785692 0.6488507 -0.7046195 -0.2872353 -0.5992705 -0.7867932 -0.1477547 0.6852453 -0.7189443 0.1164393 -0.9156333 -0.03886002 0.4001323 0.7289745 0.3604964 0.5819267 -0.6212791 0.6085317 0.4936614 0.360365 0.9227233 -0.136817 -0.2592194 0.9006387 -0.3487914 0.03620678 0.8395971 -0.5420017 -0.7315984 0.475642 -0.4883938 -0.6901013 0.5791653 -0.4339676 -0.9926893 0.1099631 -0.04976069 -0.7373368 0.5689724 -0.3641495 -0.1647318 0.7898728 -0.5907322 -0.7182976 0.6282283 -0.2989613 -0.8331874 0.5298745 -0.1582148 -0.2680125 0.8993937 -0.345341 -0.7916114 0.6041128 -0.09164708 -0.2540132 0.956749 -0.1418052 -0.8466608 0.5317637 0.01982247 -0.06029313 0.9961663 -0.06338375 -0.753774 0.649092 0.1024916 -0.2952946 0.9512297 0.08923685 -0.740909 0.6426904 0.1949433 -0.4260983 0.8405736 0.3344794 -0.1397692 0.955116 0.2611862 -0.8782421 0.4297276 0.2098212 -0.3591542 0.7976616 0.4845042 -0.6124396 0.5817406 0.5352529 -0.6098521 0.6339808 0.4755511 -0.7398595 0.4699779 0.4813821 -0.9418119 0.1947311 0.2739896 -0.0341345 0.6393089 0.7681921 -0.4423666 0.4406527 0.7811127 -0.4480766 0.4171029 0.7907291 -0.8028113 0.2050421 0.5598678 -0.8152599 0.144306 0.5608271 -0.1457541 0.3220099 0.9354493 -0.461647 0.0864104 0.8828451 -0.9675011 -0.005401432 0.2528093 -0.4552091 0.07586073 0.887147 -0.8596801 -0.09955406 0.5010383 -0.6381936 -0.08352321 0.765332 0.001809358 -0.04841589 0.9988257 -0.8314527 -0.1988403 0.5187959 -0.3194007 -0.2118015 0.9236468 -0.2626402 -0.3055306 0.9152439 -0.4406115 -0.3977642 0.8047642 -0.953789 -0.1821218 0.2389945 -0.4276267 -0.4164562 0.8023089 -0.6029032 -0.5255459 0.6002578 0.1813992 -0.6100239 0.7713398 -0.7687279 -0.4579699 0.4464539 -0.8834337 -0.3349053 0.327694 -0.2345641 -0.6877057 0.6870521 -0.9265576 -0.3382635 0.1645266 -0.4911794 -0.7460525 0.4496094 -0.3191766 -0.8052787 0.4996525 -0.8203411 -0.5332692 0.2065539 -0.6912292 -0.6634404 0.2864422 -0.1335354 -0.8649669 0.4837363 -0.1578937 -0.9661614 0.2039653 -0.7770591 -0.6276032 0.04788911 -0.2029516 -0.9597172 0.194303 -0.4647989 -0.8844559 0.04123038 -0.9003019 -0.4344069 -0.02733504 -0.3613827 -0.9263015 -0.106622 -0.8131015 -0.5564393 -0.1710013 -0.7733378 -0.6028411 -0.1962943 -0.2709851 -0.9527042 -0.1375565 -0.7254316 -0.64103 -0.2506585 -0.1447262 -0.9207769 -0.362249 -0.1092044 -0.9288371 -0.3540284 -0.9955194 -0.07135891 -0.06204175 -0.6798355 -0.6011326 -0.4200753 -0.7812358 -0.4724056 -0.4080486 -0.9779095 -0.143564 -0.151929 -0.3406687 -0.7676908 -0.5427666 0.01716488 -0.7304301 -0.6827717 -0.5444334 -0.474055 -0.6920001 -0.4343969 -0.5098098 -0.7425587 -0.7648477 -0.2739477 -0.5830615 0.1179509 -0.3647742 -0.9235949 -0.7435805 -0.156716 -0.6500217 -0.7447936 -0.1556268 -0.6488935 -0.3525863 -0.2075747 -0.9124668 -0.9748962 -0.006167531 -0.2225748 -0.6788341 0.03887027 -0.7332622 -0.1201022 0.005989074 -0.9927436 -0.7958197 0.107383 -0.5959362 -0.2597692 0.05617564 -0.9640354 -0.7503696 0.2048914 -0.6284626 -0.7641408 0.2264244 -0.6040042 -0.2205283 0.2721439 -0.9366456 -0.0824126 0.3229395 -0.9428247 -0.937194 0.1890051 -0.2931628 -0.4144813 0.5069602 -0.7557756 -0.4116526 0.5134295 -0.7529491 -0.1493809 0.6147292 -0.7744634 -0.9999817 0.001579284 0.005844116 -0.9999682 0.006171464 0.005047261 -0.9999909 0.003608286 -0.002309799 -0.9999945 -6.88212e-5 -0.003330111 -0.9999569 -0.003134369 0.008745193 -0.9998725 -0.01117169 0.01141434 -0.9999996 6.46442e-5 -9.83231e-4 -0.9998445 0.004812479 -0.01696676 -0.9997751 0.01942884 0.008501052 -0.4509962 -0.5629183 0.6926222 -0.4304497 -0.5731481 0.6972907 -0.9540661 -0.1943028 0.2280449 -0.5529704 -0.4069555 0.7270564 -0.8032155 -0.27007 0.5309494 -0.3536967 -0.3899033 0.8502202 -0.834227 -0.1885612 0.5181795 -0.6707609 -0.2038885 0.7130984 -0.6204891 -0.1649467 0.766672 -0.6815024 -0.09041899 0.7262086 -0.9928989 -0.0191223 0.1174151 -0.9531194 -0.01660674 0.3021383 -0.5055906 -0.01037484 0.8627113 -0.5775489 0.1019574 0.8099642 -0.8321899 0.08321553 0.5482111 -0.4558395 0.1580905 0.8759096 -0.4957124 0.2864848 0.8198754 -0.9237347 0.1164324 0.3649081 -0.7472331 0.2778124 0.6037077 -0.2220616 0.5326811 0.8166637 -0.7356632 0.3248208 0.5943831 -0.8005623 0.3276455 0.5017457 -0.4636987 0.5841071 0.6661851 -0.4177621 0.6488385 0.6359901 -0.9531856 0.1981932 0.2283787 -0.6173337 0.6044479 0.5035294 -0.8707379 0.3797655 0.3123998 -0.4716121 0.7617633 0.4441832 -0.6155915 0.7062612 0.3496316 -0.9329369 0.3214873 0.1620953 -0.9425982 0.2960075 0.1545588 -0.5350394 0.795032 0.2857572 -0.7187408 0.6762857 0.1613981 -0.7172619 0.6882912 0.108585 -0.7978691 0.6009315 0.04781717 -0.5311177 0.8428694 -0.08651763 -0.7619661 0.6475831 -0.006621241 -0.4734396 0.8665976 -0.1576821 -0.643788 0.7278254 -0.2362358 -0.9666587 0.246805 -0.06825262 -0.7878541 0.5735106 -0.2244367 -0.1707287 0.8388605 -0.51688 -0.7521831 0.5741373 -0.3233993 -0.8079113 0.481349 -0.3399744 -0.6219353 0.5994623 -0.5038269 -0.9671837 0.1910611 -0.1674853 -0.5139822 0.608052 -0.605058 -0.6597065 0.4113821 -0.6289294 -0.6971313 0.4017945 -0.5937754 -0.7116167 0.3935695 -0.5819835 -0.4929934 0.2887678 -0.8207135 -0.5239931 0.2869727 -0.8019214 -0.9610812 0.09588062 -0.2590945 -0.8574292 0.1405347 -0.4950407 -0.3003344 0.1712869 -0.9383285 -0.5433006 0.06092303 -0.8373249 -0.7002681 0.03274124 -0.7131288 -0.7756094 -0.01337623 -0.6310714 -0.7247977 -0.09825879 -0.6819189 -0.2088652 -0.1791728 -0.9613909 -0.8120393 -0.1464275 -0.5649348 -0.5300701 -0.3089806 -0.7896562 -0.7482417 -0.2286431 -0.6227815 -0.3057383 -0.4222517 -0.8533625 -0.8355842 -0.2638753 -0.4818392 -0.5333973 -0.4496816 -0.7164313 -0.8285682 -0.2732693 -0.4886705 -0.4365741 -0.5429622 -0.7173529 -0.6065834 -0.5593371 -0.5649766 -0.2679678 -0.7288789 -0.6300229 -0.8776491 -0.3532296 -0.3239768 -0.8977429 -0.3211953 -0.3014819 -0.4874216 -0.765605 -0.4198442 -0.6851146 -0.6482099 -0.332328 -0.7819167 -0.5804278 -0.2273982 -0.6607467 -0.7286639 -0.1801744 -0.6738176 -0.722208 -0.1561579 -0.5390379 -0.8416697 -0.03209674 -0.9220622 -0.3868617 -0.01181477 -0.7624985 -0.6453006 0.04672622 -0.7526772 -0.6528801 0.08499795 -0.6022055 -0.7800543 0.1698943 -0.6075657 -0.7395939 0.2895945 -0.9769382 -0.2006958 0.07289028 -0.7836346 -0.5552073 0.2786785 -0.5855727 -0.6448795 0.4911569 -0.7032597 -0.5774701 0.4146736 -0.9337199 -0.2404965 0.2651952 -0.004468679 -0.6326032 0.7744632 0.007493853 -0.5400664 0.8415891 0.002556622 -0.4564036 0.8897693 -0.007478654 -0.4062263 0.913742 0.003609776 -0.2614653 0.9652062 -0.005483865 -0.2091561 0.9778669 -0.00339967 -0.04962253 0.9987623 0.004761815 -0.0122947 0.9999132 0.004113078 0.1491621 0.9888042 -0.002349793 0.1873348 0.9822933 0.005581319 0.3565529 0.9342585 0.001920342 0.3722957 0.9281123 -0.005278289 0.5566177 0.8307521 0.003194034 0.5280311 0.8492192 4.05712e-4 0.7296723 0.683797 5.36298e-4 0.7293137 0.6841793 7.53072e-4 0.8599752 0.5103355 -0.0028342 0.8692966 0.4942828 0.001609861 0.9389761 0.3439791 -0.002048134 0.9479789 0.3183268 0.00326389 0.9741778 0.2257584 -0.008053064 0.9919401 0.126452 0.001078486 0.999913 0.0131433 -9.51885e-5 0.999996 0.002876698 0.005596935 0.9869031 -0.1612172 -4.83634e-4 0.977868 -0.2092224 0.006069481 0.9518666 -0.3064528 -0.005874335 0.9223033 -0.3864223 -0.003795862 0.8485121 -0.5291624 -6.85841e-4 0.8570362 -0.5152559 0.006670057 0.7572439 -0.6530982 -0.005171 0.6970764 -0.7169782 0.003512561 0.6079118 -0.7939968 -0.005996763 0.558276 -0.8296337 0.004890501 0.3706264 -0.9287692 0.005949139 0.3750922 -0.9269685 0.00201565 0.1752991 -0.9845132 0.001286983 0.1718387 -0.9851243 0.001801192 -0.02575272 -0.9996668 0.001494288 -0.02711689 -0.9996312 -0.01068609 -0.1685457 -0.9856359 0.009461522 -0.2740225 -0.9616768 0.006252646 -0.493884 -0.8695054 -0.003979742 -0.4434302 -0.8963001 -0.002705752 -0.6216412 -0.7832974 0.003306567 -0.661707 -0.7497553 -0.005495309 -0.7474052 -0.6643457 0.005179643 -0.7874262 -0.6163872 0.004473447 -0.866227 -0.4996308 -0.006605267 -0.8999541 -0.4359347 0.002102553 -0.9422124 -0.3350099 0.00397706 -0.9772463 -0.2120706 -0.003437459 -0.9644169 -0.2643637 1.81109e-6 -0.9994778 0.03231644 -0.00890094 -0.999804 -0.01769089 -0.004657924 -0.9852083 0.1712979 0.003906846 -0.9751681 0.2214317 0.001047074 -0.9017762 0.4322023 -0.004748165 -0.9153696 0.4025869 -0.00598216 -0.8227077 0.5684334 6.38488e-5 -0.804668 0.5937252 0.004449963 -0.6714891 0.7410011 -0.9999291 0.008873522 -0.007942974 -0.9999737 -0.003604352 -0.006304264 -0.9997268 -5.98936e-4 -0.02336734 -0.9992564 -0.03081065 -0.02318316 -0.9998975 0.006161928 -0.01292669 -0.9999232 -8.48105e-4 -0.012371 -0.9998533 0.01711463 6.95088e-4 -0.9999288 -0.009657442 -0.007022559 -0.9999153 -0.01214474 0.004699945 -0.9996931 0.0240643 0.005888342 -0.999989 0.00468713 8.25309e-5 -0.999962 -0.008683502 7.91487e-4 -0.9999907 0.003939986 -0.001785755 -0.9999622 -0.008580744 -0.001443207 -0.9999883 0.004209458 -0.002414345 -0.9999725 -0.005380034 -0.005110919 -0.9999821 -0.005987703 2.23638e-4 -0.9999914 0.004137635 2.96939e-4 -0.9999847 0.005073666 0.002234935 -0.9999676 -0.007958114 -0.001174151 -0.999983 0.005422413 -0.002197086 -0.9998538 0.01482611 -0.008525192 -0.99992 -0.006929695 0.01058024 -0.9998511 0.007926046 0.01533371 -0.999728 0.02043098 0.0112521 -0.9999207 -0.006665647 0.01069134 -0.9998767 -0.003206431 0.01537692 -0.9997124 0.008505463 0.02242672 -0.9996517 -0.01683294 0.0203281 0.7276988 -0.4478893 0.5194706 0.4766488 -0.6219637 0.6212626 0.4451539 -0.7090192 0.5469276 0.6460735 -0.645585 0.4071967 0.9249209 -0.3222721 0.2016482 0.9326987 -0.3040432 0.1939876 0.420311 -0.8201519 0.3881877 0.6145603 -0.7544107 0.2306084 0.7908354 -0.5829634 0.1863684 0.504538 -0.8395371 0.2015413 0.6242213 -0.7799811 0.04446715 0.9544894 -0.2968721 0.02858453 0.4247654 -0.9053031 -8.61219e-4 0.8968808 -0.4421743 0.009329378 0.4227156 -0.8940928 -0.148019 0.7380638 -0.6524595 -0.1719257 0.8638902 -0.4892974 -0.1195066 0.5302539 -0.7808784 -0.330242 0.9652766 -0.2453749 -0.08962285 0.5518428 -0.7367689 -0.3906934 0.6944216 -0.6048535 -0.3897832 0.8374511 -0.4580804 -0.2980576 0.5114375 -0.6718772 -0.5357358 0.9593529 -0.2003996 -0.1987016 0.532384 -0.5598447 -0.6349341 0.6683499 -0.4547702 -0.5886362 0.7999591 -0.36149 -0.4789472 0.3731727 -0.4611935 -0.8050109 0.8824543 -0.1740216 -0.4370252 0.6300892 -0.2781961 -0.7249791 0.3986563 -0.2393651 -0.8853121 0.9297011 -0.1170868 -0.3492085 0.5814796 -0.1192992 -0.8047665 0.8028464 -0.08900058 -0.5895055 0.3892645 -0.03386485 -0.9205033 0.9074786 0.01922577 -0.4196582 0.6336668 0.1059221 -0.7663204 0.713973 0.1123929 -0.6910938 0.7448326 0.1591495 -0.6479938 0.3469667 0.3594011 -0.8662824 0.9103243 0.1445629 -0.3878292 0.6634082 0.4082455 -0.6270768 0.8144564 0.3074942 -0.4920449 0.5629249 0.4930033 -0.6633729 0.66625 0.5448001 -0.509219 0.9622161 0.1816647 -0.2028253 0.7519284 0.4999985 -0.4296571 0.7500394 0.5132318 -0.4171741 0.4967301 0.7490885 -0.4383215 0.6459265 0.7006712 -0.3030492 0.916545 0.3647694 -0.1639771 0.9112457 0.3749057 -0.1705199 0.498243 0.8191782 -0.2840796 0.6360792 0.7650521 -0.1004917 0.9189989 0.3878768 -0.07065987 0.6644128 0.7422486 -0.08730816 0.6141874 0.7889985 0.01598304 0.9827024 0.1848627 -0.01104378 0.6746493 0.7364304 0.0501874 0.6510044 0.7454373 0.1432358 0.7483451 0.6353667 0.1904961 0.6593903 0.696551 0.2828798 0.481144 0.7415708 0.4675181 0.6735744 0.6463768 0.3584614 0.9088085 0.3342692 0.2496627 0.3901596 0.678268 0.6226782 0.5197567 0.6081562 0.5999994 0.7955412 0.4264757 0.4303866 0.4983051 0.491537 0.7142013 0.8383501 0.3197984 0.4414728 0.6894901 0.3769072 0.6185017 0.6841611 0.3349665 0.6478587 0.377141 0.3316692 0.8647314 0.9058486 0.1206383 0.4060602 0.6653811 0.1275101 0.7355332 0.638969 0.1098655 0.7613465 0.6647221 0.05430251 0.7451147 0.3994038 -0.03225171 0.9162077 0.9963621 0.01117217 0.08448588 0.9118185 -0.02007788 0.4101024 0.5468536 -0.1718565 0.8194001 0.8022658 -0.1255307 0.5836194 0.3945944 -0.2400164 0.8869541 0.5014201 -0.3250904 0.8018069 0.8794638 -0.1564078 0.4495333 0.7367903 -0.300593 0.605627 0.7510861 -0.3556206 0.5562406 0.7787241 -0.3539098 0.5180122 0.02008593 -0.2877506 -0.9574947 0.02096587 -0.2868963 -0.9577322 0.02104556 0.6840777 -0.7291055 0.02008277 0.6847994 -0.7284549 0.02111953 0.9734632 0.2278668 0.01998239 0.9732241 0.2289885 0.739356 0.182032 0.6482416 0.5442151 0.2512352 0.8004442 0.5351099 0.8223168 0.1935266 0.5422354 0.8181004 0.1915528 0.7382623 0.4524613 -0.5002475 0.5373277 0.5850053 -0.6074931 0.7431097 -0.1937978 -0.6404924 0.7336166 -0.1952769 -0.6509022 0.7385444 -0.6552308 -0.1588229 0.6828373 -0.7120006 -0.163672 0.741679 -0.4555137 0.4923612 0.6767918 -0.5073798 0.5334029 0.0250833 -0.9725201 -0.2314643 0.02336448 -0.9729694 -0.2297495 0.0227552 -0.6839177 0.7292043 0.02549713 -0.6859528 0.7271992 0.02597934 0.2894906 0.9568284 0.01989567 0.2834752 0.9587733 0.9999325 0.006133556 -0.009871363 0.9999933 0.00345999 0.001215219 0.9999852 0.004161775 0.00353527 0.9999598 0.003061592 0.008435606 0.9999853 0.00533545 -0.001007854 0.9999811 0.005544841 -0.002686917 0.999965 0.002528488 0.00798422 0.9998329 -0.00919348 0.01579904 0.9999915 0.004074692 7.06504e-4 0.9998887 -0.003721356 -0.01445454 0.9999737 0.002967953 0.006617069 0.9998727 -0.01314568 -0.009051978 0.9999851 0.003757476 -0.00397998 0.9999674 0.001868069 0.00786072 0.9999815 0.005241215 0.003129482 0.9999626 -0.002586424 -0.0082587 0.9999921 -0.002374351 0.00321871 0.9999611 -0.002521038 -0.008456885 0.9999907 -0.001985192 0.003861427 0.9999443 -0.00813812 -0.006716489 0.9999938 -0.002154052 0.002801656 0.9999002 -0.0141046 -7.61573e-4 0.9999596 -0.008734405 -0.002176523 0.9999654 0.003330707 -0.007622003 0.9999538 -0.006770372 0.006828069 0.9996695 -0.01638412 0.01981174 0.9961652 -0.08572155 -0.01751488 0.999988 0.003877103 -0.003030419 0.9997982 -0.0189563 -0.006640195 0.9979845 -0.04847556 0.04095447 0.998063 -0.05167108 -0.03464561 0.9997271 0.02027028 -0.0116133 0.9984652 -0.01596444 0.05303084 0.9991537 -0.004083633 0.04093182 0.9991351 1.86114e-4 0.04158049 0.9999512 -0.009840786 8.65192e-4 0.9999743 0.001619219 0.006994009 0.9999947 0.002363264 0.002259194 1 -6.60371e-5 -6.08447e-5 1 -1.30267e-4 -1.02094e-4 0.9997852 0.01321476 0.01597142 0.906471 0.2111306 0.3656969 0.6215906 0.5747976 0.5321963 0.8689536 0.4257817 0.2522491 0.6896148 0.6788969 0.2520529 0.8850988 0.4649952 0.01948946 0.7718034 0.6315288 -0.07410103 0.8691745 0.4512053 -0.2023603 0.7912027 0.5227302 -0.3174135 0.8473165 0.3468989 -0.4021394 0.7864603 0.3518559 -0.5076197 0.8268233 0.1923269 -0.5285583 0.7515602 0.1476199 -0.6429353 0.8080334 -0.01943206 -0.5888161 0.8793414 -0.09567016 -0.4664826 0.8090777 -0.2350685 -0.5386428 0.8449339 -0.3437095 -0.4098178 0.8521371 -0.3328171 -0.4038505 0.8046981 -0.4895855 -0.335808 0.8967444 -0.4171858 -0.1476669 0.8213046 -0.5633869 -0.08974421 0.8930894 -0.4419847 0.08391112 0.846473 -0.5159686 0.1313771 0.763279 -0.5725886 0.2992448 0.878275 -0.324192 0.3514723 0.8512015 -0.3403526 0.3995199 0.7815859 -0.2304999 0.5796493 0.8732053 -0.03771561 0.4858911 0.8398665 -0.01332318 0.5426294 0.8347724 0.2155308 0.5066573 0.8524647 0.1937728 0.4855473 0.8282688 0.3983315 0.394085 0.8419796 0.3780855 0.3848662 0.8540055 0.4964098 0.1557299 0.8766993 0.4676673 0.1126302 0.7941931 0.607342 0.01982951 0.840934 0.5251002 -0.1307662 0.8071348 0.5640967 -0.1741503 0.8484817 0.416913 -0.3259789 0.827151 0.4323009 -0.3590784 0.8191201 0.2829276 -0.4989934 0.8821715 0.1694255 -0.4393957 0.7723112 0.07418859 -0.6308973 0.8426709 -0.08990502 -0.53087 0.8866434 -0.1247593 -0.4453076 0.7915318 -0.2900548 -0.5379087 0.8668552 -0.3798644 -0.3229014 0.8174049 -0.465009 -0.3400234 0.8439649 -0.512641 -0.1578688 0.8147581 -0.5604099 -0.1486946 0.833004 -0.5482075 0.07465302 0.8282814 -0.5557643 0.07124835 0.8377081 -0.4714837 0.2755873 0.8345196 -0.474604 0.2798715 0.8118581 -0.3612342 0.4586897 0.8615977 -0.2696771 0.4300276 0.7967173 -0.1916282 0.5731669 0.863617 -0.02866166 0.5033332 0.8338251 0.003191292 0.5520195 0.8447068 0.1720645 0.5068177 0.8255797 0.195858 0.529205 0.8459111 0.3621898 0.3914757 0.8252975 0.3941354 0.4044026 0.8671847 0.470049 0.1644525 0.8242508 0.5162237 0.2326455 0.783661 0.6189788 0.05235153 0.8915277 0.4328177 -0.1335941 0.8078708 0.5399258 -0.236273 0.8753833 0.3665462 -0.3151956 0.7905442 0.3802986 -0.4800135 0.8779876 0.1910693 -0.4388966 0.785915 0.1519216 -0.599381 0.8678174 -0.09305161 -0.4880928 0.8391799 -0.06474256 -0.5399866 0.7999757 -0.2095178 -0.5622643 0.8462316 -0.3659138 -0.3872975 0.8536021 -0.3629577 -0.3736645 0.7959938 -0.5475218 -0.2580968 0.8466484 -0.5005289 -0.1807136 0.813684 -0.5813058 -0.001448452 0.859048 -0.5098465 0.04575175 0.7810003 -0.5802214 0.2310445 0.8742403 -0.3930715 0.284954 0.8096148 -0.419071 0.4109788 0.8582031 -0.2346066 0.4565603 0.8263415 -0.2333354 0.5125569 0.8231098 -0.03483343 0.5668129 0.8781375 0.02753698 0.4776154 0.7906318 0.1959606 0.5800871 0.8702421 0.3046807 0.3871028 0.8603811 0.3070945 0.4067398 0.8098576 0.4940879 0.3162402 0.856024 0.4626346 0.230634 0.8103244 0.5752155 0.1118108 0.8689263 0.4940391 0.02987402 0.8091699 0.5666359 -0.1554604 0.8439314 0.506323 -0.1772485 0.8112393 0.4772287 -0.3378515 0.8589955 0.3799663 -0.3431509 0.8135223 0.3238788 -0.4829949 0.8362007 0.2775872 -0.4729839 0.7495 0.1756423 -0.6382787 0.8160382 -0.009975969 -0.5779119 0.8077289 -0.0193541 -0.5892365 0.8570875 -0.1995105 -0.47497 0.8214735 -0.2478342 -0.5135751 0.8384469 -0.4016457 -0.3683581 0.8750254 -0.3416857 -0.3429018 0.7864144 -0.5332301 -0.3117982 0.8586706 -0.5088654 -0.06116294 0.8405202 -0.5354301 -0.08270794 0.787336 -0.6056082 0.1155028 0.8643133 -0.4685045 0.1829375 0.8450215 -0.4787261 0.2382438 0.8732735 -0.3177383 0.3693723 0.8655839 -0.3233311 0.3823893 0.7826626 -0.2742886 0.558753 0.8518158 -0.06634354 0.5196236 0.8680223 -0.04818224 0.4941819 0.7479929 0.2037973 0.6316434 0.8865958 0.2633785 0.3802366 0.8109993 0.3913198 0.4349127 0.827582 0.5186251 0.2147935 0.8691329 0.4705393 0.1523183 0.8259327 0.5594992 0.06925189 0.8926662 0.4387763 -0.1030662 0.8464462 0.5085868 -0.1576974 0.7700058 0.5530973 -0.3180795 0.8725497 0.3466815 -0.3441932 0.8056561 0.364174 -0.467221 0.8455247 0.1606333 -0.5092004 0.8173338 0.1511327 -0.5559898 0.8357272 -0.0557602 -0.5463067 0.8279093 -0.06250572 -0.5573683 0.8203343 -0.2661373 -0.5061843 0.8556952 -0.2732908 -0.439429 0.8093941 -0.4468765 -0.3810284 0.8536124 -0.4310584 -0.2924632 0.805381 -0.5554839 -0.2068794 0.8746023 -0.4757221 -0.09359174 0.7764722 -0.6264193 0.06848341 0.8687686 -0.4695195 0.1574562 0.8020394 -0.5176359 0.2979698 0.8615473 -0.3794829 0.3372374 0.7938644 -0.3857227 0.4701037 0.8468886 -0.2161155 0.4858743 0.8449103 -0.21928 0.4878966 0.8561115 -0.008628189 0.5167194 0.8340911 -0.03891885 0.5502522 0.796056 0.1478587 0.5868839 0.8647677 0.2303491 0.4462243 0.8240568 0.2955864 0.4832796 0.8216429 0.470475 0.3218014 0.9010918 0.3870388 0.1955364 0.8009375 0.5974404 0.03954929 0.9027197 0.4237618 -0.07431906 0.8264935 0.5246493 -0.2040873 0.849995 0.4293003 -0.3053031 0.8241861 0.4480347 -0.3463848 0.8224198 0.294682 -0.486609 0.8572303 0.285775 -0.428356 0.814212 0.1344363 -0.5647882 0.8744115 0.01207739 -0.4850347 0.8163111 -0.04673624 -0.5757188 0.8003349 -0.2195276 -0.5579175 0.8791255 -0.248942 -0.4064066 0.7691397 -0.4463029 -0.4574254 0.8491406 -0.485535 -0.2078851 0.8641439 -0.467534 -0.1861917 0.7993581 -0.6002863 0.02613347 0.8690105 -0.485305 0.09643626 0.7831031 -0.5665974 0.2563533 0.8726133 -0.3618874 0.3279994 0.8377523 -0.3837726 0.3884452 0.7803174 -0.3128029 0.541534 0.8601465 -0.09654533 0.5008264 0.8645734 -0.09134668 0.4941344 0.7991841 0.1428824 0.5838575 0.8580917 0.1840115 0.479394 0.795263 0.3517628 0.493781 0.8136296 0.3547466 0.4606101 0.7545334 0.5500648 0.3579221 0.8586954 0.4844069 0.1673089 0.7925458 0.6055599 0.07189303 0.8647592 0.5010125 -0.03432476 0.7959076 0.586514 -0.1501081 0.8739189 0.4243772 -0.237002 0.7787208 0.4810994 -0.4026628 0.9091838 0.1955238 -0.367635 0.8175367 0.2022945 -0.5391759 0.8652479 -0.05002957 -0.4988418 0.8720598 -0.06112879 -0.4855666 0.7877169 -0.1855304 -0.5874357 0.8575079 -0.276117 -0.4340964 0.8002458 -0.3852371 -0.4595641 0.8580414 -0.4146956 -0.3029729 0.7972854 -0.5325459 -0.2841319 0.857947 -0.5014853 -0.1115328 0.8102882 -0.5814919 -0.07280284 0.8517484 -0.5151671 0.09553956 0.8276309 -0.5475468 0.1233683 0.8327738 -0.4685366 0.2948921 0.8507649 -0.4296656 0.3026331 0.8167215 -0.407979 0.4080677 0.8613247 -0.2852064 0.4204487 0.7985154 -0.2680857 0.5389836 0.8510261 -0.07929575 0.519102 0.8292885 -0.0642246 0.555118 0.8347582 0.141785 0.5320488 0.8467562 0.1283186 0.5162736 0.8093137 0.3601152 0.4640349 0.8787746 0.2661195 0.3961511 0.7701215 0.4918206 0.4062331 0.8690283 0.4711929 0.1508874 0.8014001 0.5824992 0.135841 0.8295418 0.5562632 -0.04931282 0.9046851 0.409414 -0.1180049 0.8162699 0.5093113 -0.2725903 0.7942494 0.4604921 -0.3963774 0.8823006 0.2922624 -0.368956 0.7804166 0.2830083 -0.5575447 0.8619732 0.04627144 -0.5048378 0.8088786 0.009765803 -0.5878946 0.8402583 -0.1903721 -0.5076659 0.8254834 -0.2082116 -0.5246189 0.8350161 -0.38479 -0.3932998 0.8137713 -0.4178375 -0.4039655 0.8405458 -0.4949523 -0.2202385 0.8161646 -0.5359773 -0.2158789 0.8715667 -0.4900967 0.01329827 0.8249785 -0.5631726 0.04740518 0.8123315 -0.5187641 0.2664611 0.8917919 -0.3540419 0.2817118 0.7662141 -0.416679 0.4891775 0.8943697 -0.1061466 0.4345524 0.8018579 -0.06995832 0.5934054 0.8586446 0.08899468 0.5047865 0.8126792 0.1490366 0.5633298 0.8540788 0.2951816 0.4282723 0.8272977 0.3393071 0.4477158 0.8415604 0.4520307 0.2957102 0.8364298 0.4607304 0.2968381 0.8205214 0.5514925 0.150336 0.8678689 0.4932188 0.05949032 0.8129065 0.5823899 -0.002245545 0.8298494 0.5222883 -0.1963791 0.8529775 0.4805271 -0.2037722 0.8496267 0.3683809 -0.3773992 0.8204799 0.4319701 -0.3744524 0.8023998 0.3223522 -0.5022388 0.8732826 0.1618975 -0.459529 0.8210579 0.1215754 -0.5577486 0.8436411 -0.0864467 -0.5299026 0.8365675 -0.0916109 -0.5401503 0.8000644 -0.3668402 -0.4746844 0.8758127 -0.3528892 -0.329274 0.7983621 -0.5104727 -0.31943 0.8705744 -0.4733568 -0.1342893 0.8010781 -0.5936869 -0.07622307 0.8583191 -0.5063716 0.08292329 0.7932814 -0.588955 0.1543915 0.8712471 -0.3927063 0.2944663 0.7530804 -0.4561778 0.4741012 0.8682377 -0.23861 0.4350041 0.7991627 -0.1702551 0.5765 0.8288851 -0.1143471 0.5476078 0.7594342 0.0189808 0.6503073 0.8064832 0.196325 0.5577109 0.8190258 0.1794334 0.5449775 0.814082 0.3249722 0.4813144 0.8653717 0.3281272 0.378767 0.8090032 0.4670484 0.3569031 0.8753688 0.4459416 0.1867228 0.8187619 0.5502064 0.164018 0.8249428 0.5643613 -0.03107655 0.8772519 0.4719769 -0.08756089 0.7851573 0.5735564 -0.2335832 0.882422 0.3402557 -0.3248962 0.7576709 0.4023094 -0.513889 0.8459844 0.1625998 -0.5078108 0.8852127 0.1081421 -0.4524423 0.8396411 -0.05345451 -0.540505 0.8831853 -0.09896939 -0.4584635 0.8582398 -0.2796884 -0.4303473 0.8427866 -0.2622885 -0.4700165 0.7902685 -0.4109115 -0.454563 0.8639419 -0.4242682 -0.271295 0.8090724 -0.5316272 -0.2505483 0.8370457 -0.5384857 -0.09689098 0.8576509 -0.509871 -0.06683248 0.789325 -0.6079461 0.08583503 0.8700744 -0.4623779 0.1708136 0.8090721 -0.5066578 0.2978262 0.8666528 -0.3566478 0.3488773 0.8245133 -0.3640012 0.4332218 0.8461424 -0.1996868 0.4941338 0.8296576 -0.197167 0.5222964 0.8264619 0.0229988 0.5625227 0.8142669 0.01264941 0.5803529 0.7796451 0.2379241 0.5792632 0.8249701 0.2451974 0.5092176 0.7816182 0.4872034 0.3894942 0.8398846 0.3994892 0.3674267 0.8232103 0.5306761 0.2017617 0.853193 0.4983162 0.1540864 0.806641 0.5910131 0.005834698 0.8660761 0.4960302 -0.06217986 0.7660421 0.5895363 -0.256177 0.8719706 0.3709611 -0.3194608 0.8134543 0.4038184 -0.4185962 0.8589066 0.177025 -0.4805638 0.8191736 0.1671592 -0.548646 0.8655014 -0.02959161 -0.5000319 0.7626112 -0.1145125 -0.6366406 0.8367349 -0.2996818 -0.4583292 0.8640354 -0.2942204 -0.4085062 0.8357906 -0.4690763 -0.2853444 0.8295553 -0.4793334 -0.2864919 0.8287057 -0.555074 -0.07169151 0.8744035 -0.4777087 -0.0849297 0.7585069 -0.6395503 0.1250717 0.8689389 -0.429625 0.2456985 0.827311 -0.4692403 0.3088205 0.8226574 -0.341131 0.4548236 0.8789867 -0.2310982 0.4171043 0.7917106 -0.1609211 0.5893207 0.8227007 -0.02838587 0.5677658 0.8838952 0.0415163 0.4658387 0.7921586 0.1702105 0.5860999 0.8317604 0.3379315 0.4404283 0.8759739 0.3297102 0.3520808 0.7919875 0.5107378 0.3345188 0.8694493 0.4777755 0.1256529 0.8100094 0.576261 0.1086657 0.7990252 0.599927 -0.04057621 0.8967776 0.4057433 -0.1765287 0.8571639 0.4589396 -0.2337619 0.8041096 0.4489313 -0.3897029 0.8521211 0.3261185 -0.4093124 0.8051767 0.3218619 -0.4980917 0.8627943 0.1098362 -0.4934796 0.8185787 0.08910667 -0.5674408 0.8263405 -0.113308 -0.5516545 0.8553637 -0.1308711 -0.5012242 0.8265774 -0.3478804 -0.4424355 0.8514373 -0.3126549 -0.4210721 0.848588 -0.4700154 -0.2428665 0.7996014 -0.5084913 -0.3194908 0.8143901 -0.5729787 -0.09200054 0.8488361 -0.5276868 -0.03199911 0.8058216 -0.5879701 0.07030445 0.8599781 -0.4840602 0.1616272 0.7897 -0.5453717 0.2809695 0.8700389 -0.346996 0.3501803 0.8045042 -0.3759353 0.4598322 0.8165584 -0.1618423 0.5541115 0.863474 -0.0990628 0.4945699 0.8099324 0.04721307 0.5846199 0.8686863 0.1131729 0.4822616 0.8034946 0.2983166 0.5151734 0.8655929 0.3142137 0.3898959 0.7875411 0.4778397 0.3891636 0.8604981 0.4625614 0.213495 0.8007823 0.5723852 0.1764168 0.8637147 0.5039731 0.002880513 0.7903572 0.6088302 -0.06827569 0.8831322 0.4056712 -0.2356026 0.8110648 0.479723 -0.3347233 0.8606359 0.2183629 -0.4600257 0.8839096 0.1732708 -0.4343745 0.7784863 0.0899477 -0.6211832 0.8968781 -0.07566434 -0.4357575 0.8299493 -0.2003459 -0.5206205 0.8952558 -0.2546859 -0.3655849 0.8070805 -0.4083528 -0.4264612 0.8476351 -0.4807447 -0.2244979 0.8244536 -0.5193792 -0.2247705 0.8892487 -0.4573798 -0.006367862 0.7925549 -0.6031379 0.08989751 0.8745779 -0.4420222 0.199324 0.8041318 -0.5098249 0.3056968 0.812833 -0.3619825 0.4563676 0.838302 -0.3180065 0.4428561 0.7577375 -0.2323834 0.6097803 0.825284 -0.02681499 0.564081 0.8162814 -0.01867151 0.5773527 0.835474 0.1711034 0.5222134 0.8231011 0.1854943 0.5367462 0.8320673 0.3727712 0.4107381 0.8426337 0.3575049 0.4026893 0.7850661 0.5670124 0.2493354 0.8904514 0.4442468 0.09869712 0.8032551 0.594737 -0.03269934 0.8610988 0.4884788 -0.1410586 0.8131157 0.5413556 -0.2139559 0.8492237 0.3948888 -0.3505453 0.8425214 0.3989278 -0.361959 0.8279851 0.2528623 -0.5005012 0.8537815 0.2494814 -0.4569643 0.7882729 0.1172707 -0.6040477 0.8690914 -0.01317089 -0.4944762 0.7814306 -0.1187811 -0.6125826 0.8499333 -0.2905149 -0.4395619 0.8419792 -0.2911679 -0.4541942 0.8183168 -0.4538483 -0.3526746 0.8594533 -0.4351097 -0.2683647 0.8177326 -0.5452268 -0.1845029 0.8705024 -0.4863671 -0.07531791 0.7835816 -0.6210865 0.01586276 0.8688533 -0.4625258 0.1765334 0.8008871 -0.5303989 0.2779513 0.8572442 -0.3679878 0.3601632 0.8042526 -0.3875629 0.450525 0.8429057 -0.184414 0.5054717 0.8727901 -0.1371136 0.4684414 0.7953206 -0.006329596 0.6061559 0.8644692 0.1511226 0.4794319 0.8461469 0.172407 0.5042929 0.7821363 0.3663973 0.5039999 0.8729301 0.3726643 0.3148248 0.805369 0.511762 0.2991328 0.8676774 0.4779014 0.1369177 0.8088423 0.5791632 0.1017067 0.7941082 0.6066902 -0.03632384 0.8757767 0.4662068 -0.1251656 0.7995107 0.5412778 -0.2603868 0.8656499 0.359863 -0.3480644 0.8470639 0.3725119 -0.3791013 0.7727652 0.3039885 -0.5571579 0.8659331 0.0659697 -0.4957903 0.8759786 0.05398845 -0.4793192 0.785566 -0.1067313 -0.6095035 0.8394789 -0.2500246 -0.4824552 0.8731142 -0.2545517 -0.4157824 0.7951362 -0.4668934 -0.3870001 0.8714905 -0.4109388 -0.2676448 0.8762425 -0.47265 -0.09381437 0.8083629 -0.5847123 -0.06827306 0.8511261 -0.5060589 0.1396021 0.8441038 -0.5157061 0.1467517 0.7812782 -0.4950025 0.3802329 0.8663694 -0.3377034 0.3679138 0.7841159 -0.2759215 0.5559044 0.8602973 -0.1514129 0.4867883 0.8040837 -0.04595881 0.5927372 0.8798606 0.1069102 0.4630504 0.8274405 0.1676172 0.535954 0.7938979 0.3695061 0.4828991 0.8328 0.3666347 0.4147567 0.7441 0.5693102 0.3495729 0.8565633 0.5031006 0.1148443 0.8627215 0.4915337 0.118771 0.8145566 0.5751039 -0.07584899 0.873023 0.4587689 -0.1654149 0.8391649 0.5005179 -0.2128007 0.8094826 0.4423543 -0.3860837 0.8594817 0.3437776 -0.3782966 0.858224 0.1796326 -0.4808157 0.8206817 0.2747175 -0.5010109 0.7903465 0.1212335 -0.6005455 0.8590876 -0.03418105 -0.5106862 0.807915 -0.1048568 -0.5798951 0.8645605 -0.2448562 -0.43884 0.8458186 -0.27396 -0.4577521 0.7883729 -0.4959509 -0.3640068 0.8420933 -0.4554562 -0.2888572 0.8300961 -0.554086 -0.06268346 0.8632256 -0.5043439 -0.02188384 0.8057622 -0.5783895 0.12733 0.8724712 -0.4399719 0.2126472 0.804431 -0.4959161 0.3270443 0.8338006 -0.3453629 0.4306983 0.8609793 -0.2954775 0.4140141 0.8012924 -0.2096172 0.5603492 0.8837617 -0.02876615 0.4670523 0.8038927 0.03135299 0.5939474 0.8057212 0.2318705 0.5450226 0.8707271 0.2495831 0.4237248 0.8115814 0.3991336 0.4266474 0.8431836 0.4363777 0.3140318 0.8274416 0.4664075 0.3127372 0.8393089 0.5298426 0.1217684 0.8255887 0.5521391 0.116387 0.8272763 0.5530157 -0.09893244 0.8396133 0.5358887 -0.08873003 0.8740217 0.3578495 -0.3286792 0.855898 0.37408 -0.3570755 0.8653703 0.1985895 -0.4601051 0.8620757 0.1984785 -0.4662958 0.8855441 0.01404845 -0.4643429 0.8762879 0.005851626 -0.4817525 0.9082658 -0.1520861 -0.3897733 0.9269375 -0.1165462 -0.3566564 0.9323822 -0.2423916 -0.2681601 -0.2212814 -0.8399875 -0.4954348 -0.05911904 -0.0426169 -0.9973408 0.2087273 -0.4836859 -0.8499888 -0.4506224 -0.5089229 -0.7334418 0.416588 -0.7773188 -0.4714129 -0.3820194 -0.8329659 -0.4002864 0.3474935 -0.9375816 -0.01375418 -0.4643833 -0.8831051 0.06688535 0.5709745 -0.7119607 0.4087788 -0.6947293 -0.5474807 0.4664934 0.7086332 -0.2948254 0.6410281 -0.6468583 -0.1494891 0.747815 0.529151 0.170106 0.8313021 -0.291719 0.3045843 0.9067131 0.2217413 0.6548264 0.7225187 -0.1735014 0.6139011 0.7700797 0.3636058 0.8341324 0.4147456 -0.5380684 0.7929336 0.2859 0.4233115 0.9052011 -0.03766465 -0.2678861 0.9505141 -0.1573535 0.3784171 0.8186061 -0.4320701 -0.4018973 0.7685344 -0.4978288 0.2203246 0.4167616 -0.8819109 -0.3615015 0.4648811 -0.8082094 0.4827668 0.02027928 -0.8755141 -0.6754856 -0.1102422 -0.7290858 0.5531075 -0.4126168 -0.7237538 -0.3454225 -0.6547592 -0.67229 0.2786679 -0.7730175 -0.5699021 -0.443431 -0.8292541 -0.3401568 0.4349107 -0.8932207 -0.1140602 -0.2727985 -0.960866 0.04813998 0.380203 -0.8833224 0.274203 -0.4585489 -0.8041163 0.3783252 0.3356617 -0.6289616 0.7012408 -0.3014584 -0.5773615 0.7587994 0.4686696 -0.2354031 0.8514306 -0.4693034 -0.1355633 0.8725692 0.001304864 0.2558137 0.9667253 0.4349204 0.3010488 0.8486542 -0.3231959 0.5798787 0.7478537 0.3377584 0.6941019 0.6357216 -0.4792931 0.7958739 0.3699496 0.5939083 0.7867905 0.1680292 -0.5423948 0.8259879 -0.1534668 0.437419 0.8249791 -0.3578745 -0.3047088 0.7774407 -0.5502169 0.4162441 0.5649818 -0.7124159 -0.4974909 0.4258727 -0.755735 0.4671763 0.1776583 -0.8661316 -0.4272393 -0.08098512 -0.9005043 0.2369946 -0.2056738 -0.9494903 -0.3226577 -0.5968297 -0.7346336 0.3172006 -0.6777616 -0.6633423 -0.2591107 -0.8791257 -0.3999995 0.4947119 -0.8459333 -0.1991407 -0.5407823 -0.8410904 -0.01101762 0.4946199 -0.8209357 0.2853344 -0.388142 -0.7950171 0.4661477 0.3307998 -0.7012858 0.6314822 -0.3850963 -0.4952 0.7787669 0.514753 -0.2894407 0.8070029 -0.6295241 -0.04677212 0.775572 0.6303566 0.216908 0.7453868 -0.532577 0.439853 0.7231121 0.3066118 0.6616491 0.6842586 -0.203589 0.8371952 0.5075982 0.4005859 0.8496837 0.3428829 -0.4734042 0.8691208 0.1432397 0.4412861 0.8807321 -0.1719818 -0.1428902 0.955631 -0.2575884 0.02432519 0.789236 -0.6136082 0.2039584 0.7514004 -0.6275336 -0.2938901 0.444199 -0.8463546 0.5428357 0.06207805 -0.8375415 -0.5244908 -0.250216 -0.8138189 0.5087385 -0.4891816 -0.7084395 -0.4223824 -0.610979 -0.6695505 0.5715672 -0.747534 -0.3383842 -0.5558243 -0.8110923 -0.1821773 0.3794137 -0.9244177 0.03869217 -0.3695092 -0.8932643 0.2560116 0.4068953 -0.801231 0.4387084 -0.4693783 -0.6404636 0.6078573 0.5036467 -0.4777356 0.7197976 -0.623829 -0.1624469 0.7644923 0.378719 -0.01454907 0.9253973 0.07765161 0.3989351 0.9136854 -0.6066598 0.3709828 0.70309 0.5718346 0.6295818 0.5259582 -0.5603807 0.7568667 0.3363426 0.2836983 0.9366658 0.2053595 -0.2044451 0.9700109 -0.1314576 0.1397286 0.9713349 -0.1923135 -0.1535929 0.7587518 -0.6330126 -0.1464394 0.7588816 -0.6345505 0.233314 0.419768 -0.8771314 -0.213631 0.3662695 -0.9056536 0.2559186 0.05500799 -0.965132 -0.3338354 -0.01875042 -0.942445 0.2429997 -0.3991593 -0.8840945 -0.1706687 -0.4504501 -0.8763373 0.252521 -0.7012697 -0.6666738 -0.2620541 -0.7503792 -0.6068434 0.2343639 -0.9279447 -0.2898142 -0.09431171 -0.9577975 -0.2715317 -0.04943579 -0.9694421 0.2402879 0.5477554 -0.7828997 0.2950121 -0.5192165 -0.692843 0.5003828 0.5489992 -0.408531 0.7291792 0.2088291 -0.4508194 0.8678435 -0.4720784 -0.09859102 0.8760262 0.4388545 0.09985357 0.8929927 -0.3918921 0.3417129 0.8541972 0.3273835 0.4821072 0.8126456 -0.315667 0.7978279 0.5136391 -0.4065615 0.7601022 0.506905 0.4973194 0.8581703 0.1273469 -0.4928683 0.8688499 -0.04670095 0.337503 0.9051752 -0.2583595 -0.3660517 0.8017048 -0.4725207 0.5438708 0.5814802 -0.6050499 -0.4248878 0.532621 -0.7319735 0.2466373 0.146555 -0.9579623 -0.2085837 0.1117008 -0.9716048 0.3260144 -0.3189492 -0.889936 -0.5432628 -0.3605364 -0.7582077 0.6312037 -0.6040802 -0.4864866 -0.6600353 -0.660893 -0.3571747 0.554014 -0.8305466 -0.05710536 -0.4847971 -0.8708652 0.08102965 0.3601294 -0.8604385 0.3604895 -0.4503853 -0.716962 0.5320888 0.3723562 -0.6442244 0.6680763 -0.330982 -0.2574138 0.9078485 -0.1716878 -0.2435801 0.9545638 0.3437017 0.1774474 0.9221614 -0.3471906 0.2567036 0.9019767 0.3043642 0.6136008 0.728599 -0.09705185 0.860848 0.4995214 -0.04170423 0.9990982 0.007981836 0.245294 0.96863 -0.03983718 -0.3285792 0.8641878 -0.381071 0.359879 0.7900632 -0.4962735 -0.1989808 0.5802662 -0.7897455 -0.4587504 0.5081182 -0.7289473 0.5085331 0.1543286 -0.8470991 -0.4123075 -0.02490019 -0.9107046 0.3985407 -0.2139761 -0.8918405 -0.5185645 -0.3850699 -0.7634212 0.4495577 -0.6929996 -0.5636041 0.09157639 -0.7320597 -0.6750572 0.02148282 -0.9501411 -0.3110794 -0.1419023 -0.9461845 -0.2908588 0.09733384 -0.9918592 0.08210748 -0.130167 -0.9857944 0.1061418 0.1734681 -0.8469046 0.5026544 0.08494359 -0.8525527 0.5156922 -0.2532309 -0.6080691 0.7524135 0.4979473 -0.4209309 0.758199 -0.5195404 -0.2115592 0.8278409 0.5041725 0.09910225 0.8578981 -0.1215581 0.1852978 0.975135 -0.1700479 0.5492254 0.8181902 0.328969 0.591424 0.7362046 -0.1211709 0.9140605 0.3870542 -0.2095226 0.902569 0.3761242 0.2315491 0.9615621 -0.1475921 -0.1851214 0.9672533 -0.1736409 0.1165953 0.6719864 -0.7313275 0.1520345 0.6698899 -0.7267277 -0.2401119 0.172055 -0.955376 0.4607604 0.04494452 -0.886386 -0.4486444 -0.2371171 -0.8616807 0.4145351 -0.443853 -0.7944529 -0.2519729 -0.6206884 -0.742466 0.4151643 -0.7433008 -0.5245404 -0.3874735 -0.8068203 -0.4459878 -0.04014927 -0.9977487 -0.05371785 0.4809282 -0.8763288 0.02749359 -0.442111 -0.7572968 0.4806658 0.3365332 -0.729356 0.5956385 -0.2306909 -0.3238684 0.9175462 0.4219954 -0.1999542 0.8842728 -0.4434149 0.07114666 0.8934884 0.4350433 0.3014785 0.8484387 -0.2729157 0.4770944 0.8354029 0.3766469 0.643487 0.6663796 -0.4299901 0.7087385 0.5592838 0.2608329 0.9310836 0.2550485 -0.2462301 0.9480301 0.2015189 0.4732548 0.8636693 -0.1735088 -0.476304 0.8382372 -0.265505 0.002602398 0.7467882 -0.665057 0.3433443 0.6614481 -0.6667842 -0.209214 0.4067833 -0.8892452 0.2111011 0.3267071 -0.9212486 -0.395794 -0.06914383 -0.9157326 0.5387739 -0.1995253 -0.8184819 -0.4925351 -0.5699061 -0.6577357 0.3503867 -0.7176465 -0.6018411 -0.2585373 -0.9024915 -0.3444815 0.3910537 -0.9013779 -0.1859977 -0.4356984 -0.8980318 0.06087625 0.5613805 -0.7813528 0.2726528 -0.5094392 -0.7382916 0.4420377 0.5174872 -0.4495691 0.7280761 -0.1033756 -0.6052354 0.7893058 0.08909142 -0.1344804 0.9869032 0.3763563 0.1886146 0.9070725 -0.3810086 0.5359833 0.753362 0.2914451 0.6599527 0.6924754 -0.2909061 0.845331 0.4480953 0.2995242 0.889257 0.3456981 -0.2063664 0.9705773 -0.1240677 0.1607659 0.9810077 -0.1085272 -0.333357 0.7428817 -0.5805171 0.5043003 0.5969364 -0.6239777 -0.4456219 0.2978116 -0.8442331 0.331395 0.1685894 -0.9283076 -0.1690788 -0.1174381 -0.978581 0.3194339 -0.2339539 -0.9182742 -0.4582347 -0.4124568 -0.7873376 0.4050007 -0.6351434 -0.6576985 -0.2813812 -0.7594987 -0.5865038 0.4418098 -0.840259 -0.3142752 -0.5041333 -0.841078 -0.1960549 0.3589131 -0.9001599 0.2467664 0.1672755 -0.9467065 0.2752557 -0.2256662 -0.7525889 0.6186153 0.2576405 -0.6801477 0.6863094 -0.2636183 -0.432455 0.8622577 0.1955653 -0.3483817 0.9167249 -0.0803374 -0.0292409 0.9963387 0.1221964 0.01190626 0.9924346 -0.2705656 0.4031611 0.874217 0.4759225 0.6345897 0.6089283 -0.4492066 0.8246156 0.3438353 0.5635145 0.8214723 0.08737677 -0.4331808 0.900989 -0.0239436 0.5168587 0.7260128 -0.4536107 -0.339042 0.7663806 -0.5456294 0.08508664 0.4102517 -0.9079944 0.4945325 0.2921279 -0.8185957 -0.514095 0.03470492 -0.8570309 0.494962 -0.2143197 -0.8420687 -0.3690923 -0.4403554 -0.8184486 0.3982647 -0.5789857 -0.7114498 -0.4454491 -0.7199095 -0.5322645 0.4067338 -0.8674917 -0.2864016 -0.4151851 -0.8888989 -0.1935983 0.6188176 -0.7640388 0.1825087 -0.6214168 -0.7186614 0.3120368 0.4096683 -0.6595962 0.6301625 -0.4093431 -0.5216012 0.7485791 0.3657481 -0.3714329 0.853385 -0.3569837 -0.008375763 0.9340731 -0.4688488 -0.0272665 0.8828575 0.5665157 0.3439607 0.7488331 -0.5980245 0.4768509 0.6441895 0.4400544 0.7236185 0.5317221 -0.5193889 0.7999438 0.3005418 0.5824469 0.8072642 0.09529113 -0.5817983 0.7797337 -0.2313571 0.4183393 0.7992596 -0.4314818 -0.294907 0.6560443 -0.6947199 0.3595039 0.5228464 -0.7729092 -0.3912121 0.2829474 -0.8757247 0.5218985 0.07319056 -0.8498619 -0.5275517 -0.1316631 -0.839258 0.4707263 -0.4436689 -0.7626105 -0.1182662 -0.5563276 -0.822504 0.01327514 -0.8477674 -0.5302022 -0.08147388 -0.8503204 -0.5199204 0.211642 -0.968097 -0.1341487 0.1007534 -0.9867818 -0.1269268 -0.3958791 -0.894432 0.2080178 0.3817789 -0.8461067 0.3719522 -0.3680368 -0.7127673 0.597086 0.2627231 -0.6558527 0.7076962 -0.05325567 -0.2446938 0.9681368 0.2474321 -0.2513658 0.9357311 -0.432663 0.1192873 0.8936293 0.5284262 0.3289599 0.7826566 -0.4485328 0.4888114 0.7482524 0.3601888 0.7101003 0.6049972 -0.2892979 0.8313761 0.4744687 0.4245695 0.8660646 0.2639561 -0.4974382 0.8624479 0.09348177 0.4849461 0.8399442 -0.2435595 -0.55391 0.761388 -0.3368563 0.5731516 0.5685927 -0.5900844 -0.5460957 0.395425 -0.7385246 -0.004230439 0.3633999 -0.9316236 0.2763283 -0.0541867 -0.9595346 -0.03077745 -0.07888925 -0.9964083 -0.4247187 -0.4362117 -0.7933053 0.6530792 -0.503143 -0.5659812 -0.5176618 -0.7352737 -0.4374915 0.4486981 -0.8688631 -0.2091579 -0.2916484 -0.9506419 -0.1059303 0.2124746 -0.9518073 0.2211726 -0.4153184 -0.8617914 0.2912495 0.4899227 -0.7118847 0.5031859 -0.3989432 -0.5203158 0.7550601 -0.09014248 -0.2231766 0.9706012 0.1770104 0.2524871 0.9512716 0.187029 0.2513629 0.949651 -0.5169662 0.5135686 0.6848309 0.6610722 0.5984247 0.4526274 -0.5618152 0.7819825 0.2699395 0.4397075 0.8945719 0.07999199 -0.4094777 0.8964529 -0.1694115 0.4250241 0.8295716 -0.3621676 -0.3571349 0.7505827 -0.55595 0.4298497 0.563117 -0.7057822 -0.3854756 0.4832639 -0.7860437 0.3235155 0.03239554 -0.9456682 0.008726418 0.0789529 -0.9968402 -0.01079916 -0.4723719 -0.8813332 -0.06881833 -0.4753293 -0.8771123 0.1696439 -0.767727 -0.617913 -0.1713852 -0.7937001 -0.583667 0.08778887 -0.9714698 -0.2203168 0.1154015 -0.968311 -0.2214867 -0.2296049 -0.936536 0.2649185 0.4932559 -0.7943211 0.3546164 -0.4705384 -0.6871128 0.553597 0.4535408 -0.4963823 0.7402064 -0.4495995 -0.3344008 0.8282732 0.4445241 -0.1424095 0.8843744 -0.5493555 0.1647701 0.8191822 0.3368409 0.3447405 0.8761805 -0.0296635 0.7249323 0.6881811 0.1807182 0.7050442 0.6857505 -0.514206 0.7963928 0.3183566 0.6211895 0.779495 0.08069318 -0.4767522 0.8683594 -0.1365999 0.3635555 0.8589938 -0.3604957 -0.4835073 0.6858133 -0.5439494 0.2697456 0.655308 -0.7055557 0.319802 0.3137006 -0.8940462 -0.6911956 0.1684434 -0.7027628 0.6979744 -0.206995 -0.6855545 -0.545277 -0.3588073 -0.7575819 0.2798311 -0.7688448 -0.5749543 0.4641247 -0.7282483 -0.5042248 -0.4479374 -0.8548501 -0.2618842 0.4849565 -0.8743466 0.01831293 -0.5020554 -0.8521332 0.1476807 0.4459598 -0.7905701 0.4196653 -0.2902747 -0.7074445 0.6444091 0.3430459 -0.5924397 0.7289271 -0.5044326 -0.3382472 0.7944412 0.4493942 -0.118487 0.8854409 -0.4505977 0.1118155 0.8856969 0.2622528 0.2595391 0.9294424 -0.03642982 0.6796562 0.7326257 -0.4097624 0.8307828 0.3766895 0.4300002 0.8900599 -0.1513054 -0.4376376 0.872051 -0.2190905 0.4192245 0.6979089 -0.5806668 -0.1205115 0.7254718 -0.6776192 -0.2153992 0.4147255 -0.8840849 0.5231344 0.2352601 -0.8191356 -0.4705327 0.02713847 -0.8819652 0.521784 -0.2989854 -0.7989677 -0.1983428 -0.4038266 -0.8930758 -0.05929905 -0.8021517 -0.5941686 0.1451185 -0.8134167 -0.5632886 0.04541385 -0.9907312 -0.1280215 -0.07432538 -0.9899897 -0.1199839 -0.2215155 -0.9126135 0.3436096 0.480846 -0.7731659 0.4135236 -0.4586168 -0.5827586 0.6708675 0.4694073 -0.4284119 0.7720881 -0.5269852 -0.1445629 0.8374893 0.6281738 0.06672132 0.7752071 -0.5965005 0.3275324 0.7327412 0.5016297 0.5766907 0.6448222 -0.2248354 0.7424129 0.6310881 0.2606461 0.890876 0.3720265 -0.2863801 0.9136116 0.2886181 0.2030649 0.9791097 0.01043397 -0.3683511 0.9255831 -0.08725601 0.5471299 0.7633784 -0.3433691 -0.5438108 0.6748013 -0.4989119 0.5430198 0.4489489 -0.7096298 -0.1198443 0.4654982 -0.8768973 -0.3184236 0.1228847 -0.9399499 0.5734843 -0.07354921 -0.8159084 -0.3484284 -0.2389912 -0.9063558 0.1223562 -0.5814041 -0.804362 0.5168334 -0.5552713 -0.6515805 -0.436608 -0.7670947 -0.4700416 0.5109903 -0.8395249 -0.1846262 -0.3733866 -0.9267749 -0.04087817 0.5661347 -0.7912098 0.2312548 -0.7964515 -0.5020959 0.3369941 -0.9462671 -0.2386488 -0.2182323 -0.5363671 -0.8167982 -0.2124881 -0.9101852 -0.4107862 -0.0530833 -0.8468742 -0.4866227 0.2144823 -0.7962052 -0.544206 0.2643811 -0.8918864 -0.2321845 0.3881096 -0.8817228 -0.2479799 0.4013366 -0.7808587 -0.06426739 0.6213932 -0.9059076 0.03379887 0.4221244 -0.7987387 0.2353737 0.553729 -0.8554158 0.296291 0.4248242 -0.8095796 0.3881687 0.4403478 -0.861401 0.4318585 0.2673698 -0.7896119 0.5603857 0.2499624 -0.8449804 0.5346631 0.01198923 -0.8235851 0.566707 0.02347278 -0.8625515 0.4676922 -0.1930524 -0.8220014 0.5110508 -0.2512787 -0.792291 0.3907206 -0.4686282 -0.8674629 0.2727466 -0.4160738 -0.8033986 0.2058247 -0.558737 -0.8822675 0.06220948 -0.4666199 -0.7496185 -0.1045525 -0.6535602 -0.8700287 -0.1978509 -0.4515585 -0.8227354 -0.2947666 -0.4860239 -0.8658193 -0.3743198 -0.3320266 -0.8090845 -0.4797687 -0.3394176 -0.8940832 -0.4356901 -0.1038724 -0.7969762 -0.6034414 -0.02622145 -0.8773559 -0.4701561 0.09591752 -0.791235 -0.5634675 0.2375956 -0.8541257 -0.3702263 0.365242 -0.8385139 -0.3955092 0.3747892 -0.8142673 -0.2703792 0.5136767 -0.8663901 -0.1811534 0.4653513 -0.7678854 -0.08078873 0.6354725 -0.856778 0.1253453 0.5002199 -0.8587384 0.1256934 0.4967592 -0.8319277 0.2850958 0.4760428 -0.8978381 0.2899469 0.3313876 -0.7844858 0.5353588 0.3130066 -0.8810344 0.4485132 0.1503815 -0.8213486 0.5616423 0.09972292 -0.8169482 0.5633476 -0.1234316 -0.878482 0.4550681 -0.1455421 -0.8015589 0.4920818 -0.3396454 -0.8668432 0.3466118 -0.3583899 -0.8043529 0.3425987 -0.4854304 -0.8487532 0.1541755 -0.5058143 -0.8250066 0.1370648 -0.5482494 -0.8525969 -0.06794506 -0.5181333 -0.8711407 -0.04603958 -0.4888705 -0.7693309 -0.2554678 -0.5855478 -0.8650655 -0.3254448 -0.3817688 -0.8134001 -0.4211836 -0.4012292 -0.8317728 -0.5159031 -0.2049343 -0.867238 -0.4709401 -0.161598 -0.783102 -0.6213299 0.02646923 -0.8687124 -0.4821895 0.1132788 -0.8004938 -0.5455675 0.2481248 -0.8586159 -0.4100721 0.3076032 -0.8051257 -0.4212995 0.4174678 -0.8701331 -0.2135805 0.4441305 -0.8561927 -0.2104592 0.4718487 -0.781019 -0.04058307 0.6231874 -0.8597728 0.08708655 0.5031967 -0.8321536 0.1248787 0.5403016 -0.8165317 0.3512609 0.4581396 -0.8422751 0.3424116 0.4163256 -0.8209301 0.4893188 0.2943483 -0.8637484 0.4478366 0.2310437 -0.7764204 0.6267302 0.06618678 -0.9079868 0.41786 -0.03087103 -0.8088701 0.5353581 -0.2431477 -0.8599078 0.4176916 -0.2934153 -0.7767149 0.4436302 -0.4471087 -0.8304417 0.3313288 -0.4478704 -0.7423201 0.2253863 -0.6310007 -0.8416103 0.03172552 -0.5391529 -0.838213 0.02821153 -0.5446128 -0.7933533 -0.1847689 -0.5800439 -0.8741058 -0.2335999 -0.425876 -0.8156636 -0.3416195 -0.466893 -0.8226613 -0.4795656 -0.305361 -0.8577672 -0.444109 -0.2588488 -0.8206797 -0.5709311 -0.02286154 -0.858741 -0.5100662 -0.04895305 -0.8010133 -0.5743219 0.1689148 -0.8658236 -0.4599161 0.1970449 -0.8071392 -0.4660103 0.3624375 -0.8783582 -0.3058922 0.3673103 -0.8012735 -0.2995717 0.5178973 -0.8202562 -0.09689801 0.5637292 -0.8672922 -0.05383759 0.4948795 -0.8177884 0.1248995 0.5618028 -0.8659691 0.1632466 0.472703 -0.8106456 0.321634 0.4892906 -0.8595743 0.3563467 0.3662638 -0.8129106 0.4461513 0.3743333 -0.8213546 0.5507513 0.1484916 -0.841759 0.5159721 0.1587916 -0.836723 0.5442219 -0.06097036 -0.8291096 0.5548114 -0.06900501 -0.8157935 0.4915754 -0.304688 -0.8563156 0.4172692 -0.3043189 -0.800552 0.3930859 -0.4523275 -0.8584027 0.2590131 -0.4427833 -0.8151336 0.2194286 -0.5361048 -0.8654721 0.07291179 -0.4956226 -0.8101792 0.0135253 -0.5860263 -0.8205957 -0.1755766 -0.543871 -0.8476919 -0.1796019 -0.4991611 -0.8281272 -0.3518317 -0.4363713 -0.8491206 -0.3506549 -0.3950132 -0.8085085 -0.472288 -0.3510815 -0.8724682 -0.4512821 -0.1874669 -0.8119683 -0.561905 -0.1580201 -0.7987372 -0.5995044 0.05112338 -0.8997148 -0.4237335 0.1047061 -0.7284278 -0.5624849 0.391157 -0.8840718 -0.2649388 0.3849995 -0.8729182 -0.282495 0.3977568 -0.776288 -0.1365045 0.6154215 -0.8733973 0.006326317 0.4869673 -0.7925744 0.1275117 0.5962941 -0.8754568 0.2051937 0.4375739 -0.7960829 0.3669282 0.481265 -0.8642324 0.4023759 0.3019872 -0.8055093 0.518368 0.2871404 -0.8598079 0.4954326 0.1236008 -0.7726438 0.6333908 0.04286962 -0.8812246 0.46542 -0.08262848 -0.789266 0.5527903 -0.2673616 -0.8740525 0.3719365 -0.312563 -0.817447 0.3969192 -0.4174154 -0.7884032 0.2363023 -0.5679627 -0.8840643 0.112865 -0.4535327 -0.7989086 -0.0183708 -0.6011719 -0.8640581 -0.1254696 -0.4875047 -0.8094214 -0.2170185 -0.5456557 -0.844793 -0.3792334 -0.377501 -0.876466 -0.3213598 -0.358518 -0.7622048 -0.5883001 -0.2700865 -0.8740927 -0.4780237 -0.086344 -0.7890126 -0.6143737 0.002034187 -0.8531026 -0.4967755 0.1594683 -0.8070328 -0.5397226 0.2395782 -0.8567534 -0.3895552 0.3379651 -0.8399487 -0.3975275 0.3694024 -0.8066171 -0.2584827 0.5315597 -0.8539782 -0.1614012 0.4946423 -0.8163361 -0.1240832 0.5640912 -0.8476411 0.05465286 0.5277478 -0.8416047 0.06228268 0.536491 -0.81635 0.2699692 0.5105777 -0.8271918 0.2716177 0.4919123 -0.7602795 0.4634464 0.4551842 -0.865379 0.4412485 0.2375273 -0.8053132 0.5561349 0.2053893 -0.9017711 0.4313873 0.02672046 -0.7886062 0.6071105 -0.09755712 -0.8638355 0.4400696 -0.245208 -0.8373646 0.4854662 -0.2512829 -0.820088 0.3443114 -0.4570619 -0.8476589 0.3396428 -0.4075751 -0.8136629 0.2115322 -0.5414858 -0.8609095 0.1408722 -0.4888661 -0.8223502 0.03387743 -0.5679723 -0.8768421 -0.06608533 -0.4762149 -0.8069491 -0.1665528 -0.5666512 -0.8239366 -0.3611869 -0.4366605 -0.8631905 -0.3421257 -0.3712846 -0.792249 -0.5318688 -0.2990939 -0.8570203 -0.4765554 -0.1959879 -0.8041814 -0.5930323 -0.04006272 -0.8516687 -0.5240664 0.003883957 -0.7983892 -0.5720987 0.1878242 -0.8718249 -0.4409304 0.2133113 -0.8107064 -0.4492869 0.3753617 -0.8578177 -0.2939344 0.4216061 -0.8713125 -0.2920501 0.3943622 -0.7585873 -0.1748535 0.6276718 -0.8669658 0.008174061 0.4983008 -0.8315886 0.04942524 0.5531888 -0.8310638 0.2848593 0.4776905 -0.8623688 0.2791749 0.4223523 -0.7831179 0.4929434 0.3791217 -0.8695345 0.4398373 0.2246174 -0.7820042 0.6067704 0.1424751 -0.8716286 0.4891235 -0.03196883 -0.8165105 0.5695098 -0.09470599 -0.8001832 0.5297674 -0.2811643 -0.915512 0.3026632 -0.2650145 -0.8413905 0.333085 -0.4255779 -0.8257536 0.1346076 -0.5477334 -0.8884868 0.07167124 -0.453271 -0.7837182 -0.1436345 -0.6042805 -0.8653126 -0.2021779 -0.4586482 -0.8041926 -0.3328506 -0.4924275 -0.869796 -0.3731204 -0.322856 -0.8094576 -0.4868915 -0.3281998 -0.8010768 -0.5847229 -0.1279659 -0.8835127 -0.4671254 -0.03462928 -0.8040109 -0.5903442 0.07113724 -0.8171117 -0.5246764 0.2388371 -0.8420989 -0.4192851 0.3392189 -0.881841 -0.3934632 0.2598909 -0.7748668 -0.3367248 0.5349746 -0.8300397 -0.1182894 0.5450154 -0.8786067 -0.1512057 0.452976 -0.8026893 0.07283502 0.5919333 -0.866339 0.1215127 0.4844495 -0.816841 0.245736 0.5219051 -0.8689482 0.3087982 0.3867463 -0.8093293 0.4204504 0.4101312 -0.8344644 0.517951 0.1881379 -0.8361584 0.5158147 0.1864795 -0.8488621 0.5258038 -0.05444103 -0.8114754 0.5774703 -0.08964276 -0.8147967 0.4695855 -0.3399938 -0.8664759 0.3821223 -0.321251 -0.8007185 0.3267707 -0.5020665 -0.8719634 0.2054831 -0.4443608 -0.7772271 0.0681138 -0.6255228 -0.8802887 -0.06186109 -0.4703882 -0.8112322 -0.1554117 -0.5636929 -0.8067901 -0.3746984 -0.456827 -0.8753435 -0.339749 -0.3440123 -0.7869753 -0.5577251 -0.2638421 -0.8603186 -0.4872986 -0.1496396 -0.7787609 -0.6266776 -0.02840244 -0.8793849 -0.4641451 0.1060744 -0.8142874 -0.542344 0.2068793 -0.8113675 -0.4681109 0.3500788 -0.9007898 -0.2935192 0.3200379 -0.8391973 -0.2895422 0.4603403 -0.8747848 -0.1577592 0.4581087 -0.7935997 -0.08003532 0.6031533 -0.8038663 0.1278475 0.5809081 -0.8424028 0.08589857 0.5319578 -0.796112 0.3118078 0.5186345 -0.862809 0.3145245 0.3957715 -0.7997217 0.4633235 0.3818072 -0.8608912 0.4560422 0.2255924 -0.8227244 0.5307597 0.2035159 -0.8103166 0.5820177 0.06813567 -0.8818905 0.4707646 -0.02549546 -0.7805973 0.6019006 -0.1684741 -0.8148766 0.4891629 -0.3109599 -0.8899449 0.3506295 -0.2916452 -0.789219 0.355663 -0.5006368 -0.8112949 0.2062278 -0.5470564 -0.8673238 0.1318919 -0.4799522 -0.8358122 0.05408531 -0.5463449 -0.8900152 -0.06795722 -0.450838 -0.8335027 -0.1558808 -0.5300705 -0.7845451 -0.3175814 -0.5325704 -0.8645498 -0.312927 -0.3932309 -0.7948111 -0.4884003 -0.3601952 -0.8681501 -0.4458941 -0.2179309 -0.782817 -0.6015365 -0.1592221 -0.847839 -0.5217242 0.09472626 -0.8461423 -0.5245427 0.09432989 -0.8228405 -0.5057128 0.2592068 -0.8960601 -0.3422196 0.2827757 -0.8343074 -0.3484377 0.4272266 -0.8505409 -0.2247072 0.475486 -0.8225172 -0.2127705 0.5274412 -0.844095 -0.03336429 0.5351545 -0.8458016 -0.03505331 0.5323449 -0.8058561 0.1047686 0.582769 -0.8374606 0.149544 0.525639 -0.7657566 0.3112922 0.5627736 -0.8259126 0.4164651 0.3800335 -0.8290272 0.4110895 0.3791033 -0.8017091 0.5568552 0.2171981 -0.8738803 0.4747596 0.1045786 -0.8179472 0.5730624 0.05061572 -0.7886101 0.5865546 -0.1845207 -0.8869316 0.4161608 -0.2004063 -0.8567472 0.4355118 -0.2762498 -0.8258625 0.3225895 -0.4624794 -0.8823319 0.2038978 -0.4241653 -0.8149389 0.1778586 -0.5515806 -0.8824862 -0.06567227 -0.4657312 -0.8160238 -0.1475884 -0.5588585 -0.8559247 -0.2888615 -0.4288964 -0.8307625 -0.3313381 -0.4472682 -0.8130186 -0.4959435 -0.3050262 -0.8736567 -0.444153 -0.1986255 -0.8243301 -0.5439077 -0.1569854 -0.8168736 -0.5760477 0.02977961 -0.8657615 -0.4965296 0.06257355 -0.7803256 -0.5676103 0.2625086 -0.8698648 -0.3698114 0.3264581 -0.831938 -0.4318615 0.3483889 -0.8485236 -0.2489646 0.4669306 -0.8425238 -0.2574673 0.473143 -0.8247039 -0.05292588 0.5630829 -0.8402655 -0.04101151 0.5406221 -0.8529882 0.1693342 0.4936974 -0.8309181 0.1991392 0.519537 -0.8084077 0.3945878 0.4367809 -0.862597 0.3757085 0.3387765 -0.7911881 0.5400606 0.2869772 -0.8705841 0.4795281 0.110165 -0.8121146 0.5796189 0.06717008 -0.8060778 0.5647553 -0.1768897 -0.8756002 0.4453731 -0.1869956 -0.7867619 0.453819 -0.4183948 -0.8580472 0.3255885 -0.3971741 -0.7782469 0.2559472 -0.5734307 -0.8802796 0.0927056 -0.4653102 -0.856002 0.06152284 -0.5132988 -0.8183479 -0.1546081 -0.5535368 -0.8652294 -0.2085981 -0.4559221 -0.8284588 -0.270955 -0.4901425 -0.8148335 -0.4562238 -0.3576399 -0.8429349 -0.4355733 -0.3158115 -0.8202703 -0.548052 -0.1636943 -0.8611693 -0.4960548 -0.1109831 -0.7799836 -0.6238898 0.04886072 -0.8762893 -0.4581586 0.1490237 -0.8069164 -0.5183401 0.283213 -0.8585269 -0.3795859 0.3447407 -0.8044959 -0.3888585 0.4489716 -0.8175925 -0.2582911 0.5146149 -0.8877075 -0.1492103 0.435559 -0.800704 -0.05751192 0.5962933 -0.8085935 0.1170402 0.5766093 -0.8664957 0.1439878 0.4779672 -0.7986813 0.2979988 0.5227857 -0.85655 0.3622192 0.3675859 -0.8085942 0.4594222 0.3675689 -0.8571452 0.4768133 0.1948106 -0.8264838 0.5327709 0.1818785 -0.8369845 0.5372877 -0.1038227 -0.8353083 0.539951 -0.103504 -0.8204413 0.4790585 -0.3120564 -0.8730319 0.3748458 -0.3119392 -0.8006981 0.3568313 -0.4812008 -0.8568479 0.2208927 -0.4658519 -0.7977613 0.1579676 -0.5819135 -0.8680465 0.01822805 -0.4961483 -0.7989715 -0.0616433 -0.5982012 -0.8225715 -0.262942 -0.5042199 -0.8970996 -0.249623 -0.3645556 -0.7633305 -0.5213419 -0.3814831 -0.8678936 -0.4734473 -0.1503615 -0.8522534 -0.4953083 -0.1683271 -0.8128982 -0.5821154 0.0183928 -0.8603053 -0.5044521 0.07350647 -0.7996461 -0.5592722 0.2185881 -0.8634886 -0.4392207 0.247937 -0.80282 -0.4226863 0.4204953 -0.832844 -0.3701542 0.41153 -0.7522786 -0.2390985 0.613929 -0.8395407 -0.09688508 0.5345885 -0.7971244 -6.03861e-4 0.603815 -0.8731657 0.08357381 0.4802054 -0.7667408 0.2541458 0.589507 -0.8434967 0.3762324 0.3833571 -0.8707706 0.355999 0.3391509 -0.7886185 0.5689962 0.2330754 -0.8718795 0.480861 0.0927304 -0.768344 0.6396167 -0.02319598 -0.8648526 0.4745538 -0.1637947 -0.8509868 0.4985813 -0.1650403 -0.8816148 0.331467 -0.3359834 -0.8037059 0.3695092 -0.4663903 -0.8147987 0.2043383 -0.5425395 -0.9064688 0.07250082 -0.4160024 -0.8248333 -0.01996737 -0.5650236 -0.8905897 -0.1808419 -0.4173085 -0.7860873 -0.345005 -0.5128726 -0.8621244 -0.3663368 -0.3500556 -0.8044635 -0.5012046 -0.3187986 -0.9117946 -0.3889186 -0.1318069 -0.7466489 -0.6648284 0.0227769 -0.8826483 -0.4470415 0.1452104 -0.8162369 -0.5178414 0.2561202 -0.8009884 -0.4274126 0.419209 -0.8634333 -0.3197442 0.3901879 -0.808893 -0.2586486 0.5280085 -0.8627598 -0.1289325 0.4888986 -0.8214865 -0.09081619 0.5629495 -0.8169697 0.1298565 0.56187 -0.861356 0.1437338 0.4872438 -0.8093081 0.3403481 0.4787315 -0.8734977 0.3255059 0.362005 -0.7384718 0.6002382 0.307203 -0.8719207 0.4784497 0.104117 -0.8244056 0.5631626 0.056598 -0.8357771 0.5265056 -0.1557842 -0.8479322 0.5054544 -0.1597712 -0.8095622 0.4792608 -0.338996 -0.8628311 0.3739305 -0.3401452 -0.8194973 0.3420114 -0.4598397 -0.8706864 0.2046412 -0.4472443 -0.8115547 0.1715671 -0.5585191 -0.8421258 -0.05938786 -0.536001 -0.8795802 -0.07873922 -0.4691895 -0.7771155 -0.2813165 -0.5629855 -0.8540394 -0.3749586 -0.3605867 -0.886817 -0.3499246 -0.3018415 -0.7880862 -0.5643507 -0.2458218 -0.8380223 -0.5436395 -0.04663497 -0.847387 -0.5294542 -0.04017251 -0.8129257 -0.5424409 0.2119196 -0.8361135 -0.5048525 0.2145652 -0.8262282 -0.4113954 0.384839 -0.858502 -0.3571288 0.3680128 -0.7832784 -0.2526747 0.5680057 -0.8685224 -0.08168715 0.4888725 -0.8161662 -0.1252831 0.5640718 -0.8434233 0.09460157 0.5288551 -0.851227 0.09831708 0.515506 -0.8141372 0.311492 0.4900545 -0.8291061 0.3111384 0.464517 -0.742261 0.5455183 0.3891767 -0.8349227 0.5051261 0.2185214 -0.8101426 0.5521799 0.1968918 -0.8344132 0.5511202 -0.004603505 -0.8693565 0.4929561 -0.03483492 -0.7887747 0.5795725 -0.2047686 -0.866795 0.411786 -0.2812453 -0.8370264 0.4302541 -0.3380363 -0.8019484 0.3360103 -0.493939 -0.8816481 0.180374 -0.4360756 -0.8101482 0.1393775 -0.5694155 -0.8044067 -0.05682444 -0.5913551 -0.8754621 -0.1216665 -0.4677217 -0.8349657 -0.1891441 -0.5167755 -0.7920608 -0.4041771 -0.4574722 -0.9037865 -0.325303 -0.278115 -0.813507 -0.5615007 -0.1514048 -0.8580559 -0.5028883 -0.1041322 -0.7749748 -0.6221013 0.1113746 -0.8772506 -0.444127 0.1821611 -0.8104802 -0.5025526 0.3009366 -0.8582117 -0.2921407 0.4220506 -0.8338133 -0.2957673 0.4661301 -0.8278967 -0.07951086 0.5552164 -0.8812656 -0.01353943 0.4724274 -0.799474 0.1017768 0.592016 -0.8248009 0.2985885 0.4801545 -0.8714115 0.286266 0.398364 -0.7956367 0.4834103 0.3650711 -0.8683002 0.4390505 0.230845 -0.7764719 0.6242487 0.08605319 -0.8284532 0.5580818 0.04701203 -0.8394796 0.5232245 -0.1466631 -0.8657054 0.4752475 -0.1571443 -0.7897255 0.4930916 -0.364958 -0.8792471 0.2901062 -0.3778401 -0.8669496 0.3104988 -0.3898576 -0.7706518 0.1847593 -0.6098851 -0.882227 0.0100978 -0.4707161 -0.8178077 -0.06427347 -0.571891 -0.8001726 -0.2317067 -0.5532049 -0.8844945 -0.2619249 -0.3860893 -0.8688529 -0.2960662 -0.3967863 -0.8210176 -0.4925442 -0.2886701 -0.8739103 -0.4615084 -0.1526132 -0.8287709 -0.5455615 -0.1245046 -0.8654911 -0.4971604 0.06129306 -0.8259534 -0.553797 0.1054033 -0.7905039 -0.5539169 0.2613043 -0.8396009 -0.4572761 0.2932047 -0.7624965 -0.4455924 0.4690914 -0.8338985 -0.2565287 0.4886781 -0.8095335 -0.2454822 0.5332861 -0.8340365 -0.06276941 0.5481269 -0.8162116 -0.05004906 0.5755813 -0.8150208 0.1880403 0.5480711 -0.8671303 0.1949086 0.4583622 -0.7725784 0.361679 0.5218343 -0.8382087 0.4282068 0.3377059 -0.8833754 0.3823108 0.2710835 0.2830671 0.9262973 0.2486895 -0.4978739 0.8672106 -0.008214175 -0.4914538 -0.06006169 0.8688302 0.2591087 0.3703287 0.8920311 -0.8085185 -0.08873391 -0.5817423 -0.5698027 -0.6904484 -0.4456525 0.6078516 -0.7807829 -0.1445501 -0.7392593 -0.672879 -0.02701389 0.7453862 0.4653278 0.4773569 -0.707822 0.6104702 0.3554071 -0.591916 0.8038926 0.05824273 0.7104389 0.6504715 -0.2686327 -0.8352726 -0.4560424 0.3071566 -0.830847 0.5547239 0.04443776 0.6089757 0.6506172 0.4537025 -0.664305 0.7056064 0.2466145 0.676414 0.7340139 0.06072735 -0.7067925 0.6982166 -0.1137448 0.6951655 0.5528224 -0.4594913 -0.5820721 0.480753 -0.6557962 0.6019732 0.2992468 -0.7403241 -0.698881 0.1657681 -0.6957631 -0.8289029 0.5530748 -0.08383548 0.7411481 -0.4357503 0.5107067 -0.61153 -0.4013827 0.6818528 0.6729378 -0.1082736 0.731732 0.8285116 -0.09281605 -0.5522261 0.905756 -0.2799678 0.3181576 0.8453189 0.3215858 -0.4266365 -0.6888716 0.2012943 -0.6963739 0.621663 -0.05420827 -0.7814069 -0.6956027 -0.1863682 -0.6938327 0.8328685 -0.104376 -0.54354 -0.8282524 0.5500229 -0.1071118 0.7702832 0.5241327 -0.3632474 -0.7406383 0.4161213 -0.5275397 0.7067587 0.1027045 -0.6999601 -0.6649486 -0.04300779 -0.7456499 0.669912 -0.2511731 -0.698663 -0.6759795 -0.4130532 -0.6102777 0.5562437 -0.7597566 -0.3366941 -0.2053452 -0.9777639 0.04255819 0.5923209 -0.6167277 -0.5184621 -0.4646296 -0.8571465 -0.2223043 -0.8785554 0.471594 0.07575994 0.9006316 -0.3578531 -0.2465844 0.6937767 0.7108749 -0.1154587 -0.1357801 0.9492512 -0.2837005 0.06967473 0.7598909 -0.646306 -0.7776727 0.4158278 -0.4715004 -0.7043038 0.5456334 -0.454137 -0.04168146 0.7794979 -0.6250167 -0.7497646 0.5675272 -0.3402441 -0.9745289 0.21455 -0.06528222 -0.6117713 0.7214877 -0.3243324 -0.3130401 0.8505035 -0.4226699 -0.9051901 0.4200969 -0.06441766 -0.6265209 0.7633092 -0.1575778 -0.6307119 0.7603661 -0.155068 -0.3422198 0.9236698 -0.1723942 -0.4685798 0.8722034 0.1403359 0.01628834 0.9998192 -0.009809553 -0.832425 0.541288 0.1186422 -0.4329355 0.894968 0.1077 -0.8405178 0.5273837 0.1240825 -0.2994589 0.9123474 0.2791893 -0.202787 0.9253792 0.3202355 -0.7849598 0.5699812 0.2428162 -0.8009963 0.5228654 0.2915765 -0.9757679 0.1630005 0.1459726 -0.6328342 0.6251027 0.456911 -0.2590703 0.8089828 0.5276641 -0.02376991 0.8000435 0.599471 -0.6365743 0.5267419 0.5633083 -0.7854622 0.3674877 0.4979982 -0.2862264 0.630356 0.7216134 -0.7649082 0.3425871 0.5454811 -0.04822087 0.5677859 0.8217628 -0.4971951 0.3603239 0.7892806 -0.3662906 0.3979361 0.8411172 -0.926792 0.06878995 0.3692216 -0.8710157 0.06458604 0.4869912 -0.5892361 0.1537858 0.7931903 0.03369992 0.2428437 0.9694799 -0.4168809 0.1232536 0.9005659 -0.9981818 -0.001165926 0.06026357 -0.3181397 0.1265623 0.939558 -0.7875254 -0.08301746 0.6106652 0.01279127 -0.05659955 0.998315 -0.5314685 -0.1267729 0.8375381 -0.894661 -0.1299933 0.427415 -0.4226979 -0.1672379 0.8907065 -0.8288398 -0.2284974 0.510699 -0.3925961 -0.2700176 0.8791809 -0.1198402 -0.422998 0.898171 -0.8036073 -0.3373516 0.4903155 -0.7065258 -0.4134942 0.5743204 -0.3083332 -0.4958308 0.8118389 -0.887893 -0.296335 0.3518972 -0.8373662 -0.4382048 0.3267945 -0.4385455 -0.6778987 0.5900265 -0.6720274 -0.6227865 0.4006449 0.09931087 -0.7637096 0.6378756 -0.1270737 -0.7356379 0.665349 -0.6326601 -0.679375 0.3717404 -0.981177 -0.1762012 0.07902449 -0.2699671 -0.8506397 0.4511429 -0.8165538 -0.5593975 0.1425287 -0.6706488 -0.6940854 0.2616786 -0.03158795 -0.959044 0.2814905 -0.1966699 -0.9491739 0.2457435 -0.8129999 -0.5761198 0.08436453 -0.6293108 -0.7771292 0.006178915 -0.9732461 -0.2272641 -0.03381007 -0.4000619 -0.9153502 0.04565626 -0.638918 -0.765549 -0.07562255 -0.8631476 -0.4842977 -0.1429413 0.1585186 -0.9525343 -0.2599043 -0.08578348 -0.9785214 -0.1874496 -0.2885928 -0.9068046 -0.3072779 -0.7550517 -0.5819578 -0.3020299 -0.7518076 -0.5850943 -0.3040563 -0.9118954 -0.3160045 -0.2618929 -0.4359569 -0.7354221 -0.5187446 -0.2306987 -0.7971842 -0.5579208 -0.1178338 -0.8013327 -0.5864992 -0.7392798 -0.4146257 -0.5306137 -0.6900094 -0.4478008 -0.5686489 -0.370037 -0.5061458 -0.7790309 -0.2357945 -0.5552597 -0.7975511 -0.8785349 -0.183336 -0.4410947 -0.9270929 -0.1224184 -0.3542777 -0.3709263 -0.3655114 -0.8537067 -0.5530778 -0.2674745 -0.7890263 0.0687415 -0.2972334 -0.9523271 -0.4730517 -0.118363 -0.8730477 -0.6887958 9.83184e-4 -0.7249549 -0.3005308 -0.1211766 -0.9460431 -0.6913 0.01630324 -0.7223839 0.1127571 0.02817571 -0.9932231 -0.849416 0.1201255 -0.5138701 -0.9996603 0.01004219 -0.02404946 -0.2628178 0.1226852 -0.9570137 -0.7992166 0.1799817 -0.5734627 -0.3233388 0.3178679 -0.8912981 -0.4456234 0.3272163 -0.8332763 0.2459216 0.4187127 -0.8741866 -0.7729341 0.4161548 -0.4789448 -0.4198358 0.5038114 -0.7549252 -0.263727 0.55175 -0.7912143 -0.9999979 -5.53916e-4 -0.002038359 -0.9999784 -0.005744874 -0.00320667 -0.9999881 -1.80635e-4 -0.004879295 -0.9999922 0.002703368 -0.002883255 -0.9999963 -0.002035439 0.001813769 -0.9999932 0.00246334 -0.002737879 -0.9999992 -0.001262605 2.88373e-4 -0.9998599 0.01380258 0.009480714 -0.472613 -0.5170354 0.7136605 -0.4808306 -0.5164152 0.7086024 -0.9730303 -0.1400808 0.1832749 -0.505576 -0.3806239 0.7742859 -0.991849 -0.06302922 0.1107385 -0.7840881 -0.1905046 0.5906894 -0.1904196 -0.2090134 0.9591944 -0.7728596 -0.1852733 0.6069282 -0.7620502 -0.07924091 0.6426512 -0.5537033 -0.05429035 0.8309424 -0.4335596 0.008711397 0.9010829 -0.9537335 0.02191859 0.2998535 -0.6179387 0.1347888 0.7745862 -0.3647251 0.2130922 0.9064036 -0.999389 0.007400751 0.03416115 -0.790817 0.1214885 0.5998744 -0.4039276 0.3704429 0.8364297 -0.831101 0.2340484 0.5044727 -0.6598229 0.3510597 0.6643726 -0.7168659 0.3297004 0.6143297 -0.7693569 0.4031804 0.4955157 -0.4390097 0.625864 0.6446431 -0.4406838 0.7056103 0.5548982 -0.5909514 0.6567199 0.4685035 -0.943042 0.2521684 0.2169861 -0.9022229 0.3465933 0.2566459 -0.4381 0.8045005 0.4010579 -0.6953753 0.6884023 0.2062898 -0.8732762 0.460885 0.1580311 -0.6705427 0.7139346 0.2016679 -0.6059631 0.7900471 0.09292125 -0.6300733 0.7737282 0.06597304 -0.5001998 0.8656038 -0.02302956 -0.9971218 0.07554465 0.006423771 -0.9580448 0.2836667 -0.04103159 -0.9064645 0.4206455 -0.03714191 -0.5908929 0.7999173 -0.104775 -0.4650589 0.8668053 -0.1799134 -0.5195564 0.8168935 -0.2504918 -0.4047003 0.8569266 -0.3192093 -0.881752 0.4487381 -0.1454219 -0.9351984 0.3191277 -0.1534976 -0.4948676 0.7653951 -0.4114325 -0.2782576 0.8108321 -0.514902 -0.8728963 0.4222341 -0.2444801 -0.4210498 0.7006411 -0.5760374 -0.6275294 0.5721965 -0.5280134 -0.7980229 0.4456229 -0.4056842 -0.4285306 0.5397836 -0.7245656 -0.9059098 0.27671 -0.3205605 -0.6826457 0.3843157 -0.6215276 -0.6826595 0.3699136 -0.6301906 -0.4323414 0.3540895 -0.8292778 -0.5008795 0.2665424 -0.823453 -0.1517967 0.2173319 -0.9642223 -0.7848317 0.1510511 -0.6010183 -0.9080964 0.1419549 -0.3939666 -0.7885275 0.07576811 -0.6103144 -0.5223186 0.02156412 -0.8524777 -0.5250183 0.02128934 -0.8508246 -0.9594355 -0.01061785 -0.2817283 -0.7075536 -0.1150065 -0.6972385 -0.6898432 -0.1303539 -0.7121266 -0.385378 -0.2117281 -0.8981398 -0.2914825 -0.3903295 -0.8733161 -0.8331202 -0.231791 -0.5021792 -0.6926631 -0.3518185 -0.6296361 -0.6384058 -0.4449623 -0.6280499 -0.6342116 -0.4426512 -0.6339052 -0.4862985 -0.5979261 -0.6371798 -0.9073007 -0.2927825 -0.3018015 -0.7449259 -0.5239397 -0.4130045 -0.7366536 -0.5411524 -0.4055805 -0.7867072 -0.5284219 -0.3191585 -0.6993834 -0.6409594 -0.3162815 -0.9889202 -0.1374858 -0.0559867 -0.5299949 -0.8213949 -0.2107508 -0.7188413 -0.6660854 -0.1989911 -0.879398 -0.4638161 -0.1073965 -0.3708557 -0.9160287 -0.1528316 -0.6242359 -0.7812268 -0.003803491 -0.870774 -0.4915671 -0.01069921 -0.4244659 -0.9037832 0.05481481 -0.93746 -0.3471438 0.02568882 -0.4446253 -0.8763329 0.185335 -0.6726581 -0.7095601 0.2098945 -0.6730619 -0.6973642 0.246315 -0.4243254 -0.7707868 0.4752218 -0.7544701 -0.5909388 0.2855982 -0.8886705 -0.3984816 0.2268863 -0.3432499 -0.7383888 0.5804839 -0.8325939 -0.4142502 0.3676743 -0.6273289 -0.562236 0.5388407 -0.003422796 -0.5963419 0.8027233 0.00759375 -0.4669864 0.884232 -0.004250109 -0.3961797 0.9181632 0.00124824 -0.2832863 0.9590346 -0.008003592 -0.2244938 0.9744427 0.006616652 -0.06646567 0.9977667 -0.005594074 0.02457028 0.9996826 0.00568819 0.1650239 0.9862732 -0.003589987 0.2146682 0.9766805 0.002159357 0.4059214 0.9139055 -2.12399e-5 0.4147175 0.9099503 -0.004607319 0.5830743 0.8124059 -9.3521e-4 0.6136342 0.78959 -0.004986882 0.6461702 0.7631772 0.006434738 0.7305641 0.6828138 -0.006879627 0.8070713 0.5904139 0.002377212 0.8661093 0.499849 -0.002620875 0.8941459 0.4477682 0.004416584 0.9244405 0.381301 -0.006471693 0.9608317 0.2770573 0.004178106 0.9878939 0.1550746 -0.002241075 0.9940243 0.109136 -0.001412034 0.9998571 -0.01684957 0.006514012 0.9978298 -0.0655229 -5.91848e-4 0.9799565 -0.1992115 0.002650082 0.9829452 -0.18388 -0.003898322 0.9385467 -0.3451303 0.005501449 0.9142059 -0.4052128 -0.005084872 0.8482194 -0.5296207 0.01062035 0.7951896 -0.606268 0.007595777 0.6694931 -0.7427794 0.00344485 0.7261093 -0.6875708 -0.009119987 0.5965454 -0.8025276 0.003991067 0.4449164 -0.8955633 -3.56738e-4 0.4254332 -0.9049898 -0.001091003 0.2192512 -0.9756678 0.007945001 0.1804181 -0.983558 0.004997849 0.01980459 -0.9997914 -0.002099931 -0.01423263 -0.9998965 4.35897e-5 -0.2106696 -0.9775574 -7.0862e-4 -0.2075687 -0.9782203 0.002726852 -0.396205 -0.9181581 -0.002919077 -0.4249796 -0.9051983 -9.88263e-5 -0.5564858 -0.8308571 0.003084838 -0.571558 -0.8205559 -8.5476e-4 -0.7091292 -0.7050782 4.06773e-4 -0.7142371 -0.6999037 -0.005951762 -0.8117632 -0.5839566 0.00242412 -0.8536777 -0.5207961 -0.006019473 -0.8931536 -0.4497117 5.08791e-5 -0.9378305 -0.3470938 0.001521408 -0.9403434 -0.3402234 1.33887e-4 -0.9890291 -0.1477218 -0.0020985 -0.9905388 -0.1372171 0.006177604 -0.9974393 0.07125127 -0.003538727 -0.9998104 0.01914888 -0.005346298 -0.9690886 0.2466552 0.005305051 -0.9439209 0.3301292 8.88567e-4 -0.927747 0.3732089 0.003177106 -0.8806775 0.4737058 0.006061613 -0.8891565 0.457563 -0.001198649 -0.7855263 0.6188272 0.002181112 -0.7755221 0.6313167 0.005966484 -0.6380202 0.7699965 -0.9992618 -0.03030103 -0.02362036 -0.9999838 -0.002563118 -0.00509268 -0.9997881 0.01795125 -0.01008009 -0.9998113 -0.0137555 -0.01372146 -0.9996392 0.02298301 -0.01390302 -0.9998685 0.01083558 -0.01206779 -0.9998281 -0.006087601 -0.01751291 -0.9997497 -0.01956421 0.01085829 -0.9998671 0.003564715 -0.01591002 -0.9998086 0.01489573 0.01269233 -0.9999837 -0.002620279 -0.005079209 -0.9999986 -0.001526296 -7.79432e-4 -0.9999976 0.001784682 -0.001391291 -0.9999976 0.001777708 -0.001320123 -0.9999745 -0.004563748 0.005499005 -0.9999977 0.001897096 -0.00104916 -1 2.65751e-4 1.35009e-4 -0.9999989 -0.001455724 1.27593e-4 -0.9999517 -0.00937891 -0.002980709 -1 3.16095e-4 9.6536e-5 -0.9999911 3.14121e-5 0.004237473 -0.9999926 3.09689e-4 0.003865838 -0.9992383 -0.03460031 0.01804459 -0.9999922 0.00205028 0.003365933 -0.9996027 0.02190697 0.01773786 -0.9999859 0.001114964 0.005183458 0.6656146 -0.564104 0.4886142 0.765295 -0.5137537 0.3877895 0.7491266 -0.5740501 0.330569 0.7876041 -0.5473822 0.2829359 0.9847245 -0.1641792 0.05799037 0.6019089 -0.7696629 0.2128962 0.6715225 -0.7275668 0.1403715 0.7762356 -0.6224492 0.1000766 0.3114585 -0.9484263 0.05900025 0.8420159 -0.5394003 0.007522881 0.5167706 -0.8544589 -0.05336916 0.7395821 -0.6712111 -0.04994153 0.2416374 -0.9600147 -0.1413628 0.7987385 -0.5881452 -0.1268942 0.4851165 -0.8275894 -0.2824143 0.519232 -0.8074347 -0.2800844 0.6442036 -0.6919509 -0.3258924 0.9464018 -0.3061887 -0.1028212 0.5825414 -0.6921053 -0.4261875 0.6568197 -0.6166267 -0.4340039 0.4562774 -0.6423811 -0.6157578 0.9197783 -0.2984313 -0.2548466 0.6557397 -0.4766982 -0.5854608 0.8578931 -0.3238407 -0.3989321 0.4890167 -0.489351 -0.7220792 0.9345343 -0.1857295 -0.3035625 0.596489 -0.3586731 -0.7180213 0.8813529 -0.2114893 -0.4224804 0.4949567 -0.3449882 -0.7974968 0.8669039 -0.1417821 -0.4778864 0.6007593 -0.2065691 -0.7722808 0.5054451 -0.18034 -0.8438026 0.6258409 -0.02838617 -0.779434 0.964875 -0.02934896 -0.2610653 0.7596471 0.01105183 -0.6502418 0.4909551 0.1857534 -0.8511516 0.7254095 0.09940576 -0.6811018 0.9324106 0.1275566 -0.3381417 0.5930266 0.330464 -0.7342432 0.3838183 0.4190877 -0.8228299 0.8435713 0.2278135 -0.4863008 0.4428265 0.5692855 -0.6926895 0.8398276 0.3524737 -0.4128582 0.7550979 0.4477004 -0.4789483 0.4729334 0.7151909 -0.5146222 0.7570576 0.4936976 -0.427933 0.8930615 0.3718393 -0.2533316 0.601564 0.7127565 -0.3606923 0.8566942 0.4538593 -0.2451264 0.4345805 0.832881 -0.3427082 0.5093977 0.8242909 -0.2471004 0.9385385 0.3298846 -0.1015962 0.6764417 0.7153378 -0.1752671 0.58785 0.8087467 -0.01900941 0.5622173 0.826402 -0.03116911 0.9869602 0.1585883 -0.02755671 0.8037906 0.5945952 0.01942431 0.3121076 0.937107 0.1562674 0.5835705 0.787063 0.1999437 0.789252 0.5995143 0.132906 0.9338834 0.3396151 0.1119086 0.439259 0.8397144 0.319267 0.6304212 0.6789492 0.3762939 0.4699921 0.7434089 0.4758686 0.850881 0.4595221 0.254639 0.4552129 0.6711462 0.5851017 0.5852953 0.5874363 0.5588811 0.9312235 0.2644793 0.2507462 0.9487228 0.2360451 0.2102566 0.4266357 0.5260238 0.7357181 0.5480881 0.5056752 0.6662523 0.8410673 0.311039 0.4425613 0.374167 0.3854849 0.8434456 0.3993473 0.3760741 0.836116 0.8509061 0.2098661 0.4815756 0.8924067 0.1946526 0.4070883 0.5191522 0.1968699 0.8316991 0.3622044 0.1619052 0.9179295 0.7746416 0.1543916 0.6132647 0.9983556 0.01210784 0.05603086 0.9230179 0.02231526 0.3841095 0.6218254 -0.004583835 0.7831426 0.8749799 0.002188503 0.4841545 0.3973024 -0.07787173 0.9143778 0.4632877 -0.2216798 0.8580342 0.703714 -0.2329323 0.6712148 0.8437665 -0.1572002 0.5131729 0.6253127 -0.349987 0.6974907 0.631729 -0.508203 0.5853616 0.762106 -0.3725316 0.529542 0.9952045 -0.06189209 0.07574635 0.0250073 -0.2880321 -0.9572942 0.0258702 -0.2871649 -0.9575317 0.02003771 0.6814079 -0.7316296 0.02578109 0.6856727 -0.7274534 0.02006745 0.9731236 0.229408 0.02093946 0.972904 0.2302595 0.7390736 0.2062516 0.6412726 0.5441742 0.2324812 0.8061185 0.7379802 0.6538611 0.1668862 0.5472676 0.8168325 0.1824364 0.5444454 0.5757063 -0.610034 0.5299025 0.5806689 -0.6180832 0.7494746 -0.2039548 -0.6298336 0.5317562 -0.2341448 -0.8138868 0.7447018 -0.6494684 -0.1536562 0.7366069 -0.6584657 -0.1543806 0.7389232 -0.4708623 0.4819557 0.5447937 -0.5675703 0.6173037 0.02514588 -0.9729373 -0.2296973 0.02518594 -0.9729263 -0.2297396 0.02456742 -0.6886505 0.7246772 0.02075552 -0.6859123 0.7273882 0.02004051 0.2928878 0.9559368 0.02577704 0.2871378 0.9575425 0.9998599 -0.003694832 0.0163275 0.9999693 0.001939594 -0.007599413 0.9999886 0.004613101 0.001273691 0.9999294 0.007049441 -0.009567141 0.9999827 0.00474143 -0.003522455 0.9999742 0.005051314 -0.005111336 0.9999707 0.007439553 -0.001840054 0.9999904 0.003332972 0.00287342 0.9999949 5.85511e-4 0.003148138 0.9999979 0.002022504 4.77238e-4 0.9999933 0.00334388 -0.001493453 0.9999508 4.96871e-4 -0.009912252 0.9999648 0.004399657 -0.007152259 0.9999933 0.002520442 -0.002671062 0.9999859 7.56303e-4 -0.005262136 0.9999945 9.83483e-4 0.003179132 0.9999647 0.006323397 -0.005537927 0.9998118 -0.01895982 0.004139065 0.9999976 -6.129e-4 -0.00210005 0.9999697 0.004241466 0.006530106 0.9999951 -0.002555489 -0.001802086 0.9999991 0.001012682 -9.31332e-4 0.99998 -0.006179809 -0.001388907 0.999962 -0.00821489 0.002925515 0.9999597 -0.008719801 -0.002172231 0.9999914 -0.004119634 -4.36235e-4 0.9999775 -0.005040943 -0.004451155 0.9999378 -0.004145979 -0.01035541 0.9960163 -0.08747154 0.0173285 0.9963381 -0.08542466 0.003602206 1 2.36332e-4 5.12312e-4 0.9971291 -0.07572144 2.8917e-4 0.9992713 -0.02863067 -0.02524322 0.9994271 -0.02541345 -0.02235108 0.9947382 -0.07628148 0.06838887 0.9982933 -0.01865905 0.05533844 0.9978667 -0.0189839 0.06246429 0.9944971 -0.05005288 -0.0920341 0.9963806 -0.03595584 -0.07702684 0.9979551 -0.01292502 0.06259948 0.9995265 0.02454513 0.01855862 0.9997429 0.003418684 0.02242004 0.9995617 0.01592111 0.02495878 0.999067 0.01823627 0.03914934 0.9969749 0.0613234 0.04775482 0.9970352 0.06113994 0.04672133 0.9958103 0.07501739 0.05228924 0.9977078 0.06263065 0.02562642 0.8980115 0.367415 0.2420367 0.6775393 0.6835893 0.2713782 0.9137237 0.405981 0.01698786 0.8144879 0.5751951 -0.0758953 0.8521065 0.4775338 -0.2141872 0.8624833 0.4649161 -0.1999392 0.8072147 0.4336718 -0.4004163 0.8381492 0.3564578 -0.4128483 0.7711562 0.3366805 -0.5403373 0.8267225 0.1923514 -0.5287071 0.7700428 0.1374202 -0.6230168 0.8029516 -0.03714489 -0.5948858 0.8530645 -0.09570622 -0.5129534 0.7739449 -0.2405227 -0.5857971 0.8552894 -0.3341798 -0.3959848 0.8659304 -0.3298807 -0.3759566 0.8166842 -0.518617 -0.2531074 0.8806982 -0.4498633 -0.148303 0.7538155 -0.6570853 0.001052737 0.9054177 -0.4035691 0.1317227 0.8150756 -0.5045042 0.2848286 0.8499286 -0.349685 0.3941344 0.8610715 -0.3422576 0.3760527 0.7774012 -0.2488427 0.5776893 0.8708158 -0.03852301 0.4900979 0.8573678 -0.02919143 0.5138757 0.8051201 0.1609467 0.5708573 0.8751713 0.2143216 0.4337527 0.7825952 0.3764334 0.4958252 0.8575765 0.4311137 0.280542 0.8036227 0.5247477 0.2807676 0.8530127 0.514859 0.08537995 0.806117 0.5890039 0.05700701 0.8370096 0.5209349 -0.1674571 0.8443948 0.5078597 -0.1705171 0.7974739 0.4592651 -0.3912944 0.8637131 0.3379257 -0.3739064 0.8346363 0.2986913 -0.4627807 0.8882931 0.1297401 -0.4405711 0.8332721 0.0958575 -0.5444898 0.8111823 -0.09989929 -0.5761973 0.8624481 -0.06612247 -0.5018079 0.7816233 -0.2825557 -0.5560821 0.8996564 -0.3191171 -0.2979645 0.7949768 -0.508874 -0.330241 0.8665887 -0.4724439 -0.1606884 0.8149855 -0.5668099 -0.1205203 0.8578956 -0.5046102 0.0968697 0.854665 -0.5105122 0.09447234 0.8133131 -0.5398566 0.2169718 0.8602979 -0.36624 0.3546206 0.8837884 -0.3133626 0.3474507 0.7958363 -0.2996757 0.5261549 0.8433331 -0.1231576 0.5230887 0.7856976 -0.0891692 0.6121504 0.8623978 0.0927149 0.4976685 0.8653209 0.08866512 0.4933136 0.8325524 0.3451436 0.4332811 0.8612127 0.3358126 0.3815006 0.8329951 0.508264 0.2186025 0.8197407 0.5211688 0.2375044 0.8571142 0.5147418 -0.01990801 0.8279952 0.5605825 0.01309037 0.7731481 0.5990509 -0.2082791 0.8687769 0.4055393 -0.284191 0.8415865 0.4249169 -0.3334333 0.822129 0.329208 -0.4644631 0.8638946 0.2439512 -0.4406518 0.806602 0.1415095 -0.5739061 0.8705202 0.03359168 -0.490985 0.7927602 -0.06018692 -0.6065549 0.8106845 -0.2075525 -0.5474601 0.8794004 -0.2375446 -0.4125867 0.7892202 -0.412826 -0.4546496 0.8650501 -0.4458753 -0.2299643 0.8366758 -0.4947626 -0.2349121 0.7820134 -0.623254 -0.003103673 0.875824 -0.474555 0.08792024 0.790894 -0.566823 0.2306478 0.8727412 -0.3719497 0.3161904 0.8217713 -0.4031912 0.4026524 0.7952864 -0.2817752 0.5367703 0.8699002 -0.136916 0.4738433 0.8112569 -0.09073179 0.5776072 0.8605571 0.07170653 0.5042814 0.8141537 0.1317546 0.565504 0.8143805 0.2642349 0.5166859 0.8640779 0.2808477 0.4177248 0.7870031 0.4525377 0.4193277 0.8622085 0.4400568 0.2508918 0.8107953 0.543201 0.2180454 0.8697755 0.4914746 0.04408472 0.8217036 0.5699079 0.002872705 0.8199477 0.5454365 -0.1737384 0.8785379 0.4325641 -0.2026315 0.7595458 0.4987511 -0.4175375 0.8189345 0.3232163 -0.4742128 0.8277174 0.3095852 -0.4680182 0.7775785 0.1920551 -0.5987375 0.8666731 -0.009973049 -0.498777 0.8285986 -0.05773717 -0.556858 0.8941095 -0.1855387 -0.4076073 0.8489399 -0.2491027 -0.4660999 0.7533169 -0.4743669 -0.4555105 0.8898307 -0.3935087 -0.2309808 0.7851076 -0.6016821 -0.1469181 0.8592428 -0.5113255 0.01575565 0.8564919 -0.5159837 0.01351088 0.8075662 -0.5240054 0.2706573 0.8917484 -0.3527222 0.2834995 0.816309 -0.3907625 0.4253756 0.8015219 -0.2523746 0.5420975 0.8754859 -0.1194887 0.4682382 0.8034424 -0.05750739 0.5925989 0.8464649 0.1233344 0.5179632 0.8228382 0.1521188 0.5475375 0.846855 0.3239575 0.4217681 0.8632656 0.2992153 0.4065008 0.7897252 0.5014625 0.3533689 0.86894 0.4708465 0.152469 0.861881 0.4842184 0.1506444 0.7848216 0.6176646 -0.05045413 0.8571553 0.5054526 -0.09900808 0.8195746 0.4788092 -0.3147052 0.8484035 0.4246407 -0.3160571 0.8142161 0.3462927 -0.4659759 0.8552803 0.2691665 -0.44277 0.8009188 0.1567561 -0.57789 0.8628201 0.05365753 -0.5026553 0.803823 -0.07219409 -0.5904715 0.8657644 -0.1485773 -0.4778878 0.8053 -0.2552809 -0.5350921 0.8367937 -0.3793694 -0.3947852 0.8541306 -0.3765641 -0.3586929 0.7988629 -0.5161204 -0.30893 0.8716415 -0.4676696 -0.1467188 0.8070917 -0.5793815 -0.1136664 0.826056 -0.5524964 0.1112623 0.8624982 -0.482563 0.1524138 0.8147736 -0.5314532 0.231736 0.8423134 -0.394539 0.3672154 0.8290475 -0.4020207 0.3886641 0.8560774 -0.1790594 0.4848393 0.8292081 -0.22094 0.5134194 0.7664068 -0.007040143 0.6423169 0.8874102 0.1078642 0.4481835 0.8024029 0.268145 0.5331491 0.8761098 0.3221885 0.3586448 0.8029013 0.4500382 0.3909156 0.8622166 0.4880287 0.1356859 0.8245686 0.5371771 0.17756 0.8713977 0.4821058 -0.09077495 0.8018021 0.5764348 -0.1575955 0.8586315 0.4349917 -0.2711718 0.8174714 0.4638695 -0.3414171 0.8462025 0.2965858 -0.4426944 0.8673273 0.2532495 -0.4284952 0.794457 0.2000109 -0.5734404 0.8397592 0.001560449 -0.5429568 0.8528544 -0.009612381 -0.5220603 0.8231716 -0.2501699 -0.5097094 0.8438544 -0.2254629 -0.4869047 0.8088951 -0.4285739 -0.402509 0.8620323 -0.4032135 -0.3071144 0.7605411 -0.6053088 -0.2349015 0.8798341 -0.4752723 -0.002907276 0.8212988 -0.5686751 0.04557466 0.8230218 -0.5150664 0.2394613 0.8773492 -0.407668 0.2531112 0.7777853 -0.4419193 0.4469424 0.8848254 -0.1527169 0.4401838 0.8583078 -0.1998876 0.4726019 0.7912296 -0.0687412 0.6076433 0.8358263 0.1227363 0.5350984 0.8525756 0.132567 0.5055105 0.8092316 0.3274251 0.487788 0.8733238 0.3340864 0.3545306 0.7763146 0.5093562 0.3713381 0.8987807 0.4324005 0.07227253 0.8080688 0.5879426 0.03672194 0.8403718 0.5179436 -0.1597178 0.8957895 0.410027 -0.1715782 0.8063321 0.3710391 -0.4606068 0.8724777 0.2517603 -0.4188073 0.7964539 0.1999934 -0.5706697 0.876293 0.01021856 -0.4816701 0.7967012 -0.05848538 -0.6015369 0.8199915 -0.2619495 -0.5089169 0.798435 -0.2599858 -0.5430551 0.7658441 -0.4842749 -0.4230375 0.8573766 -0.4469243 -0.2552727 0.7688585 -0.6133506 -0.1807147 0.8780341 -0.4777714 0.02811974 0.8414119 -0.5374287 0.05653756 0.7763389 -0.5624263 0.2845603 0.8873288 -0.3441995 0.3068785 0.7966504 -0.3661908 0.4808872 0.9049338 -0.1461914 0.3996536 0.7944146 -0.07176244 0.6031215 0.8996532 0.1011219 0.4247334 0.847848 0.1664579 0.5034338 0.8569002 0.3372982 0.3898103 0.8650902 0.3391285 0.369609 0.8001043 0.4764865 0.3644089 0.8620283 0.4737272 0.1802491 0.8163641 0.5534922 0.1649124 0.8708494 0.483621 -0.08793324 0.8327955 0.5525433 -0.03387635 0.8105588 0.5614297 -0.1667073 0.8164923 0.4481363 -0.3640251 0.8730308 0.3364863 -0.3529793 0.775298 0.3027907 -0.5542842 0.8645476 0.1636908 -0.4751452 0.8161983 -0.01470261 -0.5775848 0.848112 -0.04697144 -0.527731 0.8131601 -0.2212812 -0.5383357 0.8532553 -0.2375712 -0.4642365 0.8054465 -0.4241207 -0.4139779 0.8555821 -0.409033 -0.3172875 0.8085298 -0.5389207 -0.2363135 0.8628669 -0.4877404 -0.1325527 0.799777 -0.5986708 -0.0441612 0.8462487 -0.5229025 0.1021586 0.8371573 -0.5385029 0.09582412 0.8307601 -0.4660075 0.3044251 0.8425891 -0.4547846 0.2884694 0.8042858 -0.3536039 0.4775863 0.8764773 -0.2257769 0.4252206 0.7712951 -0.1145602 0.626083 0.8707848 0.04467767 0.4896301 0.8135885 0.1120501 0.5705423 0.8432988 0.3068982 0.4412035 0.8442219 0.3056274 0.4403194 0.779156 0.4905097 0.3902773 0.8832688 0.4491164 0.1346508 0.8291234 0.519461 0.2066757 0.849084 0.5235361 -0.07047194 0.8533524 0.5169697 -0.06732088 0.7681667 0.5662998 -0.2987046 0.874572 0.356157 -0.3290532 0.8123574 0.3746252 -0.4469134 0.8593173 0.1845519 -0.4769848 0.8048697 0.1589428 -0.571771 0.8588633 -0.003376126 -0.5121938 0.8516746 -0.01176321 -0.523939 0.8796008 -0.224474 -0.4194211 0.8640017 -0.2242727 -0.4507803 0.8217936 -0.4784852 -0.3093658 0.8449393 -0.459069 -0.2744695 0.8228877 -0.5570808 -0.1118792 0.8670207 -0.4969234 -0.03663688 0.7957628 -0.596704 0.1034696 0.8728723 -0.447714 0.1940264 0.8139424 -0.5077534 0.282284 0.8153668 -0.3615463 0.4521742 0.8663313 -0.2535334 0.4303384 0.8279672 -0.2422186 0.5057672 0.8285034 -0.05668812 0.5571075 0.8348674 -0.04959988 0.5482121 0.8237112 0.1390932 0.5496845 0.8579431 0.1641368 0.4868192 0.8558618 0.3332659 0.3955181 0.8282611 0.3181916 0.461235 0.7948938 0.4620984 0.3932038 0.8697307 0.4549065 0.1913868 0.7984446 0.5749488 0.1786624 0.7960072 0.6050369 -0.01740723 0.886824 0.4490358 -0.1091332 0.8049484 0.547186 -0.2294461 0.8367752 0.3870931 -0.3872549 0.8666062 0.3300364 -0.3742588 0.8267652 0.2775963 -0.4892848 0.8875921 0.1165028 -0.4456539 0.8403409 0.07767295 -0.5364644 0.8172319 -0.07452642 -0.57147 0.8674225 -0.0345925 -0.4963685 0.8000175 -0.2508718 -0.5450096 0.877031 -0.2846399 -0.3870362 0.7921676 -0.4369807 -0.4260501 0.8228452 -0.5170748 -0.2357107 0.8506934 -0.4886079 -0.1938636 0.8124487 -0.5820475 -0.03388279 0.8707485 -0.4898889 0.04249811 0.7612215 -0.617585 0.1978151 0.8664154 -0.3813971 0.3222743 0.8098593 -0.4185795 0.4109976 0.8385356 -0.2265406 0.4955174 0.864714 -0.1863881 0.4664004 0.7971022 0.002903938 0.6038377 0.8638648 0.1101316 0.4915371 0.8453316 0.1328345 0.5174645 0.8062903 0.3025794 0.5082731 0.8963632 0.3228483 0.3038125 0.838849 0.440817 0.3193948 0.8856524 0.4452421 0.1318305 0.8419947 0.5260544 0.119633 0.8061245 0.5907688 -0.03399503 0.8609982 0.4978893 -0.1038681 0.7693688 0.5879354 -0.2498074 0.8661765 0.3745386 -0.3308461 0.8204122 0.3948769 -0.4135167 0.8666539 0.1599212 -0.4725846 0.8249762 0.1583005 -0.5425451 0.7928466 -0.06168758 -0.6062911 0.8844062 -0.1444199 -0.4438116 0.7811345 -0.2925366 -0.5515898 0.8534222 -0.4165398 -0.3133136 0.8344458 -0.4307405 -0.3437483 0.8551412 -0.5055019 -0.1148982 0.8267075 -0.5520482 -0.1086167 0.8081659 -0.573067 0.1358755 0.8790829 -0.4497179 0.1580102 0.8606683 -0.3606805 0.3593881 0.8683284 -0.3537924 0.3476158 0.787877 -0.2972469 0.5393462 0.8661226 -0.07958585 0.4934552 0.8651483 -0.07924216 0.4952164 0.7752093 0.1120255 0.621692 0.8749514 0.222213 0.4302108 0.8278099 0.2968277 0.4760507 0.8254081 0.4781882 0.3000627 0.876196 0.3946086 0.2767031 0.7854133 0.5974042 0.1619701 0.8741586 0.4855432 -0.009734332 0.8088806 0.5830686 -0.0757851 0.8646739 0.4242473 -0.2689856 0.8294156 0.4912146 -0.2660413 0.8033229 0.4011464 -0.4401748 0.8536649 0.2496213 -0.4571058 0.8383576 0.2466366 -0.4861348 0.8123362 0.03705626 -0.582011 0.8832771 0.06160259 -0.4647868 0.7779392 -0.1223613 -0.6163104 0.8179149 -0.2516366 -0.517392 0.868988 -0.2609074 -0.4204606 0.8049289 -0.4371708 -0.4012121 0.8629754 -0.4228025 -0.276607 0.7792654 -0.5852908 -0.2240094 0.8482701 -0.5189078 -0.1057011 0.7394753 -0.6699325 0.06608271 0.8337234 -0.514896 0.1994678 0.7849871 -0.5492315 0.2866013 0.8679901 -0.3606631 0.3413437 0.8215351 -0.3766983 0.4279936 0.8404677 -0.1699709 0.5145133 0.8438132 -0.165016 0.5106361 0.8474487 0.06116282 0.5273424 0.8074008 0.0249111 0.5894773 0.8164786 0.1738753 0.5505726 0.884266 0.3101888 0.3490794 0.8736483 0.3119133 0.3734285 0.800792 0.4852476 0.351094 0.8659107 0.4747797 0.1574259 0.8444431 0.5131853 0.1534823 0.7770209 0.6207739 -0.1042994 0.8793585 0.4524803 -0.1482912 0.7993893 0.4588167 -0.3878971 0.8525264 0.3598384 -0.3790977 0.7949263 0.280412 -0.5380162 0.8592465 0.1659277 -0.4839043 0.8159537 0.08098548 -0.5724167 0.8584431 -0.02997547 -0.5120324 0.8155184 -0.08854812 -0.5719171 0.826379 -0.2378862 -0.5103998 0.8457996 -0.2438194 -0.4745262 0.8329023 -0.3624292 -0.4182332 0.8881055 -0.3488109 -0.2993324 0.823115 -0.5105409 -0.2486562 0.9032252 -0.4226059 -0.07475572 0.8291866 -0.5582978 -0.02744442 0.805311 -0.5768805 0.1366865 0.8637241 -0.4692338 0.1838493 0.769151 -0.5224935 0.3679775 0.8635286 -0.3337221 0.3780848 0.8148876 -0.3217882 0.4820899 0.8962167 -0.1026116 0.431586 0.7934394 -0.03388965 0.6077051 0.8630256 0.0903843 0.4970086 0.8043481 0.1839227 0.564975 0.8577315 0.3147522 0.4064823 0.8481901 0.3294721 0.4147548 0.7919982 0.5029442 0.346101 0.8723959 0.4579049 0.1710221 0.8075051 0.5752427 0.1305047 0.8536225 0.5197069 -0.03512012 0.7931672 0.6015008 -0.09530246 0.8328712 0.5084138 -0.2187265 0.8860623 0.3993302 -0.2354342 0.8321295 0.3849991 -0.3991692 0.8734163 0.2570729 -0.4135912 0.8222403 0.2666415 -0.5028154 0.7715412 0.1294465 -0.6228707 0.8766205 -0.03518444 -0.4798944 0.8280396 -0.09536999 -0.5524989 0.8410185 -0.2506953 -0.4794161 0.820283 -0.2797309 -0.4988853 0.8919593 -0.3527675 -0.2827783 0.7953495 -0.5356771 -0.2836712 0.8614543 -0.4836694 -0.1547921 0.8098224 -0.5812284 -0.07975834 0.8723277 -0.4830076 0.07581639 0.8283513 -0.546358 0.1238031 0.8107555 -0.4899773 0.3203089 0.8885626 -0.3262187 0.3225493 0.8013742 -0.3597456 0.477894 0.8106094 -0.1469053 0.5668609 0.8707095 -0.06563723 0.4873981 0.796063 0.07057762 0.6010846 0.8831375 0.169072 0.4375876 0.7903754 0.3126056 0.5268629 0.843659 0.4495821 0.2934546 0.8783056 0.3897693 0.2768739 0.7988035 0.5797197 0.160743 0.8540329 0.5193359 0.03029823 0.8024827 0.596207 -0.02363818 0.8461739 0.4931081 -0.2020752 0.8224974 0.5179821 -0.2349311 0.8399898 0.3896621 -0.3775988 0.8268202 0.396943 -0.398503 0.8209472 0.2869427 -0.4936696 0.88919 0.1551017 -0.430447 0.8287156 0.04413908 -0.5579268 0.8869162 -0.01877832 -0.4615486 0.831488 -0.2514912 -0.4953582 0.8352068 -0.2520598 -0.4887693 0.8328272 -0.4266157 -0.3527009 0.8491721 -0.4003574 -0.3444134 0.8096172 -0.5478408 -0.2106908 0.8630256 -0.4950257 -0.1006808 0.812406 -0.5803217 -0.05677533 0.82355 -0.547181 0.1495271 0.8654611 -0.4699969 0.173436 0.7835887 -0.4981309 0.3712878 0.8749876 -0.3086296 0.3730207 0.8131474 -0.3111106 0.4919366 0.8233963 -0.09290426 0.5598101 0.8794279 -0.03145372 0.4749919 0.804609 0.1773996 0.5666868 0.8509736 0.2071001 0.4826527 0.852744 0.3630192 0.3755595 0.8145104 0.3649518 0.4509803 0.8001986 0.5101583 0.3153108 0.8601707 0.4769208 0.180701 0.8116559 0.5685365 0.1340935 0.8529766 0.5216152 -0.01866978 0.8096292 0.5831787 -0.06635791 0.8482518 0.4837875 -0.2154499 0.8349958 0.4971517 -0.2358437 0.8252085 0.4179322 -0.3799525 0.859097 0.3470295 -0.3761954 0.7919462 0.2741672 -0.5455765 0.8585895 0.158553 -0.4875296 0.7970342 0.03666305 -0.6028204 0.8442196 -0.02492302 -0.5354176 0.813291 -0.1455328 -0.5633632 0.8721076 -0.2365921 -0.4283139 0.8084691 -0.3360137 -0.48319 0.8695245 -0.4255561 -0.2506574 0.851035 -0.4582682 -0.2563781 0.796175 -0.6001492 -0.07698291 0.8812044 -0.4712113 0.03793317 0.8107849 -0.5699975 0.1331573 0.832463 -0.4601064 0.308719 0.8406593 -0.4529846 0.2968112 0.814906 -0.3180069 0.4845617 0.8463574 -0.307431 0.4349315 0.8106473 -0.1498513 0.566035 0.8549467 -0.0772795 0.5129269 0.8018257 0.04006141 0.5962136 0.8624765 0.1478262 0.4840264 0.8049355 0.2330219 0.5456919 0.8446091 0.364784 0.3918779 0.8831487 0.3422979 0.3207501 0.8219108 0.5417801 0.1758894 0.8685298 0.4849649 0.1022998 0.8211573 0.5706529 0.00748974 0.8971269 0.4286219 -0.1069889 0.789929 0.5536151 -0.2636715 0.8164333 0.4380642 -0.3762137 0.8751448 0.3369666 -0.3472394 0.8223515 0.2390487 -0.516327 0.8989233 0.09363424 -0.4279832 0.8520921 0.04029327 -0.5218386 0.9107652 -0.1631869 -0.3793109 0.565398 -0.2005711 -0.8000602 0.9363287 -0.2666352 -0.2284612 -0.4423809 -0.809859 -0.385263 -0.05925685 -0.04262214 -0.9973325 0.2086181 -0.4837091 -0.8500024 -0.4506115 -0.5089106 -0.7334571 0.4164002 -0.7773962 -0.4714512 -0.5269963 -0.7742839 -0.3503704 0.5746214 -0.8184195 5.73894e-6 -0.5389024 -0.8273786 0.1582059 0.5650253 -0.7092227 0.4216036 -0.6599289 -0.5555591 0.5058144 0.6105175 -0.3312119 0.7194214 -0.468381 -0.1606379 0.8688008 0.1166049 -0.04458314 0.9921773 -0.09358656 0.3326086 0.9384098 -0.3277478 0.3385888 0.8820085 0.5187263 0.6066328 0.6024281 -0.4371495 0.7031916 0.5607334 -0.04341542 0.9708698 0.2356413 0.2974597 0.9390097 0.1725645 -0.1482704 0.9585098 -0.2434645 0.1820648 0.9373799 -0.2969368 -0.2832124 0.7030883 -0.6522711 0.2829353 0.6295512 -0.7236111 -0.2269039 0.3652333 -0.9028396 0.3213081 0.2401685 -0.9160133 -0.4282132 -0.08298784 -0.8998591 -0.02495008 -0.1659008 -0.9858268 0.4921197 -0.4993914 -0.7130402 -0.4640311 -0.5734353 -0.6751645 0.1088312 -0.9158213 -0.3865584 0.195723 -0.9086815 -0.3687689 -0.1152209 -0.9869162 0.112786 -0.4051347 -0.912256 0.06045639 0.4836718 -0.7615622 0.4313755 -0.5602309 -0.6227856 0.5461496 0.3541635 -0.5443624 0.7604195 -0.1854133 -0.2981075 0.9363514 0.2611778 -0.1968926 0.9449971 -0.5008319 0.07412922 0.8623645 0.5935478 0.2947289 0.7488898 -0.4779539 0.510955 0.7144823 0.3639438 0.7074002 0.6059124 -0.3534353 0.8269724 0.4372645 0.5127239 0.8400288 0.1773865 -0.5253367 0.8493636 0.05101889 0.5004805 0.7928874 -0.3476333 -0.3913975 0.8018708 -0.4514548 0.3735139 0.5781691 -0.7254019 -0.2301772 0.5423752 -0.8079899 0.1629779 0.1516237 -0.9749096 0.009908676 0.1439371 -0.9895372 -0.09740775 -0.4195779 -0.9024778 0.04814952 -0.4402536 -0.8965815 0.025644 -0.803402 -0.5948846 -0.4921679 -0.7303206 -0.4737116 0.5665435 -0.8047783 -0.1770884 -0.5380898 -0.8405951 0.06212323 0.5275571 -0.804845 0.2718605 -0.6053922 -0.6590627 0.4462474 0.6751722 -0.4082788 0.6143705 -0.5403166 -0.3184797 0.7788638 0.3420768 -0.04247426 0.9387116 -0.2046327 0.05690264 0.9771835 0.3344333 0.3082588 0.890579 -0.4728953 0.4155225 0.7769884 0.3746224 0.6476718 0.6634602 -0.2904276 0.7870805 0.5442023 0.4258242 0.839599 0.3372647 -0.4961116 0.85199 0.1672915 0.4113444 0.8998268 -0.1452843 -0.5272821 0.8032321 -0.2771138 0.4589744 0.7436708 -0.4861031 -0.2913302 0.5132999 -0.8072484 0.1764286 0.1557879 -0.971907 -0.3235716 -0.3038429 -0.8960921 0.2794807 -0.395482 -0.8749198 -0.06705892 -0.7959326 -0.6016597 -0.2698652 -0.7769713 -0.5687605 0.3116242 -0.9254814 -0.2153478 -0.5533062 -0.8307084 -0.06144922 0.4354861 -0.8826985 0.1766216 -0.2054135 -0.8400908 0.5020485 -0.5040887 -0.7286591 0.4636277 0.5731796 -0.4238255 0.701311 -0.6014719 -0.2865543 0.7457334 0.5564178 0.03365981 0.8302207 -0.3052592 0.1428798 0.9414894 0.003463268 0.5515823 0.8341133 -0.07229053 0.5407342 0.8380815 0.413073 0.7611646 0.4999995 -0.5418306 0.7685529 0.3402149 0.475358 0.8727271 0.1112753 -0.5111561 0.8556929 -0.08068031 0.566348 0.7286612 -0.3851011 -0.1576327 0.8358911 -0.5257738 -0.302748 0.563672 -0.7685165 0.6551164 0.2960513 -0.6951088 -0.4671906 0.1797081 -0.8657009 0.1376439 -0.2272646 -0.9640566 0.04007667 -0.2152934 -0.9757268 0.2439235 -0.6205003 -0.7453059 -0.1644552 -0.6579861 -0.7348529 -0.1009083 -0.9219673 -0.3738902 0.3253081 -0.897792 -0.2968909 -0.2399638 -0.9475844 0.2109534 0.4419728 -0.8462659 0.2974795 -0.461892 -0.701679 0.5424966 0.4401038 -0.5371796 0.7195463 -0.4305057 -0.388671 0.8146163 0.4408749 -0.1921634 0.8767569 -0.4123911 0.1169459 0.9034696 0.20925 0.245604 0.9465164 -0.1068928 0.6015973 0.7916153 -0.3014957 0.550739 0.7783232 0.4718813 0.7906776 0.3900733 -0.4635905 0.8259091 0.3208706 0.1963343 0.9739879 -0.113139 0.4227131 0.8946943 -0.1443467 -0.4445186 0.8017494 -0.3995013 0.4334605 0.675141 -0.5969059 -0.4158465 0.5349636 -0.7354493 0.4462307 0.360907 -0.8189165 -0.5014291 0.06995767 -0.8623658 0.3854972 -0.1128681 -0.9157798 -0.2326985 -0.3630371 -0.9022503 0.4359272 -0.4924245 -0.7533164 -0.6485736 -0.5508524 -0.5252752 0.6608027 -0.7020312 -0.2655032 -0.539557 -0.8361009 -0.09906423 0.3336492 -0.9371179 0.1024133 -0.4448689 -0.8043657 0.3938115 0.518034 -0.6885909 0.5074282 -0.533266 -0.3652492 0.7630338 0.1981668 -0.3111053 0.9294856 0.0993328 0.1631208 0.9815929 -0.109314 0.1783061 0.9778842 -0.02350658 0.6262877 0.7792375 0.07919847 0.6358188 0.7677643 -0.007141351 0.9668821 0.2551236 -0.1010196 0.9584583 0.2667449 0.07590609 0.9741542 -0.2127488 -0.46757 0.8484616 -0.2479745 0.5924311 0.6415581 -0.4872664 -0.6065855 0.4819427 -0.6322859 0.3811151 0.3535148 -0.8542709 -0.357351 0.1093627 -0.9275452 0.2947601 -0.01824444 -0.9553971 -0.1634414 -0.4461178 -0.8799238 -0.1172161 -0.7617546 -0.6371738 0.169744 -0.9804977 -0.09905183 -0.5191721 -0.8536264 -0.04221683 0.6129904 -0.707949 0.3507863 -0.5582716 -0.6774966 0.4788854 0.3849786 -0.4667296 0.796213 -0.2984188 -0.4208183 0.8566553 0.4320184 -0.01064169 0.901802 -0.5259229 0.09823119 0.8448407 0.5160489 0.3958395 0.7596084 -0.5004951 0.5169759 0.6944354 0.3502038 0.8113747 0.4680048 -0.2794633 0.8645676 0.41764 0.34039 0.9382055 0.06249076 -0.578158 0.8139564 -0.05664157 0.5601376 0.7570366 -0.3363653 -0.418469 0.6878224 -0.593114 0.09100127 0.6750389 -0.7321485 -0.1080058 0.398065 -0.9109771 0.2927044 0.3064823 -0.9057554 -0.2981488 -0.003584325 -0.9545127 0.4494024 -0.1703148 -0.8769438 -0.4434236 -0.3317932 -0.8326397 0.4022023 -0.6285482 -0.6657029 -0.174028 -0.727034 -0.6641805 0.112208 -0.919309 -0.3772006 -0.2171823 -0.9169338 -0.3347601 0.2579466 -0.9642199 0.06118518 -0.1076318 -0.9887912 0.1034771 0.07335877 -0.8779437 0.4731104 -0.09217053 -0.8691697 0.4858485 0.01341509 -0.5371404 0.8433862 0.08884888 -0.5256837 0.8460276 -0.01186549 -0.01739865 0.9997783 -0.2412356 6.83894e-4 0.9704663 0.2876146 0.4061152 0.8673802 -0.4398354 0.4459071 0.7795588 0.5078617 0.7030729 0.4977599 -0.4968883 0.7731702 0.3940937 0.3807222 0.9142274 0.1387041 -0.4466893 0.8937877 -0.04015278 0.4849517 0.8412451 -0.2390156 -0.4764955 0.7049935 -0.5252963 0.3317621 0.6538382 -0.6800217 -0.179035 0.4300649 -0.8848676 0.2795754 0.3158767 -0.906675 -0.4446839 0.07934486 -0.8921664 0.5996149 -0.1948989 -0.7761937 -0.5127621 -0.3214381 -0.7960858 0.4225556 -0.6973413 -0.5789317 -0.2971588 -0.776631 -0.5554646 0.29553 -0.934808 -0.1969677 -0.1537222 -0.9758032 -0.1554914 0.07996219 -0.9581987 0.2747021 -0.3444464 -0.8925823 0.2909528 0.4974434 -0.6100738 0.6167334 -0.471517 -0.5226359 0.7102982 0.2678036 -0.3671182 0.8907893 -0.3462077 -0.1590964 0.9245694 0.3383371 0.01899695 0.9408333 -0.2255285 0.2305671 0.94656 0.3779026 0.3862861 0.8414112 -0.4671571 0.5038768 0.7265484 0.3470581 0.7741277 0.529412 -0.4035363 0.8055198 0.4339313 0.5796549 0.8078199 0.1068984 -0.7145253 0.6954842 -0.07586377 0.6946434 0.6233791 -0.3589836 -0.5552554 0.614264 -0.5606883 0.4476357 0.396372 -0.8015682 -0.2860843 0.3292027 -0.8998786 0.2893598 -0.05539703 -0.9556162 0.1296802 -0.07082164 -0.9890235 -0.3518618 -0.4810209 -0.8030021 0.3459028 -0.5729867 -0.7429924 -0.1397527 -0.8888357 -0.4363948 0.1156917 -0.9111815 -0.3954285 -0.2420818 -0.9702554 -9.13809e-4 -0.2294082 -0.9733296 0.001236319 0.5022744 -0.7956456 0.3386277 -0.467947 -0.7295329 0.4988059 0.4027736 -0.6162472 0.6767666 -0.5694483 -0.3837863 0.7269366 0.5878198 -0.1280626 0.7987917 -0.5334528 0.1009749 0.8397811 0.3083302 0.2830767 0.9081851 -0.2815637 0.6274014 0.7260093 0.3673598 0.6903888 0.6232256 -0.3824277 0.8547175 0.3510087 0.2342326 0.9407712 0.2451218 -0.1122363 0.9855505 -0.1268591 -0.08867543 0.9881443 -0.1253298 0.1630786 0.8298668 -0.5335978 -0.356498 0.7539139 -0.5518361 0.3979776 0.4779382 -0.783064 -0.5413319 0.3523398 -0.7634243 0.5481189 -0.0244745 -0.8360423 -0.6194888 -0.154783 -0.7695947 0.4353638 -0.4292199 -0.7913461 -0.2156588 -0.7309589 -0.6474491 0.008140087 -0.7378765 -0.6748867 -0.180397 -0.938393 -0.2947466 -0.1263225 -0.9491156 -0.2884823 0.4111521 -0.9069779 0.09135168 -0.4001528 -0.8906237 0.2160264 0.3999361 -0.7904288 0.4639757 -0.5399925 -0.6542414 0.5295057 0.6145489 -0.3286716 0.7171504 -0.6378485 -0.204902 0.7424045 0.6436879 0.131505 0.7539048 -0.6203526 0.2768802 0.7338256 0.5735206 0.5970264 0.5609222 -0.4475224 0.7132131 0.5394914 0.3799247 0.9108826 0.1610907 -0.4075146 0.9104301 0.07105678 0.457069 0.8572022 -0.23726 -0.5892708 0.7253266 -0.3558949 0.4943755 0.5989672 -0.6299455 -0.3130981 0.5251536 -0.7913174 0.3890181 0.2880418 -0.8750411 -0.590032 0.1247808 -0.7976792 0.6927359 -0.2300931 -0.6835014 -0.4618714 -0.3887204 -0.7972274 0.115333 -0.7911413 -0.600661 0.1900742 -0.789017 -0.5842295 -0.09567254 -0.9822229 -0.1615088 0.05156689 -0.9782444 0.200945 -0.07037478 -0.7761133 0.6266543 -0.0776177 -0.7763556 0.6254978 0.2937423 -0.4200989 0.8586224 -0.311606 -0.3671599 0.8764106 -0.06708294 0.04317253 0.9968129 0.3233052 0.1006644 0.9409254 -0.1237132 0.5756453 0.8082869 -0.03590798 0.575878 0.8167467 -0.1235001 0.9136231 0.3873508 0.2508552 0.9103786 0.3290629 -0.1761987 0.9454422 -0.2740313 0.435602 0.8705614 -0.2288537 -0.4546498 0.6719825 -0.5845795 0.5839704 0.4487607 -0.6764557 -0.3871932 0.3775311 -0.841161 0.2791827 0.002025783 -0.9602359 0.06491816 0.03824472 -0.9971575 0.02273094 -0.4194331 -0.9075016 0.270186 -0.3889977 -0.8807272 -0.464333 -0.6064993 -0.6454097 0.6466749 -0.6698991 -0.3647558 -0.60425 -0.7616137 -0.2341507 0.5719723 -0.8142732 0.09902989 -0.4503332 -0.8593735 0.2422341 0.3865718 -0.7484062 0.5389346 -0.4015774 -0.6681302 0.6263686 0.4905857 -0.3803702 0.7839925 -0.4013465 -0.3066293 0.8630756 0.09199106 0.1064663 0.9900519 0.3663552 0.1438214 0.9192928 -0.3932976 0.4937793 0.7755638 0.5604897 0.5712161 0.5996362 -0.5520603 0.7456002 0.3732425 0.4771398 0.8648604 0.1560586 -0.3414812 0.939716 0.01801401 0.3599534 0.8970831 -0.2562725 -0.3209336 0.8599245 -0.3969026 0.2976156 0.7675303 -0.5677344 -0.5189329 0.526041 -0.6737874 0.3327252 0.4421699 -0.8329346 0.2853577 0.1078914 -0.952329 -0.4471873 0.02454006 -0.8941036 0.2338401 -0.2604222 -0.9367492 -0.2773554 -0.3745948 -0.8847332 0.4650188 -0.5703356 -0.6771078 -0.2857103 -0.6843787 -0.6708171 -0.2562161 -0.892202 -0.3719262 0.5141276 -0.8336379 -0.2017937 -0.4825235 -0.8746184 0.04705351 0.4741347 -0.8433621 0.2528575 -0.4542648 -0.6983259 0.5531585 -0.448205 -0.699981 0.5560026 0.5407584 -0.3867864 0.7469784 -0.4535817 -0.2064588 0.8669709 0.2064844 -0.07551616 0.9755314 -0.3550131 0.2504754 0.900682 0.09512948 0.3423906 0.9347295 0.4182863 0.6116789 0.6714801 -0.5674102 0.6415068 0.5162507 0.4195842 0.8369138 0.3514604 -0.4505714 0.8823583 0.1357547 0.5768325 0.8059004 -0.133375 -0.3895577 0.8800229 -0.27167 -0.0532298 0.7642745 -0.6426904 0.3630734 0.6661963 -0.6514294 -0.2017301 0.418627 -0.8854697 0.4384788 0.2495729 -0.8633943 -0.5308054 0.05732369 -0.8455529 0.5329458 -0.3127232 -0.7862399 0.1369211 -0.3988672 -0.9067292 -0.4010568 -0.6541491 -0.6412819 0.4835049 -0.7361796 -0.4735638 -0.4573974 -0.8500884 -0.2610313 0.4433675 -0.8935629 -0.07050317 -0.3865773 -0.8918189 0.2349836 0.4221785 -0.8247613 0.3762103 -0.5868295 -0.5815693 0.5633901 0.6848697 -0.3461489 0.6411978 -0.6022244 -0.1428385 0.7854444 0.6421572 0.1241837 0.7564474 -0.3617922 0.2891236 0.8862923 -0.1876693 0.6246964 0.7579807 0.463837 0.6433245 0.6090885 -0.3263156 0.8504702 0.4125756 0.39414 0.8903447 0.2279037 -0.3603796 0.931375 0.05164575 0.4282351 0.8753747 -0.2243518 -0.2633821 0.9097524 -0.3209059 -0.03503572 0.7326683 -0.6796835 0.2498556 0.6757946 -0.6934508 -0.2000546 0.3301565 -0.9224831 0.2253663 0.3579159 -0.9061491 -0.288875 0.03422856 -0.9567548 0.5865775 -0.1763425 -0.790462 -0.5638936 -0.3189165 -0.7617849 0.3949012 -0.6830889 -0.6143636 -0.4233762 -0.7312554 -0.5348067 0.4768293 -0.8401735 -0.2583455 -0.5356152 -0.8441065 -0.02450942 0.2037585 -0.9704746 0.1290807 0.06345969 -0.8709787 0.4872053 -0.06629067 -0.8649618 0.4974403 -0.05251353 -0.5997574 0.7984569 0.360986 -0.4978566 0.7885607 -0.4884828 -0.2129753 0.8461833 0.628638 0.08441442 0.7731033 -0.3046291 0.196207 0.932043 -0.02150183 0.6701564 0.7419084 -0.01671361 0.6706176 0.7416149 0.2997561 0.8878676 0.3490525 -0.3801438 0.8821771 0.2779465 0.1797554 0.970659 -0.1597161 0.2815903 0.9441621 -0.17107 -0.2993009 0.7190474 -0.6272081 0.2026641 0.6849809 -0.699806 -0.1727715 0.3151042 -0.9331986 0.0480386 0.2829307 -0.9579366 0.1828277 -0.1402795 -0.9730857 -0.3980478 -0.1783611 -0.8998585 0.285333 -0.6092889 -0.7398325 -0.1973554 -0.6575175 -0.7271324 0.2449494 -0.8740001 -0.4196709 -0.00216037 -0.9167503 -0.3994549 0.1897923 -0.9811545 -0.03625923 -0.1472505 -0.9890911 0.004034817 0.2034072 -0.8793283 0.4305896 -0.9126691 -0.3124629 -0.2634431 -0.9020383 -0.4283536 -0.05329203 -0.5744172 -0.8181804 0.02501446 -0.9250136 -0.351755 0.1435911 -0.7421687 -0.4955254 0.4512652 -0.8875574 -0.2368393 0.395157 -0.8231262 -0.2082207 0.5283062 -0.8583278 -0.06311792 0.5092048 -0.7833487 0.0169779 0.6213507 -0.8999485 0.109074 0.4221324 -0.8526129 0.321367 0.4120373 -0.8147639 0.3736242 0.4433564 -0.7902311 0.5225121 0.3201814 -0.9016683 0.4148097 0.1221777 -0.8022371 0.59571 0.0393123 -0.8786959 0.4588137 -0.1318472 -0.8414512 0.5261433 -0.1230164 -0.8177855 0.4724726 -0.3286284 -0.8760167 0.3486822 -0.33319 -0.814542 0.3483793 -0.4638462 -0.8596958 0.1725942 -0.4807643 -0.8376816 0.1598433 -0.5222449 -0.81201 0.02992498 -0.5828759 -0.862493 -0.0464797 -0.50393 -0.8044416 -0.1718555 -0.5686296 -0.8695641 -0.2402985 -0.4314107 -0.805132 -0.356697 -0.473846 -0.7885125 -0.518891 -0.3301521 -0.8675424 -0.4432774 -0.2255557 -0.8169454 -0.564869 -0.1162899 -0.8968452 -0.4423423 -0.001421153 -0.8019767 -0.567749 0.1857274 -0.8597416 -0.4671268 0.2064876 -0.7981299 -0.4453005 0.4058279 -0.858947 -0.3335025 0.3885693 -0.8063216 -0.283984 0.5188436 -0.8624637 -0.1468915 0.484334 -0.8184534 -0.1082956 0.564275 -0.814951 0.1009138 0.5706763 -0.8725581 0.1278124 0.4714938 -0.7950989 0.3098762 0.5213392 -0.8760191 0.333825 0.3480684 -0.7912391 0.511879 0.3345453 -0.8705977 0.4681661 0.1512628 -0.8176257 0.5630382 0.1203174 -0.8044931 0.5818901 -0.1191422 -0.8778827 0.4560616 -0.1460481 -0.7963227 0.495912 -0.3463258 -0.8752478 0.3374155 -0.3465432 -0.7565242 0.3022006 -0.5799536 -0.884828 0.1138901 -0.4517838 -0.7713783 -0.001745939 -0.6363745 -0.8761956 -0.1769049 -0.4483146 -0.8208907 -0.262965 -0.5069398 -0.8879002 -0.3451693 -0.3041239 -0.8317428 -0.464362 -0.3042564 -0.8497952 -0.5006483 -0.164923 -0.8393279 -0.5196307 -0.1597265 -0.7959755 -0.6051424 0.01503074 -0.889975 -0.4457771 0.09605991 -0.7346851 -0.5911812 0.3327803 -0.8771084 -0.3077816 0.368716 -0.8696787 -0.3196077 0.376178 -0.8008221 -0.1340354 0.5837112 -0.8665275 -0.06761622 0.4945281 -0.8130165 0.146641 0.5634719 -0.8480159 0.1074828 0.5189572 -0.8646036 0.3267366 0.3817119 -0.8540472 0.3289119 0.403014 -0.8009757 0.5098014 0.3139115 -0.8583606 0.4563884 0.2343644 -0.7857649 0.6132146 0.08087956 -0.8704625 0.4913227 -0.02995413 -0.8064123 0.5736255 -0.1437116 -0.8587029 0.4540724 -0.237587 -0.8185765 0.4815002 -0.3131934 -0.8065421 0.3946239 -0.4401837 -0.8265852 0.3618778 -0.4310471 -0.7472934 0.2255679 -0.6250374 -0.8432227 0.06904697 -0.5331116 -0.8025406 0.01202851 -0.5964764 -0.8381146 -0.1501421 -0.5244249 -0.870571 -0.161222 -0.4648802 -0.7848201 -0.3693016 -0.4976683 -0.8623045 -0.3812835 -0.3332475 -0.8001191 -0.5079807 -0.3190066 -0.8696084 -0.4686576 -0.1553755 -0.7891393 -0.6114346 -0.05836951 -0.8608973 -0.5061422 0.05173039 -0.7975058 -0.5781514 0.1724115 -0.8634257 -0.449404 0.2291994 -0.8030946 -0.4609192 0.3776144 -0.8596552 -0.3089595 0.4068623 -0.8319177 -0.3092614 0.4607282 -0.7829768 -0.1525541 0.6030545 -0.8784515 -0.03292459 0.476696 -0.8283936 0.03949266 0.5587525 -0.8141431 0.2233601 0.5359863 -0.8654946 0.2407936 0.4392465 -0.8016087 0.3947697 0.4489772 -0.8632259 0.3937993 0.3158532 -0.7953301 0.5468339 0.2615777 -0.8579148 0.500656 0.1154376 -0.8262686 0.5563207 0.08824688 -0.795144 0.5936558 -0.1237699 -0.8875079 0.4291764 -0.167742 -0.8152547 0.490299 -0.3081666 -0.8322919 0.3367022 -0.4403657 -0.8901846 0.229084 -0.3938173 -0.7853355 0.1859698 -0.5904774 -0.8971607 -0.1091647 -0.4280023 -0.7945448 -0.09576773 -0.5996057 -0.8481819 -0.2722406 -0.4543927 -0.8853182 -0.2628434 -0.3835692 -0.8224889 -0.4606093 -0.3336934 -0.8552424 -0.475249 -0.206637 -0.8602064 -0.4657136 -0.2077401 -0.783362 -0.6215343 -0.006260931 -0.8766432 -0.467594 0.1133693 -0.8059359 -0.5513481 0.2155985 -0.8003956 -0.4612324 0.3829251 -0.8706547 -0.3313369 0.3635606 -0.8173883 -0.3007388 0.491358 -0.8633064 -0.1560022 0.4799641 -0.8152239 -0.1181335 0.5669695 -0.8394624 0.1004636 0.5340505 -0.8349328 0.09862238 0.5414433 -0.8207284 0.2751899 0.5006749 -0.8511932 0.2772964 0.4456197 -0.8146526 0.4387657 0.3792437 -0.8712695 0.4152907 0.2615783 -0.8149331 0.5281492 0.2386263 -0.808712 0.5798977 0.09850794 -0.9048972 0.4251458 -0.02030074 -0.8420776 0.5276995 -0.1115295 -0.7778421 0.5631415 -0.2789868 -0.8652122 0.4054974 -0.2949236 -0.8023897 0.400893 -0.4421037 -0.8651817 0.2466063 -0.4366304 -0.7970345 0.2163076 -0.5638679 -0.8294677 -0.005544602 -0.5585274 -0.8502473 -0.01864969 -0.5260529 -0.8183807 -0.2044801 -0.5370671 -0.8630581 -0.2335768 -0.4478532 -0.8279156 -0.3064533 -0.4697257 -0.8028923 -0.488452 -0.3417292 -0.8769225 -0.4267094 -0.2211926 -0.7965736 -0.5843905 -0.154785 -0.837787 -0.5458772 -0.01144909 -0.8601362 -0.510008 0.007589459 -0.8088998 -0.5540757 0.1966757 -0.8759825 -0.4162597 0.2436858 -0.8084198 -0.462368 0.3642436 -0.7952954 -0.3069893 0.5227456 -0.8799008 -0.1898801 0.4355688 -0.7801287 -0.04043513 0.6243111 -0.8594756 0.04343217 0.5093286 -0.7791441 0.2079857 0.5913344 -0.8801156 0.2706743 0.3900411 -0.8142449 0.395312 0.4251278 -0.8112313 0.5029867 0.298175 -0.9027534 0.4024773 0.1518176 -0.8339865 0.5459277 0.08018404 -0.8834686 0.4644544 -0.06136405 -0.8320143 0.5356994 -0.1441473 -0.842458 0.4591847 -0.2818049 -0.8515438 0.4511147 -0.2671496 -0.7917355 0.3986601 -0.4628446 -0.8593379 0.2256098 -0.4589539 -0.8410759 0.2498975 -0.4797319 -0.8202282 0.05103325 -0.5697556 -0.8392191 0.03411 -0.5427228 -0.8013651 -0.1691843 -0.5737514 -0.8264527 -0.1779273 -0.5341517 -0.7532218 -0.430351 -0.4974485 -0.8561396 -0.4034948 -0.3228266 -0.7759369 -0.5732114 -0.2633455 -0.8716867 -0.4816104 -0.09062933 -0.8054652 -0.5921595 -0.02393943 -0.8414385 -0.5113691 0.1745934 -0.8597044 -0.4790651 0.177215 -0.7760905 -0.4760789 0.4135609 -0.8792256 -0.2587655 0.4000036 -0.8413895 -0.313372 0.4402971 -0.8128715 -0.1283186 0.5681324 -0.8684687 -0.05449038 0.4927402 -0.8037151 0.07341998 0.5904672 -0.869781 0.180477 0.4592485 -0.8114358 0.2745992 0.5159142 -0.7976245 0.4557694 0.3950566 -0.8918012 0.3671137 0.2644204 -0.8598238 0.5043823 0.07938212 -0.8391756 0.539503 0.06870824 -0.8034682 0.5787002 -0.1398029 -0.8774261 0.4569388 -0.1460498 -0.8597963 0.3746112 -0.3470113 -0.8285517 0.3917933 -0.4000003 -0.8323218 0.2235518 -0.5072132 -0.8380479 0.2162471 -0.500912 -0.8041442 0.02651005 -0.5938429 -0.881696 -0.04060268 -0.4700678 -0.7733057 -0.2458391 -0.5844328 -0.8605487 -0.3141241 -0.4009763 -0.8155884 -0.3986952 -0.419354 -0.8486748 -0.4726857 -0.2373169 -0.8110535 -0.5401567 -0.2245507 -0.8359839 -0.5486055 -0.01276773 -0.8428639 -0.5380638 -0.008241653 -0.8295982 -0.5089221 0.2297071 -0.8356559 -0.5026276 0.221461 -0.8112441 -0.4726204 0.3442574 -0.8947228 -0.2694883 0.3561564 -0.8534947 -0.2738015 0.4433732 -0.8480491 -0.06577634 0.5258198 -0.8742805 -0.04654824 0.4831842 -0.870175 0.1677539 0.4633078 -0.8143772 0.2394335 0.5286412 -0.8349069 0.4001436 0.3779093 -0.8610413 0.3832966 0.3342031 -0.7966321 0.5619274 0.2227438 -0.8596736 0.4961829 0.1215065 -0.829333 0.5550383 0.06433862 -0.861512 0.4999442 -0.08861625 -0.8261755 0.5471956 -0.1342052 -0.7884851 0.522094 -0.3251295 -0.8698127 0.3730321 -0.3229134 -0.8402149 0.3678192 -0.398432 -0.8835886 0.1963515 -0.4251087 -0.845619 0.1818943 -0.5018397 -0.7726238 0.06115972 -0.6319115 -0.881646 -0.06151872 -0.4678843 -0.803253 -0.171512 -0.5704106 -0.8065637 -0.3743117 -0.4575434 -0.8730661 -0.3433451 -0.3462222 -0.7972289 -0.5290155 -0.290807 -0.8617035 -0.4851217 -0.1487419 -0.8263037 -0.5512371 -0.1155854 -0.8236006 -0.5642208 0.05776876 -0.8690084 -0.4850944 0.09750914 -0.7846458 -0.5563786 0.2734482 -0.8603318 -0.3920762 0.3257384 -0.7995398 -0.4027829 0.4455356 -0.863451 -0.2339934 0.4468776 -0.78623 -0.1713116 0.5937126 -0.8595032 -0.03385835 0.510008 -0.8033757 0.05767524 0.5926729 -0.8637025 0.167187 0.4754645 -0.8168805 0.246716 0.5213804 -0.8481361 0.3959151 0.3520177 -0.8672508 0.3828759 0.3182489 -0.8130586 0.5373562 0.2240181 -0.8736493 0.4722887 0.1169635 -0.769486 0.6386623 -0.001306056 -0.8551343 0.481661 -0.1916983 -0.8732085 0.448691 -0.1902197 -0.7861928 0.4398756 -0.4340628 -0.8775107 0.2554132 -0.4058809 -0.7981649 0.2203568 -0.5606923 -0.8575275 0.01373434 -0.5142548 -0.8389198 -0.003326714 -0.544245 -0.8670814 -0.2514983 -0.4300217 -0.886377 -0.243847 -0.3935409 -0.8183833 -0.4689111 -0.3322216 -0.8729389 -0.4296382 -0.23106 -0.8090687 -0.5664774 -0.156561 -0.8452858 -0.5334658 -0.03010237 -0.8068611 -0.5903674 0.02101153 -0.8649513 -0.4795523 0.1479494 -0.8040494 -0.5348455 0.2597014 -0.8481515 -0.3914268 0.3569653 -0.860363 -0.3854722 0.3334467 -0.7883748 -0.3125397 0.5298907 -0.8621063 -0.1135067 0.4938512 -0.8356812 -0.1375086 0.5317223 -0.8530675 0.09386694 0.5132882 -0.8275202 0.1230763 0.5477797 -0.7951127 0.255135 0.5501837 -0.8626641 0.3530915 0.3621289 -0.8443503 0.3653731 0.3918865 -0.8068366 0.5333711 0.2540275 -0.8692259 0.4659013 0.1654758 -0.8254537 0.5641381 0.01935279 -0.863518 0.5035399 -0.02800679 -0.7994092 0.574059 -0.177204 -0.8651632 0.4426957 -0.2356122 -0.8099739 0.4609814 -0.3625446 -0.8693162 0.2964893 -0.3954535 -0.7580154 0.2898623 -0.5842881 -0.8648396 0.03216898 -0.5010166 -0.8575234 0.03789603 -0.5130475 -0.8117409 -0.1918986 -0.5515901 -0.8542326 -0.2049048 -0.4778085 -0.8178734 -0.3588637 -0.4497778 -0.8652987 -0.3520581 -0.3568101 -0.8018525 -0.5185164 -0.29694 -0.8625527 -0.4730122 -0.1796178 -0.8030642 -0.5890337 -0.0901513 -0.8577069 -0.5141337 0.002329647 -0.7931485 -0.595063 0.129675 -0.8757917 -0.438476 0.2018115 -0.7696567 -0.5026888 0.3936149 -0.8695582 -0.2533959 0.4238622 -0.8368775 -0.2526074 0.4856187 -0.795657 -0.1112621 0.5954416 -0.8894935 0.02097856 0.456466 -0.8262974 0.1066922 0.5530365 -0.7792821 0.3211414 0.5381335 -0.9106884 0.2632347 0.3183621 -0.7654083 0.5792617 0.2803676 -0.8706055 0.4742386 0.1309353 -0.8216557 0.5677297 0.05064761 -0.8756869 0.4762384 -0.07980883 -0.8028344 0.5668658 -0.1847164 -0.8576456 0.3883184 -0.3371245 -0.8358983 0.3999446 -0.3759231 -0.8183854 0.2242811 -0.5290967 -0.8451862 0.2274523 -0.4836586 -0.7912107 -0.009112358 -0.6114758 -0.8858729 -0.0924552 -0.4546223 -0.8027108 -0.2209071 -0.5539453 -0.8519871 -0.3911514 -0.3480208 -0.8463979 -0.4010462 -0.3503891 -0.7887932 -0.585514 -0.1870258 -0.7932474 -0.5808944 -0.1825382 -0.7720916 -0.6343386 0.03858894 -0.87839 -0.4631551 0.1179764 -0.8159733 -0.483659 0.3166413 -0.8428732 -0.4403472 0.3092882 -0.8303592 -0.3287572 0.4499138 -0.8699237 -0.2566851 0.4211241 -0.7837706 -0.1597579 0.6001508 -0.8763043 0.03658902 0.4803665 -0.8316863 0.01524668 0.5550366 -0.8158868 0.2440678 0.5241754 -0.8752539 0.2492232 0.41451 -0.7791214 0.4700238 0.414786 -0.8810563 0.4380865 0.1783822 -0.847135 0.4841194 0.2190677 -0.7972615 0.6034674 -0.01419061 -0.8879833 0.4505057 -0.09236031 -0.7965747 0.5558269 -0.2377503 -0.8076167 0.4416896 -0.3907247 -0.8972967 0.2600938 -0.3566648 -0.8513696 0.3326884 -0.4055716 -0.7988798 0.1376112 -0.5855376 -0.8646441 0.05767482 -0.4990634 -0.8177762 -0.03698021 -0.5743471 -0.8518527 -0.1872113 -0.4891819 -0.8570114 -0.1792532 -0.4831147 -0.7746194 -0.421063 -0.4718802 -0.8797435 -0.3890847 -0.2732486 -0.8081848 -0.5258951 -0.2650887 -0.8398872 -0.5427506 -0.003373742 -0.857731 -0.5140401 0.007776796 -0.7944872 -0.5636301 0.2260777 -0.8718255 -0.4233218 0.2464123 -0.7990332 -0.4231864 0.4271526 -0.8572354 -0.2690492 0.4390447 -0.8248018 -0.2639225 0.500047 -0.800855 -0.03934299 0.5975646 -0.8861811 0.02412885 0.4627104 -0.7591887 0.274322 0.5902373 -0.8839929 0.2835079 0.3717256 -0.8123692 0.4306687 0.3931679 -0.809893 0.5458787 0.2146859 -0.8711531 0.4717143 0.1363008 -0.8503337 0.5179388 0.09312427 -0.8661244 0.4848597 -0.1214072 -0.838766 0.5342519 -0.1051029 -0.8144458 0.4909459 -0.3092737 -0.8244688 0.4833686 -0.2942893 -0.8419967 0.292294 -0.4534376 -0.8361073 0.2924931 -0.4640824 -0.8253759 0.1080865 -0.5541407 -0.8484559 0.123442 -0.5146697 -0.809718 -4.34275e-4 -0.5868191 -0.863239 -0.09391093 -0.4959831 -0.8137543 -0.1999941 -0.5457163 -0.8656828 -0.2838998 -0.4123036 -0.8064336 -0.3845816 -0.4491792 -0.8844823 -0.4487811 -0.1276191 -0.8294609 -0.5283362 -0.1812613 -0.8216561 -0.5671533 0.05673199 -0.872358 -0.4801697 0.09180861 -0.7990923 -0.5242918 0.2942275 -0.8658586 -0.4077013 0.2899461 -0.8293404 -0.3033589 0.4692205 -0.8373016 -0.30214 0.4556727 -0.8751775 -0.07983756 0.4771693 -0.837885 -0.05040436 0.5435149 -0.8186972 0.1313599 0.5589989 -0.8466543 0.1468418 0.5114822 -0.8093215 0.2962011 0.5072118 -0.8597097 0.3057328 0.4091783 -0.804282 0.4626883 0.3728942 -0.8632971 0.4445058 0.2390246 -0.7938955 0.5743777 0.1995502 -0.8414556 0.5402799 -0.007090747 -0.8770008 0.479759 -0.02647745 -0.7629519 0.5519692 -0.3365032 -0.8712372 0.3826944 -0.3073934 -0.814309 0.3448876 -0.4668549 -0.8832218 0.1754117 -0.434914 -0.81222 0.1389924 -0.5665509 -0.7777261 -0.0297482 -0.6278992 -0.8857243 -0.1186565 -0.4487907 -0.8831349 -0.1235432 -0.4525595 -0.8198221 -0.3611617 -0.444358 -0.9008224 -0.3358085 -0.2752299 -0.8271222 -0.4958093 -0.2646548 -0.8284413 -0.5477283 -0.1169569 -0.851075 -0.5174101 -0.08920937 -0.7904506 -0.6094739 0.0610696 -0.8719115 -0.464173 0.1559292 -0.8065883 -0.5283994 0.2649706 -0.8049626 -0.4046893 0.4338916 -0.8877017 -0.2656452 0.3760564 -0.7918384 -0.2142447 0.5719189 -0.852303 0.01571834 0.5228123 -0.8665624 0.0236923 0.4985063 -0.7692698 0.2625839 0.5824721 -0.898346 0.3179136 0.3031588 -0.8165103 0.3842799 0.4308596 -0.8336894 0.5062344 0.2206552 -0.8705291 0.4628934 0.1670598 -0.8058867 0.5916517 0.02224522 -0.8743777 0.480053 -0.07080155 -0.7934256 0.5763224 -0.1957756 -0.823558 0.4472568 -0.3488749 -0.8624987 0.3821025 -0.3318036 -0.8071741 0.2926223 -0.5126816 -0.8851639 0.1885005 -0.4253854 -0.839531 9.05933e-4 -0.5433113 -0.901992 -0.04085952 -0.4298151 -0.7904472 -0.2579291 -0.555577 -0.8456738 -0.3652527 -0.3891356 -0.8440541 -0.3662768 -0.3916813 -0.816411 -0.5010151 -0.2871533 -0.8663035 -0.4593836 -0.1961764 -0.8036639 -0.586666 -0.09973657 -0.854226 -0.5191631 0.02771008 -0.8114222 -0.5773319 0.09100574 -0.8508763 -0.4759029 0.2225443 -0.8133375 -0.5063503 0.2865163 -0.8748795 -0.2981823 0.3816717 -0.864005 -0.3008317 0.4037273 -0.7596836 -0.1526995 0.6321106 -0.8842875 -0.002777457 0.4669347 -0.8001154 0.09994399 0.5914614 -0.8114028 0.3192223 0.4896148 -0.867867 0.3038098 0.3930732 -0.8081898 0.4690843 0.3560749 -0.8600959 0.4557964 0.2290957 -0.8125067 0.5482031 0.1982581 -0.8258436 0.563859 -0.006755709 -0.8756662 0.4809806 -0.04320383 -0.7893757 0.5766992 -0.2104854 -0.8176174 0.4740952 -0.3267042 -0.8797163 0.3623079 -0.3079489 -0.7869492 0.3242209 -0.5249685 -0.8617397 0.180261 -0.4742477 -0.8047915 0.1144859 -0.582412 -0.8821923 -0.02518612 -0.4702156 -0.8132968 -0.1329616 -0.5664535 -0.7894436 -0.3026407 -0.5340295 -0.8576811 -0.2909928 -0.4239178 -0.7984439 -0.4769718 -0.3674035 -0.8623517 -0.4353485 -0.258498 -0.810562 -0.5705327 -0.1322187 -0.8656581 -0.497175 -0.05876308 -0.8078745 -0.5851621 0.07017415 -0.8580768 -0.4923088 0.14607 -0.7807742 -0.5571628 0.2827746 -0.8075177 -0.3816926 0.4496954 -0.8153073 -0.3795271 0.4373023 -0.7740711 -0.2264249 0.591224 -0.871908 -0.07872205 0.4833006 -0.8171279 -0.02559643 0.5758879 -0.8156034 0.1884813 0.5470522 -0.8669434 0.1949269 0.4587078 -0.7479778 0.3964713 0.5322967 -0.9316963 0.2886497 0.2205069 -0.6338091 0.715924 0.2928121 -0.8192566 0.5617614 0.1150778 -0.6541138 0.03884601 0.755398 0.6776676 0.3138284 0.6650403 -0.5202164 0.5312686 0.6686768 0.6305681 0.7210685 0.2871309 -0.7030098 0.7097733 0.04471302 0.730094 -0.6833467 4.00064e-4 -0.6392677 -0.7294105 0.24351 -0.8594464 0.245581 -0.4483769 -0.7110881 -0.3392252 -0.6158572 0.6964066 -0.5928046 -0.4044758 -0.8265313 -0.4936237 0.2705214 -0.7315423 0.1604205 0.6626547 0.7371429 0.4073571 0.5391482 -0.7116818 0.1993197 -0.6736326 0.5905357 -0.05977499 -0.8047947 -0.7087104 -0.1797727 -0.6822106 0.8306246 -0.4054672 -0.3816534 0.831214 0.5537568 -0.049362 0.743683 0.6341328 0.2116864 -0.6230737 0.7766772 0.09247624 0.6835196 0.7091706 -0.172853 -0.1552675 0.7950738 0.5863019 0.4947803 0.8630276 0.1018623 -0.490244 0.8349661 -0.2499853 0.1409429 0.6864604 -0.7133774 0.7209779 -0.4226492 0.5491436 -0.61086 -0.3940725 0.6867002 0.530937 -0.122581 0.8384986 -0.5272476 -0.07238751 0.8466228 0.6057167 0.2260991 0.7628806 -0.7350691 0.2816182 0.6167372 0.8095554 0.2790293 -0.5164909 -0.6841106 -0.03462666 -0.7285559 0.6795892 -0.3067606 -0.6663756 -0.6580384 -0.4011517 -0.6372305 0.6579338 -0.6161519 -0.4329895 -0.8305529 0.2535756 -0.4958642 -0.6799685 0.3892888 0.6213672 0.6167518 0.6235248 0.480452 -0.7469576 0.5986095 0.2893458 0.60554 -0.7756626 0.1779575 -0.6780521 -0.6138078 0.4043332 -0.8255341 0.233021 0.5139988 0.8209368 0.562482 -0.0983715 -0.6840266 -0.4904846 -0.5399374 0.6167442 -0.6986919 -0.3625692 -0.7447313 -0.6430962 -0.178333 -0.7120367 -0.3704886 0.5964411 0.5780331 -0.07982832 0.8120993 -0.829527 0.4793047 -0.2866222 0.6525049 -0.3680215 -0.662418 -0.5948994 -0.5235691 -0.6098937 0.6815755 -0.6374701 -0.3592865 -0.6590388 0.3509342 -0.6652166 0.7086021 0.06772691 -0.7023504 -0.6815699 -0.01505136 -0.7315982 0.6085796 -0.3231312 -0.7247186 0.1288147 0.6681242 0.7328144 0.2500476 0.8944224 0.3707895 0.1719391 0.9849423 0.01804584 -0.2509847 0.9259649 -0.2821274 0.07370716 0.7609313 -0.6446325 -0.7300567 0.543273 -0.4145742 -0.8379192 0.4782041 -0.2630824 -0.29756 0.8100759 -0.5052079 -0.3077306 0.8578898 -0.4114936 -0.6830869 0.693592 -0.2287412 -0.6678551 0.7253273 -0.166943 0.05879718 0.9557 -0.28841 -0.7404614 0.6653071 -0.09530758 -0.2442362 0.9516568 -0.1862745 -0.9874014 0.1579223 0.009955704 -0.6157703 0.7822063 0.09476459 -0.04383939 0.9960699 0.0769599 -0.4318739 0.8893244 0.15029 -0.9124653 0.3948473 0.1072506 -0.8272421 0.4852991 0.2831174 -0.4254868 0.850041 0.3104696 -0.8901502 0.3756198 0.2579582 -0.754437 0.568008 0.3289255 -0.9827487 0.1324754 0.129056 -0.4251213 0.7186502 0.5502853 -0.05130875 0.8748593 0.481652 -0.3750041 0.6330525 0.6772124 -0.8554888 0.2652685 0.4447151 -0.6629751 0.4250491 0.616277 -0.7182096 0.3729319 0.5874494 -0.4888706 0.52475 0.696881 0.1446801 0.378978 0.9140259 -0.9252467 0.08719444 0.3692097 -0.4134339 0.220155 0.8835181 -0.7942326 0.06119585 0.6045245 -0.4789677 0.1573827 0.8636092 -0.8196803 -0.04438668 0.5710992 -0.6930114 -0.1510696 0.7049207 -0.1859235 -0.03378576 0.9819832 0.173642 -0.112313 0.9783836 -0.6814132 -0.1735598 0.7110226 -0.4251585 -0.2870796 0.8583855 -0.8664111 -0.2351059 0.4405192 -0.9947667 -0.0586912 0.08363443 -0.3362859 -0.434745 0.8354093 -0.7211608 -0.3998917 0.5656975 -0.1539776 -0.4963043 0.8543845 -0.7029107 -0.4837434 0.5214489 -0.196313 -0.6783285 0.7080478 -0.9175052 -0.3141953 0.2438558 -0.5829584 -0.5836331 0.5652716 0.09689778 -0.7402977 0.6652595 -0.8892565 -0.4086551 0.2054852 -0.9476957 -0.3027787 0.1009852 -0.6530452 -0.6832162 0.3267223 -0.4644466 -0.7767652 0.4253529 -0.3672093 -0.8187797 0.441313 -0.1146569 -0.9089691 0.4007858 -0.8250176 -0.5647088 0.02120965 -0.5921716 -0.8003667 0.09352117 -0.729225 -0.6837757 0.02611249 -0.2664192 -0.9563897 0.1197485 -0.9329378 -0.357127 -0.04568725 0.1042042 -0.9942898 0.02300858 -0.4439947 -0.8829874 -0.1523221 -0.9986552 -0.04758071 -0.0205934 -0.456431 -0.8537443 -0.2505826 -0.780099 -0.5661708 -0.2662635 -0.7591466 -0.5895525 -0.2759065 -0.9206524 -0.3264024 -0.2141509 -0.3007252 -0.8980954 -0.3209194 -0.0593881 -0.8436835 -0.533546 -0.3320068 -0.7617139 -0.5563844 -0.8526687 -0.3657118 -0.3731102 -0.6007101 -0.5316887 -0.5970382 -0.4408788 -0.6324854 -0.6368581 -0.9108479 -0.2184271 -0.3502082 -0.7852146 -0.2665411 -0.5589221 -0.01041197 -0.5587172 -0.8292929 -0.6250873 -0.37462 -0.6847816 -0.4067471 -0.4036572 -0.8195229 -0.8096448 -0.1647506 -0.563323 -0.3075948 -0.3046712 -0.9014216 -0.9834917 0.005631089 -0.1808662 -0.4415856 -0.1204985 -0.8890908 -0.4660415 -0.1440274 -0.8729613 -0.9899488 -0.007950901 -0.1412028 -0.7216219 0.0814076 -0.6874843 -0.4708374 -0.06550663 -0.8797847 -0.06835305 0.1131777 -0.9912209 -0.6674113 0.1590521 -0.7275058 -0.2536425 0.1968157 -0.9470634 -0.7109603 0.2319661 -0.6638729 -0.8305114 0.2369491 -0.5040894 -0.1703124 0.4118847 -0.8951786 -0.1010009 0.4433604 -0.8906349 -0.8471242 0.3009554 -0.4379574 -0.719122 0.457488 -0.5230376 -0.3810017 0.579088 -0.72076 -0.9999782 0.005841314 -0.003115892 -0.9998096 0.01951479 -1.09581e-4 -0.9999289 -0.007319033 -0.009422957 -0.9999428 -0.01038908 -0.002541184 -0.9997099 -0.007303535 0.02295416 -0.9999986 5.73066e-4 -0.001584708 -0.9999784 0.004881858 -0.004417717 -0.9999889 -0.004694938 -3.10908e-4 -0.9999995 2.3305e-4 -0.001005113 -0.5432253 -0.4841437 0.6859382 -0.789086 -0.3366935 0.5137906 -0.408117 -0.4973769 0.7655435 -0.8356189 -0.2788904 0.4732455 -0.3220667 -0.3844601 0.8651378 -0.5340679 -0.2844854 0.7961404 -0.7947018 -0.2277289 0.5626621 -0.4698119 -0.2213031 0.8545769 -0.9134263 -0.1013336 0.3941879 -0.6150676 -0.1385595 0.7762044 -0.7859842 -0.08712196 0.6120774 -0.2978127 -0.01430624 0.9545172 -0.5119575 0.0387178 0.8581378 -0.7968718 0.02017694 0.6038115 -0.8197852 0.02813559 0.5719797 -0.3367324 0.1964349 0.9208825 -0.9912635 0.02405542 0.1296846 -0.5212568 0.2342713 0.8206146 -0.7662737 0.1596698 0.6223586 -0.4534183 0.3175504 0.8328107 -0.9007721 0.1467372 0.4087516 -0.8498674 0.2364354 0.4709819 -0.6199048 0.3543917 0.700089 -0.4786601 0.4554369 0.7506411 -0.9281924 0.2166671 0.3025134 -0.5586789 0.5548027 0.6164999 -0.5384795 0.5606425 0.6290627 -0.9889931 0.1040548 0.1051918 -0.6782869 0.5947526 0.4315047 -0.5389789 0.7062926 0.4589691 -0.9008131 0.3580018 0.2457042 -0.4943275 0.7851052 0.3731627 -0.6824945 0.6886249 0.2449434 -0.891383 0.4278926 0.1494809 -0.4944555 0.850789 0.1779663 -0.9396517 0.3295938 0.091775 -0.6350169 0.7678975 0.08418524 -0.8565286 0.5137836 0.04883933 -0.3843507 0.9230328 -0.01688987 -0.5257005 0.8449086 -0.098836 -0.9250441 0.3787406 -0.02914029 -0.4556306 0.8707694 -0.1848284 -0.898567 0.4361798 -0.04821449 -0.7330892 0.6447629 -0.2164741 -0.7595821 0.5969197 -0.2583063 -0.6622546 0.6670139 -0.3413376 -0.6388291 0.6407621 -0.4258185 -0.7218195 0.5441901 -0.4275907 -0.4217277 0.6122615 -0.6687912 -0.9204169 0.2761965 -0.2766739 -0.7372813 0.3684988 -0.5662376 -0.740673 0.3875544 -0.5488216 -0.5677602 0.4049536 -0.7167015 -0.9423087 0.1388975 -0.3045685 -0.5193303 0.2594453 -0.8142384 -0.6140854 0.2551801 -0.7468482 -0.7865577 0.1837019 -0.5895596 -0.8542591 0.04848164 -0.5175819 -0.4714908 0.07075405 -0.8790281 -0.7116958 0.01998746 -0.7022035 -0.9886485 -0.004617452 -0.1501765 -0.5733966 -0.1331744 -0.8083816 -0.6623317 -0.1061695 -0.7416502 -0.8866827 -0.09974187 -0.4514924 -0.417883 -0.3149865 -0.8521487 -0.8916772 -0.162849 -0.4223649 -0.5821985 -0.3287043 -0.7436386 -0.4981182 -0.4680262 -0.7299519 -0.9690353 -0.1204423 -0.2155559 -0.9157699 -0.2385885 -0.3231734 -0.6076422 -0.4711731 -0.6393489 -0.5237648 -0.5764101 -0.6272336 -0.9196246 -0.2951383 -0.2591985 -0.6634485 -0.6108842 -0.4320377 -0.7238909 -0.5373402 -0.432721 -0.9886482 -0.1259632 -0.08190202 -0.7487627 -0.6001672 -0.281343 -0.7286556 -0.625218 -0.2795776 -0.7297242 -0.6608704 -0.1753649 -0.4967634 -0.8549227 -0.1494433 -0.9446031 -0.3273786 -0.02341419 -0.5989083 -0.7998636 -0.03908008 -0.889742 -0.456459 0.002072453 -0.3277457 -0.9420347 0.07178682 -0.6292936 -0.7629072 0.1481962 -0.8383679 -0.5365684 0.09609264 -0.4398662 -0.8533067 0.2799742 -0.507429 -0.805044 0.3072785 -0.9046306 -0.411217 0.1120009 -0.7998153 -0.5500494 0.2402942 -0.3149197 -0.8334419 0.454093 -0.8266773 -0.4922487 0.2725728 -0.6496771 -0.6303085 0.4250069 -0.6196908 -0.589182 0.5185055 -0.6995653 -0.5511624 0.4547839 -0.9816453 -0.1488076 0.1192849 -0.4847777 -0.5742421 0.6597247 -0.8931552 -0.3182378 0.3178029 -0.004794597 -0.5494016 0.8355448 0.005152821 -0.4631356 0.8862725 -0.003390073 -0.4040293 0.9147398 0.004796564 -0.253382 0.9673544 -0.001190483 -0.2221938 0.9750019 -2.86368e-4 -0.01780974 0.9998414 0.00174129 -0.02773445 0.9996138 0.005619168 0.07310897 0.9973081 0.006561696 0.290395 0.9568845 -0.004509091 0.2100555 0.9776791 -0.003567755 0.3789782 0.9253988 0.004091918 0.4950113 0.868877 -7.21986e-4 0.5218288 0.85305 2.00794e-4 0.662437 0.7491177 -0.002789497 0.6747639 0.7380285 0.006061851 0.7767196 0.6298173 -0.004071235 0.8214282 0.5702974 0.006323158 0.8982994 0.4393386 -6.31286e-4 0.9163912 0.4002836 0.002120077 0.9672582 0.2537859 -0.00551337 0.9767159 0.214466 0.001908123 0.9995968 0.0283277 -0.003835678 0.9999927 2.71622e-4 0.002904117 0.9757246 -0.2189817 -0.001700401 0.9679775 -0.2510312 0.002556681 0.9527418 -0.3037706 -0.00721836 0.8914303 -0.4531006 0.002050697 0.9084713 -0.4179422 0.001725912 0.7711182 -0.6366898 -0.005228102 0.803112 -0.5958052 -0.007284224 0.6844089 -0.7290621 0.006143808 0.6249355 -0.7806524 0.002560317 0.5330113 -0.8461044 -0.004047393 0.4968332 -0.8678367 0.002833247 0.3647113 -0.9311164 -0.006457626 0.30318 -0.9529115 0.005391359 0.1871254 -0.9823212 0.001354813 0.03249448 -0.9994711 -0.00288093 0.06088805 -0.9981405 -0.005661547 -0.1031278 -0.9946521 0.01225531 -0.2171327 -0.9760652 -0.002276539 -0.3615479 -0.9323508 -7.1047e-4 -0.3556751 -0.9346094 -0.00149089 -0.5395951 -0.8419235 -2.70383e-5 -0.5457095 -0.8379745 0.002956509 -0.685126 -0.7284187 -7.49745e-4 -0.7007603 -0.7133965 0.002810001 -0.8085175 -0.5884655 -4.07179e-4 -0.8192507 -0.5734356 0.001948297 -0.8799602 -0.4750436 -0.007945477 -0.9182415 -0.3959414 9.74853e-4 -0.9521157 -0.3057366 -0.009261727 -0.9795508 -0.2009841 0.007936537 -0.9952664 -0.09686064 -0.01036471 -0.9965829 0.08194744 0.004456043 -0.9847524 0.173905 -0.005147159 -0.9585624 0.2848362 0.005939006 -0.9284156 0.3714962 -0.005145013 -0.8693973 0.4940869 2.53187e-4 -0.8502314 0.5264092 0.004306554 -0.7184513 0.6955639 -0.003575861 -0.7644538 0.6446685 9.83334e-4 -0.6910012 0.722853 0.004415571 -0.6487084 0.7610243 -0.9999963 0.002422511 -0.001293718 -0.999177 -0.03043735 -0.02681577 -0.9997773 0.02019703 -0.0061329 -0.9999482 -0.005189955 -0.008766233 -0.9996824 0.02221053 -0.01190471 -0.9999363 0.003791987 -0.01063454 -0.999838 -0.01776832 0.002876698 -0.9997252 0.0230785 0.004127919 -0.9999829 -0.00585854 -1.24275e-4 -0.9999354 0.01134359 7.24961e-4 -0.9999486 0.006171226 -0.008042573 -0.9999828 -0.004906117 -0.003200232 -0.9999756 0.006079614 -0.003438234 -0.9999962 -0.002779364 1.1752e-5 -0.9999637 0.004082441 -0.007486343 -0.9999986 0.001648664 1.91802e-4 -0.9999775 -0.004276812 0.005170881 -0.9999977 0.001841127 0.001135349 -0.9999791 -0.004440069 0.00469315 -0.9999307 -0.01123255 0.003531694 -0.9998842 0.01023483 -0.01127356 -0.9998855 0.01118862 0.01019871 -0.9999444 -0.006838738 0.008029282 -0.9998133 -0.01874923 0.004675745 -0.9997988 -0.01217931 0.01593917 -0.9998216 -0.004585087 0.01832562 -0.999979 -0.002341806 0.006051242 -0.9995951 0.02254462 0.01735973 0.7526099 -0.4517157 0.4790941 0.4576311 -0.6745751 0.5792428 0.4967651 -0.7188133 0.4863456 0.4416797 -0.7577133 0.4804059 0.9351871 -0.2892362 0.2043714 0.909032 -0.3501408 0.2259697 0.5056027 -0.7844212 0.3592346 0.4322899 -0.8327202 0.3459806 0.8611163 -0.4624817 0.2111625 0.9124075 -0.394073 0.11054 0.5857653 -0.7903296 0.1796061 0.3639901 -0.919766 0.1467714 0.8271421 -0.5507029 0.1120823 0.5281888 -0.8491073 0.005786299 0.7990269 -0.6012797 -0.004331946 0.8083769 -0.588665 -7.10462e-4 0.2643284 -0.9606418 -0.08542913 0.5681676 -0.8058216 -0.1668447 0.7918601 -0.602836 -0.09770584 0.4717431 -0.8395732 -0.2693979 0.9110162 -0.3970809 -0.1112496 0.6195346 -0.7216714 -0.308816 0.733653 -0.6153979 -0.2881645 0.7859449 -0.5331568 -0.3131049 0.7042487 -0.5708339 -0.4221168 0.7630476 -0.4538212 -0.4602225 0.388247 -0.6157334 -0.6856652 0.7640714 -0.4526888 -0.459639 0.2553628 -0.51611 -0.8175699 0.9916265 -0.0798816 -0.1014689 0.7858044 -0.3093068 -0.5355752 0.5805972 -0.3686718 -0.7259394 0.6774325 -0.3275046 -0.6586546 0.7470033 -0.2195398 -0.6275256 0.4527403 -0.1804817 -0.8731854 0.9205902 -0.08481043 -0.3812099 0.674768 -0.04216665 -0.7368244 0.640206 0.0135855 -0.7680832 0.7453368 0.08296328 -0.6615059 0.727997 0.1205113 -0.6749055 0.6322942 0.1706276 -0.7557052 0.5243092 0.3119586 -0.7923269 0.6574089 0.346287 -0.6692526 0.965647 0.1063669 -0.2370911 0.7551578 0.3254285 -0.5690633 0.6583256 0.4947739 -0.5672797 0.7124273 0.4937723 -0.4986343 0.5457029 0.66547 -0.5092723 0.6267986 0.6091909 -0.4858087 0.3845191 0.8145925 -0.434263 0.5810259 0.7559317 -0.3016229 0.911598 0.3684324 -0.1823368 0.7365573 0.6374309 -0.2261977 0.6350139 0.7657192 -0.1021349 0.7373816 0.6670526 -0.1063457 0.9307463 0.3652389 -0.0176658 0.3291746 0.9436485 0.03423118 0.9936673 0.112246 0.005124211 0.565096 0.8092689 0.1604694 0.578859 0.7994245 0.1607565 0.750797 0.629003 0.2016414 0.8640018 0.477006 0.1611409 0.4776284 0.7842465 0.3960158 0.9584382 0.2382683 0.1569223 0.6334762 0.6196135 0.4634512 0.7621042 0.4987739 0.4128219 0.7122536 0.4366761 0.5495534 0.717253 0.4349845 0.5443682 0.6213361 0.387222 0.6811759 0.6784124 0.320635 0.6610218 0.3306708 0.2609262 0.9069589 0.9196912 0.1138783 0.375766 0.5129278 0.1583907 0.8436928 0.7326441 0.09092783 0.6745108 0.7365597 0.04369294 0.6749599 0.5819361 -0.04607468 0.8119284 0.6602883 -0.1149771 0.7421587 0.9083662 -0.09146851 0.4080495 0.9625407 -0.0442838 0.2674969 0.3716603 -0.2489975 0.8943539 0.5105639 -0.3302003 0.7939096 0.3614538 -0.4324622 0.8260313 0.8486005 -0.204656 0.4878455 0.5481306 -0.4692795 0.6923363 0.9080553 -0.2193108 0.3568449 0.7592586 -0.3930622 0.5186797 0.01988869 -0.2934352 -0.9557721 0.02613967 -0.2871621 -0.9575253 0.02011555 0.6851741 -0.7281016 0.0209158 0.6857509 -0.7275358 0.02508193 0.9719048 0.2340343 0.02106523 0.9729365 0.2301111 0.7458937 0.1928763 0.6375275 0.7346849 0.1946353 0.6498886 0.7447814 0.6493114 0.1539334 0.7347502 0.6604278 0.154846 0.7369583 0.4721078 -0.4837424 0.546997 0.5664181 -0.6164129 0.7417868 -0.2052137 -0.6384668 0.5470969 -0.2316761 -0.8043702 0.7461545 -0.644982 -0.1650811 0.546187 -0.8176045 -0.182216 0.7390641 -0.4522667 0.4992386 0.5454512 -0.5813329 0.6037675 0.02505582 -0.9718136 -0.2344157 0.02045255 -0.9729967 -0.2299115 0.0195257 -0.6814178 0.7316343 0.02547127 -0.6858348 0.7273114 0.02498537 0.2883032 0.9572132 0.02614504 0.2871371 0.9575327 0.9999679 -0.007607638 -0.002540051 0.9998657 0.0116294 0.01154756 0.9999661 -0.006293296 -0.005322277 0.9999895 -0.001743853 -0.004248559 0.9999799 -4.9929e-4 0.00633955 0.9999577 2.57032e-4 -0.009192287 0.9999855 0.005250513 0.001243531 0.9999553 0.009372115 0.001235365 0.9999574 0.006766915 0.006282031 0.9999802 0.005898296 0.002248108 0.9999865 0.004845976 -0.001852214 0.9999865 0.004861772 -0.001837015 0.9999701 0.005112171 -0.005796074 0.9999818 -0.006008684 -5.1755e-4 0.9999984 5.56705e-4 0.001754224 0.9999602 -0.003545641 0.008196115 0.9999677 -0.001904785 0.007807314 0.999975 -0.001533269 -0.006906807 0.9999783 1.76824e-4 -0.006604373 0.9999961 -0.001857876 0.002107799 0.9999684 -0.002018392 0.007701635 0.9999769 -0.006695747 -0.001253545 0.9999957 -0.002399027 0.001766085 0.9999758 -0.006812334 -0.001458346 0.9999713 -0.002706944 -0.007082879 0.9971879 -0.07313477 0.01636284 0.9996954 0.001138508 -0.02465122 0.9976745 -0.06475454 0.02127218 0.9968802 -0.0684762 -0.03925329 0.9969376 -0.06761437 -0.03929036 0.9998356 -0.005333125 0.01733475 0.999567 -0.004765808 0.02903854 0.9993795 -0.02800858 0.02136445 0.9972917 -0.03857356 0.06262111 0.9999043 -0.007702291 -0.01149183 0.99736 -0.02784311 0.06706702 0.9998436 0.01111465 0.01376193 0.9992364 8.44592e-4 0.03906351 0.9997632 -0.005778491 0.02098518 0.9999915 0.002787828 0.00303775 0.9946481 0.06856405 0.07729262 0.9964836 0.03470492 0.07626473 0.9999163 0.00605905 0.01143175 0.9953431 0.08492124 0.04561263 0.8982152 0.2294728 0.3749023 0.6210978 0.5739827 0.5336492 0.868983 0.4257316 0.2522324 0.690428 0.6775277 0.2535063 0.8854552 0.4643178 0.01944303 0.7948572 0.6041028 -0.05711376 0.8558861 0.471884 -0.2116234 0.8300032 0.5004666 -0.2462274 0.8834639 0.3019103 -0.3582485 0.7602953 0.3312571 -0.5587665 0.8740743 0.09273576 -0.4768586 0.7775436 0.03172129 -0.6280284 0.836136 -0.1783885 -0.5187044 0.8634666 -0.1889259 -0.4676882 0.7990118 -0.3719992 -0.4724371 0.8774228 -0.3723946 -0.3024095 0.7666882 -0.5668612 -0.3014262 0.8039877 -0.5807612 -0.1277505 0.8897382 -0.4563881 -0.008714914 0.8077429 -0.5837619 0.08230102 0.8373456 -0.4662747 0.2853775 0.8532146 -0.4365433 0.2854031 0.8276286 -0.3776997 0.4151791 0.8933531 -0.2309803 0.3854457 0.7937127 -0.1877458 0.5785945 0.8801765 -0.01704365 0.4743405 0.8065919 0.08432829 0.5850628 0.8557711 0.1669834 0.4896654 0.7930814 0.2811889 0.5403285 0.8664965 0.3533973 0.3525539 0.8079387 0.4516005 0.3785395 0.8059348 0.5508962 0.2167548 0.8763437 0.4713395 0.09930223 0.8250873 0.5638352 0.03634524 0.8561882 0.4997557 -0.1310951 0.8280346 0.5355399 -0.1659995 0.839254 0.4292076 -0.3338168 0.8126887 0.4495216 -0.3707662 0.8174026 0.2726803 -0.5074431 0.8814762 0.1700144 -0.4405618 0.7735447 0.02095109 -0.6333953 0.8779855 -0.1274509 -0.4614085 0.8268286 -0.1890674 -0.5297246 0.8037838 -0.4090415 -0.4319918 0.8484447 -0.3985248 -0.3483098 0.809978 -0.501421 -0.3041587 0.8643134 -0.477221 -0.1588163 0.8149928 -0.5667657 -0.1206792 0.7716171 -0.6349526 0.03798013 0.8542937 -0.5116648 0.09155052 0.7819948 -0.5413022 0.3089923 0.8414138 -0.4346792 0.321056 0.7902339 -0.3887491 0.4737136 0.8743114 -0.2177772 0.4337658 0.8062783 -0.1745592 0.5651941 0.881529 0.01498001 0.4718923 0.8047805 0.07820296 0.5883985 0.8150873 0.2755241 0.5096266 0.8822823 0.2919413 0.3692536 0.7973654 0.4537106 0.3979385 0.8616195 0.4775011 0.1720595 0.845111 0.5063329 0.1715061 0.8424261 0.5243647 -0.1239358 0.8743294 0.4615296 -0.1501289 0.7693843 0.5444739 -0.3340601 0.8757216 0.3125946 -0.3679625 0.8033089 0.3308294 -0.4952242 0.8105825 0.1173077 -0.5737551 0.8768227 0.03549432 -0.479502 0.7895036 -0.1022753 -0.6051645 0.877935 -0.2418193 -0.4132235 0.8107202 -0.3412498 -0.4756906 0.8263143 -0.469335 -0.311335 0.8792418 -0.4245172 -0.2161459 0.7774663 -0.6123895 -0.1432671 0.8172458 -0.5753419 0.03303009 0.8752739 -0.4755572 0.08798301 0.7956165 -0.5580205 0.2358131 0.8776637 -0.3669896 0.3082615 0.8021003 -0.4062439 0.4377228 0.8297543 -0.212206 0.5162137 0.8634884 -0.1585727 0.478793 0.8116492 -0.03932428 0.5828202 0.8579125 0.05197978 0.5111597 0.8019126 0.1407972 0.5806137 0.858298 0.2696542 0.4365904 0.8388051 0.3030114 0.4523164 0.8387194 0.4327272 0.3306009 0.8388968 0.432433 0.3305355 0.79217 0.5600439 0.2425232 0.8662326 0.4909317 0.09288346 0.8122336 0.5829095 0.02221125 0.8567582 0.5036557 -0.1108891 0.8155953 0.5563035 -0.1591573 0.8189309 0.4471467 -0.359739 0.8755783 0.336272 -0.3468196 0.7623839 0.3266832 -0.5586135 0.8566448 0.06512409 -0.5117797 0.8444148 0.07906991 -0.5298224 0.8161461 -0.09852933 -0.5693835 0.8703266 -0.1667771 -0.4633757 0.8119069 -0.2798959 -0.512314 0.8515972 -0.3916104 -0.3484588 0.8639289 -0.3838595 -0.3260043 0.7905501 -0.576877 -0.2055327 0.8819367 -0.4688318 -0.04883104 0.7938172 -0.6068979 0.03910464 0.8681493 -0.456175 0.195502 0.8080778 -0.5200821 0.2766315 0.8057439 -0.4072827 0.4299973 0.8417549 -0.3426481 0.4171822 0.7859634 -0.2886925 0.5467343 0.8452239 -0.05675917 0.5313897 0.8404032 -0.05307388 0.5393568 0.8270636 0.1072451 0.5517829 0.8242344 0.1098396 0.5554934 0.8307905 0.3204341 0.4550923 0.8598257 0.2810819 0.4262545 0.7794733 0.5137063 0.3585068 0.8637287 0.4779966 0.1596622 0.844161 0.5132469 0.1548221 0.8060787 0.5906754 -0.03660345 0.888389 0.4494437 -0.0936228 0.8478372 0.4254205 -0.3165276 0.8384496 0.4344996 -0.3289567 0.8197327 0.2874586 -0.4953845 0.8701453 0.2692151 -0.4127596 0.7837509 0.1754105 -0.59579 0.8627705 -0.02460134 -0.5049969 0.8318492 -0.0522679 -0.5525352 0.8193647 -0.2349367 -0.5229209 0.8700373 -0.2533192 -0.4229239 0.7811419 -0.4304422 -0.4522578 0.8398475 -0.4873661 -0.2390201 0.8866677 -0.4332053 -0.1617204 0.7615324 -0.6452258 -0.06125521 0.8699004 -0.4687864 0.1533387 0.8236656 -0.5270261 0.209329 0.8266317 -0.4133694 0.3818454 0.8445785 -0.380852 0.3763498 0.8608613 -0.1683355 0.4801884 0.8177512 -0.2413327 0.5225339 0.7525732 -0.03666806 0.6574869 0.8962819 0.1403734 0.420683 0.8193382 0.2380733 0.521542 0.7984926 0.437712 0.413301 0.8748602 0.3987262 0.2750217 0.791422 0.5666528 0.229251 0.8727757 0.4872357 0.02939647 0.8109503 0.5848626 -0.01719033 0.7845097 0.5956513 -0.1724649 0.8740897 0.421821 -0.2409029 0.8174477 0.4639315 -0.3413898 0.8463858 0.2935963 -0.4443336 0.8448202 0.2966783 -0.445265 0.8143215 0.2021139 -0.5440869 0.862665 0.0915085 -0.4974287 0.7982922 0.0216552 -0.601881 0.8681176 -0.1415509 -0.4757471 0.8048801 -0.2204146 -0.5509859 0.8424867 -0.3822773 -0.379579 0.8307551 -0.4008374 -0.3862323 0.8333613 -0.5101354 -0.2127696 0.8368626 -0.5042116 -0.2131475 0.8463902 -0.5322392 0.01858079 0.7971211 -0.6017424 0.05004227 0.8442095 -0.4896831 0.217993 0.8983237 -0.3746092 0.2295266 0.8176168 -0.4020961 0.4120942 0.8375454 -0.2463682 0.4876684 0.845714 -0.2453016 0.4739145 0.8116711 -0.04416257 0.5824429 0.8405464 -0.05820304 0.538604 0.8082289 0.184475 0.5592272 0.8237072 0.1902264 0.5341539 0.8264092 0.351724 0.4397024 0.9001266 0.322204 0.2931841 0.7852059 0.5784116 0.2211149 0.8754457 0.4764865 0.0809673 0.7951177 0.6058948 -0.02606838 0.8700332 0.4633459 -0.1683829 0.8104911 0.5336477 -0.2415046 0.7979199 0.4125555 -0.4394565 0.8874933 0.2492151 -0.3876177 0.7811306 0.1910926 -0.5944061 0.8728551 0.0110023 -0.4878556 0.7988779 -0.05545282 -0.5989317 0.8135775 -0.2631702 -0.5184912 0.8649198 -0.2702729 -0.422926 0.8043289 -0.4376928 -0.401846 0.8672246 -0.4154626 -0.274431 0.8110655 -0.5598606 -0.1694962 0.8677174 -0.4916403 -0.07318705 0.7880015 -0.6149633 0.02956116 0.8635901 -0.4710626 0.1797557 0.8325144 -0.505559 0.2265613 0.8137162 -0.4135495 0.408464 0.8448572 -0.3932982 0.3626745 0.8058262 -0.2628551 0.5306144 0.8266754 -0.2296556 0.5136791 0.7554962 -0.069202 0.651488 0.8270689 0.08618712 0.5554538 0.8037131 0.1226823 0.5822322 0.838933 0.1993188 0.5064224 0.7577589 0.3357847 0.5595088 0.8229959 0.4547719 0.3403828 0.8094358 0.4772762 0.3420835 0.8481681 0.505748 0.1575753 0.8269751 0.5420657 0.1492552 0.8383583 0.5427434 -0.05084466 0.846074 0.5312531 -0.04392057 0.801441 0.5600806 -0.2097671 0.8564528 0.4521073 -0.249174 0.8044322 0.444826 -0.3937243 0.8682194 0.3039404 -0.3921932 0.7685735 0.2896194 -0.5704519 0.8528682 0.1040416 -0.5116555 0.7445077 0.002105295 -0.6676107 0.8253104 -0.208293 -0.5248588 0.8134906 -0.221958 -0.5375571 0.810914 -0.4092469 -0.418253 0.8279697 -0.403403 -0.3895283 0.7507221 -0.6075308 -0.2594664 0.8610247 -0.5004689 -0.0903747 0.79225 -0.6033667 0.09104192 0.809356 -0.5789178 0.0989803 0.8602791 -0.4223384 0.2855704 0.8206232 -0.4550359 0.3457168 0.8595002 -0.2281951 0.457369 0.8465306 -0.230992 0.4796131 0.8027917 -0.04163259 0.5948044 0.8729896 0.04833006 0.4853385 0.7938556 0.1768454 0.5818238 0.8700045 0.2624908 0.4173617 0.8073794 0.3926522 0.4404124 0.8618741 0.4116902 0.2961151 0.806316 0.5233163 0.2756716 0.8643036 0.4877827 0.1226683 0.8078132 0.5863147 0.06060564 0.8654331 0.4961079 -0.07001805 0.8035485 0.569121 -0.1743886 0.8719476 0.41044 -0.2669204 0.8093602 0.4603493 -0.3647117 0.7922278 0.3329597 -0.5113837 0.8705871 0.1997461 -0.449644 0.8186963 0.1165471 -0.5622751 0.8629034 0.01062428 -0.5052574 0.7949266 -0.07499969 -0.6020523 0.8472402 -0.2188912 -0.4840154 0.8353051 -0.2156388 -0.5057325 0.871221 -0.3778759 -0.3133428 0.8347712 -0.3819132 -0.39661 0.7791564 -0.5451669 -0.3093678 0.860303 -0.5076026 -0.04710012 0.8431251 -0.5334991 -0.06722295 0.8005446 -0.5807765 0.1477404 0.8988566 -0.3987746 0.1817572 0.7730645 -0.4330447 0.4635122 0.8780024 -0.2411122 0.4134935 0.7999657 -0.1999073 0.5657669 0.8661556 -0.01395314 0.4995797 0.8025873 0.02960079 0.5957999 0.8056955 0.2581504 0.5331165 0.8780632 0.2664258 0.3975203 0.8015244 0.4648001 0.3761909 0.872632 0.4257748 0.2392266 0.7722693 0.6106664 0.1751765 0.8570503 0.5129442 -0.048509 0.8854902 0.4588367 -0.07332187 0.7816221 0.5740073 -0.2440954 0.8033063 0.4679417 -0.368415 0.8846348 0.3060138 -0.3518193 0.770893 0.3034765 -0.5600234 0.865968 0.06863552 -0.4953671 0.895184 0.08620268 -0.437281 0.8173077 -0.1267803 -0.5620809 0.8446142 -0.2457042 -0.4756641 0.8654022 -0.2184145 -0.4509704 0.802385 -0.4300062 -0.4138516 0.8635973 -0.4247511 -0.2716363 0.7982789 -0.54058 -0.2655637 0.8141577 -0.578808 -0.04613697 0.8647217 -0.5021732 0.008856534 0.8090258 -0.5672354 0.1540174 0.8781843 -0.4311497 0.2071289 0.8157174 -0.4341659 0.382237 0.8822649 -0.3033946 0.3599454 0.8436419 -0.2243205 0.4877999 0.8898323 -0.1427178 0.4333937 0.8119167 0.02243477 0.5833423 0.8492128 0.09760093 0.5189526 0.8214463 0.1349243 0.5540951 0.877879 0.2922788 0.3793439 0.8388423 0.3043805 0.4513272 0.8437985 0.5005813 0.1934492 0.8624203 0.4783957 0.1654352 0.7903818 0.6123893 0.01661342 0.8701012 0.4829562 -0.09837287 0.7974491 0.5653504 -0.210841 0.854689 0.4002233 -0.330648 0.8294284 0.417771 -0.3708317 0.8150212 0.2809256 -0.5067754 0.8744046 0.1649452 -0.4562999 0.8046776 0.1125659 -0.5829435 0.8339204 -0.08732944 -0.5449316 0.8571677 -0.1036127 -0.5045077 0.7951357 -0.3081534 -0.5223032 0.8602525 -0.3139638 -0.4017367 0.807646 -0.4979982 -0.3157619 0.8567454 -0.4605581 -0.2321072 0.7897723 -0.6022644 -0.1163499 0.8721016 -0.4891651 0.01250863 0.7893199 -0.597523 0.1412099 0.8926246 -0.4017228 0.2045489 0.8613901 -0.3439859 0.3737393 0.8383825 -0.3945937 0.3760458 0.8682872 -0.1700382 0.466009 0.8028842 -0.2636312 0.5346734 0.8657313 0.01905387 0.5001462 0.8357534 0.03843814 0.5477581 0.7947089 0.2377804 0.5584787 0.8511899 0.2478441 0.4626544 0.8154546 0.4454244 0.3696361 0.8472421 0.4290301 0.3132314 0.8138123 0.5509575 0.1848115 0.8632027 0.4934676 0.1066348 0.7737492 0.6323282 -0.03838402 0.8698878 0.4543992 -0.1918765 0.8417316 0.5070296 -0.1854972 0.8280363 0.4230166 -0.3679849 0.8646323 0.3462284 -0.3640565 0.8125943 0.2789657 -0.5117312 0.8570265 0.1855666 -0.4806982 0.8022378 0.09666681 -0.5891267 0.8739382 -0.03759706 -0.4845809 0.7793931 -0.132724 -0.612316 0.8083451 -0.2646935 -0.5258474 0.8983506 -0.2841786 -0.3349758 0.83577 -0.4156298 -0.3588042 0.8450143 -0.4892594 -0.2158147 0.8608714 -0.4618439 -0.2135432 0.7553721 -0.655055 -0.01777338 0.873808 -0.4762894 0.09802037 0.7765024 -0.5684829 0.271793 0.8684326 -0.3895072 0.3067721 0.8104435 -0.4024919 0.4256545 0.8811952 -0.1095694 0.45988 0.802449 -0.201668 0.5616101 0.8873383 0.06316655 0.4567721 0.8552652 0.03455108 0.5170375 0.7963719 0.3273622 0.5085526 0.8774145 0.3212157 0.3563207 0.8300598 0.429841 0.3552994 0.8827627 0.4491979 0.1376638 0.862799 0.4873465 0.1344302 0.8544276 0.5137218 -0.07773965 0.8835794 0.4541253 -0.1142701 0.7988412 0.5493906 -0.2449954 0.8137609 0.4227989 -0.3987911 0.8504527 0.3595536 -0.3839942 0.8067103 0.2447687 -0.5378727 0.8207604 0.2228285 -0.5260227 0.7467783 0.02840071 -0.6644665 0.8431931 -0.08934438 -0.5301349 0.8081456 -0.2511821 -0.5327366 0.828047 -0.253803 -0.4999221 0.8462097 -0.3601268 -0.3927314 0.888059 -0.3488941 -0.2993727 0.8181688 -0.5202352 -0.2448577 0.8498683 -0.5117574 -0.1258111 0.8228693 -0.5573151 -0.1108419 0.8382632 -0.5371309 0.09383672 0.83453 -0.5423345 0.09712457 0.805639 -0.4986571 0.3198237 0.8872739 -0.331525 0.320681 0.8051494 -0.3567853 0.4737496 0.8057326 -0.1780292 0.5648899 0.8832904 -0.07249015 0.4631882 0.7655608 0.1225047 0.6315928 0.8792944 0.1919035 0.4359065 0.7971065 0.3412559 0.4981623 0.8455202 0.4453489 0.2945509 0.8513356 0.4409178 0.2842872 0.8086119 0.5632725 0.1699151 0.8593879 0.5056212 0.07615596 0.8263036 0.5631774 0.007329344 0.8953762 0.4250259 -0.13287 0.8439509 0.4964549 -0.2031734 0.8378418 0.3899821 -0.3820146 0.8718423 0.3151257 -0.3749493 0.7925803 0.2937944 -0.5343233 0.8930466 0.1165979 -0.4345949 0.8288435 -0.01898765 -0.5591583 0.8703553 -0.09986925 -0.4821909 0.7745679 -0.2144857 -0.595013 0.8526732 -0.3549916 -0.3833138 0.8259919 -0.398462 -0.3987048 0.8192512 -0.5122725 -0.2576904 0.8537967 -0.4810214 -0.199122 0.8083923 -0.5831929 -0.07992553 0.8829072 -0.4661281 0.05656611 0.8192583 -0.5594844 0.1256703 0.7773857 -0.5509898 0.3034499 0.849272 -0.4152835 0.3260012 0.7555045 -0.4302355 0.4940752 0.814487 -0.1899991 0.5481891 0.803225 -0.1853526 0.5661045 0.873844 0.007406055 0.48615 0.802295 0.08375996 0.5910221 0.8721428 0.2311697 0.4311932 0.8380393 0.2801835 0.4681746 0.7659217 0.48666 0.4201501 0.8832107 0.4311681 0.1844804 0.8292224 0.529205 0.1798125 0.7902029 0.6125535 -0.01891601 0.8804365 0.4552586 -0.1325564 0.8354806 0.5149761 -0.1917597 0.7828781 0.4818643 -0.3935848 0.8731172 0.2998892 -0.3843607 0.8200124 0.2968932 -0.48932 0.8527835 0.08323115 -0.5155901 0.8401007 0.09877055 -0.5333623 0.8264307 -0.1221168 -0.5496361 0.8177303 -0.1142011 -0.5641589 0.7485346 -0.3268444 -0.5769479 0.8364388 -0.3977804 -0.3770157 0.7934266 -0.4679228 -0.3892588 0.8312078 -0.5257715 -0.1807155 0.8582047 -0.4955117 -0.1339889 0.8046604 -0.5905436 -0.06148314 0.8595032 -0.5020987 0.09566181 0.7899621 -0.5829424 0.1901 0.8636372 -0.4174209 0.2826493 0.7980215 -0.4592265 0.3902214 0.8442646 -0.2256159 0.4861222 0.7731388 -0.3117986 0.5523025 0.817928 0.01960074 0.5749866 0.822868 0.01639401 0.567996 0.8203743 0.1952517 0.5374597 0.8144208 0.1924601 0.5474284 0.7117992 0.5214352 0.470582 0.8645582 0.3276077 0.3810675 0.7776637 0.5617343 0.2823011 0.8672388 0.4724924 0.1569967 0.7916479 0.6106027 -0.02140229 0.8752335 0.4698122 -0.1150774 0.8178976 0.5355978 -0.2101876 0.849447 0.3859867 -0.3597973 0.8344277 0.4136705 -0.3641527 0.8248079 0.2443777 -0.509874 0.8443724 0.2422346 -0.4778679 0.8119061 0.08572107 -0.5774604 0.8766874 -0.03515946 -0.4797738 0.8195868 -0.09348285 -0.5652774 0.7880938 -0.3311758 -0.5188746 0.8934355 -0.3050543 -0.3297196 0.785422 -0.5349463 -0.3113594 0.8751209 -0.475121 -0.09177863 0.7658797 -0.641765 -0.03957432 0.8846045 -0.4399999 0.1545153 0.8080212 -0.5237444 0.2698028 0.8687471 -0.3478167 0.3525651 0.810587 -0.3702767 0.4537003 0.842316 -0.1651292 0.5130654 0.8332942 -0.1630949 0.5282245 0.8003367 0.005190432 0.5995286 0.847481 0.05591559 0.5278727 0.8069482 0.219732 0.5482267 0.8627063 0.2524303 0.4381973 0.8132771 0.3824729 0.4385144 0.8922606 0.3600071 0.2725179 0.8088722 0.5630759 0.1693267 0.8671693 0.4902006 0.08786815 0.8132303 0.5819355 -0.00277096 0.882037 0.425058 -0.2033138 0.8550407 0.4774333 -0.2023932 0.8759564 0.3206499 -0.3603944 0.8583589 0.3315472 -0.3915312 0.8384627 0.2184356 -0.4992659 0.8981686 0.09417945 -0.4294455 0.8638733 0.05729657 -0.50044 0.8937381 -0.1678179 -0.4160161 0.5657177 -0.2004224 -0.7998715 0.9325636 -0.266493 -0.2435299 -0.06712698 -0.9063546 -0.4171516 0.4086116 0.2525026 -0.8770855 -0.2778439 -0.2800048 -0.9189125 0.05298143 -0.3324652 -0.9416263 -0.171302 -0.709068 -0.6840162 0.3307825 -0.7335629 -0.5936905 -0.3664665 -0.9232571 -0.1153201 0.07749933 -0.9952721 -0.05854344 0.1903296 -0.8553916 0.4817469 0.1611059 -0.8591254 0.4857451 -0.4823258 -0.5296019 0.6977705 0.6160942 -0.3066726 0.7255204 -0.4093662 -0.1275826 0.9034058 0.411176 0.1359527 0.9013608 -0.2686687 0.2344096 0.9342748 0.159834 0.6493446 0.7435085 0.2958501 0.6434769 0.7059817 -0.3956862 0.875108 0.2786011 0.329756 0.9287936 0.1691254 -0.182933 0.9679317 -0.1721737 0.395053 0.8727295 -0.2868387 -0.4980234 0.730549 -0.4671948 0.4884552 0.5651214 -0.6648679 -0.5206938 0.3931612 -0.7578274 0.4257941 0.2245159 -0.8765228 -0.2898358 -0.1471647 -0.9456944 -0.4413939 -0.1505051 -0.8846015 0.5504681 -0.4817405 -0.6818438 -0.4809035 -0.6018691 -0.6375622 0.1745709 -0.9110934 -0.3734087 0.1957358 -0.9087151 -0.3686794 -0.09964358 -0.9911205 0.08804255 -0.1352291 -0.887964 0.4395827 0.2775045 -0.5622932 0.7789851 -0.3039032 -0.504773 0.8079895 0.3302093 -0.1892356 0.9247443 -0.5669228 -0.06488358 0.8212118 0.6252794 0.2877537 0.7254127 -0.561675 0.4352915 0.7035926 0.3999011 0.6972817 0.5948759 -0.5197558 0.7709606 0.3680676 0.267978 0.9251403 0.2688927 0.322406 0.9404984 -0.1073186 -0.5591699 0.8118014 -0.168249 0.3761921 0.7645278 -0.523428 -0.4652387 0.6380015 -0.6136018 0.5622821 0.4122159 -0.71688 -0.6707651 0.143163 -0.7277215 0.6385756 -0.09479111 -0.7636989 -0.548869 -0.339223 -0.7639834 0.4495823 -0.5624642 -0.693909 -0.5028024 -0.7248902 -0.4708756 0.1039319 -0.891166 -0.4416123 0.4341307 -0.9002698 -0.03232747 -0.5690538 -0.8202067 0.05864322 0.3492203 -0.8215775 0.4506171 -0.3642825 -0.7670805 0.5280966 0.5513333 -0.4733231 0.6870204 -0.5846433 -0.3364691 0.7382282 0.4729835 0.04571545 0.8798845 0.1446919 -0.003876507 0.9894692 -0.07673603 0.4553838 0.8869821 0.2992267 0.4990101 0.8132973 -0.4375764 0.6646716 0.6055895 0.6062104 0.7283298 0.3194445 -0.3512052 0.8991667 0.2610636 0.01429891 0.9891961 -0.1458994 -0.03988897 0.98968 -0.1376317 0.3275017 0.794709 -0.511058 -0.6018623 0.6159339 -0.5083181 0.6467157 0.341448 -0.6820352 -0.6107525 0.1988168 -0.766455 0.4879433 -0.1213642 -0.864397 -0.3263437 -0.2342914 -0.9157552 0.2876455 -0.545609 -0.7871282 -0.4808421 -0.5965583 -0.64258 0.536352 -0.7222642 -0.4366475 -0.5493764 -0.8166664 -0.1767533 0.4810166 -0.8764069 0.0231114 -0.4822997 -0.8357126 0.2626246 0.4723821 -0.755331 0.454236 -0.4323175 -0.553915 0.7115334 0.4824485 -0.2034755 0.8519632 -0.5057143 0.08786231 0.8582153 0.4692913 0.3704063 0.8016015 -0.3503206 0.4738635 0.8079165 0.5295014 0.6981242 0.4819242 -0.56227 0.7532268 0.3413237 0.502134 0.8588961 0.1007919 -0.533918 0.8419309 -0.07800036 0.5149908 0.7499652 -0.4151347 -0.07445347 0.8421332 -0.5341055 -0.2696118 0.5450052 -0.793901 0.3088254 0.455354 -0.8350327 0.09806835 0.0540992 -0.9937081 -0.1993786 0.03348428 -0.9793503 -0.1727961 -0.4314209 -0.8854476 0.1299122 -0.4744304 -0.8706542 0.3541503 -0.7773567 -0.5198982 -0.6944906 -0.6375476 -0.3334907 0.6889731 -0.7245588 0.01818281 -0.5856587 -0.7934622 0.1655953 0.4442015 -0.7304015 0.5188438 -0.2150755 -0.746703 0.6294262 0.1855795 -0.3835026 0.9047022 -0.08632552 -0.4242084 0.9014407 0.2074419 0.1133058 0.9716633 -0.5739157 0.1610283 0.8029263 0.5218216 0.4446649 0.7279942 -0.5158978 0.6510012 0.5568187 0.5283635 0.7546478 0.389023 -0.6046411 0.784814 0.1359273 0.5918035 0.7971416 -0.1197246 -0.507394 0.7894982 -0.3453172 0.268019 0.7912784 -0.5495857 -0.1219306 0.6105046 -0.7825708 0.3021886 0.5092439 -0.8058243 -0.4596103 0.2459309 -0.8533911 0.4024164 0.04043722 -0.9145633 -0.355017 -0.1830126 -0.9167712 0.3699511 -0.3352942 -0.8664376 -0.3765947 -0.5980245 -0.7074908 0.2405277 -0.7253942 -0.6449418 -0.2205793 -0.8694119 -0.4421175 0.3266618 -0.8954989 -0.3022812 -0.3351506 -0.9408611 -0.04954308 0.3338371 -0.9370369 0.1025406 -0.4206988 -0.8201758 0.3877167 0.5471585 -0.6727488 0.4980228 -0.5359535 -0.4522296 0.7129111 0.4572412 -0.2708727 0.8470882 -0.2866706 -0.1408769 0.9476147 0.4136292 0.1830688 0.8918502 -0.2058278 0.2592501 0.943623 -0.1001388 0.6697858 0.7357712 -0.1312873 0.6639106 0.7361973 0.4370127 0.8400905 0.3213533 -0.4756435 0.8467587 0.2382499 0.2077785 0.9615445 -0.1796118 -0.3930264 0.8904413 -0.2294446 0.5902724 0.6428328 -0.4882053 -0.6359946 0.4911969 -0.5951777 0.5777322 0.2660441 -0.7716516 -0.5800381 0.106848 -0.8075515 0.5713594 -0.1949463 -0.7972104 -0.4704019 -0.3983887 -0.7874063 0.387475 -0.5994617 -0.7003634 -0.3620492 -0.7265776 -0.5839567 0.3727942 -0.8717085 -0.318039 -0.407921 -0.8856778 -0.2217553 0.5114251 -0.8474239 0.1425383 -0.3833718 -0.8899587 0.2469807 0.1304534 -0.7427064 0.656787 0.1592046 -0.7364087 0.657538 -0.1691601 -0.3631147 0.9162602 0.001999974 -0.02937787 0.9995664 -0.02922451 0.4107442 0.9112823 0.3306161 0.6745456 0.6600616 -0.4887675 0.8049105 0.3364902 0.5335475 0.840331 0.09576475 -0.2617952 0.9650396 -0.01271784 0.239232 0.8944473 -0.3777992 -0.03184121 0.9087169 -0.4161968 -0.1034333 0.6702157 -0.7349234 0.0429266 0.6553653 -0.7540913 0.1141639 0.1761699 -0.9777171 -0.1162194 -0.2184135 -0.9689111 0.16666 -0.7217568 -0.6717824 0.1862033 -0.9255162 -0.3297698 -0.3020929 -0.9489696 0.09053593 0.4218441 -0.8761907 0.2331039 -0.410921 -0.7992969 0.4384843 0.513265 -0.6159148 0.5976689 -0.591442 -0.4344236 0.6793177 0.631775 -0.1466053 0.7611619 -0.5482674 -0.008256793 0.8362625 0.4131091 0.3357058 0.8465474 -0.2009055 0.4483827 0.8709707 0.3006321 0.7022564 0.6453343 -0.113335 0.7570422 0.6434612 -0.3623588 0.8796913 0.3079602 0.6206528 0.7813725 0.06517159 -0.2683582 0.9620826 -0.04879546 -0.0411368 0.8779533 -0.4769757 0.02846485 0.8734907 -0.486008 0.3053526 0.479637 -0.8226227 -0.08438539 0.4783425 -0.8741096 -0.3264324 0.1048993 -0.9393817 0.6249673 -0.08780252 -0.7756975 -0.4886161 -0.282993 -0.8253299 0.452405 -0.6535931 -0.6067502 -0.3459591 -0.611943 -0.711223 0.4469129 -0.8502031 -0.2782512 -0.4371472 -0.8835867 -0.1678602 0.3864039 -0.9176523 0.09277015 -0.6038821 -0.7601002 0.239946 0.6506675 -0.5906504 0.4772462 -0.5094741 -0.5117589 0.6917652 0.3539556 -0.3657106 0.8607969 -0.4876486 -0.1118537 0.8658452 0.6387494 0.1053985 0.7621616 -0.5886477 0.3729363 0.7172256 0.4311882 0.6133671 0.6617081 -0.4350374 0.7377653 0.5161831 0.5933035 0.7620292 0.2594275 -0.6591677 0.7515011 -0.02728134 0.1500121 0.9698258 -0.1921831 0.3788053 0.7593429 -0.5290605 -0.5591093 0.6123621 -0.5589359 0.4572815 0.4461983 -0.769286 -0.5965961 0.1961346 -0.7782059 0.6315248 -0.03973776 -0.7743367 -0.5487098 -0.3104159 -0.7762472 0.3499794 -0.5262577 -0.7749628 -0.3594769 -0.7370172 -0.5723479 0.1156426 -0.8364643 -0.5356813 0.3220524 -0.9360728 -0.1415986 -0.4265275 -0.9015948 -0.07211941 0.1550601 -0.919448 0.3613475 0.216934 -0.9046219 0.3668772 0.2663251 -0.6262279 0.7327412 -0.1135526 -0.7058896 0.6991607 -0.4631842 -0.3666111 0.806881 0.6448515 -0.08327054 0.7597583 -0.5212432 0.07592898 0.8500239 0.3102846 0.4177656 0.8539294 -0.3702223 0.4930933 0.7872704 0.5231489 0.6630214 0.5354605 -0.573037 0.7419054 0.3481452 0.3306347 0.9227646 0.1979553 -0.2235633 0.9685674 -0.1090728 0.1378349 0.9738665 -0.1805148 -0.1196704 0.8115655 -0.5718746 -0.3010605 0.796797 -0.5239057 0.3370662 0.5334765 -0.7757508 -0.5171344 0.3759879 -0.7688987 0.4922373 0.1189655 -0.8622932 -0.4570556 -0.09636521 -0.8842024 0.2332617 -0.2708241 -0.9339398 -0.1920541 -0.5383273 -0.8205601 0.3145499 -0.6079982 -0.7289696 -0.379508 -0.7849714 -0.4896872 0.232101 -0.8864698 -0.4003755 -0.1192963 -0.9923034 -0.03320276 0.1009278 -0.993687 -0.04898631 -0.138396 -0.9205698 0.3652368 0.2537627 -0.8666727 0.4295148 -0.3165119 -0.7020784 0.637892 0.3275516 -0.5779467 0.7474541 -0.2152548 -0.4124436 0.8851867 0.2654767 -0.2751668 0.9240159 -0.3658261 -0.05052351 0.9293109 0.3575679 0.1247117 0.9255227 -0.3642119 0.3654505 0.8566188 0.3801334 0.5126391 0.7698702 -0.3157099 0.7156389 0.6230475 0.3697133 0.8038718 0.4659423 -0.5101256 0.8177969 0.2664211 0.5556498 0.8313665 -0.009111702 -0.4455484 0.8650605 -0.2305582 0.2055474 0.8937724 -0.3986492 -0.2666079 0.7215854 -0.6389326 0.3558617 0.5983372 -0.7178824 -0.2778308 0.4225865 -0.8626881 0.3799807 0.2282427 -0.8963928 -0.5764134 0.02561557 -0.8167568 0.6830362 -0.2374547 -0.6907076 -0.5646621 -0.4539936 -0.6892362 0.5364449 -0.6893503 -0.4868503 -0.4284929 -0.7892719 -0.4398226 0.562236 -0.8261371 0.03725838 -0.2974201 -0.9485744 0.1083884 -0.1118025 -0.8279641 0.5495231 0.5589115 -0.630809 0.5382361 -0.5116863 -0.3587312 0.780698 0.4789704 -0.1796875 0.8592438 -0.4508832 0.02868312 0.892122 0.5393931 0.2565604 0.8020174 -0.4754551 0.5167707 0.7119625 0.1515961 0.6777491 0.7194963 -0.09767419 0.9223352 0.3738415 0.2655814 0.9142732 0.305894 -0.4079712 0.9032483 -0.1330497 0.1021131 0.9679092 -0.2296186 0.3091816 0.7392029 -0.5983192 -0.3081203 0.7078621 -0.6356047 -0.03542631 0.3514123 -0.9355504 0.532414 -0.04094499 -0.8454933 -0.480998 -0.3239921 -0.8146595 0.3432232 -0.5766983 -0.7413616 -0.2519549 -0.6707469 -0.6975797 0.4751068 -0.7885084 -0.3905485 -0.4336074 -0.8516524 -0.2944027 0.2203213 -0.9688322 0.1132378 -0.2356728 -0.970699 0.04692548 0.449081 -0.7691966 0.454602 -0.6479334 -0.6068803 0.4603029 0.6074714 -0.3042947 0.7337461 -0.5101059 -0.2264633 0.8297629 0.4743052 0.1371697 0.8696087 -0.5843625 0.2386561 0.7756054 0.5451968 0.5354722 0.645004 -0.3701984 0.734218 0.5691022 0.2032012 0.8575435 0.4725763 -0.293668 0.9294239 0.2234512 0.2446596 0.9649149 0.09529441 -0.3116433 0.9309989 -0.1900512 0.1160647 0.9541047 -0.2760676 0.3214728 0.728775 -0.604601 -0.444003 0.6427727 -0.6242632 0.2878485 0.3167964 -0.9037607 0.04435682 0.3689107 -0.9284058 0.06622481 -0.04070615 -0.9969741 -0.4376645 -0.09469079 -0.8941384 0.4274155 -0.3768306 -0.8217754 -0.3285179 -0.5792564 -0.7460148 0.2824693 -0.6970165 -0.6590745 -0.3614225 -0.8266377 -0.4313282 0.4606786 -0.8555893 -0.2360981 -0.5939749 -0.8044623 0.005874931 0.5807581 -0.7798703 0.2335003 -0.4989426 -0.6715963 0.547736 0.1383815 -0.4667361 0.8735033 -0.1205152 -0.06888693 0.9903185 0.2611746 0.003833055 0.965284 -0.4705806 0.3377651 0.8151494 0.3434137 0.4857472 0.8038139 0.2243362 0.7960972 0.5620522 -0.6681102 0.6430734 0.3742798 0.6204667 0.7835407 0.03294217 -0.6412491 0.7567628 -0.1269249 0.3754666 0.8410381 -0.3894611 -0.1026204 0.6905725 -0.715946 -0.2506296 0.6637135 -0.7047477 0.3130834 0.282658 -0.9066881 -0.2954907 0.2323841 -0.9266515 0.08360928 -0.2510772 -0.9643494 -0.169392 -0.5860968 -0.7923365 0.2690771 -0.8872635 -0.3746479 -0.273204 -0.9031556 -0.3311639 0.2440636 -0.968839 0.04223871 -0.2074468 -0.9729768 0.1013995 0.1186848 -0.8746736 0.4699577 -0.1155275 -0.8656569 0.4871258 0.2734763 -0.4596703 0.8449344 -0.1096768 -0.1297548 0.9854617 0.08068108 0.3641027 0.9278578 0.1947639 0.6543822 0.730651 -0.0572496 0.9246785 0.3764203 0.06668901 0.9212146 0.3832967 -0.2181974 0.9650062 -0.1454406 0.187398 0.95994 -0.2083202 -0.07359695 0.7932796 -0.6043932 0.3451493 0.6945415 -0.6312561 -0.4553146 0.4510914 -0.7675969 0.4318413 0.2540701 -0.8654257 -0.4783306 0.02581608 -0.8778004 0.3639757 -0.1366538 -0.9213292 -0.08450746 -0.552033 -0.8295289 -0.5341027 -0.498167 -0.6830548 0.5040603 -0.7327858 -0.4571085 -0.5157316 -0.818847 -0.2520131 0.3372841 -0.9364647 -0.09629815 -0.3007888 -0.9262145 0.2272728 0.4620262 -0.8138923 0.3522939 -0.5031248 -0.6660726 0.5506476 0.5158478 -0.4686309 0.7171375 -0.4020177 -0.3557734 0.8436866 0.3611859 -0.09594792 0.9275446 -0.2701948 0.02127408 0.9625706 0.3511037 0.2884965 0.890784 -0.3890574 0.3837692 0.8374699 0.2820609 0.7203172 0.6337072 0.06050401 0.72412 0.687015 0.03204339 0.9586139 0.2829007 -0.2491772 0.9339567 0.2561947 0.3000442 0.9066959 -0.2964391 0.05474191 0.9437917 -0.3259764 -0.2564872 0.6979877 -0.6686012 0.455802 0.5500192 -0.6998025 -0.4915366 0.2944816 -0.8195562 0.6439291 0.03252643 -0.7643935 -0.6191155 -0.140455 -0.7726373 0.6147421 -0.4844378 -0.6224245 -0.003629088 -0.6585634 -0.7525165 -0.4160042 -0.8173788 -0.3985378 0.5043236 -0.8351093 -0.21966 -0.3205996 -0.9311226 0.1738584 0.05138307 -0.9719632 0.2294497 0.0332939 -0.6602902 0.7502722 -0.767633 -0.4639211 -0.442173 -0.9301474 -0.3616384 -0.06358903 -0.5745252 -0.8181046 0.02501463 -0.9250173 -0.3517416 0.1436 -0.7426654 -0.4952822 0.4507147 -0.8937676 -0.2204941 0.3905917 -0.8351541 -0.2056257 0.510133 -0.8171844 -0.04482358 0.5746307 -0.8974356 0.01821845 0.4407693 -0.7973363 0.2401304 0.5537078 -0.8730055 0.2935511 0.3894733 -0.8397695 0.3550707 0.4107456 -0.7743035 0.5779941 0.2576376 -0.8719807 0.4713965 0.1320419 -0.7998415 0.5999134 0.01890939 -0.8656569 0.4872743 -0.1148998 -0.8695931 0.4818041 -0.108041 -0.843944 0.4158671 -0.338841 -0.8901586 0.3313446 -0.3127754 -0.820963 0.2590228 -0.5088488 -0.8558567 0.1741194 -0.4870234 -0.7896013 0.1117066 -0.6033669 -0.8596072 -0.04737603 -0.5087544 -0.8122525 -0.1264794 -0.5694285 -0.8587635 -0.2509904 -0.4466871 -0.8252289 -0.305788 -0.4748589 -0.799901 -0.4852735 -0.3530836 -0.8860701 -0.4115933 -0.2132388 -0.8215954 -0.5496389 -0.1512556 -0.8405687 -0.5398477 -0.04481798 -0.7774834 -0.6280722 0.03233063 -0.7903734 -0.541293 0.2869005 -0.8368397 -0.5001976 0.2224902 -0.8153644 -0.3929815 0.4251428 -0.8582718 -0.3341014 0.3895456 -0.8810295 -0.1405721 0.4516929 -0.8451842 -0.1247259 0.5197184 -0.7651935 0.004720628 0.6437832 -0.8724712 0.127853 0.4716435 -0.8206081 0.2122844 0.5306013 -0.8347002 0.3733601 0.4048184 -0.8542217 0.3627904 0.3724094 -0.8215336 0.5119108 0.2510581 -0.8614194 0.4738847 0.1827298 -0.8093297 0.5831142 0.07045203 -0.8490265 0.5281628 -0.01407653 -0.7985568 0.5953768 -0.08850789 -0.8519233 0.4440184 -0.2776229 -0.8120062 0.5054436 -0.2918434 -0.8651529 0.2951304 -0.4054731 -0.8207786 0.3013452 -0.4852975 -0.7807023 0.09194475 -0.6181021 -0.8831703 -0.002594232 -0.4690455 -0.7914705 -0.1463084 -0.5934379 -0.8554496 -0.2851188 -0.4323346 -0.8472694 -0.3001058 -0.4382592 -0.8320965 -0.4571329 -0.3140782 -0.8610134 -0.4372076 -0.2598183 -0.8118048 -0.5589037 -0.1691145 -0.8632783 -0.5003911 -0.06602495 -0.7947885 -0.6065993 0.01867413 -0.8430716 -0.4890051 0.2238401 -0.8516454 -0.4800436 0.2103769 -0.811784 -0.3735962 0.4488127 -0.8828291 -0.3383898 0.3257377 -0.7552073 -0.2395145 0.6101598 -0.866814 -0.0425502 0.4968129 -0.8150496 0.008792102 0.5793246 -0.8275448 0.1979497 0.5253434 -0.8766778 0.2102245 0.4327146 -0.7803172 0.4312928 0.4528705 -0.869479 0.424342 0.252864 -0.8817471 0.408349 0.2361636 -0.8084706 0.5885291 0.002999007 -0.8663183 0.4985177 -0.03118854 -0.8376612 0.486001 -0.2492524 -0.8246065 0.4986835 -0.2670937 -0.8157134 0.371444 -0.4434424 -0.8786767 0.2625626 -0.3987334 -0.7700516 0.19209 -0.6083767 -0.8672396 -0.01829499 -0.4975549 -0.8385826 -0.05097472 -0.5423846 -0.8107489 -0.2796514 -0.5142775 -0.8351978 -0.2772909 -0.4749258 -0.8273217 -0.4333936 -0.3573638 -0.8568867 -0.4126083 -0.3090303 -0.7909341 -0.575168 -0.2088179 -0.8692927 -0.4928362 -0.03798526 -0.8520773 -0.5230243 -0.0202493 -0.7919152 -0.5802749 0.1901351 -0.8636047 -0.4556596 0.2157805 -0.7903916 -0.4603229 0.4042079 -0.8225216 -0.4007089 0.4035971 -0.7500443 -0.3151709 0.5814645 -0.8364765 -0.117551 0.5352466 -0.8252684 -0.1092997 0.5540629 -0.7915368 0.1025448 0.6024568 -0.8999425 0.1804527 0.3969135 -0.8243221 0.1927991 0.5322797 -0.8257232 0.38903 0.4084568 -0.8743094 0.3682762 0.3161576 -0.8071556 0.5294796 0.2610582 -0.8607927 0.49667 0.1111526 -0.8369811 0.5391814 0.09352093 -0.7772922 0.6179234 -0.1182689 -0.8806797 0.43611 -0.1849637 -0.8210613 0.489415 -0.2938222 -0.8361019 0.3127339 -0.4507009 -0.8511942 0.290463 -0.4371497 -0.8127512 0.1528316 -0.5622083 -0.8746755 0.06681144 -0.4800823 -0.8095028 -0.04846721 -0.5851122 -0.8605878 -0.2007102 -0.4680855 -0.8507195 -0.2163398 -0.4790338 -0.8047749 -0.397563 -0.440773 -0.8751122 -0.3737443 -0.3073985 -0.7843344 -0.5656779 -0.2546136 -0.8628088 -0.5034161 -0.0461874 -0.8383179 -0.5445296 -0.02666002 -0.7967162 -0.5651428 0.214143 -0.881926 -0.4105817 0.2315803 -0.8112485 -0.4345112 0.3912492 -0.8532586 -0.253642 0.4556486 -0.7929914 -0.2500175 0.5555682 -0.8556669 0.03753793 0.5161637 -0.8265098 0.02410739 0.5624058 -0.8498157 0.2300884 0.4742074 -0.8244838 0.2684949 0.4981335 -0.8130121 0.4286348 0.3940603 -0.8850666 0.3865965 0.2592306 -0.7938044 0.5650011 0.2250524 -0.8112338 0.5839592 0.02985817 -0.8928335 0.4501541 -0.01447987 -0.825124 0.4927766 -0.2762999 -0.8379764 0.4712888 -0.2751046 -0.82767 0.3686703 -0.4231368 -0.862984 0.3070798 -0.4011992 -0.7887958 0.2136627 -0.5763242 -0.868382 0.03274661 -0.4948135 -0.8080145 0.07174623 -0.5847779 -0.8587283 -0.1397401 -0.4930097 -0.8249654 -0.188813 -0.5327118 -0.8072063 -0.3566541 -0.4703362 -0.8632307 -0.3472137 -0.3664364 -0.803026 -0.5053868 -0.3158062 -0.8600887 -0.4672689 -0.2047129 -0.7872043 -0.6063218 -0.1126199 -0.8698899 -0.493214 0.005639374 -0.7815614 -0.6013832 0.1658317 -0.874222 -0.4188047 0.245639 -0.816735 -0.4614319 0.346446 -0.7889121 -0.3272493 0.520121 -0.8840045 -0.1874736 0.4282401 -0.7808381 -0.06376314 0.6214709 -0.866338 0.05223262 0.4967197 -0.7897043 0.1685773 0.589872 -0.8603036 0.3340624 0.3850715 -0.8242224 0.3543732 0.4416754 -0.8343882 0.4890157 0.2542833 -0.8497874 0.4727417 0.2331879 -0.790035 0.6080045 0.07858341 -0.8772373 0.4778619 -0.04585635 -0.8291484 0.5446681 -0.1258962 -0.8423662 0.4592751 -0.2819317 -0.8516051 0.45104 -0.2670797 -0.7945252 0.4009725 -0.4560165 -0.8601163 0.2292404 -0.4556852 -0.8732987 0.2096138 -0.439786 -0.7752761 0.07285362 -0.6274068 -0.8615189 -0.06849813 -0.5030838 -0.8039082 -0.1532399 -0.5746731 -0.8612931 -0.2938905 -0.4144907 -0.8105559 -0.3807306 -0.4450207 -0.8152893 -0.5103159 -0.2736443 -0.852487 -0.4724225 -0.2237924 -0.8312518 -0.5356569 -0.1486339 -0.8894073 -0.4564158 0.02528411 -0.8518167 -0.5193184 0.06867957 -0.742502 -0.5904142 0.3163889 -0.8778397 -0.3832162 0.2873029 -0.8029603 -0.3264135 0.4987072 -0.8299825 -0.2812451 0.4816954 -0.7532889 -0.1404768 0.6425125 -0.8475877 0.00690329 0.5306105 -0.7937216 0.120763 0.5961731 -0.8303287 0.1375563 0.5400302 -0.7326917 0.4936013 0.4685305 -0.8766293 0.2957038 0.3795793 -0.8047652 0.5481671 0.2277408 -0.8785184 0.4662449 0.1040254 -0.8079237 0.5882288 0.03530323 -0.8314198 0.5309492 -0.1638115 -0.8487616 0.5020478 -0.1659873 -0.8225049 0.4008063 -0.4035344 -0.8533813 0.3834791 -0.3531064 -0.7769562 0.2628922 -0.5720375 -0.8364285 0.1904545 -0.5139207 -0.751891 -0.001768052 -0.6592851 -0.8450119 -0.1305825 -0.5185588 -0.7833616 -0.2295035 -0.5776442 -0.8496248 -0.3557264 -0.389354 -0.7769437 -0.3942298 -0.4908578 -0.7732073 -0.5795651 -0.2574002 -0.8426865 -0.5122231 -0.1658526 -0.7783795 -0.6274815 -0.01981306 -0.8859859 -0.4517626 0.1045936 -0.8339834 -0.5435968 0.09473258 -0.8568314 -0.4095898 0.3131715 -0.8433725 -0.4198729 0.3353052 -0.7746244 -0.3314055 0.5386349 -0.877185 -0.1443397 0.4579437 -0.8409787 -0.1187726 0.5278712 -0.793681 0.06898927 0.6044096 -0.8668185 0.1391137 0.4788248 -0.8019474 0.2644816 0.5356585 -0.8622167 0.3406486 0.3748881 -0.8169542 0.4236758 0.3912606 -0.7936772 0.5705507 0.2110652 -0.8818315 0.4623503 0.09276622 -0.8399459 0.5407991 0.04502856 -0.8020355 0.5753906 -0.1602025 -0.8758538 0.4395264 -0.1992405 -0.7996073 0.4854045 -0.3535684 -0.8319683 0.3019206 -0.4654811 -0.8545575 0.2994562 -0.4243319 -0.8146817 0.05625522 -0.5771734 -0.8793231 0.002712368 -0.4762181 -0.7697021 -0.1834933 -0.6114645 -0.8611239 -0.314045 -0.3998018 -0.8532971 -0.3182498 -0.4130391 -0.7913408 -0.5445272 -0.277975 -0.8424328 -0.49468 -0.2135385 -0.8266845 -0.5535069 -0.1011093 -0.8983833 -0.4391942 -0.003997266 -0.8229164 -0.5514491 0.1367945 -0.8413559 -0.4533219 0.294312 -0.8420268 -0.4527544 0.2932649 -0.7917495 -0.3413946 0.5065398 -0.8597719 -0.2432155 0.4490419 -0.7977735 -0.1037594 0.5939626 -0.8789893 0.01023197 0.476732 -0.7911348 0.1233635 0.599072 -0.8320627 0.3158931 0.4559422 -0.8669869 0.3023951 0.3960945 -0.8115653 0.4902684 0.3178029 -0.872543 0.4418518 0.2084127 -0.7896831 0.5998893 0.1285833 -0.8711065 0.4830713 -0.08840662 -0.8188289 0.5694221 -0.0726493 -0.846919 0.4594338 -0.2676733 -0.8433455 0.4656445 -0.268223 -0.8485227 0.313515 -0.4262835 -0.8396097 0.3157488 -0.4419937 -0.7840908 0.2011656 -0.5871406 -0.8766848 0.01558005 -0.4808131 -0.858988 0.02751642 -0.5112558 -0.8028763 -0.2153053 -0.5559077 -0.8559058 -0.2505574 -0.4523785 -0.8207868 -0.3266971 -0.4685915 -0.8439034 -0.4389508 -0.3084629 -0.8229981 -0.4562218 -0.3384315 -0.8387219 -0.5271264 -0.1366867 -0.8510757 -0.5105673 -0.1224386 -0.7871463 -0.6107113 0.08621263 -0.9035331 -0.4116658 0.1189925 -0.807902 -0.4151839 0.4182303 -0.8596727 -0.3795548 0.3419079 -0.7794532 -0.2659054 0.5672276 -0.8785178 -0.1053433 0.4659498 -0.8096589 -0.04358679 0.58528 -0.8491751 0.1902719 0.4926442 -0.8401355 0.2033924 0.5027963 -0.836515 0.3808365 0.3939626 -0.8119413 0.419881 0.4055261 -0.8076701 0.5498672 0.2128738 -0.8518608 0.5009065 0.1530551 -0.8062543 0.5911759 0.02156567 -0.862558 0.5034555 -0.05026429 -0.810199 0.5626857 -0.1642032 -0.8567491 0.4311832 -0.2829528 -0.8208354 0.4919165 -0.2902541 -0.8445957 0.3396602 -0.4138711 -0.8065721 0.3430902 -0.4813841 -0.8637977 0.1178432 -0.4898637 -0.7847769 0.06609863 -0.6162438 -0.8649671 -0.09724873 -0.4923157 -0.8080228 -0.2000411 -0.5541505 -0.8593615 -0.2914725 -0.4201689 -0.8361317 -0.3365173 -0.4331742 -0.8327964 -0.4752834 -0.283824 -0.8529844 -0.4567112 -0.2526513 -0.817189 -0.5674143 -0.101209 -0.8573565 -0.5119664 -0.05320024 -0.778801 -0.6132384 0.1319385 -0.8505718 -0.4917796 0.1862272 -0.8626738 -0.4707407 0.1849244 -0.8614854 -0.333994 0.38248 -0.8394172 -0.3657385 0.4020125 -0.887423 -0.1749458 0.4264674 -0.809401 -0.1243797 0.5739336 -0.8762446 0.01810145 0.4815268 -0.8172447 0.1070171 0.5662672 -0.8416607 0.2592789 0.4736896 -0.8301045 0.2776643 0.4835589 -0.8918207 0.3653876 0.2667359 -0.802962 0.5300732 0.2725336 -0.8263764 0.5587434 0.07005739 -0.8533614 0.5192589 0.04630923 -0.8103953 0.5694565 -0.1377637 -0.8614653 0.4796164 -0.1668706 -0.7967332 0.4846445 -0.3610209 -0.8613989 0.3585911 -0.3597282 -0.8073042 0.338353 -0.4835053 -0.8402466 0.1678794 -0.5155602 -0.8527582 0.17487 -0.4921625 -0.7989034 -0.03472083 -0.6004565 -0.8790583 -0.09997808 -0.4661126 -0.7819194 -0.2619619 -0.5656661 -0.8709623 -0.367442 -0.3262073 -0.841799 -0.4212447 -0.3375315 -0.772648 -0.6113455 -0.1710903 -0.8817667 -0.4707906 -0.02904927 -0.8486579 -0.5287328 0.01489317 -0.8531911 -0.4367431 0.2851675 -0.8689963 -0.4090814 0.2783845 -0.8018238 -0.3696923 0.4694744 -0.8959685 -0.1387904 0.4218741 -0.8092967 -0.09715574 0.5793098 -0.8723886 0.09904712 0.4786732 -0.8002088 0.1978157 0.5661581 -0.8563694 0.3219613 0.4036983 -0.8089929 0.4073997 0.4237408 -0.8380411 0.494496 0.2305665 -0.8606205 0.467795 0.2012472 -0.7885739 0.614173 0.03070604 -0.8742547 0.4801695 -0.07152736 -0.821065 0.5436736 -0.1739859 -0.8574345 0.4268981 -0.2873397 -0.8351029 0.4427615 -0.326444 -0.7787671 0.3704881 -0.5062217 -0.838752 0.2712073 -0.472167 -0.7493143 0.1606736 -0.6424268 -0.8297485 -0.03684127 -0.5569204 -0.8249592 -0.04193615 -0.5636344 -0.8276614 -0.3121278 -0.4664258 -0.8192992 -0.315588 -0.4786996 -0.8463161 -0.4499346 -0.2851458 -0.8541516 -0.4422437 -0.2735795 -0.7897236 -0.6084514 -0.07825487 -0.8713539 -0.4905545 -0.009936869 -0.8097973 -0.5502107 0.2037076 -0.8672327 -0.4515291 0.2098309 -0.7592632 -0.4461757 0.473758 -0.9119433 -0.2048361 0.3555302 -0.8244526 -0.1497767 0.5457517 -0.8452278 0.03170543 0.5334649 -0.8543442 0.02271783 0.5192109 -0.8470113 0.2823766 0.4503726 -0.8633449 0.2820547 0.4184265 -0.7979103 0.4633625 0.3855312 -0.8778001 0.3972101 0.2677524 -0.8595491 0.5023863 0.09371989 -0.7977136 0.6000503 0.05993986 -0.8684536 0.4788556 -0.1283974 -0.8276945 0.5486243 -0.1180395 -0.8597208 0.420198 -0.2903686 -0.8278121 0.4423037 -0.3451009 -0.8211581 0.2809073 -0.4967802 -0.8608006 0.2238362 -0.4570776 -0.7971954 0.08659356 -0.597479 -0.8594635 0.01939582 -0.510829 -0.8125367 -0.1999362 -0.5475488 -0.8267933 -0.1824291 -0.532102 -0.8567565 -0.3432592 -0.3848916 -0.7851637 -0.4625775 -0.4117524 -0.8672688 -0.463995 -0.1804254 -0.8274975 -0.5376347 -0.1618548 -0.7973941 -0.6020287 0.04152446 -0.8730739 -0.4795687 0.08806693 -0.7903452 -0.5404528 0.2885574 -0.8267456 -0.4713692 0.3070874 -0.7567536 -0.4494183 0.4747075 -0.8243206 -0.2458003 0.5099784 -0.7983636 -0.2334463 0.5550844 -0.8604683 -0.06760793 0.5049985 -0.8863264 -0.04254639 0.4611025 -0.8155243 0.1541867 0.5578051 -0.855679 0.2285281 0.4643149 -0.8276246 0.2781024 0.4875413 -0.821741 0.4395051 0.3627356 -0.8649104 0.3613219 0.3483914 -0.7936678 0.5667769 0.2210325 -0.8722575 0.4832373 0.07515686 -0.8085287 0.588338 0.01183134 -0.8934032 0.4250738 -0.1454067 -0.7929758 0.5152206 -0.3251726 -0.8617283 0.377434 -0.3390691 -0.8255358 0.3623369 -0.4326694 -0.8939192 0.1763782 -0.4120671 -0.78936 0.1297737 -0.6000581 -0.8588618 -0.03765571 -0.5108215 -0.7503985 -0.1847541 -0.6346402 -0.815141 -0.3547411 -0.4579346 -0.8298563 -0.3300688 -0.4498815 -0.831223 -0.47585 -0.2874638 -0.8643702 -0.4445803 -0.234973 -0.8003262 -0.5868521 -0.122812 -0.8513794 -0.5241569 -0.02031463 -0.8159862 -0.5769355 0.0362221 -0.8489759 -0.4837017 0.2127742 -0.8520926 -0.4802853 0.2080007 -0.7828027 -0.450322 0.4294534 -0.8484002 -0.3383811 0.4070816 -0.7344967 -0.2546538 0.62902 -0.828837 -0.04960083 0.5572873 -0.7742781 0.01939839 0.6325482 -0.8459465 0.104192 0.5229901 -0.7780644 0.2438873 0.5789084 -0.8177405 0.4039283 0.4100517 -0.8196991 0.4005389 0.4094658 -0.8486239 0.4755035 0.2318059 -0.8449593 0.4822281 0.2313005 -0.7918913 0.609404 0.03918057 -0.8729027 0.484139 -0.06041926 -0.8242247 0.5490669 -0.1384899 -0.8240686 0.4737367 -0.3106195 -0.866699 0.3976621 -0.3011607 -0.7906574 0.3614674 -0.4941683 -0.8554769 0.1923564 -0.4807894 -0.8105899 0.1659802 -0.5616001 -0.8419695 -0.02918297 -0.5387355 -0.8460099 -0.03179758 -0.532218 -0.8113806 -0.2418801 -0.5321239 -0.8593816 -0.2528768 -0.4444286 -0.8044613 -0.4241112 -0.415899 -0.8569111 -0.4088913 -0.3138653 -0.8176423 -0.5027136 -0.2806069 -0.8596602 -0.5010849 -0.099491 -0.8402783 -0.5354861 -0.08477616 -0.7974438 -0.59298 0.1116161 -0.8811053 -0.4507421 0.143126 -0.7881478 -0.4965457 0.3636831 -0.8741227 -0.3077915 0.3757315 -0.7852594 -0.3016007 0.5407446 -0.8180118 -0.0754081 0.5702371 -0.84495 -0.1003897 0.5253395 -0.8324338 0.143909 0.5351113 -0.8519322 0.117465 0.5103071 -0.7992094 0.3325647 0.5006649 -0.8697678 0.3292909 0.3675209 -0.8499562 0.3811671 0.3637115 -0.873531 0.453391 0.1771453 -0.8719985 0.4564688 0.1767904 -0.767682 0.639506 0.04118752 -0.871015 0.4785292 -0.1110981 -0.837971 0.5218302 -0.1596811 -0.7903519 0.5061787 -0.3451479 -0.8807216 0.3307425 -0.3390263 -0.7918512 0.3276249 -0.5153966 -0.8349363 0.1294257 -0.5349117 -0.8776063 0.07484096 -0.4735041 -0.8093027 -0.01346033 -0.5872377 -0.8284066 -0.2684187 -0.4916239 -0.8696972 -0.2558776 -0.4220824 -0.7629448 -0.5151655 -0.3905382 -0.8804798 -0.4457702 -0.161383 -0.871424 -0.4595229 -0.1716361 -0.8415713 -0.5374444 0.05395823 -0.8589518 -0.5057286 0.08025324 -0.7759871 -0.5963388 0.2054848 -0.8644338 -0.3621676 0.3486958 -0.8511806 -0.3837372 0.3581026 -0.7771133 -0.2725655 0.5672768 -0.8764387 -0.07747775 0.4752394 -0.8248956 -0.03936249 0.5639131 -0.8101399 0.1789439 0.5582585 -0.8705915 0.1923812 0.4528357 -0.7351714 0.4008344 0.5466763 -0.9431455 0.275103 0.1865344 0.03800457 0.9328199 0.3583334 -0.3037028 0.9518312 -0.04221427 -0.03333014 0.01629108 0.9993117 0.1046267 0.3851303 0.9169123 0.7092427 0.6328851 -0.310534 -0.5995323 0.6041775 -0.5249102 0.7408493 0.3448019 -0.576415 -0.6717552 -0.4843392 0.5605003 0.6893183 -0.2381393 0.6842002 0.649053 0.7191561 0.2480823 -0.7067781 0.7074342 -0.001254558 -0.8760843 -0.2070783 0.4354253 0.04629474 0.9975193 -0.05302894 -0.2947397 0.8304641 -0.4727135 0.8253599 -0.562357 0.05035549 -0.8746912 -0.4335947 0.2165895 -0.711025 0.4575536 0.5339366 0.5803879 0.7491102 0.3193491 0.9063817 -0.4149262 0.07942551 0.2595166 -0.9375667 0.2315595 0.1457713 -0.7263906 0.6716453 -0.8357225 0.0631746 -0.5455061 0.6847452 -0.5516199 0.4762768 -0.6269389 -0.4924992 0.6036491 0.5772913 -0.3643143 0.7307599 -0.6300811 -0.1559289 0.7607128 -0.4840734 0.4834085 0.729376 0.1392905 0.8836948 0.4468578 0.6065632 -0.7748463 0.1780291 -0.6788882 -0.6131351 0.4039508 0.7207869 -0.3083523 0.620794 -0.7148182 -0.1108543 0.6904681 -0.8309036 -0.3091614 -0.4626214 -0.6559103 -0.506585 0.5596011 0.7221647 -0.1967253 0.6631572 -0.7346074 0.05642402 0.6761422 0.667148 0.3848819 0.6377926 -0.6837278 0.5731244 0.4517133 0.6392441 0.7340582 0.2291846 -0.7963414 0.6018543 0.06009817 -0.8307307 -0.4126121 -0.3736815 0.8592724 0.1072036 0.5001583 -0.6795894 0.7335516 -0.007769465 0.5931677 0.7546243 -0.280525 -0.6784673 0.6201738 -0.3937851 0.6646331 0.3620584 -0.6535875 -0.744731 0.1391994 -0.6526864 0.8601126 0.4595346 0.2214369 0.8520374 -0.5227868 -0.02694839 -0.1038995 0.6455575 0.7566112 0.3634194 0.8711041 0.3303091 -0.3323997 0.9423282 -0.03909021 0.3486341 0.8690802 -0.350933 0.001100003 0.9191033 -0.394015 -0.3195517 0.7910889 -0.5215987 -0.9704759 0.1800289 -0.160519 -0.6365491 0.5302813 -0.5600064 0.1056573 0.6884549 -0.7175419 -0.8196605 0.4875269 -0.3007894 -0.3156993 0.792308 -0.522094 -0.7658879 0.5831282 -0.2708824 -0.7629494 0.5800645 -0.2853658 -0.9658096 0.2526118 -0.05830299 -0.6441923 0.7317155 -0.2227303 -0.6513089 0.7543615 -0.08207029 -0.2518405 0.9253904 -0.2832473 -0.718486 0.695042 -0.02635365 -0.1725432 0.9787538 -0.1107695 -0.7030546 0.7107874 0.02226525 0.03971123 0.9981483 -0.04607653 -0.8518038 0.5077853 0.1287804 -0.3660433 0.9215735 0.1292855 -0.2948836 0.9155821 0.2734106 -0.7623692 0.5912776 0.2630284 -0.6653178 0.6812883 0.3052845 -0.480677 0.8513375 0.2101765 -0.8995396 0.3581902 0.2500566 0.07068252 0.8811506 0.467523 -0.3142352 0.7731943 0.5508421 -0.3224427 0.6947772 0.6428961 -0.7440841 0.4481654 0.4954661 -0.4886633 0.5845596 0.6476868 -0.8829531 0.2088466 0.4204486 -0.308098 0.4729673 0.8254561 -0.1623945 0.4633821 0.8711517 -0.7526739 0.2211053 0.6201568 -0.7042285 0.154482 0.692963 -0.241494 0.1728666 0.954881 -0.8436812 -0.01712125 0.5365716 -0.8669874 0.008243024 0.4982619 0.04006433 0.08879917 0.9952436 -0.4343332 -0.1276029 0.8916682 -0.3454535 -0.2704108 0.8986322 -0.8506781 -0.2237058 0.4757128 -0.9480379 -0.1627184 0.2733992 -0.7172226 -0.3147807 0.6216952 -0.4473447 -0.3428799 0.8260242 -0.01245754 -0.5624569 0.8267329 -0.6038441 -0.5488108 0.5780823 -0.4374205 -0.6229482 0.6485359 -0.7586801 -0.482392 0.4378384 -0.8016018 -0.4836694 0.351424 -0.9547289 -0.2701458 0.1245552 -0.05800211 -0.8222143 0.5662149 -0.5127395 -0.7864549 0.3443646 -0.4291098 -0.8292636 0.3580319 -0.8337082 -0.5364901 0.130802 -0.1835066 -0.9505779 0.2504536 -0.7885611 -0.6132323 0.04601776 -0.439181 -0.8978223 0.03217399 -0.8821873 -0.4698686 -0.03113383 -0.3616919 -0.9320745 -0.02039939 -0.3981565 -0.9070374 -0.1369475 -0.8094379 -0.5675237 -0.1507551 -0.8262407 -0.5237535 -0.2073848 -0.1324615 -0.9416234 -0.3095149 -0.6816521 -0.6360833 -0.3615918 -0.4934708 -0.7593815 -0.4240593 -0.7766124 -0.4768888 -0.4116435 -0.1086159 -0.7808746 -0.6151728 -0.9302875 -0.2396899 -0.2776943 -0.3730762 -0.6001765 -0.7075326 -0.5437902 -0.5290381 -0.6514683 -0.852055 -0.2585567 -0.4551385 -0.6629595 -0.3739391 -0.6485787 -0.6039442 -0.3672947 -0.7073515 0.08766871 -0.4931952 -0.8654899 -0.9241276 -0.1207931 -0.3624878 -0.187386 -0.424046 -0.8860425 -0.5870707 -0.1767246 -0.7900105 -0.8331481 -0.09704041 -0.54447 -0.2656722 -0.2297965 -0.9362756 -0.644576 -0.1413136 -0.7513669 0.06954741 -0.1489737 -0.9863924 -0.8796727 0.01087129 -0.4754555 -0.5435563 0.01338219 -0.839266 -0.6987638 0.1006404 -0.7082378 -0.2095138 0.02906239 -0.9773738 -0.02050673 0.1212836 -0.9924061 -0.6766471 0.159536 -0.7188165 -0.9915027 0.0334829 -0.125704 -0.9260544 0.1607232 -0.3414548 -0.4287962 0.2757757 -0.86028 -0.3783487 0.3386538 -0.8614906 -0.1020067 0.4414536 -0.891467 -0.8766392 0.2721456 -0.3967878 -0.6321418 0.4927863 -0.5979619 -0.6784192 0.4484111 -0.5819579 -0.2548379 0.5939518 -0.763072 -0.9999968 6.1013e-4 0.002489328 -0.9999612 -0.00429213 0.007701456 -0.9999668 0.00807017 0.001179337 -0.9999831 0.004442989 -0.003760099 -0.9999806 0.005728244 -0.002449035 -0.9999781 0.005841374 -0.003136754 -0.9999939 0.003433227 -7.81354e-4 -0.9999338 -0.009590029 -0.006376028 -0.9999635 0.0066576 -0.005365371 -0.9999946 -0.001420497 0.002970516 -0.9999772 -0.005126178 0.004388153 -0.6676931 -0.4486793 0.594031 -0.7360872 -0.3270819 0.5926156 -0.521624 -0.3523298 0.7770278 -0.3926627 -0.2826133 0.8751833 -0.9476548 -0.116091 0.2974449 -0.6830227 -0.1210677 0.7202934 -0.6892448 -0.138804 0.7111084 -0.1562881 -0.0306822 0.9872348 -0.822461 0.004283726 0.5688055 -0.6041544 0.05823135 0.7947368 -0.9345383 0.02890092 0.3546872 -0.5064145 0.1729078 0.8447765 -0.4950601 0.2614611 0.8285853 -0.6533995 0.219204 0.7245818 -0.56669 0.3124389 0.7623939 -0.6125586 0.3546394 0.7064014 -0.3730442 0.4993402 0.7819831 -0.7640778 0.3036187 0.5692107 -0.4870389 0.5682517 0.6632369 -0.9429955 0.1999266 0.2660619 -0.7539958 0.4679463 0.4609952 -0.6901249 0.5893764 0.4199562 -0.6727083 0.5927084 0.4428999 -0.4097305 0.8299786 0.3784925 -0.9155035 0.3541369 0.1908938 -0.6598317 0.715994 0.2279798 -0.6613679 0.7211925 0.2060921 -0.2450462 0.9566057 0.1576642 -0.820272 0.5633447 0.09897786 -0.5467274 0.8373076 -0.00225681 -0.6256179 0.7800692 -0.009715676 -0.9940367 0.1089872 0.003586411 -0.776955 0.6231092 -0.08986622 -0.72538 0.6727421 -0.1457472 -0.77542 0.5808964 -0.2475546 -0.6821511 0.6549263 -0.3251792 -0.6392897 0.6589397 -0.3963677 -0.7065114 0.5522561 -0.442555 -0.6412566 0.5751309 -0.5079512 -0.6123839 0.5159094 -0.5990188 -0.6989178 0.4316327 -0.5702695 -0.9957443 0.05721968 -0.07224541 -0.45324 0.4052528 -0.7939419 -0.9316834 0.1863056 -0.3118594 -0.5475491 0.3315732 -0.7682768 -0.3878374 0.2966673 -0.8726803 -0.8088489 0.2189215 -0.5457445 -0.5075532 0.1480346 -0.8488084 -0.8431019 0.1200863 -0.5241743 -0.4927409 0.1529886 -0.8566218 -0.9202476 0.05795401 -0.3870218 -0.5144959 0.03080856 -0.8569393 -0.7412615 -0.03597235 -0.6702518 -0.7540265 -0.0660777 -0.653512 -0.5502474 -0.1604335 -0.8194444 -0.9292482 -0.08128094 -0.3604044 -0.5206483 -0.2979096 -0.8001096 -0.8875529 -0.156661 -0.4332521 -0.581826 -0.2980532 -0.7567318 -0.6126577 -0.4298331 -0.6632452 -0.9499171 -0.1604906 -0.2681423 -0.7557028 -0.3938537 -0.523252 -0.7246235 -0.4609338 -0.5123093 -0.7845645 -0.4693555 -0.4051717 -0.6909849 -0.5859045 -0.4233862 -0.6798948 -0.6295337 -0.3760726 -0.7464182 -0.5970944 -0.2938337 -0.5834478 -0.7730569 -0.2489413 -0.6498978 -0.7188265 -0.2468222 -0.4331241 -0.8832677 -0.1795596 -0.9957011 -0.0901457 -0.02129054 -0.9549207 -0.2946677 -0.03602033 -0.508853 -0.855866 -0.09253126 -0.7048841 -0.7089644 -0.02253884 -0.8554767 -0.5176692 -0.01335525 -0.4943231 -0.8658058 0.07762193 -0.5268188 -0.8285168 0.1897948 -0.6533225 -0.7266536 0.2124724 -0.825731 -0.5417533 0.1570722 -0.5051537 -0.7999944 0.3237728 -0.8711286 -0.4682161 0.1480165 -0.6342736 -0.6666784 0.3914551 -0.8622291 -0.4374988 0.2552564 -0.5330448 -0.7072403 0.4644078 -0.9209208 -0.3229702 0.218163 -0.5376815 -0.6416673 0.5469568 -0.7421697 -0.4662667 0.4814348 -0.7506284 -0.4458154 0.4876533 -0.009992957 -0.5891842 0.807937 0.002772569 -0.4912087 0.8710376 0.003408074 -0.4970561 0.8677118 0.006401777 -0.3672295 0.9301084 -0.006652295 -0.3005268 0.9537502 0.006594955 -0.1121481 0.9936697 -0.004913926 -0.02716821 0.9996188 -0.004255294 -0.02968376 0.9995503 0.002641379 0.184694 0.9827925 -0.002724587 0.2143257 0.9767585 0.003537237 0.3688306 0.9294899 -0.001419782 0.3421429 0.9396468 -0.004221856 0.5349859 0.8448505 0.00551331 0.5796098 0.8148757 -0.003018677 0.693484 0.7204658 0.006253182 0.7550397 0.6556494 -0.003505825 0.7911171 0.6116547 3.90804e-4 0.8970928 0.4418421 -0.003559827 0.9051575 0.4250615 0.005955696 0.972384 0.2333107 -0.003823459 0.9864352 0.1641069 0.008000493 0.9976449 0.06812274 1.72688e-4 0.9978443 -0.06562578 9.97152e-4 0.997354 -0.07269179 -0.005878746 0.971584 -0.2366222 1.41202e-4 0.9607553 -0.2773976 -0.006610333 0.9346197 -0.3555875 0.0042364 0.8811627 -0.4727944 0.002360224 0.7795314 -0.6263589 -0.004026353 0.836196 -0.548416 -6.63785e-4 0.7639275 -0.6453019 0.003812611 0.6619604 -0.7495291 -0.002739131 0.6295151 -0.7769834 0.001630187 0.5159144 -0.8566386 -0.003535747 0.4869117 -0.8734441 0.003310739 0.328895 -0.9443607 0.002974748 0.3270836 -0.9449908 0.005313575 0.1198577 -0.9927769 4.10808e-4 0.1535083 -0.9881473 -0.006254613 -0.005552411 -0.9999651 0.002149462 -0.1048029 -0.9944907 -0.002474784 -0.1506529 -0.9885836 0.006007552 -0.2738398 -0.9617566 -0.007028758 -0.3597111 -0.9330374 0.008106648 -0.5004848 -0.8657075 -0.006119191 -0.5694254 -0.8220204 -0.003690481 -0.6790774 -0.7340575 -0.002171277 -0.6857593 -0.7278252 -0.005540788 -0.7823374 -0.6228303 6.3705e-4 -0.8089888 -0.5878237 -0.006176292 -0.8723235 -0.4888902 0.001572132 -0.9103204 -0.4139013 -4.32573e-4 -0.925311 -0.3792091 0.007555365 -0.9554834 -0.2949483 0.004207968 -0.9761286 -0.217153 0.001809895 -0.9786368 -0.2055894 0.002908945 -0.9998675 0.01601755 -0.002641439 -0.9993734 -0.03529888 0.003210604 -0.9917491 0.1281542 -6.93532e-4 -0.9975931 0.06933808 -0.002171039 -0.9778438 0.2093245 0.005022287 -0.9590879 0.283064 0.003819167 -0.9051405 0.4250956 -0.001663029 -0.9229435 0.3849319 -0.002600073 -0.8250535 0.5650488 0.004034638 -0.8419437 0.5395503 -0.005218565 -0.7463126 0.6655752 0.004257023 -0.6929486 0.7209745 -0.9999635 0.004980802 -0.006949186 -0.9999763 -9.45654e-4 -0.006836593 -0.9999677 0.004568219 -0.006629467 -0.9998956 -0.007707774 -0.01221871 -0.9999294 -0.01107883 -0.004312038 -0.9999197 -0.0123732 -0.002743005 -0.9999741 -0.005574226 -0.004550874 -0.9999039 0.009504854 -0.01009953 -0.9998199 0.01376986 0.01306289 -0.9999716 -0.006608128 -0.003627955 -0.999985 0.00450164 -0.003149628 -0.9999862 0.004492402 -0.002730786 -0.9999914 -0.004163503 5.41466e-5 -0.9999882 -0.004594624 0.001636266 -0.9999737 0.006873488 0.002321779 -0.9999646 0.008401513 4.76823e-4 -0.9999837 -0.003532111 0.00451678 -0.9999635 0.008551716 -1.14294e-4 -0.9999563 -0.009199857 0.001662731 -0.9999873 0.004389166 0.002508878 -0.9998478 -0.002278089 0.01729804 -0.9998924 -0.008852362 0.01170158 -0.9996548 -0.02105712 0.01571643 -0.9999863 0.003746509 0.003674983 -0.9999803 0.005045771 0.003753721 -0.9996635 0.01813137 0.01855206 -0.9999737 -7.6495e-4 0.007212519 0.4485223 -0.6032349 0.6594964 0.9782158 -0.1105306 0.1757178 0.9245359 -0.2583905 0.2801211 0.5486996 -0.5786566 0.6033949 0.6419886 -0.6162664 0.456143 0.6969016 -0.5860138 0.4134201 0.7684954 -0.5222203 0.3697308 0.5789695 -0.7433538 0.3349921 0.9418408 -0.3142107 0.1191956 0.7036833 -0.6771422 0.2151938 0.7365599 -0.6476686 0.1949485 0.6884399 -0.7174676 0.1062586 0.467818 -0.8830844 -0.03617036 0.7318657 -0.6800308 0.04394209 0.9295693 -0.3679085 -0.02333217 0.4906624 -0.8633548 -0.117766 0.7700285 -0.620841 -0.1470129 0.7643494 -0.609151 -0.2114359 0.7270349 -0.6444916 -0.2367508 0.9533676 -0.2703913 -0.1340849 0.5708616 -0.7272621 -0.3810603 0.6029121 -0.662626 -0.4443241 0.4556443 -0.7125806 -0.5334953 0.8560011 -0.4198445 -0.3016499 0.4305034 -0.6313602 -0.6450203 0.9162745 -0.2787069 -0.2876867 0.6307588 -0.4972434 -0.5957285 0.7732018 -0.3935791 -0.497247 0.2133328 -0.4897246 -0.8453751 0.7929573 -0.3106374 -0.5241405 0.6584094 -0.3196993 -0.6813879 0.6653215 -0.2284889 -0.7107321 0.6195869 -0.2255719 -0.7518175 0.5206569 -0.07294154 -0.8506444 0.9587488 -0.04518765 -0.2806399 0.6584613 0.003458797 -0.7526068 0.8321288 0.008776545 -0.554513 0.4132589 0.1064326 -0.9043723 0.9336553 0.08283573 -0.3484624 0.6216264 0.2515942 -0.7418093 0.598044 0.2523091 -0.7607126 0.8646468 0.1500441 -0.4794505 0.5832653 0.4176059 -0.6967115 0.8449741 0.281403 -0.4547871 0.6220368 0.415212 -0.6638293 0.5728564 0.5277734 -0.627129 0.9610617 0.1817876 -0.2081198 0.7028273 0.497541 -0.5084159 0.8899602 0.3250394 -0.3198751 0.4689537 0.707742 -0.5283785 0.5874286 0.6961315 -0.4127088 0.776977 0.5459869 -0.3133769 0.4355607 0.7968009 -0.4188021 0.9089845 0.3839948 -0.1621579 0.3918929 0.8792873 -0.2706914 0.6729089 0.7214933 -0.1632216 0.6804709 0.7260304 -0.09919327 0.7970627 0.6037558 -0.01303935 0.7230923 0.6885784 0.05474758 0.747303 0.6519352 0.1285256 0.5012348 0.8299343 0.2448934 0.4671596 0.7950984 0.3867564 0.4817663 0.7888957 0.3815035 0.9504583 0.2884715 0.1158154 0.7759616 0.552628 0.304115 0.1505289 0.7493637 0.6448218 0.9972833 0.06458431 0.03542518 0.7895316 0.4550702 0.4117658 0.7268232 0.4882338 0.4830691 0.7388783 0.4429573 0.5077872 0.4047227 0.5121264 0.7575793 0.9299147 0.1949886 0.3118307 0.858135 0.2171942 0.4652215 0.5349267 0.3278452 0.7786983 0.5092996 0.3391017 0.790964 0.5755159 0.2236359 0.7866184 0.3902831 0.1568506 0.9072359 0.9019836 0.09668207 0.4208067 0.5235023 0.06422275 0.8496004 0.9378166 0.04996114 0.3435171 0.7407909 0.00766927 0.671692 0.4914414 -0.1587426 0.8563213 0.7005673 -0.0901252 0.7078722 0.4406088 -0.2755637 0.8543586 0.9429777 -0.1007295 0.3172487 0.7725321 -0.2754834 0.572104 0.4164776 -0.4872254 0.7675662 0.7642992 -0.2941255 0.573879 0.02112549 -0.2895511 -0.9569295 0.0254749 -0.2937292 -0.9555492 0.02508729 0.6887033 -0.7246092 0.02112716 0.6858665 -0.7274206 0.02539443 0.9729315 0.2296946 0.02578127 0.9728294 0.2300834 0.08252167 -0.05340945 0.9951572 0.1204748 -0.136289 0.9833164 0.1498287 -0.127988 0.9803931 0.06408268 -0.07546848 0.9950869 0.03446447 0.01274567 0.9993247 6.82675e-5 9.77133e-4 0.9999995 0.003532588 -0.001932859 0.999992 -4.82694e-4 -8.24111e-4 0.9999996 0.01667547 -0.01080554 0.9998027 0.03907495 0.01963835 0.9990434 0.006249308 -0.02232861 0.9997312 0.05017304 0.01645308 0.998605 0.09750467 0.1456448 0.9845204 0.04269558 0.1536121 0.9872084 -0.01582753 0.4026564 0.9152144 0.2840392 0.6376575 0.716041 0.2599617 0.3739864 0.8902551 0.5236478 0.4308858 0.7349357 0.484502 0.1555764 0.8608449 0.4355618 0.1060534 0.8938896 0.6513004 -0.02522164 0.7584008 0.5455305 -0.263692 0.7955269 0.581549 -0.2611278 0.7704629 0.3999388 -0.4649575 0.7898502 0.2544928 -0.4272574 0.867574 0.1066226 -0.5331733 0.8392603 0.1033142 -0.5558105 0.8248642 -0.1272709 -0.5286322 0.8392558 -0.1359051 -0.5391453 0.8311753 -0.3458344 -0.5045784 0.7910748 -0.3461529 -0.6055705 0.7165631 -0.5094179 -0.2886319 0.8106696 -0.5274925 -0.327924 0.7837204 -0.5940009 -0.08680462 0.7997674 -0.4806188 0.02903354 0.876449 -0.5959133 0.160352 0.7868766 -0.4096207 0.2877829 0.8656743 -0.4263994 0.3165419 0.8473398 -0.3361417 0.5356674 0.7746414 -0.1236268 0.4416283 0.88864 -0.08955585 0.5605558 0.82326 0.1309552 0.5965886 0.7917909 0.1858223 0.4429851 0.87706 0.4313328 0.5388059 0.7236299 0.4929648 0.3017208 0.8160579 0.6530517 0.2563385 0.7126109 0.5535803 0.07064336 0.8297942 0.6571944 -0.08019822 0.7494423 0.457188 -0.2364249 0.8573695 0.5472707 -0.3821347 0.7446261 0.2192373 -0.4395635 0.8710448 0.2295424 -0.5449846 0.8064131 -0.07723933 -0.5578618 0.8263319 -0.06791394 -0.581445 0.8107463 -0.2711632 -0.4531802 0.849175 -0.2712128 -0.4521411 0.8497129 -0.4857614 -0.3265128 0.8108177 -0.4447138 -0.2401079 0.8628892 -0.5840404 -0.04533708 0.8104577 -0.55249 -0.02328246 0.8331944 -0.5430553 0.2155119 0.8115698 -0.556086 0.21246 0.8035106 -0.4212775 0.4715587 0.7746986 -0.4098625 0.4685572 0.7826027 -0.06189918 0.5196299 0.8521464 -0.117898 0.5733886 0.8107562 0.08762723 0.6138875 0.784515 0.2377796 0.458842 0.8561103 0.2340776 0.4963286 0.8359819 0.4559301 0.4677363 0.7571991 0.4879249 0.293219 0.8221631 0.6358831 0.2552219 0.7283643 0.5824133 0.04913014 0.8114069 0.6756468 -0.03568655 0.7363613 0.4067179 -0.2471531 0.8794862 0.4565758 -0.3175204 0.8310953 0.3760195 -0.5029756 0.7782191 0.1691945 -0.4301411 0.886765 0.1413365 -0.5569632 0.8184229 -0.04347211 -0.6139062 0.7881811 -0.1444832 -0.4344415 0.8890361 -0.2784335 -0.5270679 0.8029161 -0.436712 -0.3784945 0.8161033 -0.3933517 -0.2538219 0.8836566 -0.6462478 -0.1683514 0.7443263 -0.4880994 0.064493 0.870402 -0.6687315 -0.01896083 0.7432622 -0.5408237 0.2990428 0.7861828 -0.3618781 0.3038427 0.8813195 -0.3235915 0.5560207 0.765591 -0.1871811 0.4913011 0.8506388 -0.08121013 0.6512283 0.7545242 0.1327645 0.5827364 0.801743 0.1686177 0.4944113 0.8527167 0.352804 0.5082067 0.785656 0.3624549 0.2878212 0.8864455 0.4743418 0.2988061 0.8280791 0.5804494 0.1468023 0.8009542 0.5141792 0.05767154 0.8557417 0.6682435 -0.08002197 0.7396264 0.4719738 -0.2822149 0.835222 0.5008919 -0.3541802 0.7897239 0.3071047 -0.4176019 0.8551581 0.3147621 -0.4947013 0.8100589 0.1337943 -0.5628337 0.8156698 0.03345745 -0.4739334 0.8799248 -0.08569085 -0.5898761 0.8029342 -0.231694 -0.4614511 0.8563766 -0.2604267 -0.4820489 0.8365446 -0.4514214 -0.4188982 0.7878724 -0.4314362 -0.3408073 0.8352923 -0.6658086 -0.1491689 0.7310593 -0.5577348 -0.02241468 0.8297165 -0.5359454 0.1276534 0.834546 -0.4734568 0.1446934 0.8688513 -0.4699953 0.3967838 0.7884587 -0.2595723 0.3867083 0.8849176 -0.2574144 0.6362402 0.72728 -0.007157146 0.4631556 0.8862481 0.125028 0.5904033 0.7973656 0.2366955 0.4139391 0.8789936 0.3634872 0.4765479 0.8004868 0.437152 0.25577 0.8622528 0.4939635 0.2553458 0.831143 0.5599304 0.05068171 0.8269881 0.5377853 0.05628103 0.8412013 0.5373288 -0.2754528 0.7971221 0.6185095 -0.276643 0.7354691 0.2740082 -0.501747 0.8204691 0.2643004 -0.4590721 0.8481734 0.09990227 -0.6343302 0.7665799 -0.1124758 -0.4541112 0.8838169 -0.09929049 -0.5026821 0.8587504 -0.3770483 -0.483686 0.7898623 -0.3491133 -0.33256 0.8760845 -0.7412942 -0.1401349 0.656388 -0.4264429 -0.1319267 0.8948418 -0.6485395 0.04561924 0.7598128 -0.50229 0.1655619 0.8487014 -0.57938 0.3045361 0.756027 -0.3711778 0.5130652 0.7739453 -0.3612908 0.4141467 0.835435 -0.2139716 0.5163971 0.8291864 -0.1258007 0.4654056 0.8761118 -0.02866119 0.6280715 0.7776277 0.1997696 0.4754205 0.8567774 0.200936 0.4678606 0.8606575 0.4076926 0.4615814 0.7878638 0.4224227 0.2510337 0.8709428 0.4760811 0.254301 0.84183 0.5815911 0.04018825 0.8124881 0.4779191 -0.05925995 0.8764028 0.5902507 -0.1720253 0.788677 0.4026392 -0.3205323 0.8574035 0.433461 -0.4038933 0.805594 0.2259989 -0.4863567 0.844027 0.2273616 -0.5541536 0.8007625 0.02166193 -0.5767039 0.8166661 -0.1014677 -0.4136987 0.9047419 -0.2105779 -0.5185259 0.8287267 -0.3782989 -0.4206201 0.8246023 -0.354752 -0.4095627 0.8404818 -0.535837 -0.1898648 0.8226969 -0.4109458 -0.1810307 0.8935052 -0.6565932 -0.05810207 0.7520037 -0.483142 0.149612 0.8626645 -0.5064155 0.1733057 0.8446944 -0.4689313 0.3646498 0.8044465 -0.3106853 0.3701881 0.875463 -0.3065157 0.544503 0.7807463 -0.1227279 0.5072573 0.8530111 -0.0353502 0.6662826 0.744861 0.2219364 0.5665869 0.7935512 0.2032927 0.5499181 0.8101001 0.3863505 0.4579123 0.8006559 0.364949 0.3127248 0.8769354 0.5356649 0.2743664 0.7986153 0.4683159 0.03608441 0.882824 0.570021 0.002474248 0.8216264 0.5508339 -0.2601779 0.7930257 0.501277 -0.2642332 0.8239553 0.4238342 -0.4975387 0.7568486 0.2216441 -0.4843731 0.8463195 0.1769201 -0.586498 0.790392 0.0660631 -0.5395725 0.8393433 -0.03088867 -0.6627953 0.7481634 -0.254292 -0.5364487 0.8047102 -0.3537051 -0.5770257 0.7361617 -0.3996227 -0.312091 0.861917 -0.5168798 -0.2854843 0.8070527 -0.4610393 -0.1210026 0.8790911 -0.6591215 -0.02544659 0.7516058 -0.4377478 0.1623927 0.8843109 -0.526089 0.2678555 0.8071456 -0.3717104 0.4638118 0.804183 -0.2513148 0.4047864 0.8791978 -0.07524478 0.6282261 0.7743839 0.01853388 0.5060421 0.8623096 0.2908657 0.6490094 0.7029822 0.3252232 0.3505963 0.8782439 0.4517401 0.2874138 0.8445852 0.4413971 0.2386759 0.8649869 0.5886587 0.1679916 0.7907337 0.5136695 -0.001228868 0.8579873 0.603904 -0.06598424 0.7943212 0.419282 -0.2353892 0.8768093 0.5283113 -0.4190565 0.7384301 0.1875891 -0.4492039 0.8735137 0.1899168 -0.512799 0.8372388 -0.05895102 -0.5836058 0.8098946 -0.1490134 -0.454892 0.877991 -0.2322907 -0.5185452 0.8228924 -0.3839593 -0.3271028 0.8634691 -0.4020191 -0.4142873 0.8165457 -0.5710213 -0.232164 0.7874227 -0.496142 -0.08969199 0.8635962 -0.6997579 0.04467844 0.7129816 -0.5143881 0.263373 0.8161125 -0.5475713 0.3338999 0.7672526 -0.2886898 0.4225981 0.8591095 -0.3206588 0.440133 0.8387258 -0.06033104 0.5177311 0.8534137 -0.0394293 0.5878161 0.8080331 0.2161216 0.4657329 0.8581284 0.1834448 0.429269 0.8843507 0.476822 0.480266 0.7361966 0.43292 0.1879724 0.8816159 0.6139716 0.1619475 0.772536 0.5029439 -0.09013432 0.8596066 0.5682654 -0.1365416 0.8114376 0.3750804 -0.3416133 0.8617511 0.4019913 -0.4036428 0.8218733 0.2113364 -0.7897929 0.5758162 0.2114626 -0.4971533 0.8415 -0.006349444 -0.6301781 0.7764247 -0.1285661 -0.4333918 0.8919879 -0.2644789 -0.535681 0.8019332 -0.3824051 -0.3995341 0.83315 -0.4660942 -0.4160342 0.7808148 -0.6109412 -0.2388454 0.7547873 -0.5111376 -0.09413486 0.8543284 -0.6394407 0.1041913 0.7617478 -0.4480506 0.1857463 0.8744994 -0.4983528 0.3051241 0.8115072 -0.3603783 0.4155471 0.8351336 -0.3052445 0.4011805 0.8636435 -0.177488 0.5587795 0.8101009 -0.06337422 0.4889472 0.8700083 0.003847062 0.5909779 0.8066786 0.1854195 0.5474317 0.8160504 0.2210407 0.4086447 0.8855227 0.3867185 0.4522609 0.8036848 0.4651059 0.2833692 0.8386767 0.4243859 0.2019227 0.88268 0.5947716 0.1231944 0.7943992 0.5346866 -0.07451802 0.8417585 0.4758763 -0.1025579 0.8735124 0.3335191 -0.3048042 0.8921096 0.5184859 -0.3325518 0.78777 0.2294264 -0.5750739 0.785273 0.06221944 -0.4357353 0.8979219 -0.06740576 -0.6202996 0.7814633 -0.1920661 -0.7296169 0.6563306 -0.2310937 -0.4699109 0.8519269 -0.4390619 -0.3884786 0.8101292 -0.4143052 -0.3149511 0.853907 -0.4665001 -0.04595834 0.8833265 -0.5345982 -0.1375498 0.8338375 -0.6226384 0.06040716 0.7801747 -0.4848017 0.2178854 0.8470498 -0.5488481 0.3303508 0.7678765 -0.3501326 0.5088855 0.7864114 -0.3535464 0.5737029 0.7388302 -0.101056 0.6013439 0.7925739 -1.08713e-4 0.505527 0.8628108 0.1290049 0.5996725 0.7897788 0.2474799 0.4155281 0.8752658 0.326324 0.461316 0.8250457 0.4878213 0.3055509 0.8177219 0.4847655 0.2974132 0.8225253 0.6477253 0.1591453 0.745067 0.5531897 -0.05713886 0.8310936 0.6245958 -0.1080961 0.773431 0.4239041 -0.2738791 0.8633051 0.4996578 -0.4472644 0.7418198 0.1993998 -0.5372347 0.8195235 0.1932744 -0.5641026 0.8027661 5.51626e-4 -0.4857947 0.8740728 -0.05978214 -0.5805372 0.8120362 -0.2809956 -0.5257946 0.8028584 -0.2851934 -0.3987156 0.8716024 -0.4518246 -0.3966068 0.7990981 -0.4772472 -0.1934397 0.8572143 -0.5585174 -0.1799151 0.8097462 -0.5146601 0.04045146 0.8564396 -0.5791043 0.07775151 0.8115374 -0.4592216 0.3140531 0.8309549 -0.3771433 0.3139276 0.871328 -0.3570801 0.5006673 0.7885595 -0.1426985 0.4785168 0.8664057 -0.1385259 0.5058979 0.8513977 0.04162883 0.6239232 0.7803763 0.1710831 0.4748741 0.8632643 0.1923778 0.4923807 0.8488534 0.3797279 0.4378296 0.8149307 0.3840808 0.3098211 0.869766 0.4985921 0.3046372 0.8115431 0.5360316 0.1001893 0.8382317 0.4865003 0.0403288 0.8727491 0.6598839 -0.09017258 0.7459372 0.4136003 -0.2516781 0.8749817 0.4699897 -0.3842547 0.7946435 0.3699221 -0.4109838 0.8332167 0.3027139 -0.6057468 0.7358229 0.1349044 -0.5513335 0.8233057 -0.02989631 -0.7021095 0.7114412 -0.1402077 -0.5314599 0.8353995 -0.353003 -0.5328516 0.7690632 -0.3712582 -0.3739769 0.8498874 -0.553075 -0.3351047 0.7627667 -0.439157 -0.109314 0.8917353 -0.6244189 -0.02687287 0.7806273 -0.4825654 0.1569595 0.8616812 -0.5589774 0.2517963 0.7900272 -0.492424 0.4531092 0.7431089 -0.29734 0.4569905 0.8383011 -0.2787901 0.5782961 0.7667136 -0.006905078 0.5025877 0.8644987 0.00472486 0.530957 0.8473857 0.1774337 0.5804434 0.7947344 0.2480265 0.4235702 0.8712469 0.3851838 0.4614449 0.7991886 0.4795438 0.2652704 0.8364626 0.4731231 0.2554227 0.8431571 0.596103 0.02404582 0.802548 0.4793294 -0.06110298 0.8755056 0.5537682 -0.1820142 0.8125341 0.393588 -0.332478 0.857057 0.4049059 -0.3516556 0.8440318 0.1913517 -0.5890856 0.7850877 0.07738107 -0.4765039 0.8757604 -0.101415 -0.6291658 0.7706267 -0.1591262 -0.5206275 0.8388241 -0.3991123 -0.5336969 0.7455717 -0.4456962 -0.2978639 0.8441753 -0.4944341 -0.3054428 0.8137811 -0.48751 0.02786844 0.8726726 -0.5564104 -0.0127508 0.8308098 -0.5874543 0.2757058 0.7608441 -0.4248526 0.3028081 0.8531164 -0.4256746 0.5385244 0.7271813 -0.1139388 0.5065948 0.8546226 -0.1591054 0.5407731 0.8259842 0.03543752 0.6139889 0.7885187 0.1707159 0.4413512 0.8809456 0.2427358 0.5075179 0.8267436 0.4245626 0.4485504 0.7864791 0.4201121 0.211434 0.8824974 0.4388887 0.2406274 0.8657224 0.6270543 0.04463893 0.7776956 0.4594299 -0.0861901 0.8840223 0.5743032 -0.228567 0.7860871 0.3109933 -0.3411485 0.8870744 0.3364645 -0.4046603 0.8503186 0.1997312 -0.6007225 0.774106 -0.007689952 -0.4693174 0.8829961 -0.04612094 -0.5446688 0.8373821 -0.2752453 -0.5199419 0.8086413 -0.2945386 -0.4380682 0.8493195 -0.4761861 -0.4571116 0.7511962 -0.5391364 -0.225166 0.8115617 -0.5472369 -0.2393087 0.8020368 -0.6495387 -0.005629539 0.7603077 -0.5851802 0.05356389 0.8091322 -0.6361927 0.2616548 0.7258069 -0.3941226 0.3187264 0.8620214 -0.3874906 0.5204647 0.7608993 -0.1669582 0.4516993 0.8764089 -0.1267921 0.5804339 0.8043757 0.1086761 0.4977544 0.8604825 0.115462 0.5077626 0.8537247 0.3134001 0.5503435 0.7738879 0.3769072 0.354192 0.8558558 0.368091 0.3267049 0.8705016 0.5730827 0.1825751 0.798901 0.5034754 0.06516921 0.8615484 0.6248313 -0.02558082 0.7803407 0.5612553 -0.194536 0.8044553 0.4437065 -0.2125496 0.8706016 0.4206252 -0.5363368 0.7317222 0.396999 -0.4267266 0.8125861 0.243599 -0.4963717 0.8332315 0.1685996 -0.4582921 0.8726641 0.0545361 -0.6125751 0.7885288 -0.1250395 -0.4589637 0.8796122 -0.1789223 -0.5226764 0.8335444 -0.4292678 -0.4425812 0.7873063 -0.3986992 -0.2919441 0.869372 -0.5804978 -0.2272486 0.7819082 -0.5288793 -0.1299708 0.8386861 -0.6538922 0.03524535 0.7557665 -0.5407091 0.156846 0.8264581 -0.6025663 0.3377086 0.7230954 -0.4116001 0.3776507 0.8294368 -0.1601595 0.5072663 0.8467762 -0.3461741 0.5943474 0.7258889 -8.82919e-4 0.6122599 0.790656 0.0927661 0.4942525 0.8643547 0.2050575 0.5913415 0.7799145 0.4342699 0.3683259 0.8220375 0.5090374 0.3971076 0.7636665 0.4588651 0.08164846 0.8847466 0.6761047 -9.43536e-4 0.736805 0.4904221 -0.2749207 0.8269853 0.4934552 -0.2787926 0.8238792 0.2892503 -0.478053 0.8293368 0.3284871 -0.5015749 0.8003242 -0.07120895 -0.5222803 0.8497956 0.004379153 -0.6356941 0.7719287 -0.2788658 -0.5694915 0.7732486 -0.2958862 -0.3487442 0.8892856 -0.5665025 -0.3753686 0.7336031 -0.4984376 -0.08107519 0.8631262 -0.4401747 -0.03352308 0.8972862 -0.6095584 0.1055111 0.7856884 -0.5496473 0.2739784 0.7891919 -0.4070844 0.2928599 0.8651679 -0.4387363 0.4790865 0.7602543 -0.1936426 0.5424056 0.8174955 -0.1655235 0.6352767 0.7543378 0.1041568 0.6025814 0.7912315 0.06408232 0.5392138 0.8397272 0.3045414 0.4865427 0.8188595 0.3107605 0.4040036 0.860354 0.5104087 0.38199 0.7704327 0.4565958 0.181304 0.8710047 0.6213589 0.09541529 0.7776947 0.4953297 -0.03604346 0.8679571 0.5808864 -0.2202396 0.7836235 0.3985372 -0.2709782 0.8762072 0.4398999 -0.398079 0.8049976 0.2995049 -0.5220119 0.7986241 0.144379 -0.4484617 0.882064 0.06367683 -0.5974989 0.7993375 -0.07574647 -0.4704221 0.8791846 -0.2644673 -0.605438 0.7506677 -0.2789484 -0.4214277 0.8628942 -0.6492133 -0.3188223 0.690561 -0.5306833 -0.2983872 0.7933098 -0.632257 -0.01954478 0.7745122 -0.5207186 0.06422674 0.8513091 -0.5768497 0.2245454 0.7853814 -0.4793832 0.25689 0.8391659 -0.4575713 0.5011277 0.7345064 -0.321212 0.4825155 0.814863 -0.1383014 0.6653382 0.7336197 0.01707023 0.5048212 0.8630552 0.2118536 0.6400719 0.7385297 0.2964546 0.3631774 0.8832989 0.3845238 0.4009196 0.8315078 0.5442645 0.2792859 0.7910599 0.4474055 0.0663349 0.8918678 0.5894322 0.02194046 0.8075199 0.5435705 -0.2357673 0.8055712 0.4286579 -0.2523623 0.8675054 0.4305565 -0.4334116 0.7916916 0.2476437 -0.438556 0.8639105 0.2272814 -0.5426835 0.8086025 0.01961714 -0.4885262 0.8723288 -0.02890086 -0.5741348 0.8182507 -0.2411001 -0.4319168 0.8690907 -0.2229011 -0.5108407 0.8302753 -0.4286926 -0.4802502 0.7652336 -0.4448874 -0.1766903 0.877984 -0.5069115 -0.174598 0.8441305 -0.603653 0.02485692 0.7968597 -0.555031 0.05407184 0.8300704 -0.6135124 0.2928618 0.733372 -0.4027621 0.3628059 0.8403301 -0.3774514 0.4745985 0.7951646 -0.19602 0.4522787 0.8700692 -0.1824525 0.5760331 0.7968042 -0.004716515 0.5396538 0.8418739 0.1506574 0.6811705 0.7164559 0.332419 0.4434646 0.8323683 0.3515114 0.4546738 0.8183591 0.5625764 0.2125247 0.7989626 0.4780834 0.1296826 0.8686879 0.5851737 -0.09660327 0.8051334 0.431871 -0.1662788 0.8864755 0.5077888 -0.3202189 0.7997565 0.3647518 -0.4587813 0.8102321 0.3019118 -0.4357861 0.8479033 0.1851775 -0.6396597 0.7460193 -0.03397804 -0.5589945 0.828475 -0.04590857 -0.5725786 0.8185636 -0.2165835 -0.4469999 0.8679186 -0.2633821 -0.4858939 0.833389 -0.4491288 -0.3587049 0.8182996 -0.4117819 -0.1994729 0.889183 -0.5367624 -0.1895574 0.8221644 -0.5887386 0.06229072 0.8059199 -0.4478574 0.1338367 0.8840314 -0.569722 0.3206323 0.7567112 -0.2965292 0.4284523 0.8535216 -0.2746385 0.4164156 0.8667018 -0.06231701 0.5851818 0.8085041 -0.03793478 0.5578182 0.8290959 0.1813139 0.6439556 0.7432674 0.2954689 0.4745409 0.8291617 0.4135504 0.5139143 0.7515771 0.425215 0.2708485 0.8636164 0.6150606 0.2471823 0.7487332 0.6023003 -0.0110985 0.7981925 0.6254862 -0.0274744 0.7797514 0.5966632 -0.2459182 0.763883 0.5184898 -0.2671161 0.8122915 0.4685931 -0.4680981 0.7492027 0.3089032 -0.4714725 0.82601 0.2626099 -0.5964862 0.758446 0.00516653 -0.5435148 0.8393838 -0.03477025 -0.6211997 0.7828806 -0.1658275 -0.4992154 0.8504619 -0.3523979 -0.5752053 0.7382105 -0.4085898 -0.2746828 0.8704045 -0.4396097 -0.3745725 0.8163571 -0.5005201 -0.1044589 0.8593999 -0.4931797 -0.1049709 0.8635711 -0.5071677 0.1658701 0.8457353 -0.4211928 0.1952657 0.885702 -0.5172919 0.408837 0.7518388 -0.2245444 0.470095 0.8535752 -0.2928566 0.5129326 0.8069295 -0.07427424 0.6607866 0.74689 0.09704703 0.4829187 0.8702709 0.206721 0.5728981 0.7931295 0.3558593 0.3925656 0.8480899 0.369225 0.4669398 0.8035174 0.6028563 0.2798529 0.7471591 0.4930363 0.08273458 0.8660659 0.6329377 -0.008640289 0.7741546 0.4490724 -0.2115712 0.8680852 0.4634472 -0.2267765 0.856615 0.4126151 -0.468357 0.7812749 0.1882788 -0.4334065 0.8813115 0.1872407 -0.4999401 0.8455772 -0.09334146 -0.617606 0.7809292 -0.16926 -0.4079389 0.8971828 -0.3299093 -0.4992539 0.8011901 -0.4590549 -0.337812 0.8216761 -0.4078374 -0.205735 0.8895739 -0.6259804 -0.143188 0.7665806 -0.5240688 0.1047329 0.8452118 -0.5710295 0.09023648 0.8159551 -0.5337488 0.3562743 0.7669295 -0.3287656 0.4138715 0.8488955 -0.3347544 0.4401999 0.8331649 -0.215125 0.5938221 0.7753043 -0.08562588 0.5286676 0.8444992 0.02193439 0.678439 0.7343293 0.2357524 0.5179346 0.8222923 0.374459 0.5851126 0.7193217 0.4590187 0.3010734 0.8358567 0.5189867 0.3040997 0.7988594 0.4915875 0.02170234 0.8705577 0.5212715 0.01166653 0.8533111 0.5606553 -0.1745966 0.8094329 0.414222 -0.2486783 0.8755451 0.4839832 -0.4271402 0.7637484 0.1898618 -0.4240863 0.8854961 0.1842383 -0.6042519 0.7752006 -0.09407681 -0.5858122 0.8049682 -0.1169342 -0.5157133 0.8487439 -0.392458 -0.5238164 0.7560377 -0.4083425 -0.2883033 0.8661049 -0.5445032 -0.2963497 0.7846612 -0.5402359 -0.001733541 0.8415119 -0.4874977 0.02765929 0.8726861 -0.5760624 0.2333298 0.783396 -0.3845691 0.2994229 0.8731854 -0.4110401 0.488647 0.769591 -0.2294462 0.4466481 0.864789 -0.1092457 0.6291669 0.7695547 -0.08421641 0.6048259 0.7918921 0.1175775 0.6055047 0.7871084 0.2170711 0.4236664 0.8794243 0.3219798 0.4578585 0.8286705 0.3885085 0.315038 0.865917 0.5285896 0.3425939 0.776674 0.4515002 0.07997226 0.8886799 0.6749266 -0.02107566 0.7375838 0.5541294 -0.2517632 0.7934457 0.5649411 -0.2719349 0.7790334 0.3892598 -0.4431328 0.8075335 0.4010332 -0.4454805 0.8004496 0.257497 -0.6067792 0.7520069 0.09477448 -0.5604452 0.8227509 0.02075618 -0.6701979 0.7418922 -0.2166602 -0.4799838 0.8501023 -0.1816052 -0.5872402 0.7887766 -0.4044833 -0.4767342 0.78046 -0.4175677 -0.2630754 0.8697291 -0.414928 -0.2592941 0.8721247 -0.5949986 -7.32796e-4 0.8037264 -0.5276533 0.02758777 0.8490117 -0.5172337 0.2899584 0.8052288 -0.5219827 0.2977782 0.7992886 -0.3878961 0.4581481 0.7997732 -0.209736 0.3993019 0.8925071 -0.1375665 0.4447847 0.8850097 -0.06836986 0.3986365 0.914557 -0.04176938 0.4350795 0.8994228 0.1669235 0.3485779 0.9222962 0.489157 -0.6404395 0.5920835 0.2517753 -0.8220139 -0.5107862 -0.02353227 -0.9462877 0.3224684 -0.1384929 -0.9404721 -0.310374 -0.5435482 -0.8381425 0.04552537 -0.68553 -0.1298621 -0.716369 -0.8546185 0.1926485 0.4821967 -0.780309 0.431892 -0.4523134 -0.7973369 0.585255 0.1474128 -0.4334419 0.8980311 0.07528805 -0.3267191 0.7771154 -0.5379093 0.07990068 0.8032253 0.5902923 0.235348 0.5823493 -0.7781264 0.9535856 -0.3010911 -0.004325628 0.5574404 -0.7790119 0.2870556 0.4831879 -0.7476516 -0.4555727 -0.02217137 -0.8862178 0.4627382 -0.05318379 -0.9955224 0.0781458 -0.3673453 -0.7875533 -0.4947901 -0.5240562 -0.5815222 0.6222516 -0.7344828 -0.5046547 -0.4537166 -0.8578181 -0.2383951 0.4553195 -0.8873553 -0.1226216 -0.4444823 -0.7791455 0.3150154 0.5419387 -0.2673771 0.7142741 -0.6467784 0.1031002 0.8449534 0.5248088 0.3355777 0.71173 -0.6171126 0.6508279 -0.1904578 -0.7349482 0.6063209 -0.5980359 0.5241451 0.4148513 -0.7692382 -0.4859744 0.3947188 -0.9176293 -0.04640698 -0.2168717 -0.9677231 0.1283694 -0.2244117 -0.9744176 -0.01223945 -0.7694926 -0.6126061 -0.1805413 -0.7919068 -0.6079095 -0.05770319 -0.9272105 -0.01736205 0.3741382 -0.8591389 0.4632352 -0.2174711 -0.3211916 0.8557642 0.4055907 0.07788228 0.8061299 -0.586591 0.460069 0.7699916 0.4420967 0.6022819 0.6077755 -0.5175572 0.7688412 0.4994422 0.3993005 0.8468636 0.09312468 -0.5235932 0.573688 -0.3101353 0.7580886 0.535664 -0.5728099 -0.6204459 0.2561357 -0.7914209 0.5550203 0.1642042 -0.8895917 -0.4262203 -0.2219257 -0.8210428 0.5259637 -0.3198436 -0.839099 -0.4400147 -0.7899426 -0.5904374 0.1654522 -0.7653033 -0.1074727 0.6346341 -0.753763 0.1304848 -0.6440615 -0.6029087 0.4091721 0.6848937 -0.5254915 0.6029734 -0.6002348 -0.385539 0.8214786 0.4201579 -0.1174088 0.9052301 -0.4083795 0.07477098 0.883199 0.4630001 0.3402355 0.796484 -0.4998531 0.5180726 0.6559075 0.5489866 0.7097734 0.5248081 -0.4698917 0.8374721 0.2391342 0.4913811 0.9108627 0.1643855 -0.3785587 0.7581538 -0.3415218 0.5554869 0.4247995 -0.4660851 -0.7760865 0.2099981 -0.7361328 0.6434356 -0.05896157 -0.7771282 -0.6265745 -0.2666816 -0.8475676 0.4588138 -0.6404314 -0.6024242 -0.4763748 -0.9435188 -0.2477309 0.2200039 -0.9229232 0.3211619 -0.2122917 -0.4424372 0.5644821 0.6968568 -0.2996494 0.7400409 -0.602121 -0.01943886 0.8215268 0.5698387 0.2865331 0.7315665 -0.6186351 0.3196259 0.9185909 0.232444 0.7557803 0.5602061 -0.3390653 0.7253831 0.3698822 0.5805227 0.8171572 -7.00774e-4 -0.5764147 0.8135809 -0.2035096 0.5446743 0.7636225 -0.4904802 -0.4198929 0.6192697 -0.6589036 0.4270258 0.4371779 -0.7331243 -0.5209647 0.172328 -0.8013882 0.5727828 -0.1000391 -0.8857877 -0.4531803 -0.2516501 -0.9323225 0.2597057 -0.5625522 -0.7514058 -0.3448542 -0.6228557 -0.5058752 0.5967755 -0.7033641 -0.3371278 -0.6257985 -0.770888 0.004068553 0.6369577 -0.8197007 0.1560826 -0.5511161 -0.6738955 0.4673538 0.5722285 -0.6011752 0.5611304 -0.568965 -0.1778541 0.7997134 0.5734338 0.2295108 0.645983 0.7280321 0.5062867 0.5615362 -0.6544852 0.6896878 0.3601936 0.6281651 0.7611947 0.1567719 -0.6292895 0.8848227 -0.06292343 0.4616597 0.8612513 -0.4760867 -0.1777296 0.5827668 -0.8125768 0.01009058 0.08402132 -0.9360775 -0.3416131 -0.5944018 -0.5861457 0.5505632 -0.8107984 -0.3170148 -0.4920442 -0.8480537 -0.109937 0.5183809 -0.8391129 0.2036013 -0.5044167 -0.8578732 0.3743103 0.3520588 -0.5866796 0.7545734 -0.2939833 -0.5442103 0.8197115 0.1786291 0.04299515 0.9824115 -0.1817114 0.4926909 0.7444958 0.4505351 0.7455151 0.5112038 -0.4276423 0.7930149 0.2769268 0.5426225 0.8697946 0.09125417 -0.4849023 0.7862015 -0.2348072 0.5716229 0.8074524 -0.3390622 -0.4827604 0.4897933 -0.7858079 0.3776357 0.435715 -0.7867833 -0.437178 -0.08688747 -0.7933099 0.6025862 -0.1702322 -0.8343299 -0.5243231 -0.7031911 -0.6986747 0.1318176 -0.6528543 -0.5681315 0.5010071 -0.7816947 -0.1310862 -0.6097294 -0.7955862 0.310444 0.5202569 -0.5950549 0.7515627 -0.2847164 -0.6250512 0.7528154 0.2063493 -0.1960023 0.885882 -0.4204714 0.03479552 0.7809172 0.6236647 0.2326181 0.7177444 -0.6563017 0.4902027 0.621824 0.610767 0.7821469 0.407887 -0.4710355 0.8753597 0.4807201 -0.05151444 0.9886974 -0.08993095 -0.1199582 0.8865152 -0.1654848 0.4320944 0.5833174 -0.5613373 -0.5870617 0.1924998 -0.760949 0.6195971 -0.1806464 -0.8484556 -0.4974837 -0.1844431 -0.9756153 -0.1189776 -0.7009059 -0.692552 0.1705951 -0.9334976 -0.3566104 -0.03756713 -0.8841537 0.240702 0.4004184 -0.9357426 0.2865199 -0.2056509 -0.6339262 0.6796391 -0.3690913 -0.3907471 0.6684256 0.6328696 -0.2002477 0.8032133 -0.5610252 0.06466406 0.8496486 0.5233697 0.3223707 0.8169028 -0.478275 0.4950636 0.7909236 0.3596555 0.7698598 0.4794161 -0.4212792 0.7927123 0.3237552 0.5165172 0.8404988 -0.08078104 -0.5357578 0.7546078 -0.2820251 0.5924771 0.6776384 -0.4785968 -0.5583471 0.3649167 -0.6021239 0.7101287 0.1998402 -0.6721326 -0.7129528 -0.155421 -0.6300051 0.7608797 -0.6230514 -0.7240571 -0.2958858 -0.9752191 -0.1808642 0.1274196 -0.964718 -0.2177644 -0.1479791 -0.857662 0.402676 0.3197938 -0.1922152 0.7579365 -0.6233664 0.2281566 0.7719861 0.5932807 0.3280857 0.7398899 -0.5873013 0.7210916 0.4253032 0.5469408 0.9928585 0.05005687 0.108288 0.8174904 -0.5370632 -0.2080208 0.3451237 -0.7255635 0.5953548 0.09651499 -0.8143584 -0.5722807 -0.2035371 -0.7548802 0.623481 -0.3873457 -0.709674 -0.588495 -0.6160183 -0.5829645 0.5297867 -0.768983 -0.4126812 -0.4882205 -0.8812407 -0.1485047 0.4487331 -0.8924376 -0.02224367 -0.4506223 -0.8129022 0.2986894 0.4999746 -0.738097 0.4872626 -0.4666777 -0.7050751 0.6654772 0.2449681 -0.358546 0.8709713 -0.3359374 -0.3241348 0.9459615 0.009666621 0.1169124 0.9301792 0.3479918 0.2003248 0.831036 -0.5188922 0.5183385 0.7288822 0.4472762 0.6119305 0.6200973 -0.4909384 0.7914034 0.3497597 0.5013473 0.7915561 0.161897 -0.5892609 0.7635775 -0.1128571 0.6357773 0.7157695 -0.3179598 -0.621752 0.4993914 -0.5955485 0.62923 -0.5187171 -0.7922497 -0.3213613 -0.8759586 -0.3575105 0.3238564 -0.9009442 -0.3313789 -0.2801568 -0.9160308 0.3080536 0.2568863 -0.5151466 0.6475999 0.5614609 -0.1049523 0.9243508 -0.366825 0.03431552 0.8907468 0.4532029 0.345982 0.7855322 -0.5130651 0.5323344 0.6062764 0.5908039 0.6665949 0.4700132 -0.5785663 0.8312247 0.2517744 0.4956563 0.9372171 -0.02264082 -0.3480108 0.9579981 -0.1423406 0.2489552 0.7367528 -0.4990766 -0.4561996 0.7417432 -0.6406 0.1986169 0.3405129 -0.8727942 0.3496876 0.2201703 -0.7590318 -0.6126954 -0.2371849 -0.727374 0.643949 -0.4206091 -0.4855824 -0.7663537 -0.7993082 -0.3474338 0.4903023 -0.9460089 -0.02170878 -0.3234131 -0.9940453 -0.03358215 -0.1036641 -0.7965353 0.5783317 -0.1762503 -0.3566586 0.9171552 0.1778232 0.2460979 0.9157974 -0.3174129 0.3290067 0.7611663 0.5589102 0.636916 0.4581838 -0.6200045 0.8014166 0.3458305 0.4879885 0.9471229 -0.1164965 -0.2989764 0.9848566 -0.1018466 0.1403032 0.6951073 -0.6131184 -0.3753822 0.5577281 -0.6525825 0.5129089 0.09226036 -0.8973163 -0.4316382 -0.04091399 -0.890621 0.4529023 -0.4722962 -0.7016118 -0.5335516 -0.8701074 0.4533407 -0.1933787 -0.5205592 0.7326944 0.4383801 -0.3681114 0.7108082 -0.5993711 -0.02061921 0.8436573 0.536486 0.09481817 0.863458 -0.495429 0.4472838 0.6946716 0.5633549 0.5290972 0.6011074 -0.5989374 0.7708473 0.3169838 0.5525538 0.8448071 0.2033663 -0.4949173 0.9078908 -0.1236483 0.4005566 0.7155451 -0.2643841 -0.6466037 0.4630067 -0.5634142 0.6842436 0.3886572 -0.7815657 -0.4879558 0.02983391 -0.8028824 0.5953906 -0.09998452 -0.7366673 -0.6688232 -0.4315757 -0.558294 0.7085551 -0.5896338 -0.5541565 -0.5875734 -0.8754985 -0.185304 0.4462791 -0.450605 0.8743471 0.180201 -0.01172113 0.9298626 0.3677204 0.1011175 0.6356202 -0.7653512 0.6588765 0.687724 0.3048237 0.9742987 0.1614485 -0.1570876 0.9264864 -0.3215526 -0.195517 0.5470197 -0.837112 -0.003647923 0.07605022 -0.8157855 -0.5733327 -0.3909921 -0.7666387 0.5093038 -0.4295301 -0.6629501 -0.6131894 -0.7122488 -0.3084881 0.6305052 -0.6633495 -0.1525785 -0.7325895 -0.774478 0.1182146 0.6214573 -0.5754893 0.4095152 -0.7078908 0.08325725 0.8540093 0.5135529 0.4570138 0.750925 -0.4767075 0.5803789 0.5544324 0.5964605 0.7580676 0.4030313 -0.5127374 0.841009 0.1028814 0.5311492 0.9696497 0.0228393 -0.2434293 0.8947169 -0.4330002 0.10951 0.8254538 -0.4403144 -0.3531987 0.4310574 -0.6906562 0.5806751 0.3527657 -0.7696193 -0.5322055 -0.08327388 -0.9340254 0.3473644 -0.03164982 -0.9994397 -0.01090312 -0.5665304 -0.7973663 0.2079676 -0.9392919 -0.06962716 -0.3359802 -0.7950593 0.4582189 0.3973866 -0.1370556 0.9900239 -0.03268915 0.5436232 0.8372859 0.0585339 0.5437375 0.8181257 -0.1871358 0.9117687 0.2914578 0.2893614 0.8591271 0.2345561 -0.4548454 0.7930487 -0.3424694 0.5037742 0.8972576 -0.4255062 -0.117785 0.5396059 -0.7597191 -0.3628394 0.3492677 -0.7676271 0.5373648 0.1328903 -0.900977 -0.4130143 -0.1494514 -0.7864646 0.5992811 -0.2725081 -0.6785956 -0.6820905 -0.5939981 -0.483773 0.642752 -0.7444607 -0.4049174 -0.5308674 -0.8964316 -0.1736909 0.4077278 -0.7399069 0.09086841 -0.6665439 -0.4502264 0.3848544 0.8057191 -0.3638556 0.6092092 -0.7046087 0.004316031 0.6404795 0.7679632 0.355203 0.7777564 -0.5185807 0.6348965 0.4255506 0.6448358 0.6596336 0.2748327 -0.699536 0.8119781 -0.04376864 0.5820446 0.8007788 -0.1960883 -0.565953 0.6562925 -0.4692782 0.5908116 0.3999999 -0.5661711 -0.720729 0.03417009 -0.8507385 0.5244773 -0.2755391 -0.7890502 -0.5490701 -0.4877105 -0.6761919 0.5521802 -0.7441453 -0.4761107 -0.4685792 -0.8758159 -0.4754204 -0.08319932 -0.957066 0.161263 0.2408714 -0.9482505 0.1809635 -0.2609086 -0.6262069 0.7711732 0.1147037 -0.62093 0.7797962 -0.07977354 -0.04416412 0.9840179 0.172506 0.3882751 0.8359756 0.387798 0.7602985 0.4693753 -0.4490359 0.1885097 -0.8589803 -0.4760431 -0.3300088 -0.9009706 0.2816848 -0.6691944 -0.6189565 0.4111832 -0.8071298 -0.2646003 -0.5277577 -0.8184085 -0.04261416 0.5730548 -0.7886216 0.2534982 -0.5601916 -0.860923 0.4394916 0.25624 -0.4955667 0.8649314 0.07941806 -0.0133506 0.9123656 -0.4091588 0.5986028 0.7511662 0.2782521 0.684656 0.3004784 -0.6640475 0.8565922 -0.04074293 0.5143831 0.7575305 -0.2490344 -0.6034315 0.816752 -0.4801948 0.3198894 0.5785731 -0.8024694 0.1459317 0.3790231 -0.6251932 -0.6822572 -0.02382779 -0.6913954 0.7220837 -0.1665381 -0.6580706 -0.734308 -0.5060436 -0.6798648 0.5307578 -0.7192096 -0.4794677 -0.5028403 -0.8802506 -0.4341559 0.1914882 -0.9804026 0.1551372 -0.121422 -0.6514887 0.5297485 -0.5430737 -0.131389 0.8573954 0.4976046 0.7367064 0.6552675 0.1669976 0.9293525 0.1354948 -0.3434313 0.8755317 -0.002952933 0.4831517 0.8126347 -0.3687043 -0.4513115 0.7036192 -0.51647 0.4880357 0.4328423 -0.7202809 -0.5420729 0.2610635 -0.7886166 0.5567135 -0.1705603 -0.8008551 -0.5740561 -0.4884486 -0.5560756 -0.6724566 -0.7258663 -0.242787 0.6435624 -0.7294546 -0.05820882 -0.6815481 -0.7759309 0.2266135 0.5887084 -0.7490808 0.4614462 -0.4753372 -0.6072854 0.6773084 0.4152802 -0.5038295 0.7769179 -0.377564 -0.09371846 0.7960359 0.5979496 0.2197632 0.9247897 -0.3105934 0.7126873 0.6904219 -0.1240751 0.7098668 0.5749164 0.4068912 0.9073756 0.1368224 -0.3974282 -0.2676622 -0.8064129 0.5273093 -0.6945493 -0.5486639 -0.4653699 -0.8052487 -0.466527 0.3659604 -0.9545123 0.01612615 -0.2977355 -0.5781902 0.7159004 0.3913856 -0.2613322 0.8251613 -0.5008139 -0.008669495 0.8382096 0.5452793 0.1979942 0.8707657 -0.4500727 0.4280478 0.7978261 0.4245569 0.7467093 0.6522189 -0.1305212 0.7876186 0.5684095 0.2378394 0.9360222 0.3048409 -0.1758819 0.8824473 0.1503579 0.4457346 0.7147456 -0.1456014 -0.6840607 -0.5327552 -0.8457897 -0.02849203 -0.4180447 -0.3830375 -0.8237238 -0.6529163 -0.1184503 -0.7481109 -0.6415905 -0.1212173 -0.7574088 -0.4613637 0.04892903 -0.885861 -0.5559783 0.178277 -0.8118532 -0.4071392 0.2407369 -0.8810695 -0.4264969 0.4905592 -0.7599027 -0.232252 0.3810272 -0.8949174 -0.07018756 0.5773106 -0.8135024 -0.009209215 0.5068812 -0.8619668 0.1877582 0.6216079 -0.7604936 0.2066109 0.5440921 -0.8131887 0.4673786 0.4619419 -0.7537686 0.454326 0.3875619 -0.8021122 0.601592 0.2696781 -0.7519049 0.5555767 0.1307985 -0.8211129 0.6480356 0.0474472 -0.7601308 0.5219684 -0.1679332 -0.83627 0.5440663 -0.1945009 -0.8161871 0.3339013 -0.3577971 -0.8720616 0.344308 -0.4002557 -0.8492628 0.2083764 -0.6241638 -0.7529934 0.04201823 -0.4618216 -0.8859772 -0.04918712 -0.5715367 -0.8191011 -0.2855287 -0.5153816 -0.8079947 -0.2659867 -0.3855757 -0.8835059 -0.4817147 -0.3429567 -0.8064315 -0.4360694 -0.1788108 -0.8819695 -0.5707086 -0.1238547 -0.8117584 -0.5900948 0.07749998 -0.8036056 -0.5473417 0.09100478 -0.8319467 -0.5723676 0.3218649 -0.7541872 -0.4288381 0.3739119 -0.8223673 -0.4068384 0.5376887 -0.738494 -0.1843219 0.5227261 -0.8323359 -0.1501802 0.5838389 -0.7978585 0.007557094 0.5281428 -0.8491219 0.0677486 0.591634 -0.8033552 0.1854076 0.5125402 -0.8384072 0.3498798 0.5712969 -0.7424312 0.421149 0.3344307 -0.8430834 0.6159253 0.2910313 -0.7320771 0.5453502 0.1455476 -0.8254751 0.4847463 -0.01923906 -0.8744432 0.7739555 -0.2165831 -0.5950502 0.5782184 -0.3185868 -0.75111 0.3931243 -0.309046 -0.865993 0.3014933 -0.520372 -0.7989462 0.2476615 -0.4767574 -0.8434252 -0.01402503 -0.5775099 -0.8162633 -0.05511635 -0.4582755 -0.8870996 -0.2727922 -0.5558034 -0.7852815 -0.3929703 -0.3501147 -0.8502906 -0.4041516 -0.3523175 -0.8441172 -0.5693379 -0.1176475 -0.8136421 -0.5647796 -0.1191884 -0.8165893 -0.6194702 0.1782147 -0.7645235 -0.4314617 0.234768 -0.8710481 -0.4688943 0.4435831 -0.7637881 -0.2720994 0.4128776 -0.8691916 -0.2056105 0.6265837 -0.7517428 0.07048875 0.6049183 -0.7931615 0.03097158 0.5605154 -0.8275647 0.185887 0.5602253 -0.8072135 0.2115395 0.4578747 -0.8634824 0.381365 0.4468237 -0.8092647 0.3961976 0.3188663 -0.861018 0.5475352 0.3036324 -0.7797515 0.5139148 0.1177969 -0.849715 0.6895092 -0.01028668 -0.7242039 0.5335479 -0.2274767 -0.8146048 0.4321446 -0.2306044 -0.8718214 0.4300118 -0.4853433 -0.7612699 0.1769183 -0.4374625 -0.8816612 0.215281 -0.4776766 -0.8517507 0.01314175 -0.5989117 -0.8007072 -0.07005131 -0.4724268 -0.8785817 -0.2099584 -0.5674132 -0.7962158 -0.3928359 -0.4189463 -0.8186355 -0.3854346 -0.3994554 -0.8317906 -0.6114757 -0.2412477 -0.7535895 -0.4757604 -0.06929868 -0.8768408 -0.59218 0.03068321 -0.8052213 -0.4965488 0.2339763 -0.8358795 -0.4558753 0.2314081 -0.8594347 -0.3842384 0.500895 -0.775542 -0.2654128 0.4403796 -0.8576841 -0.1435313 0.581691 -0.8006463 -0.01183718 0.4906989 -0.8712489 0.06145715 0.5722227 -0.8177922 0.2775481 0.4672609 -0.839425 0.2751989 0.4424211 -0.8535392 0.4651849 0.4055391 -0.7868553 0.4618639 0.1897031 -0.8664263 0.4595449 0.1874236 -0.8681537 0.6315398 -0.0351718 -0.7745454 0.5145566 -0.09390527 -0.8522989 0.5939472 -0.2995522 -0.7466561 0.3770824 -0.4251465 -0.8228362 0.3682972 -0.4855986 -0.7928122 0.1916704 -0.4523676 -0.8709915 0.1652459 -0.5426399 -0.8235507 0.002059698 -0.6102006 -0.7922444 -0.0898348 -0.4657863 -0.8803255 -0.2032166 -0.5395639 -0.8170519 -0.3934027 -0.438531 -0.8080378 -0.3971854 -0.4494792 -0.8001328 -0.4977248 -0.1784303 -0.8487831 -0.6345778 -0.1555463 -0.7570446 -0.5923792 0.1049386 -0.7987958 -0.5513846 0.1179021 -0.825878 -0.5689231 0.361459 -0.7386974 -0.3198434 0.3994073 -0.8591707 -0.3195323 0.3888986 -0.8640931 -0.1291236 0.5170657 -0.8461503 -0.06781804 0.4742102 -0.8777959 0.05948269 0.5964018 -0.8004791 0.1550559 0.4618459 -0.8733018 0.3588325 0.5513841 -0.7531367 0.4286765 0.3368625 -0.8383079 0.3825297 0.2604501 -0.8864743 0.6633262 0.1268985 -0.7374925 0.4736306 -0.06092309 -0.878614 0.4765877 -0.06399327 -0.8767948 0.4654223 -0.3047153 -0.8309817 0.377516 -0.3238317 -0.8675338 0.3875361 -0.48784 -0.7821943 0.1614462 -0.4789271 -0.8628811 0.14253 -0.5294173 -0.8363029 -0.09899282 -0.5502097 -0.8291381 -0.0518518 -0.4890664 -0.8707041 -0.3623096 -0.5140478 -0.7774873 -0.3376618 -0.3504844 -0.8735818 -0.5702064 -0.3146998 -0.7588339 -0.4896842 -0.04763144 -0.870598 -0.515817 -0.05781835 -0.8547455 -0.4752558 0.2563033 -0.8416892 -0.4170786 0.1836759 -0.8901172 -0.4468244 0.4352012 -0.7816315 -0.2993984 0.5177809 -0.8014136 -0.2101149 0.4573175 -0.8641253 -0.08342993 0.651715 -0.7538614 0.1349405 0.578611 -0.8043633 0.1567825 0.4721443 -0.867467 0.373459 0.5044288 -0.7785114 0.4178387 0.2656922 -0.8688029 0.4423521 0.3001474 -0.845125 0.5877779 0.1513352 -0.794742 0.4819831 0.01890373 -0.8759766 0.5980234 -0.1234813 -0.7919095 0.5032715 -0.1814178 -0.8448701 0.5406279 -0.3841051 -0.7484549 0.3037347 -0.4368735 -0.8466917 0.29309 -0.5480136 -0.7834407 0.1168678 -0.4915758 -0.8629572 -0.0779972 -0.7214791 -0.6880294 -0.1538563 -0.584492 -0.796679 -0.3911197 -0.5406336 -0.7448092 -0.3805778 -0.3525247 -0.8549193 -0.4903419 -0.3312633 -0.80612 -0.5001121 -0.1102404 -0.858915 -0.5239052 -0.124525 -0.842625 -0.527943 0.1755744 -0.8309333 -0.4666036 0.1160778 -0.8768165 -0.517877 0.3207065 -0.7930642 -0.3175796 0.3953856 -0.8618662 -0.3221312 0.4365242 -0.8400466 -0.07744562 0.5946226 -0.8002664 -0.04909074 0.5535547 -0.8313648 0.1350251 0.6474142 -0.7500821 0.3078559 0.4543327 -0.8359466 0.3018871 0.4516911 -0.8395471 0.4903457 0.2908163 -0.821576 0.4472674 0.2164726 -0.8678085 0.6387883 0.08754724 -0.7643855 0.4608728 -0.07547891 -0.8842507 0.5880135 -0.2163152 -0.7793895 0.4492771 -0.4128502 -0.7922784 0.2837027 -0.3595355 -0.8889584 0.2503694 -0.5230392 -0.8147056 0.00459063 -0.4972609 -0.867589 0.004862964 -0.4967777 -0.8678643 -0.3193854 -0.6143161 -0.7215323 -0.3097791 -0.3425441 -0.8869614 -0.4503961 -0.3552712 -0.8191006 -0.549639 -0.07188004 -0.8323042 -0.6734687 -0.1349347 -0.7267962 -0.5643254 0.1833286 -0.8049395 -0.4717633 0.1937748 -0.8601691 -0.3690499 0.4050865 -0.836485 -0.3743293 0.4222048 -0.8256034 -0.1476095 0.6237263 -0.7675786 -0.03978031 0.4625368 -0.8857073 0.1139248 0.574734 -0.8103715 0.2269915 0.3819124 -0.8958895 0.4113382 0.449139 -0.7931425 0.4148467 0.2497518 -0.8749437 0.5494776 0.218858 -0.8063346 0.5668044 -0.001236021 -0.8238515 0.4723954 -0.03381007 -0.8807381 0.5695427 -0.3699979 -0.7339774 0.4120892 -0.3392435 -0.8456338 0.2815581 -0.6191443 -0.7330657 0.1325933 -0.5145161 -0.8471672 0.03708028 -0.5859425 -0.8095039 -0.07588499 -0.490092 -0.8683613 -0.1612064 -0.5489719 -0.8201478 -0.3373262 -0.4123038 -0.8462959 -0.3573088 -0.4911532 -0.7944174 -0.5633283 -0.3104262 -0.7657003 -0.4887234 -0.1751399 -0.8546787 -0.6240112 -0.02375489 -0.7810543 -0.4380733 0.06579363 -0.8965283 -0.5744583 0.2860633 -0.7669194 -0.346894 0.4189265 -0.8391455 -0.2978302 0.3890421 -0.8717473 -0.1153467 0.6436815 -0.756551 -0.01773262 0.5089299 -0.8606253 0.1435137 0.5768187 -0.8041666 0.2114889 0.4350878 -0.8751978 0.3870711 0.4855855 -0.7838257 0.3978144 0.2242195 -0.8896456 0.5717772 0.2096793 -0.7931618 0.5939545 -0.09717214 -0.7986086 0.4766525 -0.1173012 -0.8712307 0.4983187 -0.3502373 -0.793103 0.286431 -0.3501008 -0.8918446 0.2880849 -0.5176512 -0.805633 0.03395164 -0.5811697 -0.8130739 0.002636551 -0.5208263 -0.8536586 -0.2090548 -0.6289068 -0.7488474 -0.3533358 -0.4128833 -0.839453 -0.3642045 -0.4160495 -0.8332215 -0.5537793 -0.2639778 -0.7897115 -0.4493767 -0.1407006 -0.8821929 -0.6357403 0.02487975 -0.771502 -0.489955 0.1139361 -0.8642701 -0.5632584 0.2824617 -0.776502 -0.429277 0.4702998 -0.7710638 -0.4198767 0.4014949 -0.8139445 -0.1793591 0.7203481 -0.6700217 -0.2228924 0.450226 -0.8646478 -0.05059027 0.5964634 -0.8010444 0.08230221 0.4867088 -0.8696786 0.12216 0.5282058 -0.840283 0.3522754 0.5389918 -0.7651077 0.3856005 0.3049589 -0.8708113 0.4295243 0.3794472 -0.8194686 0.6118359 0.1980935 -0.7657778 0.5595806 -0.002556204 -0.828772 0.5203266 0.02699142 -0.8535408 0.544006 -0.1913733 -0.8169662 0.4493674 -0.2000765 -0.870654 0.4558019 -0.4690617 -0.756456 0.1997397 -0.4233967 -0.8836512 0.1679381 -0.5681219 -0.8056268 0.03861826 -0.6426373 -0.7651968 -0.06229597 -0.4571645 -0.8871978 -0.2130157 -0.5410248 -0.8135827 -0.3347752 -0.3942267 -0.8558685 -0.4142119 -0.4178531 -0.8085959 -0.5481961 -0.2525341 -0.7973128 -0.4571435 -0.1314116 -0.8796311 -0.6127694 4.78258e-4 -0.7902618 -0.4809935 0.1183791 -0.8686953 -0.5299848 0.2249493 -0.8176271 -0.3696053 0.2810977 -0.8856501 -0.3721847 0.5044123 -0.7791321 -0.1967278 0.4479506 -0.872146 -0.1353749 0.5595924 -0.8176369 0.01564037 0.5308126 -0.8473449 0.04891943 0.5690187 -0.8208684 0.2685779 0.4687856 -0.8414903 0.2757237 0.4728685 -0.8368822 0.4694801 0.3944568 -0.7899318 0.4298554 0.2509402 -0.8673254 0.5513533 0.2005859 -0.8097993 0.5631572 -0.03987419 -0.8253872 0.5180382 -0.01234346 -0.8552685 0.495516 -0.3624891 -0.789345 0.4531788 -0.3492981 -0.8201342 0.26652 -0.5891544 -0.7628003 0.2226598 -0.5600521 -0.7979751 0.04269576 -0.6386462 -0.7683151 -0.0436843 -0.5364482 -0.8428019 -0.2000802 -0.4553849 -0.8675209 -0.4247925 -0.6267293 -0.6532701 -0.4260699 -0.4464051 -0.7868843 -0.4706571 -0.2361164 -0.8501359 -0.4466133 -0.2378183 -0.8625423 -0.6239516 0.03972196 -0.7804528 -0.5245918 0.07990235 -0.8475961 -0.5959109 0.2844117 -0.7509996 -0.3460845 0.4320386 -0.8328076 -0.3390479 0.395109 -0.8537771 -0.2426787 0.5693169 -0.7854843 -0.03571981 0.4884253 -0.8718743 -0.03497755 0.4898734 -0.8710917 0.1911532 0.5986068 -0.7779012 0.2901462 0.4572175 -0.8406947 0.2822342 0.4094247 -0.8675917 0.4867414 0.3661177 -0.7931209 0.4733954 0.1873093 -0.8607045 0.4928748 0.2073701 -0.8450279 0.5618245 -0.02211183 -0.826961 0.5312948 -0.03207498 -0.8465797 0.4740859 -0.3216511 -0.8196238 0.4338226 -0.3143211 -0.8443934 0.3284766 -0.5011214 -0.8006126 0.2247525 -0.4372727 -0.8707921 0.01350015 -0.6492039 -0.7604947 -0.04141902 -0.5332801 -0.8449242 -0.2952008 -0.6126357 -0.7331671 -0.3540804 -0.3983203 -0.846149 -0.51283 -0.357729 -0.7804071 -0.4609915 -0.2588715 -0.8488065 -0.5785151 -0.09631544 -0.8099653 -0.5009654 -0.04405891 -0.8643452 -0.5948372 0.1853213 -0.7821924 -0.3612815 0.266538 -0.8935509 -0.5499628 0.3179675 -0.7722939 -0.3319767 0.5514142 -0.7653325 -0.1828039 0.4679229 -0.8646565 -0.08567196 0.6208637 -0.779223 0.1169076 0.5108763 -0.8516678 0.1295459 0.4423888 -0.8874176 0.3114022 0.5180863 -0.7966275 0.4800577 0.3282723 -0.8134998 0.4137151 0.2380389 -0.8787361 0.5887755 0.08406752 -0.8039129 0.4790967 -0.02297675 -0.8774615 0.5758131 -0.1300265 -0.8071756 0.5142658 -0.3517251 -0.7821893 0.3327372 -0.3059301 -0.8920161 0.2870709 -0.6207807 -0.7295354 0.03534525 -0.4412017 -0.8967117 -0.06281924 -0.5944589 -0.8016686 -0.2888859 -0.5294348 -0.7976489 -0.2886025 -0.5209527 -0.8033164 -0.5473555 -0.401573 -0.7342624 -0.5001569 -0.2847037 -0.817794 -0.6573961 -0.09672081 -0.7473122 -0.5799792 -0.03200995 -0.8140021 -0.6348552 0.2150636 -0.7420961 -0.4362136 0.2466449 -0.865381 -0.3672396 0.4240298 -0.8278489 -0.3542287 0.3744404 -0.8569226 -0.2103907 0.5623981 -0.7996525 -0.0686832 0.4991346 -0.8637983 -0.03718602 0.5542316 -0.8315315 0.1705714 0.5702615 -0.8035592 0.2012037 0.4180126 -0.8858795 0.378586 0.455111 -0.8059446 0.4749528 0.3229433 -0.8186132 0.4267843 0.2373908 -0.8726401 0.6139616 0.1130165 -0.7812032 0.4874692 -0.01436793 -0.873022 0.6014775 -0.1964048 -0.7743707 0.6181064 -0.1897279 -0.762855 0.4921745 -0.4367048 -0.7530294 0.3182072 -0.3962053 -0.8612582 0.2524022 -0.5428025 -0.8010361 0.07442289 -0.4674006 -0.8809075 0.01547932 -0.5739878 -0.8187175 -0.1850643 -0.5515825 -0.8133314 -0.2120552 -0.3799133 -0.9003879 -0.4122467 -0.4424885 -0.7964023 -0.5294827 -0.2838226 -0.7994329 -0.4848922 -0.2119559 -0.8485013 -0.6483872 -0.08581721 -0.7564585 -0.5678197 0.07164859 -0.820029 -0.6553162 0.2148147 -0.7241653 -0.45702 0.3178995 -0.8307062 -0.4569652 0.5047318 -0.7324129 -0.229563 0.4873615 -0.8424842 -0.1819579 0.5808975 -0.7933785 -0.05787694 0.5108743 -0.857705 0.02177882 0.5834435 -0.8118616 0.05930662 0.5596367 -0.8266132 0.292344 0.6133002 -0.733756 0.392814 0.4245223 -0.8157685 0.3818401 0.3818808 -0.8416444 0.5452883 0.2919999 -0.785746 0.4703937 0.1598227 -0.8678632 0.6595667 0.01573115 -0.7514815 0.5225198 -0.1868449 -0.8319028 0.5169839 -0.1794487 -0.8369743 0.4799392 -0.3937068 -0.7839984 0.349649 -0.3744118 -0.858814 0.3174371 -0.5420705 -0.7780703 0.05391371 -0.6670252 -0.7430819 0.1146056 -0.5213095 -0.8456371 -0.1419394 -0.5751922 -0.8056098 -0.1713677 -0.4594253 -0.8715283 -0.3690131 -0.5229788 -0.7683246 -0.4124206 -0.2446723 -0.8775219 -0.4880918 -0.2403371 -0.8390499 -0.5541397 0.02434128 -0.8320677 -0.46393 -0.02266675 -0.8855819 -0.6075811 0.2687053 -0.7474241 -0.4571729 0.2837007 -0.8429157 -0.3933803 0.5773106 -0.715517 -0.2894083 0.5316478 -0.7959859 -0.08448219 0.6633396 -0.7435344 0.05709588 0.5172271 -0.8539416 0.1529299 0.6006264 -0.7847677 0.3149988 0.4071397 -0.857329 0.2979368 0.3672844 -0.8810992 0.5289652 0.1960179 -0.8256954 0.4213963 0.1079007 -0.9004348 0.5713618 -0.05310165 -0.8189787 0.501344 -0.1952334 -0.8429343 0.5212074 -0.2224425 -0.823931 0.359679 -0.445053 -0.8200968 0.3377334 -0.4307457 -0.8368957 0.06736993 -0.5838551 -0.8090578 0.02525371 -0.503924 -0.8633789 -0.2093989 -0.5816476 -0.7860269 -0.2172777 -0.4735811 -0.8535287 -0.5255966 -0.4024246 -0.749535 -0.5073264 -0.344797 -0.7897691 -0.6460922 -0.1788627 -0.7420061 -0.5514823 -0.02810549 -0.8337131 -0.5804738 0.003319382 -0.8142723 -0.5021736 0.1572219 -0.8503547 -0.5497966 0.2327857 -0.8022061 -0.497992 0.4522566 -0.7399107 -0.3880277 0.4382 -0.8108115 -0.2364894 0.6188049 -0.7491017 -0.07136166 0.5059118 -0.8596283 0.01096361 0.6207117 -0.7839623 0.2204747 0.503283 -0.8355221 0.2172154 0.4146681 -0.8836674 0.4762589 0.4241183 -0.7702605 0.4327588 0.1887779 -0.881523 0.5851769 0.151291 -0.7966675 0.530134 -0.1288045 -0.8380737 0.4567695 -0.1359438 -0.8791365 0.5040279 -0.3759469 -0.7775731 0.3157181 -0.4553218 -0.8324688 0.2524976 -0.4184396 -0.8724411 0.13186 -0.6295894 -0.7656566 -0.01050657 -0.4983527 -0.8669108 -0.0264638 -0.4463773 -0.8944535 -0.3101465 -0.5408151 -0.7818748 -0.2816851 -0.307865 -0.9087754 -0.5043979 -0.2999656 -0.8096935 -0.4894962 -0.1481034 -0.8593363 -0.5969108 -0.09743374 -0.7963694 -0.5459145 0.01730656 -0.8376621 -0.6456052 0.2135721 -0.7331992 -0.4254029 0.3523038 -0.8336153 -0.4330826 0.3729726 -0.8205674 -0.1921359 0.5919832 -0.7827131 -0.126267 0.5009285 -0.8562287 0.1528466 0.6548135 -0.7401738 0.2206512 0.4661358 -0.8567558 0.3687297 0.4641525 -0.8053577 0.368727 0.3218402 -0.8720433 0.5017958 0.3147068 -0.8057051 0.6013805 0.1049853 -0.7920352 0.4780045 0.03295129 -0.8777391 0.5824016 -0.1814488 -0.7923918 0.4280018 -0.234133 -0.872924 0.4604427 -0.3679233 -0.8078522 0.3432243 -0.420466 -0.8398842 0.2959147 -0.6129863 -0.732586 0.06167227 -0.604537 -0.7941862 0.0121752 -0.5272343 -0.8496327 -0.1615727 -0.5921963 -0.7894288 -0.2352129 -0.4239985 -0.8745858 -0.3820015 -0.4671351 -0.7974081 -0.4741101 -0.2815333 -0.8342414 -0.4408636 -0.2841883 -0.8513967 -0.5825747 -0.03155934 -0.8121643 -0.456113 0.02867853 -0.8894597 -0.599204 0.2435654 -0.762647 -0.4097341 0.3674538 -0.8349226 -0.3322991 0.3384113 -0.8803722 -0.2475625 0.5860446 -0.7715339 -0.1207709 0.4935429 -0.8612955 0.0908038 0.6745691 -0.7326058 0.2246656 0.4780127 -0.8491344 0.3287799 0.5258438 -0.7844693 0.4226438 0.3302122 -0.8439978 0.4235699 0.3317399 -0.8429338 0.6071506 0.1607652 -0.7781535 0.5813903 0.08406537 -0.8092703 0.6975976 -0.04548937 -0.7150443 0.5242674 -0.226877 -0.8207743 0.5734912 -0.2221813 -0.7885071 0.4523195 -0.4432933 -0.7738851 0.4054853 -0.4309886 -0.8061206 0.1396446 -0.6902048 -0.7100118 0.1820579 -0.4777168 -0.8594427 -0.004266381 -0.6284153 -0.7778664 -0.0836361 -0.5356553 -0.8402848 -0.2370975 -0.6158272 -0.7513599 -0.3973752 -0.4159716 -0.8179612 -0.3803417 -0.3474355 -0.857105 -0.5679901 -0.2674697 -0.778362 -0.5588178 -0.02556669 -0.8288964 -0.4695826 -0.08141857 -0.8791264 -0.4803118 0.191355 -0.8559696 -0.509745 0.230508 -0.8288704 -0.3607667 0.4456759 -0.8192804 -0.3614977 0.4460453 -0.8187569 -0.1621724 0.6711571 -0.7233591 4.63027e-4 0.536204 -0.8440883 0.09797841 0.6155009 -0.7820224 0.2706947 0.4258711 -0.8633413 0.2976536 0.5253397 -0.7971327 0.5919381 0.2527228 -0.7653369 0.5268179 0.2585114 -0.8097129 0.5549647 0.05815422 -0.8298388 0.5144867 0.03186631 -0.8569061 0.5783417 -0.1747714 -0.7968537 0.4508247 -0.2078886 -0.8680665 0.447145 -0.3736348 -0.8126859 0.3270568 -0.3769332 -0.8665768 0.298675 -0.5376088 -0.7885239 0.04973727 -0.5222533 -0.8513389 0.04166984 -0.5410289 -0.8399711 -0.2526714 -0.5252384 -0.8125773 -0.2494702 -0.4285879 -0.8683761 -0.4854644 -0.3592377 -0.7970401 -0.4007146 -0.2491936 -0.8816635 -0.5810045 0.02205562 -0.8136014 -0.5924508 0.01903653 -0.8053818 -0.509019 0.4173671 -0.7527977 -0.4365819 0.2839999 -0.8536629 -0.3513517 0.5295068 -0.7721233 -0.1780974 0.4591494 -0.8703237 -0.1054727 0.6225733 -0.7754212 0.1422209 0.6302004 -0.763296 0.1671948 0.5614041 -0.810476 0.3770908 0.5416756 -0.751259 0.3809064 0.3334896 -0.8623777 0.5563866 0.3187096 -0.7673709 0.4988828 0.05415713 -0.8649758 0.5116215 0.04850554 -0.8578408 0.5824958 -0.2098798 -0.7852701 0.4257277 -0.2441222 -0.871298 0.4522985 -0.3815253 -0.8061419 0.2142009 -0.4574341 -0.8630597 0.2137501 -0.4663995 -0.8583604 -0.03059065 -0.6509062 -0.7585417 -0.06994664 -0.5654646 -0.8218014 -0.3154966 -0.6043924 -0.7315544 -0.3808029 -0.4172385 -0.8251674 -0.439536 -0.4133483 -0.7974656 -0.4438183 -0.213435 -0.870328 -0.5429753 -0.1921719 -0.8174642 -0.5738087 0.05881905 -0.8168746 -0.4968756 0.08290028 -0.863853 -0.5340206 0.2580329 -0.8051342 -0.3697804 0.3354547 -0.8664484 -0.3796123 0.3925693 -0.8377255 -0.2631249 0.5251608 -0.8093032 -0.1934179 0.4862385 -0.8521511 -0.02925002 0.6795603 -0.7330363 0.1360546 0.5218117 -0.8421412 0.3160898 0.609119 -0.7273661 0.3305485 0.3330644 -0.8830661 0.5035506 0.3441405 -0.7924671 0.5312892 0.09996688 -0.8412721 0.5963799 0.1431913 -0.7898275 0.61844 -0.1078111 -0.7784015 0.5709015 -0.1333267 -0.8101208 0.5489745 -0.4135391 -0.7263695 0.4178736 -0.3940118 -0.8186185 0.2819713 -0.5947845 -0.7528105 0.1757602 -0.5105273 -0.8417068 -0.07254666 -0.6409194 -0.7641724 -0.1549202 -0.4669698 -0.8705968 -0.3280454 -0.5430285 -0.7729853 -0.4296603 -0.300655 -0.8514686 -0.4133975 -0.2992373 -0.8599765 -0.5976944 -0.0748198 -0.7982252 -0.5755046 -0.05990076 -0.815602 -0.6309283 0.1857067 -0.7532879 -0.5535418 0.2160556 -0.804308 -0.4792864 0.4621654 -0.7461151 -0.3181603 0.403783 -0.857749 -0.1677139 0.5971761 -0.7843806 -0.06181108 0.4643214 -0.8835073 0.200308 0.625332 -0.7542126 0.2056148 0.4970012 -0.8430376 0.366344 0.4097588 -0.835398 0.3396742 0.3027978 -0.890469 0.5196657 0.2029114 -0.8299244 0.4409201 0.12945 -0.8881623 0.5589566 -0.05362212 -0.8274614 0.5389518 -0.07820242 -0.8386987 0.6098234 -0.2343178 -0.7571068 0.4124577 -0.3734815 -0.8308973 0.402095 -0.344014 -0.8485128 0.3051503 -0.5690021 -0.763623 0.07160013 -0.4971373 -0.8647127 0.09147483 -0.4153568 -0.9050477 -0.1658268 -0.6379891 -0.7519783 -0.2259986 -0.4678302 -0.8544353 -0.496951 -0.7199026 -0.4845409 -0.8452945 -0.533878 -0.02125108 -0.5169085 0.6268655 -0.5829626 -0.1120334 0.7683791 0.6301128 -0.1146103 0.3402952 0.933308 0.4008306 -0.2184777 0.8897204 -0.03128665 -0.451295 -0.8918262 0.2422526 0.5312603 0.811835 0.4190201 0.4569873 -0.784592 0.4831928 -0.3111113 0.8183732 0.4897609 -0.510614 -0.7066878 0.2445642 -0.6025285 0.7597026 0.4441987 0.342087 0.8280484 0.6235221 0.2218567 -0.7496665 0.5635122 -0.01452875 0.82598 -0.2273179 -0.5101548 0.8294991 -0.3714845 -0.6290784 -0.6828321 -0.6370674 -0.3802971 0.6704621 0.4725188 0.1706525 0.8646409 -0.4264215 -0.326453 -0.8435598 -0.6084908 -0.1417276 0.7808024 -0.5292675 0.01778703 -0.8482686 0.1004826 0.3724302 -0.9226045 0.4666504 0.3001871 0.8319407 0.6374341 0.2370187 -0.7331439 0.61258 -0.02779352 0.7899199 -0.8477241 -0.5299652 0.02237802 -0.8275453 -0.2643778 -0.4952507 -0.6927771 0.02040654 0.7208631 -0.9938781 0.09698224 -0.05292165 0.4548347 0.03547549 -0.8898692 0.09050619 0.03081893 -0.995419 0.6986677 0.2224527 -0.6799841 0.8912457 0.1537907 -0.4266493 0.9987518 0.04163354 -0.02759796 0.9299854 0.1552969 -0.3331819 0.7013966 0.2142114 -0.6798208 0.4537611 0.3154044 -0.8334392 0.4884293 0.4475369 -0.7490978 0.8970595 0.4414026 -0.02116692 0.7852323 0.4965375 -0.3699471 0.7988145 0.5086492 -0.3212029 0.4855092 0.4511836 -0.7488085 0.1864072 0.3561942 -0.9156299 0.520419 0.7406105 -0.4250414 0.6687088 0.7343171 -0.1166494 0.1850183 0.4766309 -0.8594133 0.4221062 0.788262 -0.4477383 0.2910723 0.7061679 -0.6454486 0.04192399 0.53003 -0.8469419 0.1148418 0.8378421 -0.5336968 0.2561902 0.9654398 0.04787969 0.01824194 0.6254057 -0.7800865 0.03883761 0.7763661 -0.6290845 0.1550002 0.9710683 -0.1816628 -0.040035 0.2175139 -0.9752359 -0.1265866 0.9313282 -0.3414727 -0.1572738 0.3971117 -0.9041943 -0.06366574 0.9858608 -0.1550004 -0.1837619 0.5810219 -0.7928715 -0.2680562 0.8731819 -0.4070618 -0.2808666 0.7667824 -0.577199 -0.2415403 0.3343687 -0.9109643 -0.3583545 0.9158148 -0.1812876 -0.1988148 0.1871709 -0.9619979 -0.5306972 0.5711767 -0.6261932 -0.543742 0.6610156 -0.5171104 -0.6250458 0.751288 -0.211859 -0.6646561 0.7422865 -0.08510673 -0.5537884 0.3100008 -0.7727988 -0.6198271 0.4216644 -0.6618259 -0.6051158 0.1802804 -0.7754573 -0.8404865 0.4899087 -0.2314564 -0.8947523 0.4354749 -0.09889441 -0.7334877 0.1501311 -0.6629152 -0.3127133 0.01250439 -0.9497653 -0.9365191 0.2470495 -0.2487943 -0.5399733 -0.08675134 -0.8371995 -0.7833944 -0.07001984 -0.6175683 -0.8880223 -0.129278 -0.4412524 -0.9067029 -0.2306175 -0.3531367 -0.4876013 -0.2201824 -0.8448459 -0.05514782 -0.05047601 -0.9972016 -0.7179692 -0.3596152 -0.5959843 -0.3249672 -0.2208963 -0.9195658 -0.9447183 -0.2904086 -0.1522176 -0.6989627 -0.518392 -0.4926673 -0.4633636 -0.5031738 -0.729459 -0.8446106 -0.5332779 0.04741126 -0.7644298 -0.6040373 -0.2253579 -0.4161992 -0.5809368 -0.6994932 -0.2767821 -0.565856 -0.7766587 -0.6037786 -0.796946 -0.01813226 -0.5395849 -0.8154696 -0.2094215 -0.2621903 -0.5809379 -0.770563 -0.03851437 -0.4792062 -0.8768571 -0.2334795 -0.8513481 -0.4697806 -0.2658383 -0.9106547 -0.3162879 0.005230307 -0.1166031 -0.9931648 0.01765203 -0.6411212 -0.7672367 -0.0183717 -0.7666411 -0.641813 -0.1453443 -0.9828675 0.1133428 0.1758986 -0.6394333 -0.7484549 0.05095285 -0.9510455 -0.3048216 0.3567922 -0.7109328 -0.6060312 0.3476804 -0.824855 -0.4457942 0.2042753 -0.3823763 -0.9011437 0.2948235 -0.9262389 -0.2348628 0.422088 -0.7780261 -0.4653142 0.4306898 -0.5409997 -0.722375 0.131139 -0.09912288 -0.9863961 0.5240482 -0.4807195 -0.7030522 0.2844717 -0.169682 -0.9435486 0.6805101 -0.5258208 -0.5103124 0.6666301 -0.7395807 -0.09287011 0.7759028 -0.4547586 -0.4372294 0.9120292 -0.3924091 -0.1192393 0.7219634 -0.1531863 -0.6747614 0.6349254 -0.1076081 -0.7650426 0.6655969 -0.1151969 -0.7373673 0.9174789 -0.1976004 -0.3452342 0.002172529 4.17354e-4 -0.9999976 -0.01434105 8.89227e-4 -0.9998968 0.006081759 0.006037414 -0.9999633 0.005467176 4.70229e-4 -0.999985 -0.005277156 -0.002976298 -0.9999817 -0.004030942 -0.002874255 -0.9999879 -0.8632587 0.4998772 0.0700525 -0.8623811 0.5011288 0.07189643 -0.002516567 0.9973726 0.07239836 -0.002123475 0.9974071 0.07193523 0.8627425 0.5005392 0.07166486 0.8629813 0.5001986 0.07116764 0.864264 -0.4980318 0.07079672 0.8648334 -0.4968155 0.0723716 0.002318143 -0.9974159 0.07180738 0.001694381 -0.9974714 0.07104891 -0.8664903 -0.4977367 0.03811579 -0.8654696 -0.4997005 0.03552019 0.007983207 0.00836718 0.9999331 0.003834903 0.01112926 0.9999308 0.008747279 0.005386888 0.9999473 0.01199376 6.6442e-4 0.9999279 0.01034468 0.004392743 0.9999369 0.01086622 -0.003996014 0.9999331 -0.001868367 0.0114991 0.9999322 -0.006409525 0.01037108 0.9999257 4.47993e-4 0.01025778 0.9999474 0.008429706 -0.00545454 0.9999496 -0.009045004 0.00697714 0.9999349 0.007404267 -0.008966624 0.9999324 -0.009147703 0.005445241 0.9999434 -0.01137536 0.003341317 0.9999297 0.00294429 -0.01082688 0.9999371 2.98703e-4 -0.01012736 0.9999487 -0.01231789 -6.55812e-4 0.999924 -0.001431703 -0.01106536 0.9999378 -0.009427607 -0.006072402 0.9999371 -0.009209334 -0.005018472 0.9999451 -0.007024228 -0.009661674 0.9999287 -0.00179249 -0.001405656 0.9999975 0.001540362 2.26848e-4 0.9999989 0.002226829 2.27841e-4 0.9999975 -0.001308441 -0.001415014 0.9999982 -0.9783498 0.2062474 -0.01713651 -0.9381736 0.3451556 0.02642214 -0.7869493 0.6163005 -0.02974051 -0.6364443 0.7708628 0.02663022 -0.4561259 0.8896241 -0.02276635 -0.2624913 0.9647009 0.02122569 -0.01146703 0.9997671 -0.01828241 0.1277887 0.9915952 0.02022469 0.4167591 0.908473 -0.03144884 0.5874375 0.8086466 0.03174763 0.8177567 0.5752428 -0.01923406 0.8780795 0.478245 0.01606905 0.9735654 0.2276212 -0.01895153 0.9984404 0.05313605 0.01713067 0.9909731 -0.1330846 -0.0161522 0.9593395 -0.2817957 0.01609134 0.8530924 -0.5215129 -0.01605373 0.7918441 -0.6105855 0.01298022 0.5830504 -0.81229 -0.01540845 0.5259259 -0.8504921 0.00808233 0.1596621 -0.9871596 0.004897713 0.09919774 -0.9948052 -0.02285808 -0.3256687 -0.9452043 0.02299839 -0.4409443 -0.897271 -0.02175009 -0.6900739 -0.7235126 0.01810234 -0.7887684 -0.6142742 -0.02261769 -0.9201124 -0.391043 0.02187764 -0.9809744 -0.1932371 -0.01867192 -0.9983835 -0.05534976 0.01291823 0.002333164 -0.003245711 -0.999992 -0.00424534 -0.02030497 -0.9997848 0.01068186 -0.00652945 -0.9999217 0.01265954 0.009714722 -0.9998727 0.006541669 -8.78837e-4 -0.9999783 4.19654e-4 -0.004205167 -0.9999911 0.02314943 -0.01728945 -0.9995825 0.006084859 0.001423597 -0.9999806 -0.001617372 0.009679436 -0.9999519 -0.007108807 -0.01446223 -0.9998702 -0.02061086 0.005412638 -0.999773 -1.87674e-4 -1.3117e-4 -1 -0.001087248 -8.38153e-4 -0.9999991 1.2901e-4 -3.26962e-4 -1 -2.56049e-5 -5.14639e-5 -1 -3.28307e-4 -0.002699971 -0.9999963 -0.002914845 -5.7482e-4 -0.9999957 0.005277395 0.003648102 -0.9999794 9.5115e-6 -5.57312e-5 -1 -0.003071784 6.49345e-4 -0.9999952 -0.02031999 -0.0187177 -0.9996184 -0.00189352 0.003682494 -0.9999915 -0.01313328 0.01028496 -0.9998609 0.01117271 0.02067625 -0.9997238 -0.9780426 -0.1558517 -0.1383591 -0.8904282 -0.4013237 0.2146559 -0.7829426 -0.6047851 -0.145726 -0.4238077 -0.8957869 0.1339881 -0.2770594 -0.9523926 -0.1272265 0.05755805 -0.992649 0.1064664 0.31549 -0.9356565 -0.1581555 0.5025737 -0.8534554 0.1379625 0.8467571 -0.5179758 -0.1212582 0.8731963 -0.486027 -0.03614002 0.9925267 -0.06546634 0.1029812 0.9858341 0.0899828 -0.1415426 0.8459358 0.5174528 0.1289779 0.8115433 0.5838866 -0.02177578 0.355678 0.9328588 -0.05716335 0.3192715 0.9468401 0.03949028 -0.2378084 0.9695457 0.05855095 -0.3105469 0.9469769 -0.0824356 -0.6544055 0.754222 0.05387669 -0.6999614 0.7133732 -0.03395283 -0.9501441 0.3090744 0.04122346 -0.9435155 0.3226661 0.07526648 -0.9626495 0.2026111 0.179596 -0.9136478 0.3904917 -0.1129789 -0.8428849 0.5258075 0.1143317 -0.7170181 0.6762453 -0.1690486 -0.540982 0.8225278 0.1754612 -0.4011574 0.9075157 -0.1244511 -0.1769361 0.9750901 0.1337649 -0.06610244 0.9902479 -0.1226359 0.2559399 0.9625822 0.08905237 0.3150113 0.9477766 -0.04987537 0.5445909 0.837217 0.04988348 0.5809862 0.812325 -0.0508275 0.8177471 0.5744147 0.03657317 0.8332588 0.5519067 -0.03284543 0.9579442 0.2837035 0.04307401 0.9687401 0.2323845 -0.08683419 0.9911615 -0.08546787 0.1014598 0.9772891 -0.1834605 -0.1060581 0.9203237 -0.3797833 0.0936433 0.8306935 -0.5280175 -0.1764823 0.6694698 -0.6913163 0.2718309 0.4348229 -0.8477934 -0.3036043 0.2043905 -0.941437 0.268181 -0.008195698 -0.9855605 -0.1691249 -0.2889919 -0.945816 0.1480402 -0.3651731 -0.9283701 -0.06912118 -0.7101936 -0.7007591 0.06754118 -0.7273542 -0.6862135 -0.008180081 -0.9395782 -0.2949268 0.1738135 -0.9275104 -0.3724753 -0.03141063 -0.9759628 -0.01308929 -0.2175441 -2.78489e-6 0 1 -2.44694e-6 0 1 -1.30065e-6 0 1 2.19073e-6 0 1 8.85264e-6 0 1 -1.28496e-5 0 1 3.91973e-6 0 1 3.18079e-6 0 1 -6.64811e-6 0 1 -9.25379e-7 0 1 4.51271e-6 0 1 -3.55641e-6 0 1 9.81164e-7 0 -1 -1.53956e-7 0 -1 -1.59625e-6 0 -1 3.61128e-6 0 -1 -4.27862e-6 0 -1 3.69017e-7 0 -1 -8.46059e-7 0 -1 2.446e-6 0 -1 -3.50172e-6 0 -1 -0.9831483 -0.1816448 -0.0206083 -0.9797528 -0.1990598 0.02144354 -0.6968712 -0.7149426 0.05681169 -0.6807274 -0.7325347 0.001787543 -0.2619222 -0.9622604 -0.07383662 -0.09859919 -0.9816922 0.1629681 0.1566559 -0.9806694 -0.1172461 0.5246516 -0.8429445 0.1191021 0.5837621 -0.8119198 -0.002886176 0.8802422 -0.4687743 -0.07365179 0.9209879 -0.3709098 0.1191954 0.9840377 0.1409548 -0.1086353 0.9747407 0.214813 0.06112384 0.6165028 0.7859924 -0.04626435 0.5970895 0.8018575 0.02255213 -0.06005108 0.9979808 -0.02069383 -0.08208912 0.9960974 0.03242737 -0.6121645 0.7897574 -0.03921431 -0.6294459 0.7770325 0.004301786 -0.9241797 0.380257 0.03600853 -0.9395104 0.3391948 -0.04761582 -0.9958677 0.08610236 0.02887827 -0.9950248 0.04697471 -0.08785802 -0.8820855 0.4710881 0.001009404 -0.8783884 0.4774779 -0.02118748 -0.6735012 0.7389373 0.01917755 -0.6617655 0.7493914 -0.02188378 -0.3572092 0.9337434 0.0229128 -0.3257708 0.94294 -0.06883084 0.0171405 0.9936782 0.11095 0.09847611 0.9880653 -0.1184464 0.4403968 0.8953775 0.06595271 0.4971061 0.8610877 -0.1068338 0.7204958 0.6752279 0.1579654 0.823409 0.5126611 -0.2432618 0.925302 0.308148 0.2210455 0.9807912 0.0414015 -0.1906165 0.9922873 -0.0855655 0.08969074 0.9231335 -0.3809408 -0.05204665 0.9358122 -0.3486351 0.05204969 0.7909969 -0.605764 -0.08587175 0.7266915 -0.6781289 0.1098212 0.5234851 -0.8464608 -0.09730082 0.4490505 -0.8881571 0.09762513 0.1640341 -0.9795116 -0.1168327 0.04975658 -0.9891306 0.138366 -0.220323 -0.9619077 -0.1618376 -0.3384993 -0.9313628 0.1340961 -0.6786795 -0.7308895 -0.07207387 -0.6612269 -0.7493596 0.03520548 -0.9197871 -0.3756875 -0.1133609 -0.94503 -0.3038219 0.1208745 1.76396e-6 0 1 5.64386e-6 0 1 -1.74313e-6 0 1 1.86173e-7 0 1 -3.37998e-6 0 1 1.70743e-6 0 1 1.01014e-5 0 1 3.7005e-6 0 1 -4.80454e-6 0 1 -7.89698e-6 0 1 -4.52194e-6 0 1 6.54139e-6 0 1 2.25282e-6 0 1 -3.36173e-6 0 1 9.80807e-6 0 -1 -4.08738e-6 0 -1 -3.32739e-6 0 -1 -4.97563e-6 0 -1 3.91807e-6 0 -1 4.26278e-6 0 -1 -2.59089e-6 0 -1 3.87161e-6 0 -1 5.91334e-6 0 -1 -4.38482e-6 0 -1 -5.92938e-6 0 -1 -2.89418e-6 0 -1 2.84156e-6 0 -1 1.94929e-6 0 -1 -7.41432e-6 0 -1 0.06244993 -0.08019042 0.9948214 0.09435492 -0.08629399 0.9917916 -0.003105401 -0.01444417 0.9998909 0.04627019 -0.0229482 0.9986653 0.1258209 -0.08791518 0.9881498 9.41769e-4 -0.002117335 0.9999974 -7.75034e-4 0.001167953 0.9999991 0.1108472 0.007227361 0.9938113 0.001250624 0.04027038 0.9991881 -4.66594e-4 0.001456499 0.9999989 0.004038929 -0.02744376 0.9996152 0.05025708 0.02313309 0.9984685 -0.008258104 -0.08122497 0.9966616 -0.6761785 -0.7366973 -0.007726848 0.03512656 0.0576508 0.9977187 0.05679428 0.09454375 0.9938994 -0.4691314 -0.2385865 0.8502896 0.05121153 0.1644382 0.9850572 0.00402677 0.07699656 0.9970232 -0.1033163 0.3882114 0.9157608 -0.01628881 0.7291624 0.6841469 0.145089 0.4561744 0.877983 0.2455937 0.577709 0.7784189 0.4333677 0.4511008 0.7801926 0.3973944 0.3649321 0.8419634 0.5330595 0.2259876 0.8153387 0.4587141 0.1200564 0.8804363 0.6116006 -0.02336096 0.7908218 0.5068126 -0.1212891 0.8534811 0.5839301 -0.2286325 0.7789435 0.4362147 -0.5102431 0.7411942 0.3366366 -0.3106088 0.8889309 0.3030685 -0.5940923 0.7451201 0.08088582 -0.4934386 0.8660115 -0.05378878 -0.7067986 0.705367 -0.2838863 -0.4580613 0.8423708 -0.3600236 -0.5038523 0.7851853 -0.4909271 -0.2972359 0.8189271 -0.4317225 -0.1965368 0.8803346 -0.613322 -0.06320816 0.7872999 -0.4987831 0.1153046 0.8590229 -0.5020098 0.1174884 0.8568446 -0.5200042 0.3818259 0.7640712 -0.2589716 0.3781589 0.8887798 -0.2745559 0.5609409 0.7810021 0.01158583 0.5037569 0.8637679 0.04156655 0.5639871 0.8247369 0.2633679 0.5189217 0.813239 0.2496399 0.6215692 0.7425172 0.5024411 0.374706 0.7791973 0.4902102 0.3414953 0.8019196 0.6290847 0.1154093 0.7687219 0.4809406 -0.03569459 0.8760263 0.6397114 -0.1941108 0.7437004 0.3796879 -0.2996995 0.8752242 0.3593313 -0.2964047 0.8848872 0.2531849 -0.481785 0.8389164 0.1607559 -0.4348226 0.8860514 0.05214327 -0.6254623 0.7785101 -0.1838939 -0.4676266 0.8645857 -0.1684186 -0.4476806 0.8781898 -0.5089912 -0.4255219 0.7482373 -0.4245837 -0.2562545 0.8683676 -0.6143241 -0.1006116 0.7826132 -0.546024 0.05332672 0.8360707 -0.5763222 0.08106577 0.813192 -0.4680593 0.2316724 0.8527886 -0.5217844 0.3230363 0.7895497 -0.3208401 0.4459489 0.8355785 -0.3833304 0.4710896 0.7944385 -0.1633185 0.6099492 0.7754284 -0.03536736 0.5349395 0.84415 0.01644444 0.5752417 0.8178182 0.1789217 0.4099084 0.8944061 0.2945165 0.5146502 0.80523 0.4238909 0.3147936 0.8492476 0.3965907 0.2524223 0.8826091 0.6300332 0.08068197 0.7723656 0.4950411 -0.02539145 0.8684985 0.5918697 -0.2126209 0.7774848 0.5318012 -0.231523 0.814607 0.4432459 -0.4846368 0.7540958 0.3340558 -0.4665346 0.8189947 0.2178016 -0.6245527 0.7499976 -0.002652943 -0.5271447 0.8497715 -0.05383408 -0.6147267 0.7869009 -0.2708123 -0.4896859 0.8287752 -0.2706278 -0.461044 0.845103 -0.4863141 -0.3086721 0.8174473 -0.4692552 -0.2740919 0.8394482 -0.6297143 -0.1176148 0.7678716 -0.5032312 0.04455935 0.8630023 -0.6305965 0.2227954 0.7434449 -0.4659259 0.324325 0.8232414 -0.4881872 0.4209807 0.7644923 -0.2934201 0.5340537 0.7929006 -0.1791236 0.4801808 0.8586857 -0.06788378 0.613357 0.7868831 0.0885573 0.4845789 0.8702533 0.1507543 0.5560223 0.8173815 0.357717 0.4658159 0.8093542 0.3709128 0.6915869 0.6197833 0.501128 0.2397062 0.8315117 0.5166493 0.2404912 0.8217285 0.5729851 0.02030193 0.8193144 0.5940381 0.03846257 0.8035169 0.6466475 -0.2136271 0.732264 0.4563201 -0.2797246 0.8447048 0.4036317 -0.4384805 0.8030046 0.2997119 -0.4042425 0.8641533 0.1350312 -0.5695717 0.8107742 0.03948271 -0.4720286 0.8806988 -0.1999559 -0.6516471 0.7316924 -0.1895999 -0.6916793 0.6968728 -0.4559358 -0.3638609 0.8122364 -0.3791827 -0.3333039 0.8632085 -0.5960158 -0.1571372 0.7874473 -0.4802105 -0.02163767 0.8768864 -0.5954072 0.08883291 0.7984979 -0.4575037 0.2286975 0.859295 -0.5187743 0.3216387 0.7920997 -0.2849943 0.4637917 0.8388537 -0.5654723 0.6018785 0.5639001 -0.06359314 0.524594 0.8489742 -0.04523551 0.5778464 0.814891 0.1875238 0.5474281 0.8155718 0.2169964 0.4059666 0.8877521 0.4835801 0.4777207 0.7334393 0.4517934 0.168093 0.8761436 0.4688271 0.187045 0.8632586 0.4482961 -0.1304285 0.8843184 0.5649812 -0.08060282 0.8211575 0.5566358 -0.3308249 0.7620444 0.3534053 -0.4559066 0.8168562 0.2288222 -0.4022606 0.8864688 0.15518 -0.6069236 0.7794632 -0.07582658 -0.4894869 0.8687076 -0.0773651 -0.492166 0.8670567 -0.3018606 -0.5898019 0.7490087 -0.3595995 -0.2995285 0.8837257 -0.4813429 -0.3253901 0.8138982 -0.4855902 -0.03966164 0.8732865 -0.542283 -0.08746552 0.8356309 -0.6178643 0.1897578 0.7630437 -0.3795449 0.2458399 0.8919128 -0.4294248 0.5465731 0.7189244 -0.1801475 0.4207562 0.889107 -0.02792108 0.605696 0.7952062 0.05968195 0.4899536 0.8697032 0.2338675 0.526796 0.8171855 0.21497 0.5101442 0.832791 0.5290391 0.4514981 0.7185173 0.4541409 0.2294989 0.8608638 0.6214123 0.1151 0.7749831 0.4319854 -0.07236933 0.8989723 0.5702494 -0.1786161 0.8018178 0.4260867 -0.3999103 0.8114938 0.3202108 -0.3743712 0.8702363 0.2257982 -0.5998026 0.7676275 0.1363475 -0.5334219 0.8347878 -0.1564633 -0.5744789 0.803426 -0.1173537 -0.6500991 0.7507325 -0.392749 -0.5370333 0.7465546 -0.4110115 -0.3543215 0.8399559 -0.4449363 -0.3528817 0.8231077 -0.4963312 -0.1199631 0.8598047 -0.467047 -0.06823664 0.8815956 -0.6289188 0.02084165 0.7771916 -0.4298083 0.2145465 0.8770602 -0.5080861 0.3110556 0.8031768 -0.3523604 0.5053879 0.7876707 -0.171797 0.420257 0.8909938 -0.09164535 0.61189 0.7856155 0.1230792 0.5147887 0.8484363 0.1133545 0.5003855 0.8583503 0.3340184 0.5260009 0.7821475 0.3800275 0.2985999 0.8754526 0.4710374 0.312837 0.8247769 0.5644655 0.177511 0.8061443 0.4981955 0.09042465 0.8623368 0.6138508 -0.09395152 0.7838115 0.4637749 -0.1704869 0.8693947 0.4804775 -0.2196266 0.8490616 0.4363095 -0.2613016 0.86102 0.4363679 -0.4976583 0.7496128 0.1980637 -0.5755897 0.7933899 0.1987773 -0.4851514 0.8515372 -0.02586454 -0.5799663 0.8142299 -0.09194004 -0.4855406 0.8693661 -0.3135305 -0.5625759 0.7649884 -0.3194837 -0.4183127 0.8502616 -0.4612955 -0.2105661 0.8618983 -0.5094475 -0.2993327 0.806761 -0.6373432 -0.05076438 0.7689061 -0.4321628 0.1121751 0.8947916 -0.5678237 0.2496712 0.7843728 -0.4093182 0.4095505 0.8153079 -0.2547802 0.3805775 0.8889588 -0.2444712 0.5468187 0.8007642 -0.05751585 0.5917825 0.8040432 0.00747466 0.492172 0.870466 0.285429 0.6007287 0.7467633 0.3391928 0.4056801 0.8487473 0.434184 0.4206784 0.7965639 0.517852 0.2124878 0.8286605 0.5018475 0.1918331 0.8434152 0.7544484 -0.1482135 0.6394063 0.5727142 -0.05498826 0.8179088 0.4309277 -0.3359385 0.8375242 0.4445538 -0.3564404 0.82178 0.2878764 -0.5258545 0.8003776 0.1403681 -0.4428951 0.8855172 0.05309778 -0.5876202 0.8073928 -0.08210176 -0.468647 0.879562 -0.3336682 -0.6373322 0.694603 -0.3759927 -0.3253027 0.867645 -0.522652 -0.3248382 0.7882356 -0.4956112 -0.1052157 0.8621481 -0.5801687 -0.07838493 0.8107159 -0.5114336 0.09945875 0.8535478 -0.6151882 0.2179182 0.7576643 -0.457246 0.4130329 0.7876103 -0.4630345 0.4340969 0.7727607 -0.2275192 0.5519425 0.8022434 -0.203688 0.6674802 0.7162272 0.07686853 0.5252752 0.8474534 0.0389713 0.4797124 0.8765599 0.2604531 0.4954472 0.8286715 0.2622202 0.4884482 0.8322614 0.5081028 0.2838838 0.8131677 0.5043277 0.4475761 0.7384642 0.6806619 0.2042357 0.7035533 0.5128316 -0.02890229 0.8580026 0.6463395 -0.1689102 0.7441201 0.3331831 -0.2945963 0.8956574 0.7572724 -0.3429629 0.5558013 0.2586762 -0.4629461 0.8478017 0.2615002 -0.5167173 0.8152429 0.06361681 -0.5816246 0.8109661 0.0576778 -0.5755341 0.8157413 -0.1593507 -0.6454771 0.7469717 -0.2801985 -0.4633649 0.8407032 -0.2828393 -0.4140651 0.8651891 -0.5190071 -0.3903219 0.7604477 -0.4538036 -0.1345848 0.8808798 -0.5627706 -0.1167914 0.8183209 -0.588801 0.08366203 0.8039367 -0.48393 0.145832 0.8628701 -0.5665907 0.3095365 0.7636505 -0.4513438 0.4624072 0.763196 -0.3109791 0.4504818 0.8368741 -0.2517454 0.5341985 0.8070045 -0.1239446 0.4954805 0.8597307 -0.04669988 0.6426505 0.7647349 0.1601593 0.5491821 0.8202123 0.2528466 0.6127223 0.748759 0.4017283 0.4261825 0.8105449 0.4110824 0.4271575 0.8053247 0.5017174 0.162972 0.8495409 0.5959309 0.1589148 0.7871548 0.5021156 -0.1043629 0.8584803 0.5260136 -0.09677904 0.8449518 0.4427738 -0.3815253 0.8114122 0.397958 -0.3722979 0.8384651 0.2359266 -0.521689 0.8198655 0.1452431 -0.4672124 0.8721336 -0.03330302 -0.6477462 0.7611281 -0.1349985 -0.4489428 0.8833038 -0.3484123 -0.5385169 0.7672082 -0.3654485 -0.2953 0.8827489 -0.5301548 -0.284171 0.7988634 -0.4792538 -0.1143406 0.8701967 -0.578437 -0.05728882 0.813713 -0.497482 0.1575297 0.8530511 -0.4682127 0.1349149 0.8732554 -0.5092093 0.354896 0.7840631 -0.3690288 0.3845478 0.8461329 -0.3588661 0.6060906 0.7098376 -0.06364792 0.5628978 0.8240724 -0.02523535 0.6459178 0.7629899 0.1884604 0.5030077 0.8434845 0.2096629 0.4084023 0.8883969 0.3887011 0.4690452 0.7930373 0.4850035 0.3175375 0.8148261 0.4441657 0.2183875 0.8689212 0.6384382 0.1403939 0.7567604 0.5733596 -0.144932 0.806383 0.5223158 -0.1114559 0.8454371 0.4768658 -0.3799751 0.7926021 0.3137295 -0.3686086 0.8750437 0.2928482 -0.5369687 0.7911414 0.1420734 -0.5182877 0.8433225 0.1001709 -0.6136323 0.7832123 -0.07571607 -0.6143413 0.7853991 -0.2132016 -0.4234107 0.8804934 -0.2826217 -0.4765632 0.8324738 -0.4903909 -0.3822759 0.783187 -0.4354911 -0.2662144 0.8599287 -0.5957543 -0.08240044 0.7989286 -0.4803439 0.02833151 0.8766226 -0.5773692 0.1182368 0.8078769 -0.4100479 0.329256 0.8505593 -0.383724 0.2869127 0.8777454 -0.3656583 0.488027 0.7925426 -0.1522802 0.4868696 0.8600981 -0.1531772 0.4715991 0.8684072 0.05432283 0.6804087 0.7308168 0.1992327 0.3578448 0.9122793 0.3708123 0.4783105 0.7960636 0.4594963 0.1636753 0.8729683 0.4642012 0.1722543 0.8688187 0.6018507 0.08664131 0.7938949 0.5016838 -0.09420239 0.8599067 0.5137968 -0.1030074 0.8517056 0.5205449 -0.3723068 0.7683885 0.3056267 -0.3563683 0.8829461 0.2969886 -0.5356297 0.7905053 0.07151299 -0.5343919 0.8422062 0.04802924 -0.5061475 0.8611087 -0.1664897 -0.5580511 0.8129331 -0.1854963 -0.4708579 0.8624871 -0.4921162 -0.4217019 0.7615704 -0.4333432 -0.2811861 0.8562408 -0.5276044 -0.05015647 0.8480083 -0.5782848 -0.09533417 0.8102457 -0.5798934 0.1335306 0.8036749 -0.4477818 0.2084015 0.8695173 -0.4980222 0.357718 0.7899442 -0.3550565 0.3925343 0.8484408 -0.4330803 0.4161215 0.7995526 -0.1804833 0.5696671 0.8018138 -0.05877751 0.5169151 0.8540165 -0.01464867 0.6079079 0.7938724 0.1944177 0.545619 0.8151698 0.2130457 0.4640395 0.8598134 0.4177751 0.4418648 0.7938638 0.3995024 0.3160901 0.8605144 0.5960763 0.1888917 0.780393 0.5900979 0.1821051 0.7865256 0.6359705 -0.1428096 0.7583845 0.6191164 -0.1285533 0.7747058 0.4638672 -0.3373856 0.8191449 0.5003707 -0.4392585 0.7461108 0.2739457 -0.5444742 0.792781 0.266017 -0.5866703 0.7648876 -0.03289836 -0.5749194 0.8175486 -0.01989251 -0.54087 0.8408711 -0.2462939 -0.5765767 0.779037 -0.3403707 -0.3078793 0.8884584 -0.3586894 -0.3570888 0.8624556 -0.6388471 -0.1401383 0.7564626 -0.4750372 -0.01112049 0.8798955 -0.5883224 0.2023525 0.7828986 -0.3897681 0.2558983 0.8846452 -0.4551423 0.4596658 0.7625962 -0.1900944 0.4816316 0.8555087 -0.1781213 0.5744288 0.7989397 0.07334721 0.650493 0.7559625 0.1209205 0.5824681 0.8038092 0.3342201 0.5953955 0.7306171 0.3601547 0.4411921 0.8219721 0.6404598 0.3039984 0.7052633 0.5284124 0.2912154 0.7974799 0.6350829 0.03262817 0.7717546 0.5012933 -0.09514021 0.860031 0.5749264 -0.1680551 0.8007605 0.4002251 -0.3770648 0.8352498 0.3363123 -0.3637107 0.8686822 0.2637688 -0.5519277 0.7910765 0.07532721 -0.4561051 0.8867322 0.002648651 -0.5959148 0.8030434 -0.2143917 -0.4336223 0.8752188 -0.1999075 -0.5149009 0.8336151 -0.511231 -0.4039636 0.7585885 -0.4246433 -0.2507133 0.8699545 -0.6117569 -0.007256507 0.7910126 -0.4382544 0.1032333 0.8929031 -0.5158065 0.177653 0.838083 -0.4735898 0.3991444 0.7851094 -0.2634153 0.3896065 0.8825074 -0.268769 0.5621783 0.7821246 0.03579801 0.506043 0.8617652 0.02444559 0.4772218 0.8784428 0.2457416 0.6057704 0.7567387 0.3595939 0.3447269 0.8670961 0.343653 0.3376832 0.8762835 0.5707302 0.2497777 0.7822265 0.4930941 0.03209346 0.8693838 0.5192196 0.02145153 0.8543716 0.5873208 -0.1638364 0.7925983 0.4512706 -0.2311418 0.8619329 0.4890775 -0.3863274 0.7820194 0.2640384 -0.4274596 0.8646167 0.2525632 -0.4213776 0.8710067 0.0824086 -0.6346716 0.7683756 -0.1059405 -0.4527112 0.8853413 -0.08151912 -0.5419991 0.836416 -0.3686498 -0.4400827 0.8187946 -0.3556265 -0.3829534 0.8525705 -0.4586105 -0.2658293 0.8479454 -0.6171413 -0.2351144 0.7509048 -0.6339561 -0.02335423 0.7730164 -0.498266 0.07657629 0.8636361 -0.5634834 0.2288755 0.7937899 -0.4017706 0.3110839 0.8612824 -0.4297249 0.4011183 0.8089749 -0.2203598 0.4594046 0.8604587 -0.2141748 0.5498265 0.8073537 0.04571384 0.5430428 0.8384598 0.03621268 0.5238346 0.85105 0.3354339 0.5022276 0.7970269 0.2368342 0.4168636 0.877573 0.469027 0.3809472 0.7968018 0.4476101 0.1748335 0.8769711 0.645166 0.1408843 0.750941 0.47162 -0.0914638 0.8770457 0.5849778 -0.2227575 0.7798591 0.3527524 -0.2998573 0.8863698 0.4131107 -0.5489558 0.7266272 0.1111766 -0.4565675 0.8827151 0.04595422 -0.6142346 0.7877843 -0.1501078 -0.4752791 0.8669357 -0.2107987 -0.5423709 0.8132637 -0.4395828 -0.3530454 0.8259091 -0.4016829 -0.2588082 0.878447 -0.587125 -0.170937 0.7912427 -0.5016072 0.009735703 0.8650408 -0.5525476 0.04420632 0.8323083 -0.5406491 0.2230219 0.8111472 -0.4400932 0.2442823 0.8640857 -0.4144955 0.3887285 0.822851 -0.2887454 0.4021944 0.8688302 -0.2593431 0.5786959 0.7732091 -0.07032835 0.4896112 0.8691001 0.08675926 0.6502896 0.754716 0.1448354 0.5090311 0.8484753 0.4073405 0.4587351 0.7897061 0.4178584 0.5084196 0.7529302 0.5541211 0.221509 0.8024235 0.5956453 0.2139452 0.7742313 0.6158913 -0.03493237 0.7870563 0.4936507 -0.106065 0.8631682 0.5130032 -0.3220462 0.7956846 0.3882276 -0.3186246 0.8647299 0.3064826 -0.5013805 0.8091268 0.263923 -0.4847034 0.833911 -0.03624719 -0.5483816 0.8354423 0.08009517 -0.6483129 0.7571493 -0.1624659 -0.6288933 0.7603277 -0.3452674 -0.4220027 0.8382745 -0.3519787 -0.4250928 0.8339108 -0.4773845 -0.2421427 0.8446722 -0.5184932 -0.2437195 0.8196131 -0.5888473 -0.03782105 0.807359 -0.5112246 0.02017074 0.8592104 -0.5610454 0.2199462 0.7980299 -0.4727072 0.243003 0.8470523 -0.4775658 0.457822 0.7498866 -0.2719087 0.5147242 0.8130958 -0.2634425 0.5105177 0.8185168 -0.03367054 0.6766957 0.7354926 0.08524131 0.5131181 0.8540749 0.2479776 0.567346 0.7852551 0.3276183 0.3218937 0.8882853 0.4152452 0.3581768 0.8362302 0.5746209 0.1557255 0.8034678 0.5319525 0.1108958 0.8394813 0.6814841 -0.2200877 0.6979548 0.5837564 -0.1441085 0.7990378 0.4747855 -0.4040811 0.781855 0.3050378 -0.3908546 0.8684381 0.2695336 -0.5849296 0.7649897 0.02488535 -0.5048085 0.8628727 -6.11184e-4 -0.5701549 0.821537 -0.2599416 -0.514881 0.8169014 -0.2600727 -0.3984641 0.879539 -0.5028631 -0.3639664 0.7840009 -0.4629986 -0.1666517 0.8705512 -0.5701882 -0.1356322 0.8102405 -0.5119768 0.06052243 0.8568646 -0.5575124 0.09601974 0.824597 -0.5151501 0.2776952 0.8108673 -0.4102994 0.2906085 0.864408 -0.3974352 0.5016056 0.7683992 -0.1563779 0.4518724 0.8782696 -0.1491659 0.5019353 0.8519452 0.1415777 0.5689806 0.8100722 0.1837592 0.4038571 0.8961763 0.507763 0.5260565 0.6822325 0.4156258 0.1776074 0.8920262 0.5980631 0.1349031 0.7900139 0.4908552 -0.05862379 0.8692667 0.5889746 -0.1448962 0.795056 0.5281574 -0.4491528 0.7206329 0.4497015 -0.3164393 0.8352453 0.3073052 -0.5014925 0.8087452 0.2121157 -0.4537393 0.8655217 0.07003158 -0.6008116 0.7963172 -0.07763063 -0.4848211 0.8711613 -0.1396164 -0.5696675 0.8099298 -0.4020079 -0.4084313 0.819496 -0.4061461 -0.4233505 0.809827 -0.6054556 -0.2301751 0.761868 -0.5760976 -0.1702147 0.7994615 -0.6497578 -0.0215162 0.7598369 -0.568647 0.07757157 0.818916 -0.6310209 0.214908 0.7454042 -0.4692366 0.3319121 0.8183224 -0.4857883 0.4311369 0.7603491 -0.3007878 0.4969188 0.8140016 -0.2658776 0.6271634 0.7321032 -0.06826502 0.5540496 0.82968 0.06948214 0.6870622 0.7232689 0.2183184 0.4785798 0.8504697 0.3140404 0.5059972 0.8033341 0.3789636 0.3227171 0.8673179 0.4890832 0.3470566 0.8002184 0.5807778 0.1775293 0.7944688 0.4903593 0.06193333 0.8693171 0.5909941 -0.06391119 0.8041402 0.5293553 -0.1146797 0.8406139 0.5945469 -0.3601645 0.718885 0.3047975 -0.3845059 0.8713517 0.3090107 -0.5982355 0.7393421 0.0582472 -0.531451 0.8450841 -6.75007e-4 -0.4580901 0.8889056 -0.1087718 -0.572757 0.8124766 -0.3073077 -0.4552924 0.835626 -0.3045114 -0.4158406 0.8569419 -0.4452055 -0.1916895 0.8746698 -0.4912617 -0.2935202 0.8200657 -0.6179528 -0.1061813 0.7790122 -0.5210001 0.07763975 0.8500183 -0.609223 0.159359 0.7768217 -0.5046443 0.3736854 0.7782632 -0.3666464 0.3673289 0.8547748 -0.2782215 0.5258523 0.8037862 -0.1229889 0.4507563 0.8841338 -0.05333238 0.619863 0.7828958 0.1873124 0.550235 0.8137294 0.2011942 0.4350437 0.8776435 0.4820451 0.3999368 0.7795403 0.4583834 0.3355526 0.8229758 0.6486539 0.09132355 0.7555847 0.6347837 0.09508663 0.766817 0.5637927 -0.2169468 0.7969141 0.5574034 -0.2101929 0.803194 0.4847599 -0.4413031 0.7551553 0.2843702 -0.4269115 0.8584172 0.2252218 -0.6082437 0.7611274 0.03001743 -0.4543276 0.8903289 -0.1242705 -0.6242629 0.7712669 -0.24699 -0.3828256 0.8901913 -0.3227994 -0.4293975 0.8434563 -0.5612639 -0.3639243 0.7433316 -0.4644644 -0.13761 0.8748351 -0.5869938 -0.08436793 0.8051834 -0.4762118 0.1226209 0.8707391 -0.5739185 0.2067518 0.7923833 -0.4257897 0.3748309 0.8235321 -0.3019805 0.3443947 0.888932 -0.2193751 0.5003463 0.8375729 -0.1044861 0.4981586 0.8607675 -0.08924525 0.5666483 0.8191124 0.1595832 0.5781026 0.8002066 0.2021093 0.4379377 0.8759923 0.3545486 0.4595822 0.814297 0.3884087 0.3167467 0.8653383 0.4969162 0.313734 0.8091015 0.5100417 0.06552934 0.8576499 0.5103827 0.06546437 0.8574521 0.6321503 -0.07599598 0.7711101 0.3924461 -0.2621858 0.8816148 0.3872404 -0.2556319 0.8858314 0.3857775 -0.5003538 0.7751271 0.1621721 -0.5231706 0.8366557 0.1261752 -0.4869533 0.8642664 -0.09283024 -0.5951576 0.7982293 -0.1645537 -0.4291297 0.8881272 -0.4051786 -0.5338795 0.7421612 -0.5164833 -0.3218565 0.7935071 -0.4435357 -0.2225779 0.8681793 -0.6886634 -0.08427709 0.7201668 -0.5206554 0.0172981 0.8535918 -0.5286605 0.2486039 0.8116122 -0.5892798 0.2344728 0.7731571 -0.4607771 0.3908972 0.7967962 -0.2839286 0.3878826 0.8768876 -0.2505203 0.5083158 0.8239265 -0.1394271 0.5114953 0.8478991 -0.1137342 0.5969666 0.7941635 0.12825 0.5238646 0.8420914 0.143843 0.4634283 0.8743817 0.3908954 0.4881174 0.7803476 0.4204942 0.2585929 0.8696635 0.4183897 0.2582416 0.870782 0.6018496 0.1488758 0.7846101 0.5264715 -0.04336893 0.8490859 0.5194211 -0.04701524 0.8532242 0.5235451 -0.2604036 0.8112277 0.4063411 -0.2730854 0.8719583 0.3770078 -0.4771885 0.7938238 0.2089085 -0.4586079 0.8637338 0.1703777 -0.5996412 0.781922 -0.05916178 -0.5020405 0.8628183 -0.04940491 -0.520471 0.8524489 -0.2455832 -0.5639609 0.7884397 -0.3015272 -0.4163771 0.8577364 -0.5312877 -0.446204 0.7201635 -0.507418 -0.1605219 0.8466167 -0.5916246 -0.1268521 0.7961714 -0.5872554 0.03422409 0.8086779 -0.6093718 0.04780465 0.7914423 -0.5253017 0.2665659 0.8080846 -0.369198 0.2651527 0.8907227 -0.3376663 0.4565176 0.8231484 -0.1270469 0.4004206 0.9074814 -0.3806908 0.6449229 0.6626833 0.09884876 0.4560466 0.8844493 0.05837643 0.6772589 0.7334252 0.2638159 0.2771805 0.9238897 0.6046959 -0.6420383 0.4713065 0.1470693 -0.9691739 -0.1976683 -0.387058 -0.8376813 0.385326 -0.7679525 -0.4627172 -0.4428789 -0.8234759 -0.3292664 0.4620295 -0.8804382 0.108183 -0.4616547 -0.9795129 0.2013817 -6.3369e-5 -0.6662566 0.5836883 0.4641231 -0.5023853 0.5519774 -0.6655298 -0.1781731 0.8046779 0.566346 -0.07249569 0.8898224 -0.4505116 0.3244649 0.7664243 0.5543612 0.652882 0.1259436 -0.7469159 0.8434891 -0.179911 0.5061209 0.7300989 -0.559091 -0.3929033 0.7541168 -0.5368211 0.3783265 0.3837582 -0.7459793 -0.5442835 0.1349409 -0.7034152 0.6978524 -0.180941 -0.7185399 -0.6715362 -0.4070589 -0.8206322 0.4010808 -0.849806 -0.5128844 -0.1215705 -0.9931629 -0.06334322 0.0980581 -0.8691446 0.3319828 -0.3665723 -0.7354986 0.4678642 0.490046 -0.5078435 0.6557731 -0.5586203 -0.169498 0.8738374 0.4557177 0.2529406 0.8463064 -0.4688141 0.3871114 0.6262077 0.6767634 0.542479 0.46055 -0.702574 0.6914715 0.1716656 0.7017108 0.8434254 0.05412644 -0.5345128 0.7378284 -0.3481115 0.5782971 0.1701107 -0.9665376 -0.1920089 -0.4131759 -0.87739 -0.2438697 -0.4600504 -0.6909093 0.5576722 -0.6763073 -0.3903546 -0.6246854 -0.429594 0.6244966 -0.6522676 -0.141708 0.8501164 0.5071697 0.05471885 0.8388194 -0.541653 0.3127549 0.6151376 0.7237335 0.5946364 0.494468 -0.633963 0.8172007 0.03808718 0.5750936 0.6464045 -0.3275011 0.6891331 0.5468907 -0.577713 -0.6059359 0.290365 -0.7794954 0.5550451 0.1720358 -0.8450707 -0.5062204 -0.1964965 -0.7071023 0.679261 -0.4273367 -0.5642873 -0.7063734 -0.7657324 -0.2696989 0.5838806 -0.8489308 -0.1390805 -0.5098757 -0.9073132 0.1362046 0.3977829 -0.8142757 0.3028676 -0.4952035 -0.4897446 0.4991233 0.7148609 -0.3027753 0.8814459 -0.3624642 0.314521 0.9171048 0.2449396 0.3308284 0.838499 -0.4329804 0.6771693 0.510729 0.5297147 0.7074649 0.3855533 -0.5923194 0.8788647 0.1250189 0.4603989 0.7873309 -0.123144 -0.6041075 0.7397775 -0.3250508 0.5891277 0.5082343 -0.6869692 -0.519395 0.4296588 -0.8208278 0.3763442 -0.04906255 -0.9253637 -0.3758921 -0.1229118 -0.9903458 0.06409269 -0.638496 -0.7132363 0.2891659 -0.6498118 -0.6763371 -0.3468613 -0.9781309 -0.1599333 0.1329711 -0.9463943 -0.2086143 -0.2466132 -0.8739789 0.3008184 0.3816666 -0.7634934 0.3691624 -0.529903 -0.6199367 0.6338169 0.4625524 -0.4264551 0.7314401 -0.532101 -0.1572111 0.7795097 0.6063411 0.007946908 0.8711618 -0.4909318 0.4089307 0.8486222 0.3355832 0.6320105 0.5380268 -0.5577545 0.8465124 0.2197281 0.4849087 0.8012793 -0.02260565 -0.5978633 0.9795007 -0.1731184 0.1029978 0.7255307 -0.5869784 0.3592514 0.6229091 -0.5822284 -0.5224887 0.2070029 -0.8783046 0.4309654 -0.627171 -0.6965297 0.3485727 -0.8813149 -0.2292162 -0.413212 -0.867742 -0.07566243 0.491222 -0.815514 0.2945635 -0.498166 -0.7334501 0.4436857 0.51497 -0.4292855 0.774113 -0.4652559 -0.2926762 0.8300828 0.4746612 0.1061758 0.8336334 -0.5420167 0.2834782 0.7234055 0.6295433 0.5873497 0.5891777 -0.5548784 0.7469406 0.4411398 0.4974691 0.8699091 0.2527951 -0.423501 0.8647314 -0.01782107 0.5019183 0.8370154 -0.2048554 -0.507385 0.634918 -0.4567121 0.6231317 0.4237118 -0.6689338 -0.6107339 0.07923978 -0.8928232 0.4433823 -0.071415 -0.8935162 -0.4433157 -0.3738444 -0.7802633 0.5014275 -0.4928516 -0.7960419 -0.3513042 -0.8681789 -0.4752836 0.1427267 -0.8477364 -0.5113661 -0.140882 -0.9122905 0.02073186 0.4090187 -0.7496105 0.08729153 -0.6560978 -0.5788099 0.5052238 0.6401 -0.5237193 0.5960645 -0.6086257 -0.1807416 0.8063946 0.5630811 -0.02785736 0.6863514 -0.7267364 0.4638979 0.6377246 0.6149033 0.7656328 0.3012034 -0.568404 0.5926606 -0.1577755 0.7898483 0.6644281 -0.408327 -0.6259428 0.420385 -0.6816245 0.598886 0.357416 -0.7776731 -0.5171833 -0.1390614 -0.7268118 0.6726117 -0.4469621 -0.6448373 -0.6200079 -0.719222 -0.3719488 0.5868338 -0.7799496 -0.2637437 -0.5675544 -0.9155732 0.2075445 0.3444576 -0.04816454 0.9568161 -0.2866762 0.4728212 0.8053865 0.3574811 0.9489917 0.1333969 -0.2856925 0.7629289 -0.3462415 0.5459456 0.6036344 -0.6793275 -0.4173004 0.06794452 -0.8232346 0.5636208 -0.2275761 -0.6542573 -0.7212188 -0.5530456 -0.5391737 0.6351633 -0.6561931 -0.2953906 -0.6943739 -0.825716 -0.1019624 0.5547944 -0.7976994 0.248367 -0.5495357 -0.5414947 0.6294617 0.5572806 -0.2156066 0.8904131 -0.4008472 0.8385944 0.4675396 -0.2795823 0.9363162 -0.08289122 0.3412347 0.9942704 -0.1068636 0.002577602 0.7318643 -0.567265 -0.3776044 0.515073 -0.606023 0.6061651 0.344396 -0.7819792 -0.5195189 0.09532666 -0.8708137 0.4822824 -0.1521549 -0.8665302 -0.4753674 -0.3204468 -0.8955672 0.3086634 -0.7376363 -0.5915147 0.325581 -0.6952788 -0.688141 -0.2074836 -0.8454561 -0.2994289 -0.4422061 -0.722054 0.007812619 0.6917926 -0.7540693 0.1426594 -0.6411145 -0.5414059 0.5792869 0.6093491 -0.1315539 0.7351553 0.6650115 0.2590474 0.7316981 -0.6304858 0.4349191 0.6256502 0.6476166 0.6366873 0.322257 -0.7005568 0.9845728 -0.1231079 0.124342 0.6952952 -0.6013365 0.3936483 0.6793385 -0.6479039 -0.3445577 0.244436 -0.9519504 -0.1845033 -0.1960201 -0.8311403 -0.5203673 -0.6699541 -0.6197978 0.4086713 -0.7123563 -0.5444654 -0.4428387 -0.8649029 -0.2208881 0.4507233 -0.7993025 -0.05264526 -0.5986185 -0.776745 0.2412855 0.5817633 -0.7207533 0.4630317 -0.5158646 -0.5929858 0.6569857 0.4655509 -0.3249814 0.7209365 -0.6120766 -0.09072142 0.7412959 0.6650189 0.2734117 0.7213871 -0.6362756 0.4806393 0.7902096 0.3802036 0.8873181 0.4258362 -0.1770036 0.8534084 0.3029689 0.4241508 0.8033096 -0.05736577 -0.5927926 0.6074172 -0.2765667 0.7446847 0.5320439 -0.4695119 -0.704619 0.3438738 -0.7184216 0.6046662 0.2074355 -0.8801403 -0.4269937 -0.06014388 -0.9255017 0.3739376 -0.2232525 -0.8246223 -0.5197658 -0.4513798 -0.7366743 0.5035546 -0.7479596 -0.5926913 -0.2987869 -0.8096936 -0.4806112 0.3367632 -0.8263442 -0.1669536 -0.5378494 -0.7693088 0.1075803 0.6297544 -0.8507894 0.2851577 -0.4414098 -0.6195861 0.6235696 0.4767327 -0.2702307 0.714756 -0.6450575 0.07739377 0.8495231 0.5218437 0.2633571 0.7974654 -0.5428555 0.5387776 0.650972 0.5347468 0.6834235 0.6574998 -0.3172166 0.9258702 0.2504405 0.2829205 0.1104289 -0.7441748 -0.6587939 -0.2984075 -0.7333686 0.6108384 -0.46435 -0.5910658 -0.6595607 -0.7366709 -0.664081 0.1277205 -0.9711101 -0.1151156 0.2090307 -0.9930674 -0.1105106 0.04005789 -0.7962657 0.3979278 -0.4556475 -0.6723937 0.5044121 0.541715 -0.344466 0.8679119 -0.3578718 0.7969502 0.02516877 -0.6035205 0.6955563 -0.4728021 0.5409803 0.6580279 -0.5656054 -0.4970813 0.4226233 -0.8265991 0.3716497 0.2397267 -0.8185295 -0.5220543 -0.03242743 -0.7938227 0.6072842 -0.2532872 -0.7317215 -0.6327948 -0.5114104 -0.5838021 0.6305827 -0.6168665 -0.4738743 -0.6284258 -0.7306334 -0.1503103 0.6660193 -0.7200192 0.06341993 -0.6910502 -0.8275344 0.3037571 0.4721425 -0.5977173 0.7076001 -0.3768769 -0.5970161 0.8022106 -0.005483746 -0.06926208 0.9862201 0.1502426 -0.03052467 0.9050909 -0.4241213 0.4836772 0.7073504 0.5154725 0.5033251 0.6167154 -0.6052487 0.7681855 0.2272046 0.5985559 0.8425893 0.1498396 -0.5172924 0.8258927 -0.3291896 0.4577506 0.9071076 -0.3824668 0.1757127 0.5163507 -0.6705745 -0.5326461 0.3316842 -0.7175324 0.612481 -0.04830443 -0.8986933 -0.4359095 -0.1958001 -0.853643 0.4826554 -0.4849869 -0.6562987 -0.577979 -0.5349269 -0.2978779 0.7906466 -0.8790755 -0.07199752 -0.4712141 -0.759716 0.4847188 0.4334505 -0.8225883 0.5444184 0.1641864 -0.4528874 0.7335885 -0.5066962 -0.1494097 0.6746061 0.7228993 -0.01999551 0.8311969 -0.5556185 0.4621906 0.7649965 0.4485089 0.4763745 0.7830643 0.3998474 0.7269255 0.3886862 -0.5661293 0.7991589 0.2053676 0.5649507 0.9203929 -0.0745362 -0.3838245 0.785708 -0.2819441 0.5506093 0.63646 -0.4104449 -0.6530342 0.3774347 -0.6563643 0.653245 0.3024133 -0.8141185 -0.4957393 -0.008405447 -0.9221804 0.3866688 -0.1563258 -0.8182704 -0.5531689 -0.3995431 -0.6250988 0.6705347 -0.5541846 -0.4693397 -0.6874589 -0.7234653 -0.2450306 0.6454131 -0.8479208 -0.08189535 -0.5237591 -0.7968369 0.2653825 0.5427919 -0.8818312 0.3859578 -0.2709435 -0.6502394 0.7546045 -0.08809655 -0.4896032 0.7225188 0.4881141 -0.2234819 0.8747451 -0.429973 0.02702659 0.8614785 0.5070745 0.1611302 0.8932487 -0.4196949 0.5476246 0.6461673 0.531578 0.8189418 0.02872169 -0.5731575 0.7740669 -0.3995928 0.4910665 0.764277 -0.5034687 -0.402989 0.4372208 -0.8469437 0.30253 -0.3545771 -0.7230226 -0.5928856 -0.7500236 -0.4931882 0.4407154 -0.8561235 -0.5166844 -0.009480416 -0.9550185 -0.05554497 -0.2912977 -0.8512244 0.09454011 0.5162162 -0.6911864 0.3558548 -0.6289904 0.047791 0.8644425 0.5004549 0.5612772 0.6966402 -0.4468338 0.6875835 0.6867753 0.2357299 0.9816055 0.1886215 -0.02954053 0.7008934 -0.5932277 -0.3960171 0.1668921 -0.9317134 0.3225792 0.1416998 -0.9642859 -0.2237718 -0.441933 -0.8672702 0.2292109 -0.4659585 -0.8796013 -0.09583526 -0.9041402 -0.4206565 -0.07469075 -0.8335479 -0.2954047 0.4668339 -0.8876999 0.01292508 -0.4602412 -0.769739 0.2721023 0.577462 -0.7567405 0.4188946 -0.5018677 -0.512802 0.7084524 0.4849014 -0.3485351 0.7034663 -0.6194018 -0.1007995 0.8284086 0.5509797 0.2709504 0.8405359 -0.4691324 0.2751655 0.8624455 -0.4248195 0.651511 0.5694956 0.5012069 0.7119281 0.4192074 -0.5634036 0.9076468 0.2858923 0.3073159 0.8631664 -0.1193766 -0.4906049 0.5923609 -0.4791363 0.6477169 0.4335395 -0.7084825 -0.5568627 0.1416193 -0.773832 0.6173557 -0.02428114 -0.7643056 -0.6443971 -0.32425 -0.7538753 0.5714316 -0.6080467 -0.6330001 -0.4791555 0.2483546 0.675234 0.6945352 0.5209686 0.5679724 -0.6371806 0.6592954 0.3044581 0.6874844 0.8525109 0.2057721 -0.4805028 0.8564378 -0.2070382 0.4729163 0.7185642 -0.6028847 -0.3466926 0.1806598 -0.8053907 0.5645422 0.1010473 -0.7666292 -0.6340892 -0.4083563 -0.7463744 0.5255192 -0.5173445 -0.8510153 -0.09015405 -0.8552762 -0.4716955 -0.2144904 -0.8851894 -0.4112396 0.2175355 -0.9769937 0.1467702 0.1547322 -0.7002055 0.432906 -0.567719 -0.5063717 0.7488711 0.4275276 -0.3109235 0.7588211 -0.5722911 -0.08265155 0.8391337 0.5376089 0.2690154 0.8250418 -0.4969274 0.4218506 0.880046 0.2180858 0.8174618 0.55985 -0.1353674 0.6137182 -0.5688993 -0.547452 0.2977758 -0.8869141 0.3531476 0.1643905 -0.873577 -0.4580819 -0.07709884 -0.8987124 0.4317081 -0.3651488 -0.7598916 -0.5378021 -0.5292317 -0.8474736 0.04125994 -0.7725501 -0.4527899 0.4451381 -0.7816776 -0.3343057 -0.5265168 -0.9072093 -0.0606091 0.4162907 -0.8271861 0.1146491 -0.550108 -0.6463121 0.3951581 0.6527869 -0.6252959 0.5526422 -0.5509915 -0.3765317 0.85685 0.3521821 -0.276946 0.8631283 -0.4222683 0.0770955 0.7996759 0.595462 0.2468269 0.7687066 -0.5900565 0.5568665 0.6247776 0.5473141 0.7117074 0.6915456 -0.1234399 0.9719849 0.2110841 -0.1033874 0.9446828 0.1471767 0.2931101 0.852164 -0.4525113 -0.2627738 0.857616 -0.4611202 -0.2277346 0.4058433 -0.8047358 0.4332339 0.3043488 -0.7913756 -0.5301854 -0.05727434 -0.8553274 0.5149125 -0.175175 -0.7446378 -0.6440716 -0.4886016 -0.5104599 0.707601 -0.6387049 -0.4892908 -0.5938439 -0.880304 -0.09253513 0.4652979 -0.740775 0.6561897 -0.1437622 -0.3396663 0.9207457 -0.1919747 -0.1907268 0.8566255 0.4793913 0.157415 0.8367339 -0.5244967 0.3288777 0.8052063 0.4934393 0.723379 0.5584495 -0.4060259 0.8319333 0.5546405 0.01615464 0.9863911 -0.01829016 0.1633952 0.9743623 -0.01490265 0.2244907 0.7707272 -0.4038815 -0.4928076 0.5852723 -0.533793 0.6103454 0.4448397 -0.7415996 -0.5021432 0.1401666 -0.7610534 0.633365 0.00307244 -0.7705515 -0.6373705 -0.4325104 -0.5869451 0.6844196 -0.8862352 -0.4622223 0.03061991 -0.9478762 -0.02245426 -0.317847 -0.7354314 0.1606777 0.6582731 -0.6591191 0.3526456 -0.6642312 -0.328143 0.5365208 0.7774752 -0.07650935 0.8848295 -0.4595903 0.416006 0.8284537 0.3749715 0.4892525 0.7551794 -0.4362754 0.7199439 0.5129877 0.4674659 0.8644594 0.4487131 -0.2266424 0.994953 0.04619175 0.08907896 0.1667759 -0.7605898 -0.6274465 -0.1928637 -0.4266984 -0.8835905 -0.3177168 -0.5799875 -0.7501139 -0.455298 -0.2430329 -0.8565272 -0.4947912 -0.2497171 -0.83236 -0.463846 0.05278068 -0.8843422 -0.55325 0.121786 -0.8240647 -0.4192461 0.2945325 -0.8587686 -0.460608 0.3906552 -0.7970123 -0.3084512 0.5654012 -0.7649702 -0.160394 0.4607671 -0.8729075 -0.06904727 0.5918791 -0.8030639 0.1076078 0.4958067 -0.8617404 0.1000205 0.541225 -0.8349081 0.4152474 0.4877175 -0.7679201 0.4019377 0.3964969 -0.8253706 0.6087909 0.3092325 -0.7305813 0.5704667 0.1012986 -0.81505 0.6234928 0.04765999 -0.7803751 0.5149546 -0.05281251 -0.8555892 0.5620424 -0.1350864 -0.8160026 0.4283867 -0.2894055 -0.8559962 0.4270167 -0.2864174 -0.8576841 0.3407143 -0.5505699 -0.7620936 0.1452388 -0.4253959 -0.8932771 0.003522753 -0.6790835 -0.7340527 -0.1650744 -0.4505397 -0.8773623 -0.2711657 -0.5124536 -0.8147763 -0.4359001 -0.3172946 -0.8422087 -0.4718567 -0.3793554 -0.79589 -0.6382367 -0.1574944 -0.7535579 -0.5348104 -0.01856923 -0.8447681 -0.6217139 0.07756197 -0.7793946 -0.4473233 0.2204979 -0.8667657 -0.4829911 0.2915025 -0.8256791 -0.364395 0.5937308 -0.7174261 -0.3895876 0.3927096 -0.8330671 -0.09051567 0.5114861 -0.854511 -0.02596879 0.6204203 -0.7838394 0.1833399 0.5194869 -0.8345777 0.182813 0.4175292 -0.8900837 0.4957343 0.4492837 -0.7432305 0.4241936 0.169959 -0.8894795 0.5239711 0.1459369 -0.8391405 0.59197 -0.1072413 -0.7987934 0.5318862 -0.1173166 -0.8386501 0.4674859 -0.5250848 -0.7111561 0.4544529 -0.4743015 -0.7539965 0.1223213 -0.5613368 -0.8184978 0.0886541 -0.5193157 -0.8499715 -0.1619028 -0.6306746 -0.758971 -0.1987446 -0.4010447 -0.8942393 -0.3235926 -0.4388252 -0.8382841 -0.4527176 -0.1833681 -0.8725956 -0.6638301 -0.38703 -0.6399511 -0.5631296 -0.001158416 -0.8263679 -0.6243932 -0.03081363 -0.7805022 -0.5515026 0.2711656 -0.788869 -0.5430445 0.2716569 -0.7945473 -0.3725559 0.4023776 -0.8362382 -0.3930744 0.5823138 -0.7116202 -0.1703039 0.4302389 -0.886505 -0.1468766 0.5386788 -0.8296098 0.04012638 0.6325299 -0.7734959 0.09354388 0.461383 -0.8822559 0.32692 0.5270554 -0.7844336 0.4682912 0.3859248 -0.7948367 0.4335801 0.3809521 -0.8166295 0.5773741 0.1632152 -0.8 0.5446966 0.1415975 -0.826593 0.6200584 -0.1780596 -0.7640828 0.449234 -0.2191237 -0.8661257 0.4977813 -0.4498667 -0.7415078 0.2288632 -0.4563193 -0.8598805 0.2327285 -0.4599254 -0.8569166 0.03631764 -0.5909622 -0.8058814 -0.01056826 -0.5074015 -0.8616451 -0.2752144 -0.5954261 -0.7548013 -0.3156905 -0.4135698 -0.8539904 -0.4982097 -0.3929069 -0.7729239 -0.4303674 -0.2119783 -0.8774105 -0.5889164 -0.1346845 -0.7968925 -0.5214393 0.02482724 -0.8529272 -0.6045129 0.1107189 -0.7888634 -0.4199079 0.2887734 -0.8603996 -0.473929 0.2989202 -0.8282742 -0.3684844 0.5471675 -0.7515498 -0.1729283 0.4981317 -0.8496827 -0.1266736 0.6062131 -0.7851495 0.05819714 0.5868329 -0.807614 0.1012562 0.4403896 -0.8920786 0.3457843 0.5119712 -0.7863326 0.3592068 0.340977 -0.8687377 0.5237013 0.3280838 -0.7861922 0.4910798 0.1246895 -0.8621445 0.5623386 0.08752918 -0.8222615 0.5620361 -0.1206063 -0.8182723 0.4609963 -0.137037 -0.8767572 0.4871076 -0.4569049 -0.7442877 0.263592 -0.3951461 -0.879988 0.2161349 -0.5991224 -0.7709332 0.04854869 -0.5413236 -0.8394117 -0.008921384 -0.4341481 -0.9007974 -0.1978418 -0.5415983 -0.8170251 -0.2825168 -0.3886038 -0.8770242 -0.4156069 -0.4334934 -0.7995964 -0.5632245 -0.2395717 -0.790812 -0.4637681 -0.139145 -0.8749617 -0.6065919 0.03235322 -0.7943549 -0.4977159 0.1161654 -0.8595257 -0.5513235 0.2352918 -0.800425 -0.3528884 0.2845792 -0.8913387 -0.3538925 0.5040932 -0.7878136 -0.1535846 0.4585928 -0.8752739 -0.1147171 0.5692466 -0.8141244 0.1278879 0.5867906 -0.7995758 0.1396743 0.5322328 -0.8349968 0.433419 0.5263291 -0.731523 0.4024717 0.3256216 -0.8555625 0.5495998 0.1997416 -0.8111988 0.4796395 0.2088794 -0.8522414 0.6207557 0.005900204 -0.7839819 0.5117295 -0.04661011 -0.8578813 0.5288074 -0.2458648 -0.8123506 0.4124723 -0.2669591 -0.8709762 0.4338035 -0.4488524 -0.7812466 0.1835651 -0.484086 -0.8555493 0.2435895 -0.5504677 -0.7985298 -0.02042615 -0.644452 -0.764372 -0.08380496 -0.5695326 -0.8176853 -0.2599251 -0.6263456 -0.7349355 -0.3401161 -0.381905 -0.8593426 -0.4867146 -0.4083727 -0.7722309 -0.5578262 -0.1657314 -0.8132423 -0.4642277 -0.09516376 -0.8805887 -0.6255813 0.127784 -0.7696228 -0.4159507 0.1846864 -0.8904358 -0.4434782 0.2773632 -0.8522892 -0.2970981 0.4788323 -0.8261068 -0.208593 0.4321354 -0.8773529 -0.1188297 0.6390651 -0.759918 0.1228002 0.4662836 -0.8760706 0.1213819 0.4808236 -0.868375 0.3365069 0.4871575 -0.8058788 0.3434262 0.2650866 -0.9009926 0.437326 0.2668946 -0.858786 0.6045345 0.1634762 -0.7796241 0.4997805 0.04536145 -0.8649636 0.6281269 -0.1150178 -0.7695631 0.4765011 -0.1984283 -0.8564888 0.5293833 -0.3831461 -0.7569363 0.2874432 -0.4624671 -0.8387495 0.2649146 -0.5763438 -0.7730771 0.09775626 -0.4883247 -0.8671695 -0.04168635 -0.6376098 -0.7692308 -0.1528825 -0.4474886 -0.8811249 -0.2890557 -0.5166084 -0.8059545 -0.4495205 -0.3096165 -0.8378955 -0.4539381 -0.315246 -0.8334029 -0.5343834 -0.04471051 -0.8440589 -0.5241103 -0.04005461 -0.850708 -0.5510892 0.2656892 -0.7910183 -0.3904193 0.2595915 -0.8832809 -0.4020776 0.47245 -0.7842989 -0.1659066 0.4680046 -0.8680132 -0.1555044 0.507795 -0.8473269 0.0706377 0.5985867 -0.7979375 -0.003079652 0.7429119 -0.6693822 0.3162446 0.5652711 -0.761878 0.3245931 0.4120517 -0.8513828 0.4255391 0.4165621 -0.8033632 0.490406 0.2012243 -0.847945 0.5411829 0.2558151 -0.8010493 0.6448732 -0.02382904 -0.7639181 0.4600729 -0.1092017 -0.8811402 0.5841836 -0.3718379 -0.7214334 0.2784751 -0.3388442 -0.8986859 0.267298 -0.5592461 -0.7847265 0.06544965 -0.5726079 -0.8172127 0.03293716 -0.5147045 -0.8567349 -0.281199 -0.6491682 -0.7067587 -0.307885 -0.4113719 -0.8578928 -0.45603 -0.302144 -0.8371055 -0.4055222 -0.2934396 -0.8657049 -0.6536136 -0.1162019 -0.7478545 -0.5006808 0.01157724 -0.8655546 -0.6348629 0.2123846 -0.7428606 -0.4866733 0.3216553 -0.8122112 -0.4963617 0.4103763 -0.7649945 -0.3448291 0.5354232 -0.770983 -0.3026191 0.516925 -0.8007562 -0.1033602 0.6474194 -0.7550926 -0.009743094 0.5340708 -0.8453837 0.187949 0.5601463 -0.8067909 0.1922112 0.5270578 -0.8278073 0.4237281 0.4959623 -0.7579419 0.4363697 0.3649141 -0.8224471 0.5984531 0.313346 -0.7373386 0.5519771 0.06029468 -0.8316767 0.6354556 4.65214e-4 -0.7721375 0.5037628 -0.09521901 -0.8585782 0.5885533 -0.3475618 -0.7299355 0.3292996 -0.3756301 -0.8662931 0.3148103 -0.5016921 -0.8057293 0.1621791 -0.4790056 -0.8627003 0.05541336 -0.6817998 -0.7294371 -0.173897 -0.4682128 -0.8663352 -0.277787 -0.5096859 -0.8142817 -0.3024436 -0.3802305 -0.874044 -0.5048319 -0.3954757 -0.7672966 -0.5326463 -0.1362006 -0.8353067 -0.5093056 -0.1210439 -0.8520307 -0.5731796 0.1327291 -0.8086088 -0.5805911 0.1308417 -0.8036135 -0.5213406 0.4178333 -0.7440561 -0.3294629 0.3949215 -0.857608 -0.31445 0.4444931 -0.8387773 -0.1977206 0.4447783 -0.873544 -0.1192957 0.5912131 -0.7976438 0.1506944 0.6655408 -0.7309902 0.1274406 0.6413177 -0.756618 0.4242085 0.4872857 -0.7632824 0.305362 0.480642 -0.8220324 0.4925605 0.2508581 -0.8333393 0.5968241 0.2284696 -0.7691571 0.4540172 0.00985831 -0.8909384 0.5977447 -0.09199756 -0.7963906 0.4504572 -0.3254752 -0.831357 0.3387728 -0.3071097 -0.889335 0.3347209 -0.4955809 -0.8014746 0.1178365 -0.5047619 -0.8551784 0.1120026 -0.5189498 -0.8474352 -0.08056741 -0.5704839 -0.8173476 -0.1227439 -0.4887443 -0.8637495 -0.2615987 -0.5347209 -0.8035172 -0.3803336 -0.3718919 -0.8467838 -0.3848925 -0.3729413 -0.8442586 -0.5831535 -0.206075 -0.7857896 -0.435461 -0.057599 -0.8983631 -0.5615794 0.03093332 -0.8268445 -0.5773009 0.2463281 -0.7784897 -0.4145853 0.2823438 -0.8651018 -0.4331686 0.3566769 -0.8277359 -0.3299109 0.5480255 -0.7686527 -0.1042817 0.5182684 -0.8488364 -0.09920442 0.5330164 -0.840269 0.1794108 0.5931083 -0.7848785 0.2040837 0.396245 -0.8951758 0.450578 0.4595993 -0.7653418 0.4175382 0.2615337 -0.870208 0.6307033 0.174183 -0.7562233 0.596931 -0.05308318 -0.8005346 0.5297186 -0.07687532 -0.8446825 0.4669898 -0.3375096 -0.8173174 0.430981 -0.275404 -0.8593068 0.3036389 -0.5437253 -0.7824106 0.212214 -0.4964658 -0.8417167 0.03309637 -0.716158 -0.6971531 -0.1279381 -0.5010918 -0.8558849 -0.3130615 -0.5705164 -0.7592784 -0.3253617 -0.3720008 -0.8693418 -0.5194249 -0.3578022 -0.7759996 -0.4745023 -0.1769036 -0.862295 -0.5575719 -0.1345364 -0.8191542 -0.5328572 0.07609313 -0.842777 -0.4903998 0.09056812 -0.8667788 -0.527154 0.2752755 -0.8039478 -0.3531766 0.3097109 -0.8828054 -0.3638306 0.5129146 -0.7775257 -0.1183447 0.4650698 -0.8773282 -0.08214348 0.564865 -0.8210847 0.1482233 0.5660863 -0.8109108 0.1964411 0.4230278 -0.8845667 0.3062434 0.4707939 -0.8273863 0.4685015 0.3874898 -0.7939509 0.4167109 0.2045316 -0.8857307 0.5284799 0.1798422 -0.8296782 0.6069744 -0.08449423 -0.7902169 0.452399 -0.1324954 -0.8819184 0.5339889 -0.301333 -0.7899711 0.3182339 -0.4463693 -0.8363502 0.2618321 -0.4105594 -0.8734329 0.1484146 -0.5756154 -0.8041394 0.02009862 -0.4907903 -0.8710459 -0.1554423 -0.6436053 -0.7494065 -0.2051774 -0.4394268 -0.8745321 -0.4467332 -0.4280642 -0.7856148 -0.3833676 -0.2869116 -0.8779015 -0.6205255 -0.1364538 -0.7722231 -0.461299 0.04254555 -0.8862242 -0.5610074 0.01632171 -0.82765 -0.5307121 0.2475857 -0.8105839 -0.4234024 0.2644283 -0.8664919 -0.4315611 0.4829859 -0.7618923 -0.2641547 0.5655204 -0.7812868 -0.1802322 0.5090306 -0.8416675 -0.005753815 0.5550442 -0.8318011 0.009745657 0.5834782 -0.8120704 0.2015717 0.54216 -0.8157398 0.2176387 0.3507764 -0.910818 0.493284 0.4000064 -0.7724415 0.4443473 0.2204429 -0.868309 0.62054 0.1313916 -0.773089 0.5965815 -0.05191349 -0.8008717 0.6399055 -0.02931922 -0.7678943 0.5687134 -0.3119629 -0.761081 0.5112197 -0.309106 -0.8019401 0.3608109 -0.4655417 -0.8081377 0.353688 -0.5581917 -0.7505511 0.08890986 -0.6442769 -0.7596067 0.1404593 -0.5194351 -0.842887 -0.113228 -0.6040344 -0.7888739 -0.1360065 -0.4885035 -0.8618971 -0.4131001 -0.4319985 -0.8017017 -0.3828045 -0.4205246 -0.822569 -0.4492727 -0.1246983 -0.8846493 -0.5358447 -0.1076548 -0.8374253 -0.6299784 0.08322858 -0.77214 -0.4894533 0.2477715 -0.836089 -0.4094162 0.2352859 -0.8814869 -0.3528642 0.5229581 -0.7758878 -0.2619215 0.4703086 -0.8427378 -0.08154022 0.6656772 -0.7417716 0.05806022 0.5621585 -0.824989 0.1625098 0.6251999 -0.7633581 0.2909489 0.5032852 -0.8136663 0.397325 0.529035 -0.7498365 0.4753879 0.3130381 -0.8222004 0.6524922 0.2670317 -0.7091884 0.5439293 0.009226202 -0.8390804 0.6448417 -0.07826906 -0.7602981 0.4385278 -0.2292561 -0.8689851 0.4902443 -0.3449432 -0.8004217 0.2955003 -0.4618502 -0.8362859 0.2925525 -0.4596979 -0.8385052 0.04017174 -0.5277482 -0.8484504 0.03893339 -0.530731 -0.8466458 -0.200052 -0.5881058 -0.7836523 -0.2771472 -0.4062138 -0.8707352 -0.3593989 -0.4378298 -0.824098 -0.5424797 -0.1833904 -0.8198071 -0.5288082 -0.173655 -0.8307864 -0.5417429 0.1414385 -0.8285589 -0.5194079 0.1222974 -0.8457298 -0.494144 0.3955873 -0.7741656 -0.3145819 0.3520378 -0.8815371 -0.2364174 0.5781982 -0.780893 -0.0807963 0.4894271 -0.8682932 -0.02543604 0.5739518 -0.8184941 0.2326579 0.4771494 -0.8474661 0.2292636 0.4325162 -0.8719909 0.5417233 0.3842925 -0.7475663 0.4236264 0.1863183 -0.8864684 0.5933496 0.09734082 -0.7990376 0.5335811 -0.1095842 -0.8386194 0.4586883 -0.1245875 -0.8798198 0.534207 -0.3869139 -0.7516121 0.2643398 -0.4336818 -0.8614202 0.2690067 -0.4375617 -0.8580065 0.07812982 -0.6060901 -0.7915495 -0.04927051 -0.4605787 -0.8862504 -0.1373099 -0.546128 -0.8263717 -0.3267595 -0.486073 -0.8105316 -0.3037518 -0.3184822 -0.8979443 -0.5228685 -0.3101418 -0.7939904 -0.6491696 -0.04873895 -0.7590807 -0.5565741 -0.08584147 -0.8263514 -0.5983332 0.1369308 -0.7894603 -0.4228514 0.2052443 -0.8826503 -0.457795 0.2774122 -0.8446693 -0.3119651 0.546751 -0.7770079 -0.1587368 0.4253645 -0.8909926 -0.0658735 0.5984889 -0.7984184 0.1579861 0.5571485 -0.8152459 0.1761732 0.3975798 -0.9004962 0.4074658 0.4793938 -0.7772729 0.5312339 0.3085758 -0.7890322 0.4396588 0.171455 -0.8816482 0.5645985 0.1017661 -0.8190679 0.5519265 -0.0707581 -0.8308854 0.450951 -0.1008744 -0.8868302 0.5328754 -0.3502948 -0.7702839 0.2976958 -0.3943327 -0.8694131 0.2999138 -0.4246621 -0.8542329 0.1747446 -0.5906023 -0.7878155 0.0476548 -0.4789612 -0.8765416 -0.09424674 -0.5934818 -0.7993103 -0.2127094 -0.4503182 -0.867161 -0.3566701 -0.5266484 -0.7716399 -0.4745299 -0.2642491 -0.8396391 -0.4320445 -0.211642 -0.8766672 -0.6215308 -0.07371008 -0.7799143 -0.4686302 0.1116437 -0.8763113 -0.4998654 0.1073539 -0.8594241 -0.4955032 0.380244 -0.7809553 -0.3061052 0.3528811 -0.8841802 -0.2832741 0.5457146 -0.788639 -0.03668743 0.5135576 -0.8572705 -0.03890371 0.5184698 -0.8542106 0.2379136 0.5625656 -0.7917811 0.2452823 0.4726358 -0.846435 0.4593958 0.4581744 -0.7609415 0.4929112 0.2868834 -0.8214235 0.4955688 0.2910684 -0.8183463 0.6256967 0.009391665 -0.7800101 0.5214071 0.05845779 -0.8513033 0.6048967 -0.158828 -0.7803035 0.4631679 -0.177154 -0.8683848 0.4435049 -0.4900279 -0.7504506 0.3502128 -0.4428415 -0.8253743 0.1160414 -0.6592113 -0.7429501 0.05066263 -0.5865761 -0.8083081 -0.196067 -0.680119 -0.7063964 -0.2584804 -0.4847061 -0.8356123 -0.4113114 -0.426695 -0.805453 -0.3654919 -0.303816 -0.8798361 -0.5861118 -0.2344094 -0.7755807 -0.5388203 -0.0448597 -0.8412255 -0.4635598 -0.004224359 -0.8860556 -0.5878621 0.2037343 -0.7828862 -0.4395757 0.2917069 -0.8495178 -0.6573073 0.3233157 -0.6807453 -0.2977395 0.4984592 -0.8141804 -0.3529314 0.5395197 -0.7644332 0.02914106 0.5908722 -0.8062388 0.00949639 0.5511168 -0.8343741 0.3427379 0.4640908 -0.8167929 0.3154717 0.3805106 -0.869304 0.5476896 0.2624632 -0.794449 0.4987694 0.1857137 -0.8466048 0.6677914 0.0206092 -0.7440631 0.5613021 -0.1004951 -0.821487 0.6245752 -0.3208702 -0.7120029 0.4086117 -0.3561064 -0.8403718 0.4041687 -0.5101156 -0.7592297 0.1146078 -0.4653873 -0.8776559 0.1420409 -0.5073179 -0.8499724 -0.08308535 -0.5867888 -0.8054663 -0.1572861 -0.4168888 -0.8952457 -0.3265895 -0.5017495 -0.8009911 -0.483994 -0.3205251 -0.8142564 -0.3939458 -0.1951016 -0.8981881 -0.6137278 -0.07846045 -0.7856094 -0.5109766 0.1160839 -0.8517204 -0.5051438 0.1166102 -0.8551209 -0.457752 0.3650699 -0.8106708 -0.3275627 0.3577783 -0.8744698 -0.312417 0.481178 -0.8190625 -0.1208676 0.5241657 -0.8429955 -0.09779536 0.5830115 -0.8065567 0.122696 0.4757407 -0.8709859 0.1981053 0.5335499 -0.8222401 0.3953483 0.44448 -0.8038266 0.3828278 0.4079579 -0.8288626 0.5178479 0.2104562 -0.8291814 0.5224208 0.2150893 -0.825114 0.5569554 0.05232411 -0.8288927 0.4999635 -6.01786e-4 -0.8660463 0.6146925 -0.1975671 -0.7636233 0.5147804 -0.3425113 -0.7859308 0.4058055 -0.3278806 -0.8531215 0.3294017 -0.5415529 -0.7734436 0.141532 -0.4511808 -0.8811383 0.0793097 -0.5864858 -0.8060672 -0.1422348 -0.4769042 -0.8673706 -0.2465203 -0.5555956 -0.7940663 -0.3771893 -0.3860687 -0.8418309 -0.426954 -0.5157257 -0.7427902 -0.5543662 -0.225691 -0.8010878 -0.6110241 -0.2037146 -0.764951 -0.5884525 0.006824433 -0.8085031 -0.6000764 1.11603e-4 -0.7999427 -0.580475 0.2549829 -0.7733256 -0.5202193 0.2677997 -0.8109595 -0.4675989 0.4708101 -0.7481237 -0.3734356 0.4540008 -0.808968 -0.2055811 0.6081391 -0.7667486 -0.1568422 0.5751851 -0.8028466 0.07710546 0.6895991 -0.7200749 0.1687498 0.4600708 -0.8716987 0.2788146 0.5043317 -0.817259 0.4054675 0.3210302 -0.8558831 0.3810251 0.2477824 -0.8907434 0.626029 0.1898602 -0.7563338 0.5417935 -0.02996861 -0.8399772 0.5726268 -0.01951837 -0.8195838 0.5802643 -0.3174353 -0.7500188 0.3848837 -0.3338298 -0.8604779 0.3657759 -0.5090983 -0.7791193 0.162503 -0.4545287 -0.8757833 0.1426463 -0.5201392 -0.8420851 -0.09836119 -0.6453767 -0.7575051 -0.1667864 -0.419032 -0.8925215 -0.3880925 -0.5076124 -0.7692294 -0.4225332 -0.2486849 -0.8715627 -0.4914111 -0.2422314 -0.8365638 -0.5776693 -0.08275824 -0.8120649 -0.5211821 -0.03042501 -0.852903 -0.6375576 0.1552336 -0.7546011 -0.477209 0.3265381 -0.8158704 -0.4830811 0.3699226 -0.7935931 -0.3289005 0.3926488 -0.8588663 -0.3073287 0.5474742 -0.7783451 -0.1045272 0.4721412 -0.8753038 0.01952701 0.6555679 -0.7548838 0.1890149 0.4705392 -0.8618969 0.1898205 0.5032833 -0.8430149 0.4184415 0.3965074 -0.8171222 0.4156886 0.3889874 -0.8221265 0.5322654 0.1939202 -0.8240684 0.6244766 0.1690323 -0.7625334 0.6770686 0.003052413 -0.7359136 0.545145 -0.1259674 -0.8288241 0.6269286 -0.3167427 -0.7117828 0.3838286 -0.3770619 -0.8429116 0.3506671 -0.525411 -0.7752263 0.2043614 -0.449786 -0.8694419 0.1053538 -0.5559704 -0.8244984 0.009537696 -0.5170468 -0.855904 -0.04676067 -0.5764608 -0.8157858 -0.2587868 -0.504306 -0.8238356 -0.2577347 -0.4894183 -0.8330922 -0.4556209 -0.3538862 -0.8168073 -0.4385305 -0.3181861 -0.8405051 -0.5605477 -0.1667222 -0.8111658 -0.4847422 -0.08513861 -0.8705036 -0.6126867 0.08322024 -0.7859322 -0.4262766 0.1878681 -0.8848695 -0.493682 0.3134286 -0.811197 -0.3400117 0.4944788 -0.7999268 -0.2469192 0.4396061 -0.8635841 -0.1281595 0.5757523 -0.8075175 -0.01555633 0.4793953 -0.8774613 0.1571653 0.6361844 -0.7553599 0.2672641 0.3836225 -0.8839704 0.4467625 0.443676 -0.776888 0.5081079 0.2702122 -0.8178091 0.3902395 0.1120656 -0.9138678 0.5630648 0.02794635 -0.8259401 0.6149643 -0.1494283 -0.7742676 0.4419696 -0.196906 -0.8751519 0.4885503 -0.3470096 -0.8005642 0.2689157 -0.4151139 -0.8691174 0.2554494 -0.5706194 -0.7804737 0.0214203 -0.5061182 -0.8621982 -0.05167531 -0.6151536 -0.786712 -0.2608666 -0.5030385 -0.8239545 -0.2569602 -0.3607103 -0.8965822 -0.4819428 -0.3885274 -0.785352 -0.6013179 -0.1204263 -0.7898825 -0.4904722 -0.1627398 -0.8561266 -0.6348729 0.1233082 -0.7627132 -0.5949565 0.1342701 -0.7924636 -0.4459893 0.4169282 -0.7920002 -0.4620267 0.4650186 -0.7551748 -0.1590712 0.464299 -0.8712766 -0.1396685 0.5392298 -0.8304963 0.09526681 0.5818292 -0.8077123 0.1318071 0.4663113 -0.8747462 0.3162035 0.5236256 -0.7910952 0.4030758 0.3352712 -0.8515416 0.3896305 0.3101964 -0.86716 0.5511118 0.1736724 -0.8161579 0.4525254 0.03808891 -0.8909378 0.5939882 -0.05919867 -0.8022927 0.5762283 -0.2504866 -0.7779573 0.3788086 -0.2647387 -0.886802 0.395727 -0.3858225 -0.8333914 0.2108796 -0.5165715 -0.8298697 0.1445699 -0.4528896 -0.8797674 -0.03647702 -0.6746612 -0.7372257 -0.2126421 -0.4203725 -0.882083 -0.2383256 -0.5403414 -0.8069895 -0.5639532 -0.2831517 -0.775746 -0.4553474 -0.2763684 -0.8463329 -0.6016762 -0.04825341 -0.7972812 -0.4536417 0.03804427 -0.8903717 -0.5638508 0.1815134 -0.8056832 -0.3990395 0.3931611 -0.828367 -0.3877313 0.3870804 -0.8365603 -0.1804725 0.6289992 -0.7561678 -0.04293495 0.5075854 -0.860531 0.110982 0.6203056 -0.7764689 0.184691 0.4823588 -0.8562822 0.2917165 0.5119643 -0.8079568 0.3801764 0.3391231 -0.8605006 0.4307662 0.3444581 -0.8341398 0.5772408 0.2093425 -0.7892837 0.508581 0.09713578 -0.8555174 0.6100411 0.01794308 -0.7921667 0.5689298 -0.2268034 -0.790493 0.5435218 -0.2295156 -0.8074074 0.4701185 -0.4232037 -0.7745239 0.2391405 -0.3664857 -0.8991664 0.2082598 -0.5664675 -0.7973346 0.02218943 -0.5171032 -0.8556355 0.003192305 -0.5590776 -0.8291093 -0.2207066 -0.6326544 -0.7423187 -0.233148 -0.4515062 -0.8612689 -0.4143685 -0.2241315 -0.8820794 0.249447 -0.2500181 -0.9355571 -0.4491041 -0.3722941 0.8122209 -0.607752 -0.2419901 -0.7563586 0.03684794 0.6162818 -0.7866633 0.3066013 0.5462052 0.7795226 -0.147682 -0.4154217 0.8975606 -0.2416287 0.3309095 0.9122032 0.3373211 0.2642886 0.9035298 -0.4832235 -0.3291771 -0.8112567 0.4214812 -0.249279 -0.8719023 0.06101328 -0.5699492 -0.8194116 -0.3063423 -0.5656166 0.7656582 -0.1029236 0.4135729 0.904635 0.0701496 0.3936331 -0.9165872 0.4321594 0.4454374 -0.7841072 0.657183 0.1852619 0.7306084 -0.09222519 -0.4505587 -0.8879704 0.3556588 0.4565755 0.8155033 0.4934421 0.4001203 -0.7722815 -0.3285737 0.4807546 -0.8129664 -0.2722862 -0.1923713 0.9427903 0.4392197 0.08109128 0.8947125 0.5705001 -0.1418486 0.8089554 0.2963058 0.2764988 0.9141944 0.5223389 0.06917399 0.8499278 -0.3646759 0.3529213 -0.8616601 -0.3909447 0.3835356 -0.8366976 -0.6831846 -0.6067199 0.4063866 -0.9991966 0.03862214 0.01070988 0.7784711 0.0792948 -0.6226517 0.9985163 0.05187475 0.01655936 0.4500329 0.2099171 -0.8679893 0.3513047 0.1508396 -0.9240306 0.5749233 0.2425457 -0.7814313 0.9533841 0.1523415 -0.260482 0.7266968 0.3808503 -0.571721 0.8800599 0.4108785 -0.2380622 0.8836427 0.4236627 -0.1992126 0.08355981 0.1470181 -0.985598 0.3333809 0.3766043 -0.8643069 0.3828341 0.5279143 -0.7581192 0.5698578 0.7041496 -0.4235984 0.5345376 0.705493 -0.4653484 0.6715368 0.7254863 -0.1506916 0.161967 0.4857432 -0.8589647 0.1559708 0.5039946 -0.8495073 0.4069495 0.8295775 -0.3823525 0.0424202 0.52271 -0.8514546 0.2345683 0.8032505 -0.5475093 0.3026886 0.9514085 0.05658304 0.1256775 0.911255 -0.3921987 -0.009062945 0.6678751 -0.7442182 0.03473657 0.9090537 -0.4152286 -0.05135393 0.234447 -0.9707716 -0.04301553 0.9466928 -0.3192532 -0.06248456 0.9665979 -0.2485644 -0.1824507 0.6534324 -0.7346686 -0.1822764 0.4687802 -0.8643035 -0.2329195 0.7665633 -0.598439 -0.2951296 0.955031 -0.02853554 -0.3828457 0.8345456 -0.3961855 -0.3657575 0.4872166 -0.7929953 -0.5071732 0.7552831 -0.4151178 -0.3729146 0.381878 -0.8456383 -0.5965782 0.7523297 -0.2794542 -0.4969854 0.3373088 -0.7995175 -0.453692 0.1974028 -0.86902 -0.7773477 0.4919174 -0.3921068 -0.5011698 0.1635622 -0.8497508 -0.8537105 0.4427801 -0.274088 -0.4235399 0.01176297 -0.9058011 -0.8682656 0.2185338 -0.445374 -0.2560393 -0.03567212 -0.9660081 -0.9112946 0.132658 -0.3898003 -0.7817339 -0.04817712 -0.6217485 -0.8539518 -0.2281099 -0.4676883 -0.9070165 -0.2551971 -0.3349562 -0.5830546 -0.331071 -0.7419161 -0.5687357 -0.4031402 -0.7169504 -0.9178251 -0.394331 -0.04582774 -0.7218119 -0.5699824 -0.3925656 -0.356319 -0.4073054 -0.8409157 -0.2146778 -0.2936908 -0.9314823 -0.1239702 -0.3621767 -0.9238287 -0.6642858 -0.7281 -0.1691002 -0.4112028 -0.7010741 -0.5825868 -0.5479673 -0.7800028 -0.3022046 -0.2616897 -0.7942274 -0.5483807 -0.01641833 -0.2543021 -0.9669855 -0.326686 -0.9450919 -0.008808135 -0.1847918 -0.7343521 -0.6531302 -0.280953 -0.9439626 -0.173205 0.04267162 -0.4703686 -0.8814377 0.01982825 -0.7339793 -0.6788824 0.04566138 -0.7808047 -0.6231044 0.03662806 -0.9680773 -0.2479616 0.2316702 -0.48706 -0.8420817 0.2444487 -0.7868068 -0.5667273 0.1527365 -0.9847627 0.08315193 0.3059207 -0.6054438 -0.7347452 0.3124208 -0.912533 -0.2639638 0.1619607 -0.2149702 -0.9630975 0.4522181 -0.6534425 -0.6070518 0.5358208 -0.7518934 -0.3841255 0.4735144 -0.8589138 -0.1950675 0.3894831 -0.2709955 -0.8802638 0.5581757 -0.3919726 -0.7312985 0.639871 -0.407233 -0.6517105 0.7451438 -0.650446 -0.1472439 0.7687505 -0.5136819 -0.3809905 0.2577243 -0.08084821 -0.9628302 0.432625 -0.06065964 -0.8995311 0.9471235 -0.3198083 -0.02607244 0.7639507 -0.116804 -0.6346151 0.7221834 -0.07824999 -0.6872614 0.9362906 -0.1570636 -0.3141512 0.0200172 -0.002067148 -0.9997975 -0.005506694 -0.004064738 -0.9999766 -0.008383452 0.01726156 -0.9998159 0.001011729 0.01108711 -0.999938 -0.001823782 0.001003324 -0.9999979 0.001794755 -0.00746864 -0.9999705 -0.0143156 -8.88148e-4 -0.9998971 0.008753061 0.006068944 -0.9999433 -0.8643854 0.4978467 0.07061707 -0.865 0.4965335 0.07231545 -0.003100335 0.997342 0.07279652 -0.001721084 0.9974631 0.07116633 0.8633298 0.4996482 0.07080602 0.86269 0.5005642 0.07212144 0.8647328 -0.4970691 0.07183098 0.8646543 -0.4972357 0.07162183 0.001816272 -0.9974734 0.07101792 0.001676321 -0.9974858 0.07084667 -0.8664495 -0.4978224 0.03792506 -0.8654531 -0.4997383 0.03539294 0.009097933 0.006614446 0.9999368 0.005990207 0.01050662 0.9999269 0.001660645 0.01117265 0.9999363 0.01147228 0.001919031 0.9999324 0.01050204 -0.003622949 0.9999383 0.009054124 0.004646837 0.9999483 -0.002516865 0.01115298 0.9999347 -2.47759e-4 0.01033258 0.9999467 -0.007600903 0.009114682 0.9999296 0.008434593 -0.007570862 0.9999358 0.008890092 -0.004817783 0.999949 -0.008720815 0.00577867 0.9999454 -0.01061332 0.004722237 0.9999326 0.004980623 -0.01063001 0.9999311 0.001236081 -0.01085174 0.9999405 3.14207e-4 -0.01036494 0.9999463 -0.01263403 -4.95535e-4 0.9999201 -0.003115892 -0.01130139 0.9999313 -0.009390234 -0.005870282 0.9999387 -0.00936675 -0.005788087 0.9999394 -0.006847321 -0.009856104 0.999928 7.5773e-4 -0.001523256 0.9999986 0.00256145 0.002545893 0.9999935 -4.32037e-4 -0.001502454 0.9999989 5.73207e-4 -9.23679e-4 0.9999995 -0.9996541 0.01340669 -0.02262961 -0.9452193 0.3261539 0.01357811 -0.9112268 0.4115808 -0.01634788 -0.7436513 0.6680544 0.02619373 -0.5702903 0.8207987 -0.03253501 -0.4239172 0.9055655 0.01567339 -0.1131478 0.9935626 -0.005555748 -0.06880807 0.99735 -0.02363395 0.2654907 0.963761 0.02606427 0.4676694 0.8836685 -0.02038228 0.5706262 0.8211506 0.00987184 0.7732074 0.6339769 -0.01495534 0.8504418 0.5254682 0.02514445 0.9713606 0.2358484 -0.02888035 0.9988411 0.03915852 0.02798217 0.9826894 -0.1844145 -0.01769489 0.913574 -0.4063414 0.01641583 0.8727355 -0.4880988 -0.009615778 0.6403834 -0.767975 0.01111131 0.5854166 -0.8105393 -0.01770579 0.2201742 -0.9752162 0.02183991 0.07253766 -0.9970352 -0.02567863 -0.1463718 -0.9890809 0.01716178 -0.3679385 -0.9297032 -0.01653248 -0.4952013 -0.8686152 0.01683545 -0.6803898 -0.7326123 -0.01868134 -0.8085959 -0.587939 0.0223692 -0.9125232 -0.4083603 -0.02331268 -0.9858971 -0.1648996 0.02854835 4.46107e-4 -6.12807e-4 -0.9999998 -0.00802493 -0.02179884 -0.9997302 0.01047807 -0.005864262 -0.999928 -9.19437e-4 -0.001019895 -0.9999991 0.01136571 -0.002132654 -0.9999331 0.003984928 0.0179944 -0.9998302 8.42861e-6 -1.41671e-4 -1 0.003428459 8.31584e-4 -0.9999938 -5.09064e-5 -1.33227e-4 -1 -0.002617955 0.007063508 -0.9999716 3.39564e-4 -5.92588e-4 -0.9999998 1.96004e-4 1.61818e-4 -1 -3.5127e-4 -3.7755e-4 -1 -4.47558e-4 4.90037e-4 -0.9999999 -1.13659e-4 -7.82968e-4 -0.9999998 -1.34161e-5 -4.27298e-5 -1 -8.79076e-4 -3.99938e-4 -0.9999995 -6.6701e-5 -4.27693e-5 -1 -0.00105822 1.4204e-5 -0.9999995 7.89619e-6 -6.76739e-5 -1 -0.00851953 -0.01494318 -0.9998521 0.0146473 0.01072782 -0.9998352 -0.01016539 0.004589974 -0.9999379 -0.006787836 0.009762525 -0.9999294 -0.008432686 0.006012797 -0.9999464 -0.9923853 -0.1172673 -0.03768187 -0.9785103 -0.1793146 0.1018041 -0.7144585 -0.6982129 -0.0452525 -0.7473807 -0.6585432 0.08799445 -0.2980173 -0.9430361 -0.1478806 -0.1061452 -0.9725812 0.2069278 0.3663828 -0.9117252 -0.185798 0.4976497 -0.8636954 0.07984453 0.8577327 -0.5140953 9.96224e-4 0.8795397 -0.4600768 -0.121405 0.9923644 0.007575929 0.1231082 0.9716449 0.1875083 -0.1440377 0.8564007 0.4953261 0.1457051 0.7326086 0.6683161 -0.1289897 0.3786944 0.9209294 0.09208542 0.441993 0.8952026 -0.05704802 0.03528887 0.9964827 0.07600539 -0.1182987 0.982185 -0.1460072 -0.4845933 0.862341 0.1467567 -0.6574801 0.7419193 -0.1314376 -0.8636848 0.4811106 0.1502707 -0.9361637 0.3378115 -0.09737056 -0.9832632 0.1042333 -0.1494285 -0.9864577 0.1599862 0.03613436 -0.8223316 0.5616468 0.09123456 -0.7779276 0.6092128 -0.1539108 -0.4251076 0.90106 0.08587557 -0.3964102 0.9177051 -0.02600783 0.02849322 0.9991897 0.02842646 -0.01125788 0.9837573 0.1791504 0.29485 0.9368665 -0.1880022 0.5296788 0.8314577 0.1676856 0.6222965 0.7755525 -0.1061398 0.8251081 0.549051 0.1331911 0.8864918 0.4486442 -0.1133604 0.9734448 0.2018268 0.1080332 0.9886949 0.1376232 -0.05951762 0.9638655 -0.2656075 0.02039486 0.9548726 -0.2829965 0.09017515 0.7659183 -0.6320892 -0.1176113 0.7072142 -0.699916 0.09982883 0.5196535 -0.8514525 -0.07063162 0.4502139 -0.8897719 0.07492256 0.1717522 -0.9783866 -0.1151559 0.08741295 -0.9878015 0.1288689 -0.3881484 -0.9129174 0.1261857 -0.3241574 -0.9387591 -0.1168481 -0.7201647 -0.679428 -0.1405003 -0.7874844 -0.6008521 0.1372781 -0.9279872 -0.3519175 -0.1224501 -0.9604088 -0.2474551 0.1279882 -4.91447e-6 0 1 -2.06439e-6 0 1 -3.57002e-7 0 1 3.21316e-6 0 1 -3.56754e-6 0 1 4.69678e-6 0 1 3.00939e-6 0 1 -1.04259e-6 0 1 -3.54617e-6 0 1 8.89551e-6 0 1 -1.99596e-6 0 -1 1.91927e-6 0 -1 -1.47617e-6 0 -1 2.52496e-6 0 -1 -5.17925e-6 0 -1 -8.15165e-6 0 -1 -6.14381e-6 0 -1 8.00733e-6 0 -1 4.08211e-6 0 -1 -7.49949e-6 0 -1 4.98878e-6 0 -1 -4.67517e-6 0 -1 -3.029e-7 0 -1 0.03199857 -0.03762358 0.9987796 0.04846596 -0.02727454 0.9984524 0.07273703 -0.05607575 0.9957735 -0.003283798 -0.01128071 0.999931 9.72986e-5 -0.00465393 0.9999892 0.1098273 2.0973e-4 0.9939507 -6.45746e-4 -0.003180444 0.9999948 0.07848966 0.02037781 0.9967067 0.01677376 -0.02217411 0.9996134 -0.03641623 -0.0491541 0.9981271 -0.01708352 -0.06977206 0.9974167 0.008273363 0.02874976 0.9995524 0.09069746 0.05054408 0.9945951 0.09298759 0.1599275 0.9827394 -0.01849329 0.07209032 0.9972267 -0.1042441 0.4115978 0.9053843 0.00439459 0.7420107 0.6703737 0.1431981 0.4409236 0.8860478 0.2503535 0.5638414 0.7870236 0.4229758 0.4780339 0.7697891 0.3356373 0.179822 0.9246685 0.5579392 0.4942966 0.6666145 0.4704176 0.1182218 0.874489 0.4763022 0.1230983 0.8706223 0.5088017 -0.09508013 0.8556172 0.5847443 -0.1509757 0.7970448 0.4297152 -0.2726624 0.8608137 0.4913962 -0.5206573 0.6981731 0.1880041 -0.4687002 0.8631191 0.1360079 -0.5838166 0.8004125 -0.02781713 -0.4718102 0.8812613 -0.1230561 -0.5889621 0.7987371 -0.3234884 -0.4691744 0.8217242 -0.3161274 -0.3562698 0.8792811 -0.4625645 -0.3541429 0.8127835 -0.5002516 -0.08957535 0.8612344 -0.5048574 -0.08894038 0.8586086 -0.602904 0.1245779 0.7880274 -0.5497549 0.1501467 0.8217211 -0.5338113 0.3894246 0.7505958 -0.4438614 0.404844 0.7994301 -0.356845 0.5832707 0.7296965 -0.1080041 0.4781612 0.8716061 -0.01886433 0.6517825 0.7581714 0.1559541 0.4852788 0.8603389 0.2862469 0.5931301 0.7525022 0.5104377 0.3446186 0.7878398 0.5696831 0.3415244 0.7475442 0.4575607 0.1144952 0.8817761 0.640395 0.00953412 0.7679866 0.4651985 -0.1744515 0.8678463 0.5014441 -0.2120401 0.8388044 0.3795022 -0.4441999 0.8115814 0.2737674 -0.4198395 0.8653244 0.2295773 -0.6214603 0.7490538 -0.08378261 -0.5692375 0.8178931 -0.0605539 -0.527483 0.8474048 -0.2840541 -0.4709659 0.8351674 -0.2746059 -0.4648444 0.8417313 -0.5322479 -0.4174453 0.7365132 -0.5110162 -0.2947654 0.8074502 -0.6848904 -0.131648 0.7166547 -0.5527208 0.02233779 0.8330671 -0.5919422 0.1711927 0.7875897 -0.4657357 0.2003109 0.8619547 -0.361914 0.4075959 0.8383817 -0.3631067 0.4102053 0.8365914 -0.1673785 0.5954261 0.7857814 -0.1300097 0.5599461 0.8182653 0.112169 0.6279371 0.7701384 0.2087659 0.4663384 0.8596193 0.3274106 0.530074 0.7821917 0.467572 0.3124048 0.8269097 0.4399263 0.2591505 0.8598291 0.5925336 0.1305319 0.7948996 0.4807396 -0.0295037 0.876367 0.5449212 -0.08904671 0.8337456 0.4664975 -0.2377943 0.851959 0.5221145 -0.3275713 0.7874602 0.4189044 -0.5101995 0.7511429 0.2551643 -0.4883319 0.8345198 0.1775968 -0.5825319 0.7931684 0.06232029 -0.5057026 0.8604541 -0.04356563 -0.6343874 0.7717866 -0.2369974 -0.5784964 0.7804961 -0.2590174 -0.5132559 0.8182166 -0.4919039 -0.4917747 0.7184625 -0.489143 -0.3239507 0.8098119 -0.5424863 -0.294664 0.7866905 -0.5404413 -0.08787375 0.8367804 -0.6107231 -0.05586665 0.789871 -0.607195 0.1894237 0.7716431 -0.6194872 0.2033205 0.7582193 -0.4940454 0.3717798 0.7859383 -0.4984564 0.3883509 0.7750644 -0.3385816 0.5385638 0.7715644 -0.2565554 0.5103335 0.8208161 -0.05256152 0.6421714 0.764757 -0.05536842 0.6340873 0.7712767 0.2830929 0.5069543 0.8141596 0.2485652 0.4714962 0.8461128 0.4970358 0.3213783 0.806022 0.4303523 0.1762664 0.8852837 0.6106129 0.1169847 0.7832411 0.5365012 -0.1285811 0.8340464 0.5139012 -0.1365703 0.8469086 0.5836807 -0.3564794 0.7295473 0.3590994 -0.4869183 0.7962149 0.363812 -0.5551173 0.7479877 0.1118142 -0.5251296 0.8436449 0.06792485 -0.4680222 0.8811025 -0.1341019 -0.6066194 0.7836006 -0.3099628 -0.5136596 0.8000481 -0.3043365 -0.5096155 0.8047803 -0.4532589 -0.2901011 0.8428511 -0.4812449 -0.2939478 0.8258318 -0.5633746 -0.07108116 0.8231382 -0.5982733 -0.06009864 0.7990351 -0.4877196 0.1972207 0.8504315 -0.5144587 0.2225757 0.8281258 -0.403674 0.4252268 0.8100799 -0.2823724 0.4080481 0.8681951 -0.24458 0.6421558 0.7265098 0.05802762 0.5949141 0.801692 0.07843822 0.6108394 0.7878596 0.1939981 0.4248141 0.8842499 0.2900702 0.4959684 0.8184587 0.4795253 0.4286593 0.7657067 0.3999691 0.1850508 0.8976531 0.6100572 0.1163206 0.7837728 0.483124 -0.06731581 0.8729605 0.5984311 -0.1591457 0.7852088 0.4159656 -0.3721745 0.8297342 0.3827489 -0.3629755 0.84956 0.1656868 -0.5376816 0.8267083 0.1670271 -0.4930552 0.8538141 -0.07149827 -0.5954407 0.8002116 -0.04594069 -0.6516916 0.7570916 -0.3336349 -0.4734353 0.8151974 -0.3329018 -0.473027 0.815734 -0.5189794 -0.3458971 0.781675 -0.4687106 -0.257786 0.8449004 -0.6525318 -0.01086086 0.7576836 -0.6714644 -0.001255929 0.7410358 -0.4842191 0.1501418 0.8619683 -0.5528762 0.2915981 0.7805758 -0.3573089 0.4647285 0.8101592 -0.3516389 0.4460753 0.8230231 -0.1552856 0.5937383 0.7895323 -0.03250634 0.4915862 0.8702222 0.05893331 0.6182013 0.7838075 0.2693998 0.6056757 0.7487195 0.3000229 0.4568259 0.8374345 0.5062227 0.4106959 0.7583321 0.4891507 0.2024947 0.8483676 0.5869843 0.1703929 0.7914644 0.5196028 -0.01368916 0.8542984 0.6323335 -0.09273624 0.7691258 0.4110372 -0.2563534 0.8748322 0.4698742 -0.4223412 0.7751429 0.2924122 -0.4229551 0.8576738 0.243366 -0.5753643 0.7808516 0.03988248 -0.4502326 0.8920202 -0.06584155 -0.5708121 0.8184366 -0.2076239 -0.4550324 0.8659318 -0.2713157 -0.5105838 0.8158996 -0.4888878 -0.3686197 0.790638 -0.4105073 -0.1874255 0.8923875 -0.6414127 -0.1288959 0.7562907 -0.5052876 0.1321317 0.8527754 -0.4758945 0.1393891 0.8683866 -0.470142 0.3815482 0.7958565 -0.3020759 0.362043 0.8818588 -0.249912 0.5650836 0.7862727 -0.04919302 0.4886486 0.8710929 -0.004597663 0.5920364 0.8058982 0.194606 0.5595248 0.8056429 0.2277916 0.4410822 0.868077 0.4332935 0.4890507 0.7570245 0.5148081 0.2111597 0.8308936 0.4722064 0.2092877 0.8562826 0.641462 0.04688227 0.765721 0.551246 -0.04460185 0.8331499 0.6300194 -0.1777712 0.7559584 0.4917142 -0.3499672 0.7973331 0.4759598 -0.3505099 0.8066009 0.342603 -0.543999 0.7659559 0.3378903 -0.5429232 0.7688072 0.1254591 -0.6539435 0.7460683 0.05246883 -0.5851959 0.8091927 -0.05759268 -0.6007065 0.7973926 -0.2276362 -0.453715 0.8615826 -0.2662863 -0.4831191 0.8340788 -0.3605479 -0.4104499 0.8375777 -0.4331162 -0.4255922 0.7945322 -0.5908149 -0.2845554 0.7549609 -0.5206482 -0.09479796 0.8484922 -0.6057162 -0.04220557 0.7945606 -0.5226026 0.1268061 0.8430935 -0.5676883 0.1761032 0.8041877 -0.3983987 0.310903 0.8629124 -0.4365771 0.4363505 0.7867648 -0.1828425 0.4791649 0.8584694 -0.182906 0.4864811 0.8543312 -0.01549988 0.6300483 0.7764013 0.1480441 0.4495707 0.8808912 0.2802546 0.5600337 0.7796279 0.4733159 0.4116546 0.7787891 0.4637192 0.3560459 0.8112927 0.6054403 0.2290611 0.7622159 0.5227074 0.04629129 0.8512545 0.6164454 -0.04752767 0.7859621 0.4886717 -0.146712 0.860044 0.5550338 -0.2824799 0.7823956 0.3078649 -0.3258075 0.8939065 0.3154461 -0.5045791 0.8036751 0.0992276 -0.4980239 0.8614674 0.08640307 -0.5625621 0.8222278 -0.206986 -0.5481412 0.8103691 -0.221311 -0.4793156 0.8492808 -0.3830378 -0.4603435 0.8008533 -0.3937316 -0.2819014 0.8749327 -0.5163766 -0.2811999 0.808877 -0.593707 -0.09674912 0.798844 -0.4593568 0.01760154 0.8880775 -0.6281564 0.1959696 0.7530043 -0.3215267 0.3221584 0.8904127 -0.5682182 0.3815994 0.7290473 -0.190361 0.5453716 0.8162921 -0.190648 0.5291483 0.8268346 0.01322025 0.728765 0.6846364 0.09989231 0.5332594 0.8400332 0.3498762 0.4766594 0.806463 0.3206999 0.4569584 0.829663 0.5150754 0.3288707 0.7915437 0.431257 0.1571044 0.8884457 0.6172419 0.0700069 0.7836528 0.5435733 -0.1122976 0.8318158 0.5046471 -0.1262043 0.8540515 0.5582891 -0.375371 0.7398716 0.3558012 -0.4154063 0.8371638 0.3424006 -0.5182061 0.7837247 0.1449658 -0.5296126 0.8357604 0.1360668 -0.52117 0.8425365 -0.06250792 -0.5695492 0.8195771 -0.1049229 -0.4971849 0.8612772 -0.2834103 -0.5446071 0.7893554 -0.2908305 -0.5244662 0.8002206 -0.5060427 -0.4657122 0.7259703 -0.505347 -0.196932 0.8401442 -0.5051743 -0.1966643 0.8403108 -0.5534333 0.04763096 0.8315305 -0.5049132 0.07447427 0.8599514 -0.5324826 0.2585929 0.8059728 -0.3785077 0.2830372 0.8812616 -0.3363786 0.4817227 0.8091927 -0.3378249 0.4821875 0.8083128 -0.08419722 0.6585585 0.7478046 -0.110827 0.5653723 0.8173564 0.1494835 0.6530891 0.7423808 0.2318583 0.4589377 0.8576817 0.3925991 0.4967894 0.7739937 0.4623869 0.3025107 0.8334781 0.4402754 0.2627462 0.8585581 0.559708 0.09044367 0.8237396 0.4860104 0.01403456 0.8738403 0.6117674 -0.1506469 0.7765606 0.4102903 -0.2875092 0.8654481 0.4192419 -0.3017766 0.8562518 0.306568 -0.5411521 0.783052 0.2191938 -0.499804 0.8379439 0.08392304 -0.6570724 0.7491414 -0.04901665 -0.5448353 0.8371093 -0.2468124 -0.6272037 0.7387146 -0.3131565 -0.4813133 0.8187006 -0.4908525 -0.4627786 0.7381734 -0.4697279 -0.2394459 0.8497184 -0.5913761 -0.1891814 0.7838909 -0.4970031 -0.008650004 0.8677057 -0.5856063 0.05164486 0.8089488 -0.5312239 0.2405432 0.812367 -0.4268481 0.2638867 0.8649652 -0.43871 0.3825932 0.8131149 -0.2419087 0.456354 0.8562834 -0.2424765 0.4636299 0.8522045 -0.1192046 0.6066381 0.7859902 0.07299327 0.4882184 0.8696635 0.009142756 0.6557347 0.7549361 0.380582 0.4917961 0.7831309 0.3807228 0.4918361 0.7830374 0.418547 0.2519892 0.8725365 0.4890201 0.2589104 0.8329614 0.5856505 0.005125522 0.8105475 0.5287224 -0.03373712 0.8481242 0.630839 -0.2080199 0.7475091 0.4027004 -0.3916668 0.8273026 0.3954079 -0.376519 0.8377864 0.2360218 -0.6032547 0.7618252 0.03956687 -0.4305431 0.9017024 -0.09448117 -0.6401871 0.762387 -0.2973959 -0.4746125 0.8284314 -0.2881377 -0.367982 0.8840622 -0.5814217 -0.328048 0.7445358 -0.5369379 -0.2399475 0.8087788 -0.6688254 0.008521199 0.7433707 -0.4616726 0.1313039 0.8772786 -0.5466672 0.2812061 0.7887193 -0.362706 0.415132 0.834332 -0.3035594 0.393073 0.8679547 -0.1640963 0.6160384 0.7704344 -5.8999e-4 0.4804612 0.8770159 0.08567517 0.5934023 0.8003333 0.2549644 0.4967799 0.8295801 0.262727 0.3497229 0.8992601 0.4353585 0.3547089 0.8274326 0.4804965 0.2085402 0.8518417 0.5497018 0.2068859 0.809337 0.5594096 -0.05043524 0.8273556 0.5321 -0.06489104 0.8441913 0.6058474 -0.3082407 0.7334417 0.4579635 -0.3835804 0.8019572 0.4529697 -0.5239592 0.7213081 0.1890764 -0.5074778 0.8406643 0.1270479 -0.5967582 0.7922995 -0.001981735 -0.4878157 0.8729444 -0.1206691 -0.5857134 0.8014854 -0.2304227 -0.4327865 0.8715511 -0.39108 -0.5093843 0.7665403 -0.5162416 -0.3160762 0.7959839 -0.5019142 -0.2669959 0.8226758 -0.7229961 -0.04435205 0.6894271 -0.5863906 -0.08179163 0.8058885 -0.4937253 0.1789969 0.8509967 -0.4874782 0.1803194 0.8543125 -0.4673141 0.4041898 0.7862877 -0.2371084 0.3917505 0.8889945 -0.2400687 0.529854 0.8134014 -0.010679 0.5793049 0.8150411 0.03855824 0.4970818 0.8668466 0.2762018 0.5767645 0.7688013 0.311649 0.3391277 0.887619 0.4049514 0.3641384 0.8387 0.5823289 0.1981711 0.7884297 0.4435611 0.02554124 0.8958801 0.540086 -0.02118587 0.8413432 0.600607 -0.2585884 0.7565735 0.3528631 -0.2888394 0.8899772 0.3911767 -0.5172985 0.7611721 0.1528408 -0.4838561 0.8616979 0.117299 -0.5728846 0.8111993 -0.07359719 -0.5209751 0.8503931 -0.06126117 -0.54307 0.8374497 -0.2718345 -0.556829 0.7848869 -0.3225485 -0.3438042 0.8819077 -0.4290031 -0.3699634 0.8240653 -0.542759 -0.2210031 0.8102902 -0.4673801 -0.1008396 0.8782867 -0.6028332 1.63589e-4 0.7978672 -0.4905984 0.151721 0.8580758 -0.5285814 0.2025402 0.824366 -0.4437423 0.3368425 0.8304396 -0.3720633 0.3327511 0.8665135 -0.2776568 0.5308533 0.8006883 -0.1362668 0.4815573 0.8657563 -0.09189355 0.5959449 0.7977502 0.139625 0.5334535 0.8342256 0.1467307 0.5089665 0.8481883 0.3755689 0.4343388 0.8187172 0.3650513 0.3756556 0.8518337 0.5231983 0.20138 0.8280759 0.453637 0.199329 0.868609 0.595036 0.08210784 0.799494 0.5296064 -0.03482162 0.8475286 0.6653702 -0.1673077 0.7275237 0.4664211 -0.3929877 0.7924721 0.4672427 -0.4211204 0.7773943 0.2827632 -0.3961225 0.8735743 0.2124674 -0.5528208 0.8057585 0.05859732 -0.4845784 0.872783 0.01426279 -0.5765842 0.8169134 -0.2674125 -0.4491302 0.8525096 -0.2711506 -0.4859549 0.8308582 -0.5316783 -0.2608839 0.8057653 -0.5136445 -0.2321833 0.8259904 -0.6837223 -0.01993829 0.7294699 -0.4789313 0.1436326 0.8660223 -0.5493846 0.2532609 0.7962636 -0.4162674 0.3469457 0.8404465 -0.3298094 0.3364375 0.8820633 -0.2712 0.6356314 0.7227886 -0.01985645 0.4884355 0.8723741 0.04436367 0.5964751 0.8014046 0.2673879 0.4780063 0.8366682 0.261923 0.5506706 0.7925643 0.5014419 0.4557948 0.735396 0.4956125 0.3063212 0.8127335 0.6342108 0.2249698 0.7397063 0.4972273 -0.01194655 0.867538 0.6541108 -0.1192018 0.7469471 0.3794295 -0.3005269 0.8750525 0.4046243 -0.340825 0.8485975 0.3323571 -0.5514143 0.7651674 0.05775499 -0.4471784 0.8925783 0.02935767 -0.5518265 0.833442 -0.2748459 -0.5152671 0.8117632 -0.2750287 -0.5189856 0.8093289 -0.6460997 -0.3179818 0.6938608 -0.504397 -0.3141621 0.8042923 -0.540722 -0.1230797 0.8321486 -0.4965734 -0.07322072 0.864901 -0.6249206 0.07894784 0.7766862 -0.4754826 0.1745035 0.8622441 -0.5506474 0.3721002 0.7472141 -0.2995389 0.473779 0.8281364 -0.2923071 0.4037657 0.8669083 -0.100682 0.5347555 0.8389874 -0.07005035 0.5175244 0.8527963 0.07996487 0.6842109 0.724887 0.2537457 0.4674701 0.8468087 0.346888 0.5120159 0.7858172 0.4552347 0.289208 0.8420928 0.5214896 0.422518 0.741301 0.5928087 0.05290591 0.8036037 0.5392103 0.06676441 0.8395206 0.6001601 -0.1539866 0.7849178 0.4243142 -0.2244137 0.8772663 0.4706867 -0.3873038 0.7927482 0.2845559 -0.4167156 0.8633517 0.2840809 -0.5541301 0.7824563 0.03977715 -0.5194418 0.8535795 -0.03708285 -0.6662534 0.744803 -0.2882831 -0.482541 0.8270714 -0.3642489 -0.5230406 0.7705526 -0.4422082 -0.2384453 0.8646362 -0.5064854 -0.3380669 0.7932108 -0.6127616 -0.07893699 0.7863157 -0.5100399 -0.01045674 0.8600873 -0.5913639 0.2980757 0.7492927 -0.5266699 0.2036818 0.8253076 -0.3764896 0.3580745 0.8544229 -0.4010969 0.4183393 0.8149316 -0.1980459 0.5135442 0.8348954 -0.1140805 0.4374057 0.8919989 0.1238657 0.5751007 0.808651 0.153427 0.4812309 0.8630626 0.3626442 0.473697 0.8025587 0.3753064 0.3531075 0.8570066 0.5464216 0.3540524 0.758993 0.5495797 0.07307946 0.8322389 0.5861111 0.1099154 0.8027406 0.5361102 -0.139755 0.832499 0.4852178 -0.1576461 0.8600649 0.4868233 -0.3219857 0.8119903 0.3401345 -0.3442693 0.8750927 0.3392499 -0.5153608 0.7869644 0.1184754 -0.5187769 0.8466606 0.2246179 -0.6277672 0.7452887 -0.1227188 -0.596704 0.7930225 -0.1697055 -0.4796065 0.8609168 -0.2325653 -0.4901748 0.8400251 -0.3922261 -0.2907963 0.8726949 -0.3650458 -0.2799636 0.8878976 -0.547248 -0.2259695 0.8058893 -0.5287846 0.01601105 0.8486051 -0.5217266 0.01363927 0.8530037 -0.5728975 0.3363182 0.7474481 -0.3486723 0.3237218 0.8795635 -0.2900184 0.5592312 0.7766273 -0.1420397 0.4791463 0.866166 -0.02070522 0.6191105 0.785031 0.1101388 0.4566891 0.8827823 0.2902186 0.5424656 0.7883554 0.3150231 0.4221247 0.8500419 0.5718299 0.4084665 0.7114531 0.5053572 0.09349286 0.8578307 0.5575023 0.08089369 0.8262249 0.6155951 -0.1765322 0.7680359 0.3820523 -0.2215845 0.8971825 0.4368871 -0.4858401 0.7570266 0.1620047 -0.4443968 0.8810595 0.1595138 -0.493071 0.8552406 0.002539694 -0.6425608 0.7662306 -0.1856222 -0.4822423 0.8561464 -0.1914355 -0.3950889 0.8984749 -0.4612532 -0.394649 0.7946683 -0.444113 -0.2773672 0.8519573 -0.6859132 -0.1840726 0.7040174 -0.5485222 0.0501123 0.834633 -0.6262019 0.1412692 0.7667557 -0.3782538 0.252092 0.8907154 -0.4630018 0.4481478 0.7647176 -0.209603 0.4687058 0.8581268 -0.192209 0.5985919 0.7776526 0.1003818 0.6314181 0.768918 0.09520906 0.6413767 0.7612957 0.3448317 0.536858 0.7699835 0.29416 0.5116842 0.8072481 0.4991811 0.4136266 0.7614009 0.493304 0.2722175 0.8261653 0.616865 0.2282758 0.7532382 0.591345 0.007065594 0.8063879 0.4957023 -0.05329489 0.8668559 0.5449992 -0.2756242 0.791838 0.3531966 -0.3203302 0.8789999 0.3761277 -0.3788799 0.8455637 0.2682324 -0.5761743 0.7720588 0.02940654 -0.4611378 0.8868412 0.01073914 -0.5136342 0.8579421 -0.2291982 -0.5948743 0.7704498 -0.2697899 -0.4157012 0.8685654 -0.4891682 -0.4165533 0.7662885 -0.4312771 -0.2219936 0.874482 -0.6370373 -0.1256926 0.7605162 -0.4911367 0.05468839 0.8693641 -0.571115 0.1343176 0.8098065 -0.4374947 0.3009669 0.8473591 -0.4500537 0.3015626 0.8405424 -0.2869084 0.4726653 0.8332294 -0.2200896 0.4381213 0.8715564 -0.04075825 0.6041748 0.7958088 0.02505946 0.5303622 0.8474007 0.1850261 0.6506956 0.7364513 0.3675594 0.4783857 0.7975258 0.4134498 0.4884893 0.7683993 0.5842161 0.3468594 0.7337439 0.5234205 0.2485072 0.8150308 0.6139461 -0.01055544 0.7892774 0.6558629 -0.04047036 0.7537945 0.410121 -0.2005546 0.889707 0.4975576 -0.3212078 0.8057681 0.3508394 -0.4774729 0.8055628 0.2498455 -0.4451164 0.859912 0.1749632 -0.624152 0.7614606 -0.02585166 -0.6260558 0.7793496 -0.01882278 -0.636193 0.7713004 -0.2398718 -0.5621941 0.7914541 -0.2564378 -0.5720869 0.779074 -0.4575243 -0.4506348 0.7665506 -0.4465925 -0.3897674 0.8053798 -0.6164715 -0.141631 0.7745345 -0.5000948 -0.1507316 0.8527515 -0.5939961 0.09093958 0.7993113 -0.5610651 0.106571 0.8208828 -0.5633054 0.3782948 0.7345613 -0.3548524 0.3890143 0.8501456 -0.3049562 0.5901735 0.7474604 -0.07274454 0.4435547 0.8932904 0.04884952 0.6469314 0.760982 0.1979023 0.4583524 0.8664571 0.2947486 0.5009745 0.8137248 0.394302 0.3437325 0.8522758 0.4081437 0.3481336 0.8439323 0.5761205 0.1669864 0.8001255 0.4869412 0.02726417 0.8730092 0.6123397 -0.05218827 0.7888705 0.4276947 -0.2480481 0.8692234 0.4591259 -0.2888079 0.8401151 0.4263785 -0.4964065 0.7561627 0.1684892 -0.4586492 0.8724977 0.1984328 -0.4863277 0.8509464 -0.005650877 -0.5148561 0.857258 -0.06027233 -0.602514 0.7958293 -0.3072984 -0.5525048 0.7747943 -0.3318141 -0.3961388 0.8561388 -0.4937837 -0.4137292 0.7648568 -0.497323 -0.1259847 0.8583693 -0.4641317 -0.09642148 0.8805025 -0.5888473 0.1179447 0.7995924 -0.4489058 0.1941086 0.8722416 -0.4977366 0.3054814 0.811751 -0.3806748 0.3876549 0.8395299 -0.3894414 0.5449622 0.7425305 -0.1741896 0.5625111 0.8082323 -0.1062101 0.6967291 0.709428 0.1449664 0.5010808 0.8531723 0.2632338 0.5799413 0.770958 0.3449802 0.3764814 0.8597969 0.4564974 0.4096382 0.7898143 0.4671996 0.1600006 0.8695542 0.6365913 0.1123326 0.7629764 0.5996038 -0.1563956 0.7848668 0.5537488 -0.1174351 0.8243612 0.5043799 -0.3275147 0.7989589 0.4229663 -0.3324731 0.842948 0.3985488 -0.5104534 0.7619687 0.1791135 -0.5396763 0.8225983 0.1560923 -0.6255827 0.7643832 -0.1378568 -0.5860065 0.7984935 -0.1381884 -0.5850534 0.799135 -0.3625673 -0.4881777 0.7938688 -0.3794955 -0.3622705 0.8513185 -0.513251 -0.3460935 0.7853616 -0.4865906 -0.1468085 0.8612067 -0.5654414 -0.1271225 0.8149331 -0.5003168 0.1596866 0.8509897 -0.4920142 0.1535336 0.856942 -0.4981942 0.3442351 0.7958046 -0.3262763 0.3702768 0.869735 -0.3387496 0.4845246 0.8065264 -0.1685054 0.5677093 0.8057991 -0.07134282 0.4753885 0.8768786 0.1392331 0.6598522 0.7383829 0.2780393 0.4480316 0.8496834 0.3554911 0.4922509 0.7945536 0.5154021 0.3880353 0.764061 0.4314714 0.1497665 0.8896081 0.554653 0.1255607 0.8225538 0.5693851 -0.1137155 0.8141679 0.5039555 -0.135403 0.8530504 0.458342 -0.390695 0.7982982 0.4001381 -0.3809782 0.8335138 0.2962151 -0.6128022 0.7326188 0.07883048 -0.566853 0.8200386 0.04178643 -0.6403764 0.7669237 -0.1681305 -0.4963953 0.8516595 -0.2392389 -0.557927 0.7946587 -0.4368565 -0.4768514 0.7627379 -0.4430202 -0.2679765 0.8555242 -0.5901483 -0.2622413 0.7635146 -0.4509766 -0.03477799 0.891858 -0.6338879 0.1152655 0.7647876 -0.5117461 0.2589364 0.8191874 -0.5388094 0.3258013 0.7768771 -0.2910593 0.4550591 0.8415497 -0.3991141 0.516052 0.7578907 -0.02992969 0.3611687 0.9320201 -0.1445971 0.5526485 0.8207749 0.2405412 0.4566113 0.8565315 0.5317564 -0.8396643 -0.1104497 0.03599691 -0.9834803 -0.1774002 0.008536815 -0.9998027 -0.01794189 -0.5128798 -0.8567889 -0.05354636 -0.4338621 -0.6401281 -0.6340345 -0.7672612 -0.29926 0.5672335 -0.8544022 -0.2470927 -0.4571018 -0.8566038 0.2553001 0.448388 -0.3322949 0.6281661 -0.7035534 -0.0638175 0.8386139 0.5409751 0.2375559 0.6848521 -0.6888722 0.5047309 0.3365539 0.7949706 0.7281382 0.2836468 -0.6239867 0.8892562 -0.1295807 0.4386712 0.8500317 -0.2134605 -0.4815402 0.6782125 -0.5038034 0.5349859 0.3906466 -0.580664 -0.7143 0.03368669 -0.9307904 -0.3639978 -0.5222434 -0.8304616 0.1938951 -0.7263656 -0.0235722 0.6869043 -0.8308116 0.2549429 -0.4947286 -0.6849163 0.5577564 0.4688257 -0.6969128 0.6608014 -0.2786652 -0.1940888 0.8716644 0.4500341 0.1398493 0.7554939 -0.6400557 0.5138791 0.547333 0.6605717 0.5937523 0.4585497 -0.6612037 0.8034551 0.08930379 0.5886297 0.9751895 0.03473281 -0.2186301 0.8750806 -0.4820106 -0.04358649 0.4996423 -0.7170433 0.4860109 0.1032831 -0.9033343 -0.416317 0.2377745 0.7583613 -0.6069196 0.6320409 0.5219988 0.5727493 0.6381808 0.3702824 -0.6749935 0.7590926 0.06233519 0.6479915 0.5769655 -0.1577514 -0.8013896 0.3644369 -0.4910604 0.7912304 0.1043494 -0.6145529 -0.7819437 -0.397899 -0.8415389 0.3653612 -0.7614089 -0.5895494 -0.2696074 -0.7713624 -0.4092813 0.4873284 -0.8515413 -0.1931375 -0.4874169 -0.8956083 0.1071931 0.4317355 -0.8401725 0.2416878 -0.4854868 -0.7083719 0.4798554 0.5176371 -0.4225088 0.6461007 -0.6356416 0.02425044 0.7006952 0.7130485 0.2227012 0.72998 -0.6461682 0.4777136 0.6031196 0.6387774 0.6988164 0.4417508 -0.562594 0.8481386 0.2899774 0.443367 0.859292 -0.01956993 -0.511111 0.7554216 -0.2239377 0.6157842 0.63528 -0.4769879 -0.607373 0.4275285 -0.6467498 0.6316123 0.3366577 -0.8150011 -0.4716301 -0.07794874 -0.8635866 0.4981388 -0.4454628 -0.8797929 0.1659139 -0.7965668 -0.503558 -0.3345309 -0.7554247 -0.04705917 0.6535435 -0.7318406 0.2295321 -0.6416576 -0.4998584 0.5818938 0.6415147 -0.07146084 0.8680565 -0.4912957 0.7222982 0.517783 -0.4584606 0.9498391 0.04590415 0.3093517 0.9794493 0.03987413 0.1977096 0.8395833 -0.4049258 -0.3621258 0.5959408 -0.4958949 0.6316193 0.5867936 -0.691725 -0.4209392 0.1577789 -0.9297046 0.3327993 0.1659909 -0.9408578 0.2953533 -0.2817358 -0.8442155 -0.4559882 -0.3895899 -0.6017073 0.6972575 -0.558305 -0.366648 -0.744221 -0.7334646 -0.1812371 0.6551204 -0.8719198 0.1582773 -0.4633619 -0.8641569 0.3162929 0.3913972 -0.6197891 0.5826487 -0.5257205 -0.4066534 0.6758259 0.6147296 -0.174897 0.7870637 -0.591559 0.0672146 0.8168424 0.5729316 0.3252732 0.6576063 -0.679523 0.8625929 0.5044484 -0.03828066 0.9525418 -0.09421503 0.2894611 -0.193199 -0.8516654 -0.4871758 -0.5843385 -0.6172556 0.5268246 -0.9279452 -0.3313524 0.1706554 -0.9479874 0.1424466 -0.2846557 -0.8484188 0.2760412 0.4516491 -0.7743458 0.4847832 -0.406662 -0.5297479 0.6685825 0.5218858 -0.3587064 0.679746 -0.6397462 -0.03677487 0.7275763 0.6850404 0.1884173 0.6213591 -0.7605339 0.8736813 0.1990429 0.4439179 0.8609862 -0.1603509 -0.4826908 0.7414259 -0.3693741 0.5602236 0.6738954 -0.5546151 -0.488126 0.3725293 -0.6992887 0.6100961 0.2356372 -0.7187781 -0.6540896 -0.1779881 -0.6932666 0.6983564 -0.3139441 -0.8929375 -0.3226482 -0.7254747 -0.6375396 -0.2592869 -0.6809909 -0.4283054 0.5939746 -0.8479181 -0.07000088 -0.5254853 -0.9474479 0.07031035 0.3120881 -0.8157824 0.5570312 -0.1556127 -0.4695763 0.841534 -0.2670555 0.02739298 0.8339857 0.5511058 0.4619793 0.8860042 -0.03964459 0.854387 0.4218984 -0.3033556 0.828103 0.2834112 0.4836566 0.8695673 -0.1927841 -0.4546285 0.6729605 -0.6066845 0.4231529 0.3379185 -0.9207827 -0.1948598 0.2086252 -0.893244 0.3982346 -0.08224451 -0.8430883 -0.531449 -0.332848 -0.5807253 0.7429471 -0.6354793 -0.4584473 -0.6212826 -0.8718474 -0.1008957 0.4792728 -0.8898499 0.03861743 -0.4546164 -0.7934346 0.3559076 0.4937524 -0.7992542 0.4708126 -0.3735347 -0.5343198 0.8388314 0.104233 0.3076199 0.9244768 0.2251946 0.7961024 0.5845046 0.1567661 0.8113068 0.580655 -0.06797772 0.9422394 0.1216241 -0.3120776 0.8760673 -0.01709032 0.4818859 0.7827201 -0.4896585 -0.3841664 0.8467944 -0.5027647 0.1736866 0.3876713 -0.8846855 -0.2589261 -0.7994856 -0.5865859 0.1293822 -0.969647 -0.1094235 -0.2186579 -0.9814697 -0.04156082 0.1870565 -0.8876013 0.4584167 -0.04492384 -0.8901939 0.4550527 0.02195566 -0.536036 0.8292943 -0.1579136 -0.4848415 0.8549452 0.1843845 0.03355759 0.9944993 -0.09922224 0.4127986 0.5906542 0.6933433 0.630688 0.4902167 -0.6015981 0.736786 0.2190882 0.6396459 0.6615945 -0.03183859 -0.7491856 0.7828379 -0.597131 0.174927 0.2838146 -0.9495494 0.1334366 0.182483 -0.7671763 -0.6149314 -0.2316753 -0.6939484 0.6817348 -0.3314612 -0.5783186 -0.7454403 -0.5436282 -0.24253 0.8035221 -0.6374179 -0.00516808 -0.7705011 -0.6668957 0.3401463 0.6629862 -0.5073004 0.5018931 -0.7005354 -0.3161232 0.7074432 0.6321316 -0.09701007 0.7970591 -0.5960586 0.1229538 0.8877548 0.443592 0.5096442 0.7640104 -0.3956654 0.5139201 0.8279021 0.2246423 0.8378652 0.4592888 -0.2950183 0.815448 0.2921731 0.4996796 0.770033 -0.09976071 -0.6301564 0.3067649 -0.6577897 0.6879012 0.09565991 -0.8599312 -0.5013657 -0.1700997 -0.8580424 0.4845921 -0.3486279 -0.6540464 -0.6713286 -0.8197833 -0.08508664 0.5663176 -0.8375988 0.2123206 -0.5033374 -0.6488227 0.3852208 0.6562271 -0.4486568 0.547056 -0.7067084 -0.1694078 0.6475729 0.7429336 -0.03390079 0.7636243 -0.6447703 0.3741936 0.7063731 0.6008463 0.4475603 0.6370418 -0.6275888 0.6889448 0.3214715 0.6496239 0.6815013 0.1413748 -0.7180315 0.8598837 -0.09326922 0.5018973 0.7826738 -0.5341374 -0.3195604 0.829953 -0.5528339 -0.07451814 0.3803855 -0.9232297 -0.05435109 0.2557229 -0.8554031 0.4504348 -0.02934533 -0.8536689 -0.5199887 -0.2863728 -0.6432606 0.710075 -0.4233318 -0.5939874 -0.6840827 -0.7254815 -0.2987473 0.6200216 -0.9169901 -0.297912 -0.265288 -0.9697998 0.221336 0.1024628 -0.8319426 0.2615812 0.489333 -0.679333 0.4796326 -0.555391 -0.4364312 0.6767972 0.5928519 -0.3192642 0.7818576 -0.5355082 -0.05498462 0.8989484 0.4345901 0.1651849 0.9002061 -0.4029181 0.3618645 0.7946228 0.4874718 0.5288851 0.6776182 -0.5109934 0.7579093 0.4191558 0.4998821 0.8980421 0.4254126 -0.1120024 0.9930372 -0.1011538 -0.06037425 0.5914453 -0.4294629 0.6824619 0.599775 -0.6692472 -0.4386094 0.2575396 -0.8552832 0.4496266 0.2079807 -0.9119908 -0.3535773 -0.3705362 -0.8338867 0.4090674 -0.4224284 -0.8778817 -0.2255616 -0.9109978 -0.4091865 0.0514723 -0.9762792 0.1001109 -0.191981 -0.6609757 0.6755346 0.3267478 -0.2160506 0.7775043 -0.5906007 0.3500171 0.7166174 0.6032807 0.8493936 0.1653724 -0.501181 0.7609559 -0.2880746 0.5813425 0.5799445 -0.3404085 -0.740126 0.3349219 -0.5901134 0.7345703 0.1870202 -0.6634561 -0.724465 -0.1031881 -0.7745714 0.6240124 -0.3191995 -0.5731817 -0.7547016 -0.5791234 -0.2447377 0.7776373 -0.848635 -0.2224569 -0.4799287 -0.911937 0.3465373 0.2197333 -0.6155657 0.7418172 0.2660568 -0.1192653 0.9841609 -0.1311615 0.3204147 0.9471905 -0.01282674 0.7692284 0.6030496 0.2112325 0.9699786 0.2337945 -0.06694531 0.9014824 -0.411781 0.13329 0.8539501 -0.3785895 0.3569864 0.5620645 -0.655111 -0.5048892 0.3355793 -0.7227842 0.6041271 0.05292069 -0.7774392 -0.6267278 -0.3630642 -0.7732784 0.5198315 -0.7032898 -0.5621527 -0.4351641 -0.7908703 -0.4036399 0.4599992 -0.7877278 -0.07757365 -0.6111197 -0.679697 0.3078123 0.6657804 -0.7041888 0.5423461 -0.4582346 -0.423673 0.7317813 0.5338514 -0.314599 0.7873938 -0.5301306 0.05987203 0.8765596 0.4775547 0.1802856 0.8761609 -0.4470338 0.4727142 0.7418696 0.4755742 0.5089178 0.4945418 -0.7045787 0.7308033 0.1444734 0.6671237 0.869007 -0.1841498 -0.4592556 0.7574397 -0.3915881 0.5224404 0.6697592 -0.5369871 -0.5129012 0.2451688 -0.689283 0.6817486 -0.06595003 -0.7168747 -0.6940758 -0.4780715 -0.7142568 0.5111603 -0.6049539 -0.5669109 -0.5591447 -0.8032034 -0.4627785 0.3751006 -0.9541602 -0.05885803 -0.2934523 -0.903245 -0.07705891 -0.4221497 -0.7598447 0.3878687 0.5217221 -0.6851451 0.4987555 -0.5308664 -0.5131966 0.725432 0.4586697 -0.3295255 0.7725594 -0.5427384 0.01329809 0.7951374 0.6062837 0.1190063 0.9322831 -0.3415932 0.6072711 0.7933669 0.0423153 0.647037 0.2881587 -0.7059091 0.7865109 -0.1544942 0.59794 0.720694 -0.2932494 -0.6281759 0.6602853 -0.5560849 0.5047702 0.3583925 -0.6847001 -0.6346185 0.1833634 -0.7802152 0.5980318 -0.2799122 -0.822025 -0.4959074 -0.4080566 -0.9101375 0.07169276 -0.8475385 -0.5086618 0.1514658 -0.8680895 -0.01495248 0.4961826 -0.7570233 0.3760834 -0.5343005 -0.6904713 0.5424588 0.4785268 -0.3744822 0.8622828 -0.3409274 0.8763628 0.09697419 -0.4717882 0.7891424 -0.3941155 0.4710918 0.6074945 -0.419399 -0.6745777 0.3817504 -0.6433314 0.6636199 0.1445273 -0.7249868 -0.6734287 -0.06094616 -0.8610658 0.5048282 -0.413586 -0.8171328 -0.4015479 -0.5416688 -0.6742019 0.5020427 -0.6863481 -0.4619582 -0.5617125 -0.7556517 -0.1943408 0.6254776 -0.8510626 -0.005614757 -0.5250344 -0.8076881 0.2842239 0.5165819 -0.7904648 0.4254905 -0.440594 -0.4967444 0.7281027 0.4723469 -0.525184 0.8445193 -0.1047337 0.06170105 0.9625123 -0.2641274 0.7638791 0.04311949 0.6439173 0.7298154 -0.241717 -0.639486 0.727616 -0.474376 0.4955225 0.4714926 -0.844814 -0.252951 -0.9346725 -0.3453152 0.08452701 -0.9728142 0.2048529 -0.1080183 -0.6876662 0.587917 0.4259915 -0.2473514 0.8611795 -0.4440577 -0.119361 0.9043266 0.4098128 0.2914007 0.9177199 -0.2699551 0.4131284 0.7762753 0.4761528 0.5510247 0.6008348 -0.5791109 0.6320387 0.2599775 0.7300267 0.7411568 0.1361102 -0.6573892 0.8481732 -0.2449437 0.469686 0.7943003 -0.3474451 -0.4983664 0.5018258 -0.5663166 0.6538017 0.3661574 -0.6621133 -0.6538614 -0.01811319 -0.7465699 0.6650605 -0.2727769 -0.5806943 -0.7670638 -0.6515928 -0.5702956 0.5001899 -0.9345576 -0.3449299 -0.08732527 -0.8189829 -0.271121 -0.5057277 -0.8530094 0.1917436 0.4853961 -0.887885 0.2766978 -0.3675576 -0.6599165 0.7188241 0.2186374 0.1361619 0.8119611 0.5676082 0.5147908 0.6993144 -0.4959334 0.6388525 0.5440348 0.5439611 0.7332975 0.2438712 -0.6346666 0.7647268 -0.1551935 0.6253863 0.6493502 -0.5158697 -0.558769 -0.4632463 -0.7019242 -0.5410227 -0.758165 -0.5217629 0.3910874 -0.7899423 -0.3365659 -0.5125569 -0.8447081 -0.09467983 0.5267865 -0.8462598 0.1739858 -0.5035606 -0.7566284 0.383321 0.5296966 -0.6118047 0.5488759 -0.5695878 -0.3463703 0.6890103 0.6366259 -0.1166234 0.6478063 -0.7528253 0.3648588 0.6942328 0.6204184 0.8000468 0.3884326 -0.4572148 0.9050663 0.3055719 0.2957719 0.9593796 -0.1642237 -0.2293937 0.8796396 -0.2618899 0.3970493 0.568558 -0.5615472 -0.601171 0.2000502 -0.8367269 0.5097727 -0.3194685 -0.9312574 -0.1752133 -0.6323327 -0.6042264 -0.4848359 -0.9027552 -0.05448663 0.4266898 -0.6188811 0.6587275 0.42786 -0.226022 0.9266045 -0.30053 0.2702523 0.7451007 0.6097448 0.6004092 0.5936944 -0.5357574 0.6592625 0.265622 0.703433 0.5964078 0.04069507 -0.8016495 -0.5222851 -0.8462035 0.1056316 -0.3036994 -0.1821085 -0.9352023 -0.7489591 -0.09219795 -0.6561707 -0.5086355 0.03014492 -0.8604541 -0.6025774 0.4331569 -0.6702803 -0.5268607 0.2983199 -0.795879 -0.4705042 0.4887048 -0.7347065 -0.2729403 0.5371302 -0.7981195 -0.2658382 0.5535293 -0.7892625 -0.09646624 0.5043907 -0.8580701 -0.04797238 0.585386 -0.8093342 0.1394522 0.5546389 -0.8203225 0.1475728 0.5237838 -0.8389713 0.3889931 0.5150374 -0.7638201 0.4205304 0.3031055 -0.8551499 0.4049778 0.3016951 -0.8631184 0.6511245 0.1108988 -0.7508251 0.4280896 -0.007252395 -0.9037072 0.543325 -0.2052081 -0.8140563 0.3878055 -0.2181637 -0.8955509 0.3659259 -0.4260736 -0.8273813 0.3294128 -0.4227049 -0.8442794 0.2130628 -0.6528559 -0.7268999 0.007343828 -0.5425392 -0.8399984 -0.05841898 -0.6076154 -0.7920802 -0.1956367 -0.5037373 -0.8414125 -0.2769644 -0.5458535 -0.7907811 -0.5277466 -0.3742642 -0.7625024 -0.4495275 -0.3702325 -0.8129286 -0.6453781 -0.2186933 -0.7318883 -0.5008873 -0.02562528 -0.8651331 -0.6022521 0.05474507 -0.7964267 -0.4739528 0.2695091 -0.8382921 -0.4068091 0.2615033 -0.8752841 -0.3783801 0.5149353 -0.7692012 -0.2231953 0.4545297 -0.8623147 -0.08012384 0.6850207 -0.7241042 0.1152521 0.5524443 -0.8255437 0.2324733 0.6138139 -0.754446 0.2647767 0.3716765 -0.8898034 0.554703 0.4076598 -0.7253401 0.462239 0.1100212 -0.8799037 0.5494569 0.07720869 -0.8319472 0.5647472 -0.1946582 -0.8019781 0.5338596 -0.1991822 -0.8217788 0.4993565 -0.4285942 -0.7529609 0.2865376 -0.4281576 -0.8570749 0.2553641 -0.5608428 -0.7875561 0.1315762 -0.5221405 -0.8426489 -0.006953239 -0.6803333 -0.73287 -0.2077299 -0.5249775 -0.8253769 -0.2035807 -0.5609859 -0.8024025 -0.4620135 -0.4339067 -0.7734783 -0.4533608 -0.4071379 -0.7929079 -0.6031234 -0.1850686 -0.7758814 -0.584426 -0.1671597 -0.7940428 -0.6035541 0.1365284 -0.785546 -0.675808 0.1175224 -0.7276483 -0.5108652 0.2970474 -0.8067092 -0.5281633 0.453014 -0.7182075 -0.3266921 0.4604433 -0.8253874 -0.234031 0.6389048 -0.7328234 -0.1197614 0.573917 -0.810109 0.04991734 0.6721758 -0.738707 0.1734749 0.5218498 -0.8352121 0.240907 0.5480032 -0.8010346 0.3281769 0.3466167 -0.8787246 0.4384739 0.3672875 -0.8202686 0.5314138 0.1655357 -0.8307812 0.4642279 0.09888964 -0.880178 0.6040092 -0.0488252 -0.7954804 0.6062214 -0.278608 -0.7448982 0.5433365 -0.1395915 -0.8278283 0.4239956 -0.4267116 -0.7988397 0.3052094 -0.3887547 -0.8693199 0.2378274 -0.5928965 -0.7693581 0.03334015 -0.5300723 -0.8472968 0.1009746 -0.6565744 -0.7474719 -0.1731364 -0.6181997 -0.7667157 -0.2243327 -0.4526107 -0.8630287 -0.3839556 -0.4799311 -0.7888247 -0.3792728 -0.2628058 -0.8871783 -0.6401779 -0.235006 -0.731399 -0.4715318 0.002781391 -0.8818447 -0.5807109 0.1189764 -0.8053692 -0.4414176 0.2315089 -0.8669222 -0.4723863 0.3146582 -0.8233114 -0.3383488 0.4604417 -0.8206787 -0.3418005 0.4619234 -0.8184126 -0.2342571 0.5878292 -0.7743259 0.01769697 0.5276169 -0.8492981 0.003835022 0.5040887 -0.8636434 0.232815 0.6242972 -0.7456879 0.2493861 0.4120784 -0.876355 0.4760264 0.405988 -0.7801106 0.4312517 0.2039484 -0.8788782 0.5647943 0.1616898 -0.8092365 0.5551143 -0.04420721 -0.8305985 0.4659487 -0.07484042 -0.881641 0.5561444 -0.2933545 -0.7775902 0.3417926 -0.3905936 -0.85476 0.3238936 -0.3794432 -0.8666694 0.08379662 -0.6306074 -0.771565 0.06793487 -0.5967937 -0.7995137 -0.2895108 -0.5454441 -0.7865585 -0.2433623 -0.5118505 -0.8238835 -0.4540626 -0.376172 -0.8076646 -0.4460948 -0.3600206 -0.8193807 -0.6350466 -0.126764 -0.7620018 -0.5031118 -0.02799373 -0.8637679 -0.5769545 0.1792823 -0.7968572 -0.6389338 0.1673269 -0.7508431 -0.3941183 0.4684287 -0.7907246 -0.3302704 0.2685781 -0.9048687 -0.2782204 0.5868213 -0.7604172 -0.1008482 0.5089144 -0.8548895 0.01594042 0.6621547 -0.7491977 0.2476432 0.5720186 -0.7819639 0.2539439 0.535244 -0.8056218 0.4766803 0.4904392 -0.7295514 0.4514497 0.3015863 -0.839785 0.5910601 0.1921414 -0.7834091 0.4599043 0.0727595 -0.8849826 0.633442 -0.09184348 -0.7683204 0.4000291 -0.2534084 -0.8807729 0.4427461 -0.3364854 -0.831116 0.277058 -0.5674552 -0.7753925 0.1279099 -0.4483777 -0.8846449 0.09500366 -0.5035351 -0.8587356 -0.1416388 -0.5180044 -0.8435697 -0.2035672 -0.4347325 -0.8772503 -0.2527688 -0.4677212 -0.8469622 -0.5445075 -0.3970924 -0.7388026 -0.4248656 -0.1670615 -0.8897078 -0.6427464 -0.06940406 -0.7629287 -0.4325751 0.1029191 -0.8957046 -0.5166093 0.2247859 -0.8261878 -0.4048686 0.4281833 -0.8079237 -0.3031223 0.3874264 -0.8706421 -0.2352428 0.573771 -0.7845048 -0.02402889 0.5157232 -0.8564183 -0.01790702 0.5032545 -0.8639528 0.2221168 0.5908513 -0.7756024 0.2329565 0.5483206 -0.8031661 0.4789978 0.4933325 -0.7260745 0.4589334 0.254262 -0.8513113 0.5355699 0.2354102 -0.811016 0.509119 0.05823934 -0.8587235 0.6551445 -0.04858708 -0.7539398 0.5111421 -0.2651336 -0.8175806 0.5597615 -0.4037134 -0.7236592 0.3491756 -0.4804096 -0.8045392 0.2971609 -0.6159505 -0.7295893 0.1488249 -0.5525442 -0.8200892 0.02797073 -0.6590761 -0.7515559 -0.149081 -0.5397015 -0.8285512 -0.2126791 -0.565205 -0.7970641 -0.2458671 -0.4296352 -0.8688861 -0.5084169 -0.4435966 -0.7380613 -0.5255219 -0.1874023 -0.8298838 -0.5403438 -0.1839458 -0.8210923 -0.5296157 0.1152284 -0.8403748 -0.4956914 0.08819395 -0.8640093 -0.5414984 0.3533918 -0.7628196 -0.3426162 0.3430452 -0.8746051 -0.3204717 0.5210105 -0.7911044 -0.08941721 0.4893468 -0.8674932 -0.07033145 0.534682 -0.8421217 0.1576479 0.5751145 -0.8027395 0.1585755 0.5727424 -0.8042511 0.4070498 0.5553415 -0.725194 0.5468537 0.3544077 -0.7585159 0.4174919 0.4026921 -0.8145795 0.5218635 0.113148 -0.8454917 0.5547615 0.1003243 -0.8259387 0.5748598 -0.1215418 -0.8091748 0.4623774 -0.1659169 -0.8710216 0.5129082 -0.2815127 -0.8109721 0.3602056 -0.4236766 -0.8311139 0.2742047 -0.3822789 -0.8824254 0.1752225 -0.6234089 -0.7620096 -0.05344057 -0.4545882 -0.8890972 -0.1509885 -0.5770194 -0.8026525 -0.3743441 -0.4699755 -0.7993682 -0.46379 -0.2871701 -0.8381124 -0.3492438 -0.2890494 -0.8913357 -0.5797377 -0.1319692 -0.8040451 -0.4525508 -0.0170443 -0.8915758 -0.5998937 0.1510955 -0.785683 -0.4848274 0.2275034 -0.8445026 -0.5251607 0.4030589 -0.7494997 -0.2586218 0.4985184 -0.8274022 -0.2575427 0.504837 -0.8239002 -0.1069834 0.5081424 -0.8546028 -0.06299448 0.5815263 -0.811085 0.2977226 0.5842661 -0.7549798 0.154915 0.4541512 -0.8773528 0.450664 0.4709232 -0.7583756 0.4560573 0.2218425 -0.8618572 0.4433394 0.2076367 -0.8719733 0.635922 0.04170376 -0.7706259 0.5209158 -0.05097877 -0.8520845 0.6262263 -0.2848109 -0.7257572 0.390735 -0.3621531 -0.8462691 0.3934003 -0.4440481 -0.8050202 0.1471309 -0.5449404 -0.825465 0.1634622 -0.473537 -0.8654726 -0.1226651 -0.5631009 -0.8172336 -0.1352059 -0.4851758 -0.8639003 -0.3911774 -0.5203132 -0.7591143 -0.4656097 -0.3314192 -0.8205907 -0.4494986 -0.3325064 -0.8290902 -0.5433242 -0.1484115 -0.8263007 -0.504155 -0.1148766 -0.8559389 -0.5977546 0.1144744 -0.7934641 -0.4519175 0.1436201 -0.8804226 -0.4731325 0.3876374 -0.7911276 -0.3658068 0.3869648 -0.8464301 -0.2821391 0.628103 -0.7251788 -0.1508284 0.5665592 -0.8100997 0.03037309 0.6907162 -0.7224878 0.1696452 0.4883412 -0.8560043 0.2512809 0.5288227 -0.8106815 0.3410314 0.3086256 -0.8879458 0.4690782 0.3259452 -0.8208078 0.6015222 0.1393146 -0.7866145 0.4907101 0.04417324 -0.8702026 0.5842481 -0.06139606 -0.8092495 0.4639922 -0.2520766 -0.8492165 0.4608403 -0.2518215 -0.8510066 0.4156398 -0.4540101 -0.7881107 0.2862114 -0.4400288 -0.8511509 0.2152739 -0.6173983 -0.7566218 -0.007856309 -0.6170162 -0.7869113 -0.004177153 -0.6125372 -0.7904307 -0.2289102 -0.5811607 -0.7809305 -0.2360413 -0.550828 -0.8005455 -0.4301625 -0.4920924 -0.7568391 -0.4218397 -0.2918907 -0.8584004 -0.539477 -0.2623363 -0.8000903 -0.4952105 -0.06724804 -0.8661665 -0.5603535 -0.0291264 -0.8277413 -0.4865095 0.1904307 -0.8526692 -0.5107259 0.2204926 -0.8309887 -0.4240738 0.4663154 -0.776345 -0.2859266 0.4105864 -0.8658319 -0.1918882 0.581795 -0.7903755 -0.05872249 0.4985461 -0.864872 0.09701156 0.6594883 -0.7454287 0.2734335 0.4998978 -0.8217886 0.2683898 0.4031631 -0.8748865 0.5053579 0.3605968 -0.7839537 0.4610318 0.2008697 -0.8643501 0.5497314 0.1721528 -0.8174098 0.5571812 -0.07022476 -0.8274163 0.6602657 -0.03139257 -0.7503757 0.5633713 -0.3028287 -0.7687051 0.3872883 -0.304826 -0.8701086 0.3668769 -0.5047222 -0.7814454 0.1793153 -0.4404203 -0.8797023 0.1029819 -0.6096848 -0.7859257 -0.102205 -0.5076376 -0.8554872 -0.1133317 -0.5195757 -0.8468749 -0.4249081 -0.4677619 -0.7750174 -0.3811207 -0.3241065 -0.8658534 -0.5878002 -0.2753823 -0.7606942 -0.5858045 -1.26093e-4 -0.8104525 -0.5951548 0.007933199 -0.803572 -0.525871 0.1497947 -0.8372702 -0.4530415 0.1609084 -0.8768478 -0.4918909 0.3742642 -0.7861106 -0.3343474 0.4547563 -0.8254749 -0.2483175 0.4084296 -0.8783643 -0.1807363 0.5626218 -0.8067162 0.02425754 0.5343736 -0.8449003 0.02116698 0.5430619 -0.8394259 0.2843135 0.4770452 -0.8316213 0.302403 0.4876461 -0.8189957 0.4980436 0.3566319 -0.7904216 0.413174 0.2074847 -0.8867003 0.6214617 0.08934652 -0.7783331 0.5383303 -0.02239209 -0.8424364 0.6386042 -0.1750312 -0.7493656 0.484447 -0.3529136 -0.8004768 0.5638652 -0.3651524 -0.7407562 0.2748765 -0.5370126 -0.7975339 0.2249676 -0.4936058 -0.8400851 -0.01420819 -0.5784173 -0.8156173 -0.04456979 -0.5046581 -0.8621681 -0.2745445 -0.5420573 -0.7942287 -0.2720092 -0.5727937 -0.7732518 -0.5370314 -0.3845734 -0.7508 -0.5126102 -0.3436701 -0.7868428 -0.5730677 -0.04721766 -0.8181467 -0.6115524 -0.02851432 -0.79069 -0.5354411 0.1679083 -0.8277136 -0.4283809 0.1821548 -0.8850478 -0.4861668 0.44791 -0.7503455 -0.1831107 0.4399773 -0.8791419 -0.1823575 0.4477937 -0.8753437 0.02818375 0.6279358 -0.7777547 0.1616209 0.4341368 -0.8862302 0.3417066 0.5501934 -0.7619212 0.5214542 0.2575741 -0.8134747 0.4163393 0.2625598 -0.8704734 0.5554006 0.01543033 -0.8314398 0.5213458 -0.001660764 -0.8533439 0.5596966 -0.1849059 -0.8078054 0.3903648 -0.2231659 -0.8932035 0.4347827 -0.4527027 -0.7784757 0.1896123 -0.4486016 -0.8733865 0.1793127 -0.504176 -0.8447802 -0.06386488 -0.575753 -0.8151257 -0.1193045 -0.4292843 -0.895255 -0.3292188 -0.5411053 -0.7738347 -0.443387 -0.3209978 -0.8368802 -0.4001352 -0.2284024 -0.8875383 -0.6138314 -0.1666025 -0.7716571 -0.472471 0.09000736 -0.8767383 -0.4928311 0.1078328 -0.8634174 -0.5046893 0.3860191 -0.7721905 -0.3200889 0.3890786 -0.8638061 -0.3167558 0.4799215 -0.8181328 -0.07755911 0.5413316 -0.8372244 -0.08636844 0.5569457 -0.8260461 0.1667484 0.4999704 -0.8498379 0.1779134 0.5100997 -0.8415137 0.4124019 0.4232343 -0.8067202 0.3923086 0.2795245 -0.8763334 0.5511559 0.2607159 -0.7926251 0.5835539 0.06756192 -0.8092592 0.522289 0.02342236 -0.8524468 0.6415365 -0.2100731 -0.7377671 0.4070428 -0.2863863 -0.8673517 0.4341098 -0.4702625 -0.7683762 0.1890235 -0.4392023 -0.8782776 0.1735247 -0.509369 -0.8428716 -0.003684043 -0.6239075 -0.7814895 -0.1425173 -0.4482327 -0.8824831 -0.1583619 -0.4617439 -0.8727623 -0.4393832 -0.4565725 -0.7736176 -0.4393935 -0.2459626 -0.8639652 -0.4958802 -0.3143227 -0.8095086 -0.6559653 -0.06963878 -0.7515718 -0.5217216 0.06090658 -0.850939 -0.5863143 0.1507209 -0.7959389 -0.4798638 0.3092963 -0.8210156 -0.4459976 0.3058744 -0.8411464 -0.4048522 0.5295863 -0.745408 -0.1437994 0.5423976 -0.8277238 -0.1306342 0.5813763 -0.8030794 0.08210134 0.5987234 -0.7967369 0.1147159 0.4812892 -0.869023 0.4109968 0.552831 -0.724886 0.4502639 0.3103682 -0.8372181 0.5297985 0.4564077 -0.7148466 0.5877918 0.1489583 -0.7951806 0.529496 0.08899039 -0.8436319 0.5823379 -0.0820713 -0.8087935 0.4651061 -0.113099 -0.8780006 0.5159807 -0.4055007 -0.7545418 0.2896043 -0.3741545 -0.8809868 0.2790244 -0.5142247 -0.8109984 0.07810544 -0.5963212 -0.7989372 -0.00342822 -0.4734639 -0.8808066 -0.04183918 -0.4993489 -0.8653903 -0.2876455 -0.4554364 -0.8425187 -0.2897093 -0.5390755 -0.7908642 -0.5271961 -0.3801398 -0.7599725 -0.4112842 -0.1979225 -0.8897595 -0.6545401 -0.05822819 -0.7537818 -0.4937175 0.08633422 -0.8653263 -0.569342 0.1950656 -0.7986233 -0.4579301 0.4418029 -0.7714338 -0.3006722 0.3753921 -0.8767423 -0.1728204 0.5213021 -0.8356897 -0.1527172 0.5121865 -0.8451879 -0.01739084 0.6643898 -0.7471839 0.1963008 0.5325338 -0.8233309 0.2172626 0.5461016 -0.8090551 0.3707348 0.4266322 -0.8249489 0.3706807 0.4263469 -0.8251208 0.6054197 0.2637574 -0.7509322 0.5101231 0.1149529 -0.8523851 0.6686181 -0.05207782 -0.7417801 0.4287551 -0.1466944 -0.8914313 0.515054 -0.3249986 -0.7931553 0.2980728 -0.4535036 -0.8399328 0.2681097 -0.435535 -0.8593176 0.1241745 -0.6319205 -0.7650212 0.0863524 -0.5888255 -0.8036342 -0.1280547 -0.6077174 -0.7837612 -0.214913 -0.4321039 -0.8758417 -0.3217251 -0.478323 -0.8171293 -0.4542903 -0.3891541 -0.8013611 -0.4001169 -0.2665033 -0.8768594 -0.5692471 -0.187155 -0.8005816 -0.5305342 -6.23642e-4 -0.8476633 -0.7441942 -0.08393502 -0.6626688 -0.47294 0.2180231 -0.8536942 -0.5044075 0.2749724 -0.8185128 -0.3144182 0.4288967 -0.8468701 -0.3248952 0.5191409 -0.7905288 0.01461374 0.5086449 -0.8608524 -0.01269894 0.5949474 -0.8036643 0.2366383 0.4812316 -0.8440489 0.2363122 0.4740425 -0.8481983 0.4685846 0.3773422 -0.798775 0.5175529 0.4982699 -0.695605 0.5074272 0.1228201 -0.8528968 0.5881902 0.09857261 -0.8026929 0.6069978 -0.08858072 -0.7897515 0.4423136 -0.1658962 -0.8813837 0.5207579 -0.3408906 -0.7826908 0.3065932 -0.4555503 -0.8357478 0.3018526 -0.4519719 -0.8394084 -0.06646734 -0.7548334 -0.6525403 0.02224153 -0.5793694 -0.8147616 -0.2565515 -0.4880495 -0.8342596 -0.2597271 -0.4900047 -0.8321282 -0.454081 -0.3184067 -0.8321224 -0.4485339 -0.3179788 -0.8352885 -0.5334313 -0.07431721 -0.8425723 -0.5191543 -0.08026909 -0.850903 -0.5484808 0.1522796 -0.8221799 -0.4672753 0.1762805 -0.8663597 -0.4783791 0.3893977 -0.7870976 -0.3225494 0.3623843 -0.8744368 -0.2476853 0.5998003 -0.7608494 -0.05255091 0.4036988 -0.9133815 0.1019914 0.6040797 -0.7903705 0.2708534 0.4692471 -0.8405033 0.2740486 0.5032042 -0.8195626 0.531937 0.4250939 -0.7323512 0.4865769 0.2108749 -0.8478059 0.5857043 0.164616 -0.7936322 0.5038217 -0.03919589 -0.862918 0.5485038 -0.07685506 -0.8326085 0.5162054 -0.2755379 -0.8109321 0.4213331 -0.2824746 -0.8617928 0.4163216 -0.4539328 -0.7877953 0.168431 -0.4527795 -0.8755694 0.1616014 -0.4914641 -0.8557733 -0.05044436 -0.637112 -0.7691189 -0.1445846 -0.4284867 -0.8919051 -0.3902104 -0.5367291 -0.7481029 -0.3693405 -0.2382605 -0.8982314 -0.4817214 -0.3953664 -0.7820677 -0.6007779 -0.0486598 -0.7979337 -0.5276449 -0.009592592 -0.8494109 -0.5782145 0.2669526 -0.7709763 -0.4082742 0.2517416 -0.8774613 -0.3341252 0.5152599 -0.7892196 -0.2840731 0.4853348 -0.8268933 -0.06643331 0.6744337 -0.7353407 0.01845073 0.5806867 -0.8139181 0.2260417 0.6256735 -0.7466176 0.243165 0.5346585 -0.8093276 0.4946798 0.4127272 -0.7648191 0.4747931 0.3645844 -0.8010304 0.690244 0.06823909 -0.7203518 0.4805346 0.1317956 -0.8670159 0.6279265 -0.1207728 -0.7688447 0.4516858 -0.1646105 -0.87686 0.4707599 -0.4206882 -0.7755042 0.2963872 -0.3794285 -0.8764638 0.2507553 -0.5548236 -0.7932797 0.06540524 -0.5443612 -0.8362973 0.02187412 -0.4758884 -0.8792338 -0.1971059 -0.6059837 -0.7706705 -0.2694808 -0.4234434 -0.8649137 -0.3712743 -0.4518591 -0.8111589 -0.4968822 -0.2011793 -0.8441772 -0.4813406 -0.1885322 -0.8560181 -0.5737263 0.0939098 -0.8136456 -0.4900713 0.114634 -0.8641119 -0.509319 0.4025481 -0.7606244 -0.3063239 0.3533625 -0.8839122 -0.2733097 0.5772705 -0.7694549 0.03844618 0.6123581 -0.7896452 -0.03448086 0.5074542 -0.8609887 0.2772564 0.5656524 -0.7766378 0.2783859 0.5609607 -0.779631 0.473576 0.4867761 -0.7340129 0.4751797 0.3153634 -0.8214319 0.5636201 0.2862526 -0.7748496 0.5503279 0.03894448 -0.83404 0.5606364 0.03372961 -0.827375 0.592214 -0.177504 -0.7859866 0.4222461 -0.2094267 -0.8819574 0.4476612 -0.3984361 -0.8005301 0.3311297 -0.4314733 -0.8391567 0.3160117 -0.5372282 -0.7819992 0.1048168 -0.6434897 -0.7582444 0.04592782 -0.5841581 -0.8103395 -0.1581265 -0.6158086 -0.7718653 -0.1654577 -0.5884389 -0.7914313 -0.3904225 -0.4504051 -0.8029356 -0.4665462 -0.4656888 -0.7519764 -0.5380128 -0.183982 -0.8226134 -0.5733937 -0.174529 -0.8004745 -0.5418758 0.05206626 -0.8388443 -0.5840153 0.03776848 -0.8108636 -0.5534331 0.3109316 -0.7726794 -0.3785931 0.3265381 -0.8660487 -0.3812001 0.5245165 -0.7612943 -0.1291255 0.5113115 -0.8496395 -0.1188871 0.4947168 -0.860884 0.1226034 0.5855776 -0.8012909 0.1730929 0.4415852 -0.8803644 0.3554145 0.5042748 -0.7870118 0.4694436 0.304866 -0.8286612 0.4193835 0.2429534 -0.874695 0.6721253 0.01350969 -0.7403143 0.474514 -0.0802977 -0.8765779 0.5526623 -0.27357 -0.7872256 0.3687758 -0.3221287 -0.8719161 0.3825005 -0.406386 -0.8297854 0.2396433 -0.5572781 -0.794992 0.1183415 -0.4821312 -0.8680696 0.02222287 -0.6315125 -0.7750473 -0.282351 -0.6088731 -0.7413175 -0.1730642 -0.5352291 -0.8267881 -0.3838691 -0.4497848 -0.8064355 -0.368535 -0.394392 -0.8418058 -0.5087414 -0.2431659 -0.8258647 -0.4919639 -0.2227271 -0.8416438 -0.57336 0.01263159 -0.8192062 -0.4754711 0.04987043 -0.8783168 -0.5553274 0.3161208 -0.7692068 -0.4367704 0.31861 -0.8412606 -0.3673205 0.5828651 -0.7248062 -0.2280406 0.5212855 -0.8223496 -0.01180613 0.6678764 -0.7441786 0.07966959 0.4987635 -0.8630689 0.2498221 0.5699088 -0.7828109 0.3558567 0.3734686 -0.8566722 0.3587364 0.3802891 -0.8524603 0.5333155 0.258201 -0.8055476 0.5184873 0.2276038 -0.8242376 0.6763902 -0.01426678 -0.7364053 0.5054482 -0.1157661 -0.8550559 0.551101 -0.2278246 -0.802735 0.459405 -0.283465 -0.8417807 0.4666401 -0.4525024 -0.7599269 0.2495583 -0.5211086 -0.8161903 0.2328799 -0.5906855 -0.7725656 0.03159213 -0.672097 -0.7397889 -0.03934752 -0.5740801 -0.8178533 -0.2407542 -0.6315426 -0.7370151 -0.3190642 -0.4113893 -0.8537897 -0.4362245 -0.3628948 -0.823417 -0.3728377 -0.3473767 -0.8604194 -0.5700603 -0.1979262 -0.7974062 -0.5012319 -0.1134027 -0.85785 -0.6334321 0.03855013 -0.7728375 -0.4422041 0.1838411 -0.8778713 -0.4909601 0.1852996 -0.8512475 -0.3979465 0.4524084 -0.7981011 -0.2618014 0.388033 -0.8836802 -0.1383178 0.6504582 -0.7468416 -0.1191215 0.6307639 -0.766777 0.1880474 0.6370019 -0.747574 0.2274386 0.4216638 -0.8777649 0.4714155 0.4806484 -0.7394218 0.4362476 0.2000797 -0.8773005 0.5506982 0.1732657 -0.8165236 0.5570687 -0.05224931 -0.8288213 0.4747316 -0.08700591 -0.8758195 0.5529566 -0.2588226 -0.7919911 0.4043654 -0.3285921 -0.8535315 0.4111105 -0.4814206 -0.7740947 0.2212303 -0.5993445 -0.7693136 0.1150783 -0.4964622 -0.8603966 -0.09450793 -0.6052084 -0.7904372 -0.1100437 -0.5640732 -0.8183592 -0.310907 -0.5829778 -0.7506489 -0.4116443 -0.384871 -0.8260892 -0.4303808 -0.3871758 -0.8153941 -0.5462887 -0.1423118 -0.8254187 -0.5373882 -0.1350539 -0.8324509 -0.6639337 0.07073307 -0.7444387 -0.5235574 0.1882196 -0.8309399 -0.5540678 0.333113 -0.7629185 -0.3789033 0.3933336 -0.837688 -0.3812828 0.4201978 -0.8234424 -0.1886126 0.5327659 -0.8249763 -0.2055154 0.5478196 -0.8109607 0.06214183 0.6709303 -0.738912 0.1587765 0.4620559 -0.8725219 0.2730987 0.5239661 -0.8067693 0.4733033 0.3884279 -0.7906377 0.5271 0.2083318 -0.8238711 0.4123795 0.2339271 -0.8804666 0.5666771 -0.04773271 -0.8225563 0.7402936 0.009311795 -0.6722193 0.485379 -0.2676489 -0.8323288 0.5229662 -0.3537724 -0.7754687 0.2695499 -0.4416074 -0.8557605 0.269685 -0.4483888 -0.8521841 0.03918576 -0.6423895 -0.765376 0.08297669 -0.4621288 -0.8829224 -0.2007862 -0.6575971 -0.7261205 -0.2193186 -0.4491983 -0.8660948 -0.6095585 -0.7444348 -0.2724985 -0.798775 -0.5019671 -0.331644 0.6128791 0.1097171 -0.7825224 0.6833041 -0.166464 0.7109045 0.6496983 -0.2569209 -0.7154607 0.3535017 -0.4065826 0.8424531 -0.4375824 -0.1749351 -0.8819974 -0.05076175 0.606355 0.7935722 0.07189631 -0.4289248 -0.9004746 -0.07011288 -0.5581933 0.8267434 -0.12317 -0.4946095 -0.8603434 0.2217144 0.3862717 -0.8953419 -0.240791 -0.421477 0.8742865 -0.4286708 0.4042301 -0.8079848 -0.2238229 0.5539597 0.8018928 -0.2285138 -0.4108083 0.88262 -0.23878 0.3506544 -0.9055526 -0.270401 0.6903165 -0.6710786 0.1343935 0.7673448 0.6269932 -0.2601835 -0.3790159 -0.8880605 -0.7118251 -0.3202683 0.6250866 -0.9487647 -0.3101422 -0.0604763 -0.9516464 -0.09249842 -0.2929392 -0.9934822 0.1139869 2.96322e-4 0.6547628 0.09334093 -0.7500489 0.9163649 0.06541866 -0.3949633 0.6210394 0.1256305 -0.7736454 0.1859319 0.09803199 -0.97766 0.7170096 0.31889 -0.619844 0.9587346 0.2590366 -0.117167 0.9125196 0.3320031 -0.2389181 0.3672136 0.3060448 -0.8783456 0.6579918 0.3989751 -0.6386438 0.7056555 0.5992206 -0.3781338 0.8212218 0.5700269 -0.02577275 0.3616122 0.5157696 -0.7766714 0.4521847 0.6690155 -0.5898705 0.5573678 0.707769 -0.4340557 0.1029683 0.3693424 -0.9235712 0.04873877 0.236232 -0.9704737 0.2687575 0.8420959 -0.4675939 0.4712779 0.874664 0.1134032 0.2608585 0.8849853 -0.3856864 0.1014277 0.5723891 -0.8136849 -0.07694905 0.3665302 -0.9272187 0.1267482 0.9558148 -0.2652416 0.1203067 0.9638555 -0.2377164 -0.08793789 0.7374334 -0.6696707 -0.08132171 0.8112295 -0.5790455 -0.1242831 0.6811922 -0.7214783 -0.1165909 0.9901385 0.07766824 -0.1756868 0.9683287 -0.1774086 -0.09726256 0.2672668 -0.9587014 -0.3832083 0.7185934 -0.5803233 -0.4164985 0.6068875 -0.6769171 -0.3964781 0.6225044 -0.6747545 -0.4311906 0.856137 -0.2847875 -0.5484021 0.826586 0.1265341 -0.04414671 0.0413618 -0.9981685 -0.4328928 0.3364283 -0.8363133 -0.2520263 0.1381884 -0.9578031 -0.6782065 0.5945061 -0.4319705 -0.638001 0.42438 -0.642539 -0.7044278 0.617926 -0.3492122 -0.749907 0.3422824 -0.5661115 -0.4549962 0.1108275 -0.88357 -0.6295463 0.1476435 -0.7628061 -0.8744552 0.4850411 -0.007962763 -0.8912538 0.3511381 -0.2869994 -0.9490094 0.2147249 -0.2308123 -0.3522989 -0.03778976 -0.9351243 -0.7735847 0.08116942 -0.6284731 -0.8192312 -0.1096201 -0.5628888 -0.9079642 -0.1368293 -0.3960795 -0.6029765 -0.1684763 -0.7797662 -0.579141 -0.2601695 -0.772598 -0.9347491 -0.3089917 -0.1754087 -0.2211781 -0.2334213 -0.946887 -0.7245457 -0.4734435 -0.5008841 -0.8568144 -0.476688 -0.1965646 -0.8467072 -0.5318018 0.01654493 -0.2710832 -0.3497071 -0.8967826 -0.01619118 -0.03196096 -0.999358 -0.5955896 -0.6248494 -0.5048131 -0.4949893 -0.6048463 -0.6238162 -0.6496433 -0.7567574 -0.07267689 -0.5683375 -0.8044394 0.1728289 -0.1368718 -0.5566788 -0.8193747 -0.3352148 -0.8429136 -0.4208654 -0.03958123 -0.4497289 -0.8922876 -0.2550886 -0.8483301 -0.4639675 -0.1821785 -0.9192509 -0.3489826 -0.032516 -0.9444341 -0.3270887 0.1297664 -0.6526877 -0.7464312 0.1659476 -0.6579297 -0.7345678 0.1353582 -0.9897702 -0.04509174 0.2233479 -0.5826976 -0.7813957 0.2420158 -0.9288156 -0.2805889 0.1232925 -0.1494667 -0.9810498 0.5123201 -0.6710962 -0.5358714 0.5650375 -0.7179438 -0.406558 0.5206311 -0.8416786 -0.1432505 0.4413071 -0.3172493 -0.8394052 0.751998 -0.6105045 -0.2485631 0.5255628 -0.3033435 -0.7948375 0.7143365 -0.3798554 -0.5877358 0.8271206 -0.5401903 0.155133 0.4913408 -0.1152942 -0.8633027 0.8581744 -0.305078 -0.412873 0.8824825 -0.2123831 -0.4196643 0.5869615 -0.08400893 -0.8052447 0.9598048 -0.1113688 -0.2576274 0.002985954 -0.005089581 -0.9999827 0.004889369 -0.001591384 -0.9999868 0.002994596 -0.003042876 -0.9999909 -0.001118123 -0.00273025 -0.9999957 0.01009297 0.005835354 -0.9999321 -0.865245 0.4962191 0.07153952 -0.865144 0.4964359 0.07125604 -0.001964867 0.9974298 0.07162457 -0.002143621 0.9974142 0.07183641 0.8650452 0.4965269 0.07181936 0.8647515 0.497155 0.07100558 0.8642261 -0.498074 0.07096189 0.864926 -0.4965773 0.07289707 0.003857135 -0.9973667 0.07242137 0.001694798 -0.997561 0.06977891 -0.8665983 -0.4975422 0.03820055 -0.8653849 -0.4998759 0.0351181 0.008741974 0.0060997 0.9999433 0.005561113 0.01008087 0.9999338 8.37253e-4 0.01044189 0.9999452 0.01250362 0.001222491 0.9999211 0.0112189 -0.004128754 0.9999286 0.008765518 0.006359815 0.9999414 -0.003184854 0.01108711 0.9999335 4.68387e-4 0.01022535 0.9999477 -0.007933497 0.008834183 0.9999296 0.008307099 -0.005886614 0.9999483 0.007321357 -0.009233057 0.9999306 -0.008533954 0.00602281 0.9999455 -0.01216095 0.00346291 0.9999201 0.001890003 -0.01084327 0.9999395 2.97452e-4 -0.01013666 0.9999486 -0.002738058 -0.01122432 0.9999334 -0.01215076 -0.003238916 0.999921 -0.008627474 -0.006099581 0.9999443 -0.008333683 -0.00831896 0.9999307 6.61651e-4 0.001094579 0.9999993 0.001044094 0.001094579 0.9999989 -0.004195809 -0.008915007 0.9999516 0.001628696 0.00165385 0.9999974 -0.9783495 0.2062494 -0.01713687 -0.9381742 0.3451537 0.02642166 -0.7709336 0.6359938 -0.03425502 -0.6210841 0.7829121 0.03610199 -0.3501252 0.9362141 -0.03025776 -0.1712906 0.9849936 0.02114748 0.09075969 0.9957553 -0.01530259 0.2367031 0.9713347 0.02192455 0.4708652 0.8816403 -0.03156864 0.7072634 0.7060291 0.03607445 0.8241304 0.5659718 -0.0220254 0.9661435 0.2574502 0.01691901 0.9737305 0.2276504 0.004931449 0.9909815 -0.1330834 -0.0156362 0.961277 -0.2736695 0.03242921 0.8528828 -0.5213857 -0.02735227 0.6679232 -0.7438892 0.0225293 0.5877181 -0.8089661 -0.01270198 0.2761967 -0.9609745 0.01560103 0.1211177 -0.9921612 -0.03077059 -0.08029699 -0.9964914 0.02360486 -0.4829459 -0.8756335 0.005406737 -0.4358217 -0.8998962 -0.01570355 -0.7889474 -0.6144137 -0.007612228 -0.8200887 -0.5720607 0.01418018 -0.9810158 -0.1932476 -0.01623225 -0.9950976 -0.0973013 0.01769572 0.01036649 -0.01427376 -0.9998445 -0.02554363 -0.01793515 -0.9995128 0.01496708 -0.009148538 -0.9998462 0.01603549 0.01336526 -0.9997821 4.59822e-4 -0.003771007 -0.9999929 0.01861721 0.02041596 -0.9996182 0.003458023 -4.64506e-4 -0.9999939 0.02292168 -0.01576673 -0.9996129 0.003387033 7.91758e-4 -0.999994 -0.001691102 0.00742793 -0.999971 -0.006430268 -0.01327091 -0.9998913 -0.01816147 0.004628956 -0.9998244 2.3399e-4 1.63122e-4 -1 -5.59308e-4 6.25319e-4 -0.9999997 -0.001077473 -8.3815e-4 -0.9999991 -4.70605e-5 -8.50097e-5 -1 3.77097e-5 -9.19701e-5 -1 8.48299e-4 -0.005585551 -0.9999842 -0.005360901 -0.001057744 -0.9999851 -5.42329e-6 -6.54535e-5 -1 -0.00602585 0.001271307 -0.9999811 0.02960622 0.006584167 -0.99954 -0.006644725 0.01774656 -0.9998204 -0.003626167 0.004836201 -0.9999818 -0.04754704 -0.01425772 -0.9987673 -0.003835678 0.003167808 -0.9999877 0.04836767 -0.05329555 0.9974067 0.05919575 -0.02480101 0.9979383 0.007876276 -0.02550858 0.9996436 0.05047047 -0.01533174 0.9986079 0.001832783 -0.04767286 0.9988613 0.02940189 -0.02196907 0.9993262 0.001269519 -0.04685217 0.9989011 -0.02577847 -0.0937125 0.9952655 0.006385922 0.01732188 0.9998296 0.01042622 -0.0970959 0.9952205 0.1003798 0.02495771 0.9946361 0.09432011 0.05290031 0.9941355 0.01225912 0.03516232 0.9993064 -0.16298 -0.1180461 0.979542 0.004686355 0.01163941 0.9999214 -0.01748985 0.07217311 0.9972388 -0.008939623 0.406402 0.9136506 0.1162734 0.6525226 0.7487955 0.2918084 0.5181546 0.8039675 0.2674674 0.3847289 0.8834279 0.5826479 0.4010517 0.7068799 0.4175345 0.1070994 0.9023273 0.6587544 0.02838879 0.7518224 0.480172 -0.236612 0.8446595 0.5345213 -0.3044103 0.7884298 0.2724435 -0.4093 0.8707744 0.2886031 -0.5272186 0.7992176 0.05814051 -0.5690283 0.8202601 0.02032625 -0.5253069 0.8506702 -0.1634182 -0.6392406 0.7514427 -0.2734425 -0.486447 0.8298184 -0.4673664 -0.5040673 0.7262816 -0.4184289 -0.2463258 0.8742087 -0.5111678 -0.1295045 0.8496683 -0.4872308 -0.08562731 0.8690651 -0.6083332 -0.008455514 0.7936368 -0.4877293 0.1857767 0.852999 -0.5099163 0.1799479 0.8411922 -0.5287969 0.4582382 0.714417 -0.2718604 0.4984099 0.823213 -0.2218627 0.5550913 0.8016549 -0.3261168 0.6294582 0.7052873 0.03832709 0.594752 0.8029952 0.05540525 0.6203224 0.7823877 0.3295931 0.530366 0.7810764 0.3458279 0.5405226 0.7669671 0.4952741 0.2288486 0.8380525 0.535129 0.3723928 0.7582615 0.596696 0.1528248 0.7877807 0.4875339 -0.04952383 0.8716984 0.5583723 -0.08887952 0.8248156 0.5171742 -0.2523949 0.8178189 0.3779555 -0.2799721 0.8824768 0.3985467 -0.4748736 0.7846373 0.2491604 -0.5784398 0.7767409 0.2439352 -0.6328763 0.734822 -0.09126073 -0.6229113 0.7769511 -0.05770647 -0.5727463 0.817699 -0.2920401 -0.5112826 0.8082715 -0.2972057 -0.3779227 0.8768371 -0.4985743 -0.3687245 0.7845165 -0.4725999 -0.1787121 0.8629667 -0.5228486 -0.1652175 0.836261 -0.5534861 0.08912432 0.8280762 -0.4831994 0.1183654 0.8674722 -0.5425738 0.2982411 0.7852808 -0.2848114 0.4001217 0.8710827 -0.3009535 0.4551486 0.8380135 -0.09917587 0.5968861 0.7961727 0.001399219 0.4928179 0.8701313 0.1420075 0.5753193 0.8055071 0.2165136 0.4496947 0.8665428 0.3407655 0.4966524 0.7982578 0.5070441 0.3976054 0.7647328 0.4536616 0.2898072 0.8427355 0.6251934 0.04947358 0.7789004 0.5620458 0.06862187 0.8242546 0.5490885 -0.1503661 0.8221266 0.4929014 -0.1753333 0.8522362 0.5508798 -0.388404 0.7386974 0.3200457 -0.4389111 0.8395999 0.3052172 -0.5907395 0.7469065 0.04874777 -0.5962259 0.8013355 -0.02168852 -0.4995527 0.866012 -0.2259339 -0.5903031 0.774917 -0.2714498 -0.474058 0.8376061 -0.4270997 -0.4926233 0.758227 -0.5408503 -0.3043429 0.7841278 -0.4811456 -0.1884962 0.8561356 -0.6353237 -0.02826964 0.7717285 -0.4753796 0.09857124 0.8742414 -0.5407849 0.1707503 0.823648 -0.3971283 0.3844603 0.8333544 -0.3010878 0.3663793 0.8804047 -0.2422957 0.5830679 0.7754513 -0.05894637 0.4883998 0.8706269 0.05418175 0.6541925 0.7543849 0.2314405 0.4288416 0.8732298 0.2222991 0.5914816 0.7750695 0.5065724 0.3958435 0.7659584 0.5015776 0.3952987 0.7695186 0.5245265 0.09563988 0.8460054 0.5853022 0.1945636 0.7871254 0.6524103 -0.02339637 0.7575049 0.4194329 -0.1950771 0.8865783 0.5025336 -0.2954983 0.8124904 0.3484625 -0.4788179 0.8057962 0.1920362 -0.4242075 0.8849691 0.1516119 -0.5671393 0.8095473 -0.05437064 -0.5354832 0.842794 -0.06098055 -0.5217617 0.8509091 -0.2971422 -0.5017385 0.8123824 -0.3106007 -0.3525546 0.8827416 -0.5212379 -0.3955991 0.7561829 -0.5327755 -0.08126181 0.8423461 -0.5845277 -0.1184233 0.8026852 -0.6014864 0.2061875 0.7718166 -0.4244243 0.2542675 0.8690295 -0.4657497 0.4619808 0.7547523 -0.2726224 0.4546138 0.8479407 -0.2201535 0.6412888 0.7350382 0.06254106 0.5563817 0.82857 0.04796499 0.5317711 0.8455287 0.2635105 0.5283953 0.8070692 0.2817307 0.4173809 0.8639566 0.4674971 0.3802862 0.7980156 0.4335504 0.2616752 0.8622994 0.5790809 0.1424823 0.8027229 0.5120272 0.0175153 0.8587907 0.6005676 -0.04960823 0.7980337 0.458455 -0.212363 0.8629723 0.4998322 -0.2854013 0.8177493 0.318996 -0.4016277 0.8584503 0.3373748 -0.4816021 0.8088497 0.05444818 -0.4612588 0.8855934 0.02769064 -0.5481061 0.8359504 -0.1612165 -0.5805433 0.7981095 -0.194258 -0.4784948 0.8563331 -0.3398953 -0.4846274 0.8059824 -0.3904809 -0.2910882 0.8733798 -0.5146794 -0.2972699 0.8041989 -0.4946193 -0.1497653 0.8561087 -0.6706613 -0.04200494 0.7405734 -0.5204706 0.198006 0.8306047 -0.5141577 0.1917148 0.8359948 -0.4539971 0.4053105 0.7934798 -0.2874877 0.382407 0.878132 -0.2501593 0.6128125 0.7495874 -0.01110738 0.4532596 0.8913094 0.1428236 0.63768 0.756945 0.1939187 0.4498853 0.8717791 0.6266346 0.4476054 0.6379488 0.3830396 0.3503921 0.8546965 0.5456387 0.252936 0.7989379 0.4875648 0.1273715 0.863746 0.6114203 0.05532354 0.7893697 0.524141 -0.07702732 0.8481409 0.6164814 -0.2196052 0.7561245 0.4158638 -0.4155628 0.8089283 0.4050629 -0.3933262 0.8253597 0.2698461 -0.5688853 0.7768866 0.1262001 -0.5866435 0.7999519 0.02523696 -0.4448423 0.8952533 -0.1308764 -0.6167229 0.7762244 -0.1548281 -0.5065861 0.8481739 -0.4466423 -0.3945271 0.8030312 -0.4006865 -0.3726159 0.8370233 -0.6254091 -0.2101221 0.7514735 -0.4858277 -0.06573992 0.8715789 -0.6597459 0.1232404 0.7413145 -0.5145493 0.2725897 0.8129785 -0.5741816 0.4216605 0.7017963 -0.2669024 0.4985734 0.8247349 -0.2681505 0.4834955 0.8332632 -0.08217233 0.5683414 0.8186793 -0.00310719 0.4911453 0.8710721 0.07327151 0.5654023 0.8215544 0.2647341 0.4601945 0.8474297 0.2475909 0.6904481 0.6796914 0.4525943 0.3257352 0.8300934 0.4617732 0.3273995 0.8243635 0.4996845 0.0985952 0.860578 0.5365551 0.08850687 0.8392111 0.5350418 -0.1446406 0.8323518 0.5183302 -0.1313733 0.8450297 0.5788458 -0.3648344 0.7292692 0.342357 -0.4209783 0.8399816 0.3238157 -0.4976178 0.8046863 0.1982663 -0.502903 0.8412961 0.162881 -0.6250253 0.7634221 -0.1121285 -0.6050725 0.7882351 -0.1175588 -0.6112908 0.782626 -0.2938855 -0.4271045 0.8551099 -0.2963733 -0.4696932 0.8315956 -0.4304994 -0.2781904 0.8586503 -0.548859 -0.298289 0.7808826 -0.6119838 -4.50651e-4 0.7908703 -0.5282409 0.03669553 0.8483013 -0.4837192 0.2507304 0.8385404 -0.4586723 0.2525434 0.8519635 -0.3435451 0.4456333 0.8266726 -0.3140598 0.4378379 0.8424159 -0.2101729 0.6473597 0.7326342 -0.02922308 0.5623862 0.8263581 0.05721437 0.6318343 0.7729889 0.2440302 0.4607251 0.8533356 0.3601413 0.5225853 0.772789 0.4104821 0.2976447 0.8619235 0.4711702 0.3060691 0.8272366 0.5569415 0.05354386 0.8288241 0.6079691 0.09390521 0.7883879 0.5983067 -0.2258403 0.7687819 0.5568498 -0.1805508 0.8107526 0.4288968 -0.4862421 0.7613253 0.3666085 -0.3538786 0.8604465 0.2663142 -0.535368 0.8015347 0.08586364 -0.4887745 0.8681746 0.06142956 -0.5654264 0.8225082 -0.2100152 -0.5291499 0.8221277 -0.2112789 -0.3984807 0.8925102 -0.4807595 -0.3532351 0.8025555 -0.4550545 -0.1532513 0.877177 -0.490435 -0.1519718 0.8581249 -0.6277524 0.06250327 0.7758997 -0.4369173 0.2046832 0.8759042 -0.486249 0.2635844 0.8331179 -0.3961116 0.4695836 0.7890418 -0.3112698 0.4449288 0.8397318 -0.1811425 0.6436439 0.7435792 0.03564137 0.5359467 0.8434993 0.05442816 0.5636813 0.8241972 0.2842212 0.5026875 0.8164089 0.289426 0.3696029 0.8829646 0.4759818 0.3809303 0.792675 0.5077551 0.1647723 0.8455974 0.6155751 0.2918679 0.7320387 0.5139716 -0.08861023 0.8532183 0.5751088 -0.05485534 0.8162357 0.5117774 -0.282639 0.8112948 0.3533092 -0.3002024 0.8860311 0.3955117 -0.5258684 0.7530159 0.0763911 -0.4911738 0.8677055 0.09560114 -0.5126795 0.853241 -0.1222205 -0.632072 0.7652105 -0.2184225 -0.4099419 0.8855729 -0.3904636 -0.486869 0.7813429 -0.4795198 -0.2510046 0.8408671 -0.4256732 -0.1574034 0.8910816 -0.5716444 -0.1096268 0.8131449 -0.5867027 0.1187012 0.8010556 -0.4467244 0.1816619 0.8760344 -0.4927711 0.2675438 0.8280078 -0.4055182 0.4363039 0.8032397 -0.3558753 0.4222789 0.8336867 -0.188302 0.6179089 0.7633683 -0.04184103 0.5193236 0.8535528 0.1103149 0.6306149 0.7682158 0.1714814 0.4793933 0.8606837 0.3623152 0.4661738 0.8070996 0.3667353 0.365462 0.8555366 0.530336 0.3175468 0.7860712 0.4449112 0.1134271 0.8883628 0.6493079 0.03186577 0.7598578 0.4567544 -0.2157735 0.863028 0.4250973 -0.1847885 0.8860844 0.4693363 -0.3825614 0.7958456 0.2536432 -0.4305624 0.8661878 0.2523239 -0.5481316 0.7974236 0.02966928 -0.4533901 0.8908182 -0.06826055 -0.6229128 0.7793076 -0.3115938 -0.5146622 0.7987692 -0.2490663 -0.4699895 0.8468034 -0.4949257 -0.4666687 0.7329863 -0.506098 -0.2861217 0.8136334 -0.7425395 -0.1301726 0.6570314 -0.4943699 -0.1622493 0.8539753 -0.6785327 0.0234155 0.734197 -0.5323212 0.2181539 0.8179506 -0.5672609 0.2748626 0.7763155 -0.3302301 0.3376924 0.8814261 -0.3317726 0.5415827 0.7724087 -0.1296275 0.4667996 0.8748113 -0.04144126 0.6489219 0.7597256 0.1253287 0.4986442 0.8576985 0.2686553 0.6055474 0.7490906 0.4411238 0.3723943 0.8165368 0.5119501 0.3746188 0.7730252 0.4571165 0.1809037 0.8708148 0.6395411 0.08074575 0.7645046 0.4818745 -0.09549009 0.8710216 0.5514642 -0.1574819 0.8191989 0.379867 -0.3989875 0.8345718 0.361715 -0.3931475 0.8453385 0.1696469 -0.5344323 0.828011 0.2076569 -0.5658463 0.7979328 -0.1572418 -0.6444699 0.7482872 -0.08421772 -0.5139378 0.8536835 -0.3365716 -0.5517005 0.7631161 -0.3344583 -0.4318668 0.8376328 -0.5875941 -0.2282508 0.7762957 -0.624208 -0.2878177 0.7263094 -0.5847036 0.07991677 0.8073011 -0.5831964 0.07912403 0.8084686 -0.5170952 0.2324117 0.8237702 -0.4183382 0.2582387 0.8708076 -0.4177846 0.4610372 0.7828798 -0.2169843 0.5182102 0.8272702 -0.2158076 0.4618567 0.8602998 -0.005555629 0.6296793 0.7768354 0.09336173 0.4574547 0.8843183 0.3425647 0.5938326 0.7280195 0.385299 0.2768411 0.8802863 0.4225459 0.3611486 0.8312802 0.5622724 0.1244428 0.8175352 0.6009795 0.162289 0.782615 0.5840829 -0.1671507 0.7942971 0.7077682 -0.1278177 0.6947855 0.4539948 -0.3360692 0.8251947 0.4785506 -0.48443 0.7323367 0.2714437 -0.4972397 0.8240577 0.2141718 -0.6307793 0.7458203 0.0477395 -0.573644 0.8177124 -0.1329786 -0.7107762 0.6907343 -0.2358044 -0.4308052 0.8710932 -0.4619112 -0.4517673 0.7632459 -0.4359021 -0.2995035 0.8486974 -0.6218422 -0.2328246 0.7477332 -0.5802712 -3.43154e-4 0.8144234 -0.7004389 -0.081272 0.70907 -0.525801 0.2235215 0.8207141 -0.5439604 0.2529013 0.8000925 -0.3859222 0.5147147 0.7655933 -0.2989815 0.3255037 0.8970271 -0.2049571 0.6234167 0.754549 0.05236166 0.4883224 0.871091 0.05193281 0.487433 0.8716146 0.3430737 0.5786005 0.7399473 0.357443 0.3174267 0.8783365 0.4167521 0.3221929 0.8500055 0.4942469 0.1062108 0.862809 0.4645081 0.05458849 0.8838849 0.6308058 -0.03337949 0.7752225 0.4477956 -0.2700767 0.8523718 0.4700573 -0.2713974 0.8398749 0.2997639 -0.5072379 0.8079922 0.2182356 -0.4667684 0.8570301 0.06562185 -0.6390063 0.7663974 -0.08594971 -0.4472208 0.8902844 -0.268147 -0.6133509 0.7428984 -0.3771167 -0.3056081 0.8742922 -0.4948561 -0.3309005 0.8035063 -0.4909864 -0.1006824 0.8653297 -0.5741885 -0.07238852 0.8155167 -0.562232 0.1398 0.8150774 -0.4602717 0.1837366 0.8685567 -0.5116452 0.2908315 0.8084778 -0.3531841 0.4490097 0.8207626 -0.2740349 0.4241946 0.8631129 -0.1879751 0.5573983 0.8086858 -0.03806704 0.5037737 0.8629966 -0.01501524 0.5492785 0.8355045 0.1574398 0.4909768 0.8568282 0.2752849 0.568207 0.7754734 0.4910028 0.3908247 0.7785708 0.3392156 0.3288004 0.8813757 0.5680848 0.2717739 0.7768002 0.5340572 0.145148 0.8328955 0.6803062 0.02841389 0.7323771 0.4968495 -0.19821 0.8448986 0.5621085 -0.2845897 0.7765583 0.4048622 -0.341493 0.8482152 0.3989486 -0.4953213 0.7716844 0.2384928 -0.5585546 0.7944421 0.09863597 -0.4761607 0.873809 -0.004868328 -0.5418493 0.8404616 -0.1006251 -0.4518907 0.88638 -0.1996983 -0.5555034 0.8071781 -0.4216492 -0.442938 0.791213 -0.36725 -0.2887843 0.8841556 -0.6343051 -0.1301352 0.7620512 -0.5673292 -0.07030332 0.8204846 -0.6163302 0.2296742 0.7532509 -0.6119486 0.2254453 0.7580853 -0.3318446 0.4750133 0.8150101 -0.3262461 0.4550128 0.8285692 -0.0675835 0.5586906 0.826618 -0.0805996 0.4913392 0.8672311 0.1854258 0.5743177 0.797356 0.2086843 0.5096089 0.8347153 0.4323465 0.5356732 0.7253487 0.4720506 0.2854602 0.8340748 0.5797224 0.2710856 0.7683975 0.5132451 0.04412239 0.8571071 0.600279 4.46024e-4 0.7997906 0.4474516 -0.2853085 0.8475766 0.5966908 -0.2114265 0.7741182 0.4720819 -0.4043965 0.7833278 0.2664106 -0.4237639 0.8657076 0.2378125 -0.7082608 0.6646894 -0.08654439 -0.5022352 0.8603894 -0.2103192 -0.6376592 0.7410511 -0.3352338 -0.3350934 0.8805287 -0.3504158 -0.3944525 0.8494799 -0.5391327 -0.192784 0.8198599 -0.6292291 -0.3099468 0.7127439 -0.5811085 0.02398705 0.8134726 -0.6453934 0.07298821 0.7603554 -0.5352929 0.3083153 0.7863862 -0.3786872 0.3137366 0.870727 -0.3255327 0.581214 0.7458008 -0.2338441 0.5248579 0.8184382 0.02365803 0.6507351 0.7589362 0.1360539 0.4897998 0.8611537 0.2253907 0.5580163 0.7986345 0.4213662 0.4372041 0.794546 0.4022054 0.3523966 0.8450134 0.5577467 0.282117 0.7805952 0.5470449 0.01556074 0.8369587 0.5213164 0.02291727 0.8530558 0.625236 -0.1363645 0.76843 0.41501 -0.2419056 0.8770681 0.4620733 -0.3573006 0.8116802 0.2880456 -0.4810027 0.8280496 0.2727622 -0.4094629 0.8705981 0.1199191 -0.6491793 0.7511231 -0.1023345 -0.4765809 0.8731543 -0.1087805 -0.4539201 0.8843775 -0.3525593 -0.529937 0.7712774 -0.3940086 -0.2874823 0.8729899 -0.4170711 -0.3418427 0.8421374 -0.6285809 -0.1617215 0.7607445 -0.5818032 -0.08079463 0.8093068 -0.6584796 0.06991386 0.7493442 -0.5510304 0.1629021 0.8184305 -0.5901396 0.3701624 0.7174364 -0.4395379 0.3804275 0.8136839 -0.2443966 0.6209102 0.7448092 -0.2325391 0.5077187 0.8295466 0.02433496 0.5757656 0.8172526 0.05157095 0.5304814 0.8461265 0.3490496 0.615686 0.7064667 0.3607859 0.4678831 0.8067955 0.5833636 0.2638539 0.7681589 0.5209426 0.2554056 0.8144857 0.5568132 -0.03375893 0.8299516 0.5252192 -0.04859882 0.8495782 0.499853 -0.308916 0.8091464 0.3736999 -0.3096467 0.8743383 0.3678357 -0.4997671 0.7841746 0.1373621 -0.4820235 0.8653236 0.09586149 -0.6519817 0.7521507 -0.221457 -0.477041 0.8505226 -0.1957061 -0.5743265 0.7948889 -0.4663743 -0.4319529 0.7719531 -0.4242602 -0.3168622 0.8482934 -0.6602526 -0.1279177 0.7400701 -0.5306513 0.002883791 0.8475854 -0.4641574 0.3095332 0.829908 -0.6514363 0.202695 0.7311263 -0.4746049 0.4467666 0.7583863 -0.2452564 0.4265783 0.8705632 -0.2243076 0.5776929 0.7848293 -0.1638209 0.5583797 0.8132496 0.1076174 0.6906157 0.7151703 0.2117265 0.4450383 0.8701224 0.4007843 0.4739241 0.7840715 0.3941497 0.3598853 0.8456527 0.5832761 0.308266 0.7515058 0.6006299 0.1007485 0.7931541 0.6388559 0.0823186 0.7649097 0.5930154 -0.1682951 0.7874069 0.6376091 -0.2200031 0.7382773 0.4384916 -0.3791341 0.8148513 0.4573491 -0.4738121 0.7525516 0.3026058 -0.5465103 0.7808689 0.1107475 -0.468827 0.8763198 0.06205433 -0.587245 0.8070271 -0.1184219 -0.6019757 0.7896844 -0.105029 -0.6412759 0.7600883 -0.4072489 -0.4496198 0.7949783 -0.3671984 -0.428361 0.8256345 -0.5631691 -0.3482053 0.7493956 -0.5059844 -0.2192268 0.8342179 -0.6318339 -0.03742849 0.7741997 -0.5331949 0.02710545 0.8455582 -0.4899447 0.3078533 0.815586 -0.439606 0.255526 0.8610768 -0.3964492 0.4998964 0.7700205 -0.1481168 0.4465246 0.8824269 -0.1376123 0.5206987 0.8425769 0.05178898 0.6283286 0.7762224 0.1229148 0.5171781 0.8470058 0.2341794 0.5632363 0.7924171 0.4213382 0.3927332 0.8174563 0.4106417 0.388725 0.8247825 0.5693879 0.2238528 0.7910041 0.5315105 0.1743618 0.8289117 0.6718846 -0.01931059 0.7404042 0.4728761 -0.1642624 0.8656824 0.3525123 -0.3155295 0.8810087 0.4983059 -0.3084559 0.8102753 0.3396914 -0.4875749 0.8042888 0.09474694 -0.4850375 0.8693457 0.07559281 -0.5921754 0.8022556 -0.1528866 -0.5787991 0.8010101 -0.2074027 -0.3936875 0.8955414 -0.4002625 -0.4761314 0.7829999 -0.4967477 -0.2496749 0.8312065 -0.461151 -0.198111 0.8649231 -0.5908575 -0.02809417 0.8062868 -0.4850325 0.06434488 0.8721258 -0.569793 0.1894336 0.7996568 -0.3836405 0.3403085 0.858493 -0.4108725 0.3901188 0.8240093 -0.1569217 0.5761796 0.8021177 -0.1950772 0.6166387 0.7626937 0.128612 0.5990793 0.790293 0.1359304 0.6074453 0.7826449 0.4551992 0.4873939 0.745145 0.321126 0.4032548 0.856892 0.5928371 0.2724026 0.757853 0.470567 0.08787912 0.8779772 0.5892503 0.01515334 0.8078084 0.5111244 -0.1996952 0.8359867 0.482706 -0.2045122 0.851569 0.411301 -0.4215912 0.8081415 0.2760758 -0.3955261 0.8759801 0.2366991 -0.5949869 0.7680912 -0.03525495 -0.4788977 0.8771626 -0.07013618 -0.5476405 0.833769 -0.2912184 -0.5157804 0.8057063 -0.2986184 -0.3522447 0.8869897 -0.5196635 -0.359008 0.7752826 -0.4846013 -0.1074104 0.8681156 -0.482168 -0.1079186 0.8694065 -0.5998485 0.07221746 0.7968478 -0.4599834 0.1872228 0.8679649 -0.4972744 0.2329335 0.8357393 -0.424251 0.4374754 0.7928596 -0.3300561 0.4175805 0.8465752 -0.1672216 0.6841146 0.7099466 -0.08076578 0.6060634 0.7913054 0.1307747 0.608796 0.7824739 0.2032402 0.4735801 0.8569805 0.3721503 0.507426 0.7771893 0.4048147 0.292366 0.8663991 0.4924693 0.5029445 0.7102963 0.5644632 0.1193858 0.8167793 0.5830846 0.1149212 0.8042422 0.5095933 -0.1913825 0.8388609 0.6585016 -0.1296179 0.7413331 0.4022486 -0.2984019 0.865536 0.445425 -0.3896232 0.8060958 0.2220544 -0.5081899 0.8321268 0.1858128 -0.4793562 0.8577245 -0.06480556 -0.5939986 0.8018516 -0.1240693 -0.4694595 0.8741937 -0.3061574 -0.5523624 0.7753473 -0.4012943 -0.4058468 0.8211281 -0.3759174 -0.2996412 0.8768702 -0.5732341 -0.2095809 0.7921354 -0.5236275 -0.116308 0.8439708 -0.6450499 -0.0137695 0.7640164 -0.5797294 0.193355 0.7915351 -0.5018253 0.2232651 0.835658 -0.4701581 0.3428059 0.8132869 -0.2844477 0.3450222 0.8944548 -0.2993614 0.5493372 0.7801356 0.006432175 0.5048516 0.8631823 0.009352803 0.5144315 0.8574805 0.2196824 0.5942487 0.7736977 0.295131 0.3113042 0.9033203 0.3706515 0.3426684 0.8632473 0.5534238 0.3153935 0.7708756 0.4778763 0.08137929 0.8746495 0.628886 0.03148013 0.7768601 0.4967522 -0.2311255 0.8365514 0.4572395 -0.2353269 0.8576441 0.4082424 -0.4380419 0.8009104 0.3324746 -0.4304818 0.839134 0.2807544 -0.5680035 0.7736596 0.07509726 -0.6193349 0.7815272 0.0490821 -0.5920183 0.8044286 -0.1764648 -0.5941575 0.784753 -0.1650611 -0.5836284 0.7950679 -0.3775704 -0.5145142 0.7698804 -0.3803419 -0.4534315 0.8060646 -0.5504711 -0.2847937 0.7847766 -0.6209577 -0.282571 0.7311396 -0.6235381 -0.004429221 0.7817806 -0.5233323 0.06053763 0.8499756 -0.5531951 0.2543357 0.7932771 -0.3835129 0.3003541 0.8733301 -0.4262154 0.4440507 0.7881367 -0.271885 0.5827502 0.7658204 -0.1626219 0.5387911 0.8265944 -0.02604615 0.6705142 0.7414394 0.08226335 0.5651835 0.8208536 0.295158 0.6013193 0.7424938 0.3297275 0.3975504 0.8562906 0.5076735 0.3861501 0.770166 0.4732931 0.2159165 0.8540338 0.6327369 0.1549925 0.7586972 0.572992 -0.09475356 0.814065 0.4975726 -0.1361653 0.8566682 0.5574716 -0.2983876 0.7747195 0.3459361 -0.3794458 0.858108 0.3289387 -0.3744186 0.8669546 0.2170417 -0.5859858 0.7807135 0.05146998 -0.4888829 0.8708297 -0.03325057 -0.5985466 0.8003978 -0.1744524 -0.4734406 0.8633773 -0.2597038 -0.5295889 0.8075208 -0.4057317 -0.361852 0.8393122 -0.3936219 -0.3173944 0.8627414 -0.6289572 -0.2194514 0.7458243 -0.5106763 0.002779006 0.8597687 -0.3733331 -0.05908232 0.9258142 -0.6434282 0.22644 0.731249 -0.2566428 0.3108481 0.9151546 -0.4412318 0.4016126 0.8025097 -0.09448951 0.4186949 0.9031978 0.03530836 0.2518392 0.9671248 -0.2154588 0.8887056 0.4046975 0.04167288 0.530094 0.8469142 0.5004996 0.6268053 0.5971728 0.6281691 -0.2833727 0.7246403 0.482897 -0.558063 -0.6748158 0.3872105 -0.785871 0.4821567 0.03230315 -0.8852835 -0.4639284 -0.7100281 -0.6204159 0.333083 -0.8813183 -0.2515586 -0.3999954 -0.8281823 -0.05605465 0.5576488 -0.6462603 0.2553772 -0.7191176 -0.2783423 0.5038982 0.8176871 0.6841858 0.3937651 0.6138721 0.8047752 0.01619094 -0.5933589 0.8412756 -0.1801477 0.509708 0.7177509 -0.5519391 -0.4244962 -0.07678967 -0.7323391 0.6765965 -0.4418542 -0.724159 -0.5294891 -0.5708487 -0.5222871 0.6335204 -0.6994411 -0.3650675 -0.6144167 -0.7636 0.009888589 0.6456139 -0.8137584 0.1027314 -0.5720521 -0.6584006 0.5387648 0.5255866 -0.5431599 0.5921756 -0.5952357 -0.2963444 0.7688691 0.5665867 -0.09456276 0.8310635 -0.5480798 0.2248322 0.8256985 0.5173708 0.3356304 0.9089251 -0.2474015 0.7645188 0.5843479 0.2721187 0.9148709 0.1633667 0.3692189 0.8421532 -0.3021771 -0.4466175 0.1508285 -0.7707597 -0.6190156 -0.3736444 -0.6375703 0.6737166 -0.6770668 -0.4710137 -0.5654439 -0.9040741 0.0109775 0.4272348 -0.8660421 0.07845991 -0.4937764 -0.6288095 0.4847057 0.607996 -0.6030443 0.5754591 -0.5524351 -0.1732724 0.9154899 0.3631185 -0.2348745 0.971491 0.03223586 0.3743382 0.9272835 0.004042506 0.8878518 0.2667407 0.3749248 0.8782941 -0.2922458 -0.3784072 0.7938637 -0.3902662 0.4663397 0.4512256 -0.750247 -0.4832441 0.2611885 -0.7624768 0.5919543 -0.0079602 -0.8535135 -0.52101 -0.2593914 -0.8011105 0.5393869 -0.4484902 -0.6597519 -0.6029794 -0.6518275 -0.5764044 0.4928275 -0.9181297 -0.1924644 -0.3464037 -0.8691768 0.3052003 -0.3890818 -0.4302802 0.739293 0.5179815 -0.07739233 0.9450252 -0.3177072 0.491325 0.8699781 0.04168891 0.4994138 0.7463599 0.4399237 0.7060357 0.5371272 -0.4615279 0.7801178 0.265024 0.5667261 0.8625049 0.1225883 -0.490976 0.8234437 -0.2363766 0.5158166 0.9320884 -0.3353046 -0.1370473 0.6620042 -0.6871697 -0.2992462 0.4696552 -0.6881954 0.5530021 0.2057588 -0.8594891 -0.4679125 -0.01251012 -0.8708487 0.4913921 -0.2381799 -0.832215 -0.5006881 -0.4572028 -0.6757261 0.5782386 -0.6172332 -0.5830299 -0.5282986 -0.782892 -0.2186065 0.5824872 -0.9652919 0.1865401 -0.1827959 -0.6863631 0.722535 0.08275812 -0.6612935 0.7227643 -0.2007556 -0.144818 0.9218239 0.3595393 -0.1233113 0.9831106 -0.1352334 0.4087691 0.8527339 -0.3251964 0.5919988 0.3980219 0.7007967 0.7705637 0.3014556 -0.5615659 0.7556987 -0.1301949 0.641848 0.7360001 -0.4915027 -0.4655416 0.3306359 -0.7377596 0.5885497 0.2580813 -0.8153454 -0.5182721 -0.2271494 -0.9579924 0.1750823 -0.6076647 -0.638998 0.4716199 -0.9209372 -0.1351029 -0.3655433 -0.3572557 0.5936618 0.7210646 -0.09853953 0.7498738 -0.6542013 0.2114964 0.6143817 0.7601346 0.6280854 0.6938695 -0.3522128 0.9571842 0.2756403 -0.08843535 0.8315196 0.1315861 0.5396853 0.7394073 -0.2097101 -0.6397644 0.582144 -0.5771993 0.5726687 0.2956357 -0.8205947 -0.4891054 -0.07790172 -0.8538479 0.5146601 -0.4298111 -0.8408239 -0.3290556 -0.5687928 -0.6986918 0.4339407 -0.668327 -0.5397978 -0.5118178 -0.7390416 -0.1974591 0.644071 -0.847764 -0.07972443 -0.5243474 -0.8423735 0.3331829 0.423552 -0.9166035 0.3960183 0.05484223 -0.5517497 0.777545 -0.3016555 0.2588229 0.9450702 -0.1996325 0.6963928 0.6837951 0.2178563 0.6938504 0.6171729 -0.3710382 0.845573 0.1178457 0.5206907 0.7315049 -0.5786316 -0.3606744 0.3743571 -0.8432668 0.3856914 0.2390151 -0.8162492 -0.5259366 -0.08800566 -0.7990902 0.5947352 -0.2326898 -0.6557321 -0.7182415 -0.501935 -0.5004224 0.7054352 -0.6373173 -0.3126874 -0.7043105 -0.9030844 -0.1981838 0.3810009 -0.9428614 0.3259376 -0.0691154 -0.9253579 0.3258531 -0.1937335 -0.5559401 0.8281844 0.07100307 -0.1161341 0.9641293 -0.2386788 0.4643036 0.8444261 0.2671455 0.4816049 0.7837401 -0.3921838 0.7788085 0.3611187 0.5128847 0.8701888 0.04714441 -0.490458 0.7758858 -0.4671244 0.4240238 0.765108 -0.518755 -0.3814486 0.265116 -0.8513476 0.4526817 0.2393378 -0.9093021 -0.3404223 -0.3243242 -0.9368241 0.131052 -0.3406518 -0.8556553 -0.3896287 -0.6217906 -0.5777457 0.5287595 -0.6388258 -0.3459521 -0.6871817 -0.9322326 -0.2707954 0.2400255 -0.8953647 0.1671214 0.4127866 -0.801433 0.2202587 -0.5560499 -0.6022586 0.6764894 0.4238476 -0.2699426 0.9589096 -0.0873118 0.2562761 0.9652614 -0.0509231 0.3137335 0.844884 0.4332924 0.5548332 0.6869316 -0.4693455 0.6823015 0.3996766 0.6121465 0.7418097 0.2928261 -0.6033004 0.7645918 -0.1145356 0.6342564 0.7397435 -0.2455151 -0.6264997 0.6392083 -0.5510238 0.5364566 0.5237588 -0.6989201 -0.4870191 0.2660345 -0.8395332 0.4737192 0.06307059 -0.7347802 -0.6753668 -0.738683 0.2423062 0.6289954 -0.6691002 0.5394105 -0.5112155 -0.469786 0.7353768 0.4883873 -0.3268677 0.8080749 -0.4900741 -0.06602782 0.8800135 0.4703366 0.2109209 0.7846924 -0.5828983 0.5637254 0.5778607 0.5901616 0.7842214 0.4141018 -0.4620788 0.7630537 0.0938183 0.6394898 0.7321869 -0.04727423 -0.6794612 0.6024246 -0.4290438 0.6730573 0.6839655 -0.6125447 -0.3962075 0.311734 -0.9354892 0.1663791 -0.1236121 -0.9819125 0.1434152 -0.6350027 -0.7721934 -0.02211427 -0.912271 -0.04073506 -0.4075567 -0.7158874 0.4574569 0.5274832 -0.4252251 0.584497 -0.6910477 -0.14744 0.8298734 0.5381187 0.06341397 0.8071554 -0.5869233 0.2652896 0.9240268 0.2753109 0.6559692 0.7400786 0.1482841 0.6365334 0.6587462 -0.4010971 0.8721081 0.2211929 0.4364646 -0.3082101 -0.9508314 -0.03043735 -0.8019105 -0.5473526 0.2394674 -0.5611219 0.5169483 -0.6464571 -0.1821131 0.7503533 0.6354563 -0.01695913 0.6980528 -0.7158454 0.2529858 0.8418247 0.4767909 0.6702669 0.6975507 -0.2533092 0.6846463 0.7283408 -0.02791202 0.9627865 0.2140881 -0.1649503 0.9718134 0.2077003 -0.1115317 0.853615 -0.2754285 0.4421319 0.7294182 -0.3376025 -0.5949569 0.5802598 -0.66992 0.4631476 0.4608052 -0.7620664 -0.4548771 0.2042835 -0.8486122 0.4879813 -0.04100364 -0.7506126 -0.6594692 -0.2784351 -0.6626704 0.695228 -0.5595907 -0.5804733 -0.591531 -0.7216296 -0.3844459 0.5757189 -0.8551977 -0.2716093 -0.4414356 -0.8646275 0.114743 0.4891353 -0.7943888 0.2152515 -0.5679906 -0.6184253 0.5220686 0.5873624 -0.542609 0.6612226 -0.5180349 -0.2709899 0.8685315 0.4149913 -0.161215 0.8861414 -0.4344689 0.2486103 0.7189461 0.6490835 0.4290485 0.535313 -0.7275696 0.6580358 0.1727561 0.7329013 0.8275761 -0.1227709 -0.5477637 0.7026513 -0.6299329 0.330856 0.2914386 -0.8001813 0.5241883 -0.08195292 -0.8393043 -0.5374494 -0.2717325 -0.7010796 0.6592791 -0.5111649 -0.529182 -0.6772569 -0.7408086 -0.4363325 0.5107021 -0.960463 -0.09755462 -0.2607566 -0.60382 0.5631413 -0.5641573 -0.2125506 0.8959485 0.3899984 -0.1952672 0.9758099 -0.09831446 0.3971142 0.9177015 0.01116037 0.6299646 0.4578189 0.6273329 0.7793159 0.06628972 -0.6231151 0.8453134 -0.3918674 0.3631601 0.4992745 -0.8155059 -0.292703 0.03796631 -0.9380344 -0.3444564 -0.4170308 -0.7817901 0.4635619 -0.4798617 -0.6798855 -0.5545164 -0.7181413 -0.3433818 0.6052785 -0.7226608 0.3489465 -0.5966556 -0.3171581 0.7238146 0.6127833 0.001211464 0.6011191 -0.7991586 0.328982 0.7912085 0.5155193 0.7412742 0.6432821 -0.1915743 0.9488888 0.2050282 -0.2399446 0.8540543 -0.212144 0.4749593 0.7794238 -0.339629 -0.5264511 0.6522116 -0.6190484 0.4374921 0.4988332 -0.6696572 -0.5502042 0.12687 -0.678676 0.7233968 -0.03910142 -0.6229504 -0.7812835 -0.3650395 -0.6383429 0.6776906 -0.5802956 -0.481083 -0.6571273 -0.4822262 0.8749657 0.0435099 0.1077917 0.9931914 -0.04417985 0.8401268 0.5354688 -0.0863735 0.9888048 -0.01627773 0.1483249 0.9965997 -0.02027249 0.07986277 0.7885653 -0.5252574 -0.3197959 0.6033822 -0.5595396 0.5681949 0.2085305 -0.7176793 -0.6644182 -0.2826861 -0.90429 0.3199189 -0.8003005 -0.5995507 -0.007635533 -0.5175702 -0.0775752 -0.8521169 -0.5794757 0.3482702 0.7368282 -0.4907413 0.6594826 -0.5694345 -0.1738367 0.6758581 0.7162378 0.1496868 0.8344125 -0.5304241 0.7433864 0.6430613 0.1839807 0.4101982 -0.9116972 -0.02336472 -0.1527842 -0.8575651 0.4911611 -0.38736 -0.6827229 -0.6195498 -0.6523141 -0.3897286 0.6500753 -0.7156793 -0.1538037 -0.6812838 -0.8070676 0.1786242 0.5627925 -0.6838549 0.330484 -0.6504788 -0.4558396 0.5650854 0.6876692 -0.3261509 0.6737111 -0.6631282 -0.05204343 0.8101869 0.5838568 0.1899503 0.7275854 -0.6591954 0.5721744 0.6655897 0.4791732 0.9402171 0.3044909 -0.1525685 0.986411 -0.1236152 -0.1082254 0.7751175 -0.5606245 -0.2913644 0.7154721 -0.634027 0.2934443 0.2977803 -0.950111 0.09282356 0.2761927 -0.9324489 -0.2329305 -0.3687373 -0.921974 -0.1183081 -0.4030178 -0.8962665 0.1851568 -0.8885878 -0.4513704 0.08171021 -0.8648002 -0.4460001 0.2306614 -0.8702867 0.01632726 -0.492275 -0.7363407 0.2172183 0.6407954 -0.6374564 0.4431647 -0.6302812 -0.6079888 0.691724 0.3897019 -0.2828339 0.9526131 0.1119526 0.5691472 0.8092674 -0.1454576 0.8565569 0.3523845 0.3770085 0.8062141 0.2550816 -0.5338093 0.8388419 -0.1517938 0.522784 0.8439235 -0.2587309 -0.4699484 0.6791524 -0.6550843 0.3310839 0.5891399 -0.6745179 -0.4449044 0.226658 -0.784994 0.5765507 0.04306292 -0.7724374 -0.6336294 -0.2304462 -0.8060302 0.5451697 -0.4502327 -0.6891539 -0.5677654 -0.6136608 -0.5229859 0.5915288 -0.7672889 -0.2694249 -0.5819606 -0.8350713 -0.06004679 0.5468549 -0.8001613 0.2220978 -0.5571487 -0.8434994 0.4272844 0.3254793 -0.6035658 0.7942959 0.06930112 0.1713489 0.9328757 -0.3168319 0.6076529 0.6102876 0.5082392 0.5143974 0.1983093 -0.8343074 0.6369111 -0.1972452 0.7452776 0.7574841 -0.4425773 -0.4799408 0.3998953 -0.7281106 0.5567215 0.4343284 -0.8833584 -0.1761731 -0.1543142 -0.9619762 -0.2253642 -0.2289454 -0.902809 0.3640331 -0.736627 -0.6358444 -0.230397 -0.6872047 -0.6286383 0.3640928 -0.8669061 -0.1804372 -0.4646681 -0.5895997 0.2373828 0.7720243 -0.5285572 0.4842412 -0.6972358 -0.3239018 0.7138397 0.620903 -0.08626103 0.8229049 -0.561593 -0.02056503 0.9836245 -0.1790529 0.4362342 0.797968 0.4158686 0.4719644 0.6549118 -0.5902036 0.671533 0.3707628 0.6415438 0.6654441 0.2102022 -0.7162397 0.6804754 -0.1892938 0.7078992 0.8552014 -0.3370727 -0.3937162 0.5924025 -0.8033316 0.06097376 -0.9631264 -0.07574862 -0.2581661 -0.8046583 0.3252008 0.4967591 -0.5076723 0.3777077 -0.7743421 0.4679006 0.8528428 -0.2317935 0.8331528 0.3768696 0.404754 0.6793051 -0.01021009 -0.733785 0.6393035 -0.3889353 0.6633403 0.5647109 -0.5030102 -0.6542802 0.1956935 -0.713204 0.6730856 0.195488 -0.9639014 -0.1807718 -0.2297489 -0.8938821 -0.3849549 -0.3618848 -0.6611703 0.6571859 -0.546648 -0.5609966 -0.6216582 -0.7530847 -0.3624672 0.549073 -0.851966 -0.08089631 -0.5173103 -0.9998806 -0.003208696 -0.01511877 -0.8115782 0.5702899 0.1269268 -0.7389211 0.5538361 -0.3837465 -0.3675386 0.8225395 0.4339863 -0.2421858 0.8208744 -0.5172149 0.1278625 0.824627 0.5510368 0.4580855 0.8018183 -0.3837253 0.8489508 0.3954034 0.3506265 0.8643184 0.3355932 -0.3746076 0.7892129 -0.1804195 0.5870195 0.3625114 -0.1481465 -0.9201295 0.07114553 -0.7144063 -0.6961049 -0.2184706 -0.5391994 -0.8133478 -0.5456681 -0.7633922 -0.3456569 -0.3514164 -0.2841268 -0.8920642 -0.4944666 -0.102829 -0.8630927 -0.664068 -0.07323664 -0.7440767 -0.4946891 0.1628413 -0.8536776 -0.5923727 0.3707631 -0.7152827 -0.315777 0.479957 -0.8184902 -0.3654507 0.5065153 -0.7809534 -0.1850935 0.6455871 -0.7409168 -0.05976104 0.5658566 -0.8223351 0.0366941 0.6462801 -0.7622176 0.2527148 0.5667842 -0.7841498 0.2557396 0.53512 -0.805136 0.5078396 0.4222573 -0.7508648 0.4258502 0.2500281 -0.8695617 0.6809571 0.08934843 -0.7268523 0.4651176 -0.04162997 -0.8842695 0.5936087 -0.2607201 -0.76135 0.4783663 -0.2752366 -0.8339129 0.373808 -0.5489977 -0.7475755 0.276258 -0.5081766 -0.8157439 0.1345958 -0.6399442 -0.7565419 -0.04386764 -0.5175973 -0.8544991 -0.08976459 -0.5693472 -0.8171818 -0.2654115 -0.5030087 -0.82252 -0.2494578 -0.306711 -0.918531 -0.5656982 -0.3368965 -0.7526528 -0.478142 -0.0556029 -0.8765207 -0.4821538 -0.05773192 -0.8741824 -0.6105581 0.1372342 -0.7799909 -0.4416041 0.2888733 -0.849434 -0.4360441 0.2873853 -0.8528044 -0.2460152 0.4744556 -0.8452032 -0.2460156 0.506429 -0.8264418 -0.01978707 0.6234465 -0.7816157 0.0661273 0.4541956 -0.8884444 0.2683072 0.5696321 -0.7768723 0.3192525 0.3743636 -0.8705917 0.4829914 0.3813129 -0.7882384 0.5995748 0.2047007 -0.7736974 0.5252128 0.08557343 -0.8466575 0.6322101 -0.006020665 -0.7747738 0.5115818 -0.1055084 -0.8527321 0.6042042 -0.3947939 -0.6921525 0.3805124 -0.3992144 -0.8341692 0.3123981 -0.618245 -0.7212356 0.08831524 -0.4868241 -0.869024 -0.03327685 -0.6125318 -0.7897452 -0.1447498 -0.4981117 -0.8549458 -0.2355912 -0.5569399 -0.7964389 -0.4756236 -0.4600664 -0.7497474 -0.4331661 -0.2924199 -0.8525596 -0.5817824 -0.2009316 -0.7881345 -0.5123617 -0.04557919 -0.8575595 -0.5581505 -0.01802527 -0.829544 -0.4557733 0.2748564 -0.8465961 -0.4022583 0.1990248 -0.8936317 -0.4446419 0.5083631 -0.7374691 -0.1394118 0.5130301 -0.8469738 -0.1544944 0.4569808 -0.8759567 0.08438855 0.604162 -0.7923805 0.1236045 0.5184701 -0.8461151 0.2966521 0.5701892 -0.7660821 0.4392877 0.3645589 -0.8210501 0.5334661 0.5755993 -0.6197575 0.5178543 0.1465665 -0.8428198 0.5633991 0.1328271 -0.8154376 0.5776699 -0.09620594 -0.8105812 0.4372361 -0.1542103 -0.8860269 0.5239516 -0.2983574 -0.797783 0.3309969 -0.4979065 -0.8015799 0.2041478 -0.4127755 -0.8876599 0.1064906 -0.6208159 -0.7766901 -0.1176339 -0.5009731 -0.8574312 -0.113487 -0.5300896 -0.840313 -0.3220728 -0.4734259 -0.8198397 -0.3267451 -0.3620018 -0.8730362 -0.5025734 -0.3546089 -0.7884622 -0.4854864 -0.1765076 -0.8562406 -0.6327383 -0.1054608 -0.7671508 -0.5645647 0.2055984 -0.7993724 -0.5208851 0.1601078 -0.8384774 -0.5279908 0.3605813 -0.7688999 -0.3422336 0.3614634 -0.8673064 -0.3180701 0.5623624 -0.7632693 -0.03870832 0.5531536 -0.8321796 -0.002438545 0.6187475 -0.7855862 0.2219818 0.4849237 -0.8459156 0.2241705 0.4300042 -0.8745536 0.4451025 0.4523637 -0.7728202 0.4705463 0.2456429 -0.847494 0.4405577 0.2106767 -0.8726537 0.6079349 0.02623188 -0.7935535 0.4518202 -0.0708599 -0.8892905 0.5821506 -0.2678297 -0.7677031 0.333634 -0.3872789 -0.8594787 0.328141 -0.3596799 -0.8734724 0.2285518 -0.5859504 -0.7774487 0.01723235 -0.4972224 -0.8674521 0.04594665 -0.5678883 -0.8218223 -0.2236347 -0.5179749 -0.825645 -0.2269566 -0.4398234 -0.8689339 -0.4584032 -0.4453294 -0.7691218 -0.4106059 -0.2389149 -0.879956 -0.6517735 -0.1528815 -0.7428449 -0.5544015 0.1139566 -0.8244106 -0.5830945 0.1420277 -0.7998931 -0.4585753 0.3602548 -0.8123578 -0.3776838 0.3353704 -0.8630653 -0.2501658 0.5597738 -0.7899814 -0.1243468 0.4630907 -0.8775449 -0.02059614 0.6150103 -0.78825 0.1907383 0.5448281 -0.8165668 0.1910244 0.5399869 -0.8197097 0.464748 0.4491529 -0.7630668 0.4177505 0.2903211 -0.8609287 0.5532995 0.2367326 -0.7986348 0.5039466 -0.009804546 -0.8636792 0.5879812 0.02292257 -0.8085497 0.6098901 -0.2554545 -0.7501848 0.4313031 -0.2990382 -0.8512073 0.4214881 -0.3823811 -0.8222728 0.2218654 -0.3530572 -0.908915 0.1805034 -0.6152512 -0.7673881 -0.06887185 -0.5093424 -0.8578035 -0.05225634 -0.5996316 -0.7985682 -0.3366174 -0.5062437 -0.7939811 -0.3527275 -0.3777986 -0.8560674 -0.5266788 -0.3882752 -0.7562091 -0.5180267 -0.1029745 -0.8491436 -0.5860571 -0.1429354 -0.7975628 -0.6272692 0.1581575 -0.7625744 -0.5240139 0.2013239 -0.8275736 -0.5448125 0.3910341 -0.7418031 -0.2710205 0.4295983 -0.8613902 -0.2718597 0.5582162 -0.7838923 -0.004336237 0.5842062 -0.8115937 0.02757817 0.4779238 -0.8779684 0.3656415 0.5687599 -0.7367622 0.3595473 0.3881796 -0.8485531 0.5368198 0.3258796 -0.7782204 0.4506464 0.1278159 -0.8835049 0.5607361 0.08613336 -0.8235024 0.594324 -0.1266238 -0.7941949 0.5933338 -0.1269581 -0.7948817 0.525418 -0.3842961 -0.759113 0.3393934 -0.3587806 -0.8695337 0.2824822 -0.5053318 -0.8153796 0.2529402 -0.4973456 -0.8298607 0.1169899 -0.6380993 -0.7610142 -0.06313621 -0.5368955 -0.841283 -0.1466512 -0.6119187 -0.777206 -0.3023929 -0.4234374 -0.8539668 -0.3175379 -0.4726225 -0.8220692 -0.5140994 -0.2227998 -0.8282887 -0.4811056 -0.1921535 -0.8553448 -0.6032564 0.01646929 -0.7973774 -0.4115326 0.1045995 -0.9053729 -0.5451127 0.3508217 -0.7614305 -0.3631743 0.3784116 -0.851416 -0.3465189 0.5103764 -0.7870455 -0.1657609 0.627095 -0.7611013 -0.09608572 0.5749805 -0.8125054 0.0364651 0.6453554 -0.7630116 0.1672285 0.5412855 -0.8240417 0.2490563 0.5784401 -0.7767742 0.3279862 0.3881068 -0.8612771 0.4428063 0.4056168 -0.7996235 0.4895755 0.1549915 -0.8580756 0.5337481 0.1919893 -0.8235613 0.6270158 -0.06253761 -0.7764924 0.5409028 -0.1258942 -0.8316098 0.5785885 -0.3251469 -0.7480073 0.4214683 -0.3573589 -0.8334622 0.3966333 -0.4347569 -0.8084977 0.2482064 -0.4312623 -0.8674137 0.2108218 -0.5559312 -0.804049 0.005843639 -0.4835261 -0.8753105 -0.04918557 -0.5653374 -0.823392 -0.2964739 -0.5056378 -0.8102061 -0.2934702 -0.38348 -0.8756817 -0.5336689 -0.3864434 -0.7522361 -0.4322636 -0.1479834 -0.8895218 -0.6390324 -0.02228081 -0.7688572 -0.4560459 0.114169 -0.8826027 -0.5371228 0.23631 -0.8097264 -0.4244981 0.4094126 -0.8075783 -0.3724024 0.3935993 -0.8404737 -0.2627525 0.6144112 -0.7439489 -0.05496513 0.5115586 -0.8574886 0.02520984 0.6098204 -0.7921387 0.2152845 0.4915287 -0.8438319 0.2353758 0.5049591 -0.8304303 0.4503603 0.3336995 -0.8281428 0.4608157 0.3542767 -0.813718 0.6688327 0.1502878 -0.7280635 0.547494 0.01312291 -0.8367068 0.5972117 -0.1168437 -0.7935274 0.4052985 -0.1841546 -0.8954441 0.4819526 -0.3693872 -0.7945281 0.3201853 -0.4833152 -0.8147932 0.1848118 -0.4136289 -0.8914908 0.126193 -0.582473 -0.8029948 -0.08687025 -0.5481067 -0.831885 -0.105239 -0.4436018 -0.8900238 -0.3560652 -0.4375669 -0.8256832 -0.3446162 -0.3978831 -0.8502522 -0.5272377 -0.2135819 -0.8224374 -0.5128751 -0.1977134 -0.8353853 -0.5747483 -0.01206254 -0.8182414 -0.4948431 0.04006564 -0.8680583 -0.5763316 0.1913427 -0.7944998 -0.3885612 0.2749388 -0.8794481 -0.4239328 0.4584611 -0.7810855 -0.1696259 0.623457 -0.7632355 -0.1993569 0.4496068 -0.8706955 0.001797795 0.5975587 -0.8018233 0.1132686 0.4554393 -0.8830319 0.2417183 0.546496 -0.8018195 0.4022341 0.4336004 -0.806349 0.3560585 0.2789309 -0.8918633 0.561423 0.2441272 -0.7906998 0.5383232 -0.01974987 -0.8425072 0.507731 -0.001804113 -0.8615139 0.584054 -0.2274968 -0.779183 0.4030036 -0.2721314 -0.8738036 0.4263581 -0.4622553 -0.777521 0.2004923 -0.4539077 -0.8681997 0.1796396 -0.5311499 -0.8280154 -0.04864555 -0.5747463 -0.8168846 0.03562128 -0.8158289 -0.5771955 -0.2423415 -0.5007421 -0.8309802 -0.3616915 -0.5414038 -0.758987 -0.5286378 -0.3558349 -0.7706644 -0.4757899 -0.3645658 -0.8004473 -0.5982317 -0.1640977 -0.784341 -0.5905503 -0.1676263 -0.7893997 -0.6605551 0.03742057 -0.7498445 -0.4764471 0.1560726 -0.8652397 -0.5304871 0.2440705 -0.8117963 -0.4511881 0.4286696 -0.7827336 -0.3139506 0.3896879 -0.865782 -0.2522818 0.548232 -0.7973681 -0.08909606 0.4719742 -0.8770988 0.05396986 0.6337545 -0.7716492 0.09470641 0.5593981 -0.823471 0.3453515 0.5591489 -0.7537141 0.3715906 0.3680402 -0.8523303 0.5013202 0.3650348 -0.7844921 0.4717128 0.1199069 -0.8735613 0.5699727 0.08737915 -0.8170043 0.59504 -0.1581012 -0.7879921 0.3680574 -0.2312467 -0.900588 0.4661043 -0.254267 -0.8474049 0.3557448 -0.4680591 -0.8089292 0.2389082 -0.4055165 -0.8823147 0.03490906 -0.6826596 -0.7299023 -0.07325536 -0.518826 -0.8517355 -0.199865 -0.5562142 -0.8066473 -0.4244429 -0.4790576 -0.7683437 -0.2565237 -0.4515011 -0.8546007 -0.4994307 -0.2993201 -0.8130047 -0.5887436 -0.2731195 -0.7607804 -0.6110802 -0.05212652 -0.7898507 -0.5400279 -0.004964888 -0.8416325 -0.5160081 0.2088062 -0.830744 -0.5667183 0.2089353 -0.7969796 -0.3985859 0.5555251 -0.7297405 -0.3944675 0.4986581 -0.771839 -0.142171 0.4835185 -0.8637114 -0.1001635 0.5872784 -0.8031634 0.09388834 0.5015482 -0.8600201 0.2014779 0.5818985 -0.7879092 0.2958945 0.4026597 -0.8662054 0.4725365 0.4303651 -0.7690873 0.4520611 0.2389643 -0.8593816 0.6440156 0.1576961 -0.7485827 0.5771508 -0.05893957 -0.814508 0.6312637 -0.1370455 -0.7633641 0.5006123 -0.2503128 -0.8286923 0.532299 -0.4440795 -0.7207296 0.3324038 -0.4583683 -0.8242611 0.2548216 -0.6260424 -0.7369782 0.1308603 -0.5753623 -0.8073623 0.00696069 -0.6706433 -0.7417473 -0.1644595 -0.4868413 -0.8578687 -0.2956051 -0.5638749 -0.7711438 -0.3516404 -0.3677438 -0.8608796 -0.6103746 -0.3590886 -0.7060441 -0.5502848 -0.101335 -0.8288051 -0.6745775 0.02507776 -0.737778 -0.5505537 0.1090512 -0.8276464 -0.5921766 0.3845256 -0.7081434 -0.3911921 0.3763513 -0.8398383 -0.3200348 0.5019446 -0.8035107 -0.1678876 0.4346511 -0.8848121 -0.06935608 0.62843 -0.7747681 0.0847491 0.4697416 -0.8787267 0.2527838 0.5693554 -0.7822626 0.2989387 0.3636342 -0.8822731 0.4334306 0.3796119 -0.8173328 0.5417762 0.1865046 -0.8195699 0.4916715 0.1446624 -0.8586803 0.5772143 -0.1312428 -0.8059771 0.5342629 -0.09740757 -0.8396875 0.4678058 -0.3913891 -0.792447 0.3895645 -0.3681961 -0.8441986 0.2728891 -0.5221644 -0.8080074 0.1619427 -0.4376696 -0.8844321 -0.08604037 -0.6436657 -0.7604548 -0.125131 -0.4654811 -0.8761677 -0.4116752 -0.5189822 -0.7491202 -0.3726921 -0.264602 -0.8894305 -0.5237314 -0.2489637 -0.8146917 -0.6012008 -0.05030786 -0.7975128 -0.4973443 0.01139128 -0.8674784 -0.5641732 0.1619253 -0.8096226 -0.4444055 0.3700846 -0.8158071 -0.4077987 0.2679099 -0.8728829 -0.2272397 0.4945486 -0.8389183 -0.20244 0.4722905 -0.8578809 -0.01543617 0.6011158 -0.7990129 0.03115224 0.5250109 -0.8505253 0.513641 0.6724521 -0.5328989 0.2052062 0.4674984 -0.8598464 0.5329059 0.3530076 -0.7690234 0.4603499 0.2621386 -0.8481517 0.6822439 0.0270102 -0.7306256 0.5400143 -0.09477591 -0.8363028 0.5871611 -0.2633008 -0.7654507 0.4526212 -0.2668065 -0.8508515 0.4099137 -0.5364872 -0.7376669 0.1716736 -0.4775969 -0.8616435 0.1197233 -0.6107554 -0.7827159 -0.1150102 -0.4695022 -0.8754088 -0.1813446 -0.5371533 -0.82376 -0.4677742 -0.3897771 -0.7932598 -0.4216317 -0.3121308 -0.8513525 -0.569643 -0.1509402 -0.8079133 -0.5659551 -0.1466892 -0.8112811 -0.6401949 0.06374907 -0.7655629 -0.5516705 0.1279659 -0.8241871 -0.5924506 0.3071069 -0.7447735 -0.4314565 0.4176954 -0.7996098 -0.4298326 0.4049209 -0.8070212 -0.2249767 0.4943633 -0.8396371 -0.160113 0.4462255 -0.8804809 -0.0478444 0.6340436 -0.7718158 0.1419008 0.5396338 -0.8298553 0.1423432 0.5362396 -0.8319769 0.4093769 0.4965546 -0.7654045 0.4211202 0.3097377 -0.852479 0.4717746 0.3089006 -0.8258385 0.5684356 0.06385934 -0.8202456 0.6074631 0.08740937 -0.7895241 0.604241 -0.2230661 -0.7649408 0.4708809 -0.2300854 -0.8516642 0.3956809 -0.4057013 -0.8239195 0.3268197 -0.3946438 -0.8587463 0.2103871 -0.7008449 -0.6815819 0.01169943 -0.5080209 -0.8612653 -0.1157986 -0.5653378 -0.8166909 -0.1736655 -0.4397688 -0.8811604 -0.4235721 -0.5121551 -0.7471839 -0.3923962 -0.3270292 -0.859696 -0.667638 -0.2130976 -0.7133365 -0.5468954 -0.06127488 -0.8349557 -0.6814281 0.1949829 -0.7054342 -0.4753746 0.2361438 -0.8474993 -0.4224603 0.4658867 -0.7774811 -0.3239768 0.4219008 -0.8467815 -0.1894932 0.6627864 -0.7244353 0.008101463 0.5499985 -0.8351263 0.09623003 0.5781569 -0.8102311 0.1320672 0.4621431 -0.8769163 0.3505951 0.4845693 -0.8014211 0.3498759 0.4099031 -0.8423576 0.5859873 0.3520728 -0.7298381 0.5345481 0.1009959 -0.8390818 0.5980181 0.05772358 -0.7994012 0.5567663 -0.1249291 -0.8212211 0.5169337 -0.07123053 -0.8530567 0.4679154 -0.3153195 -0.8256081 0.3941296 -0.3020541 -0.8680007 0.3220866 -0.4746281 -0.8191387 0.1364911 -0.3854585 -0.9125745 0.08705103 -0.5281329 -0.844688 -0.1414523 -0.6512387 -0.7455732 -0.1715518 -0.4278458 -0.8874221 -0.3721995 -0.4511698 -0.8111186 -0.3871445 -0.3847658 -0.8378989 -0.6261021 -0.3060027 -0.717188 -0.5519598 -0.1385723 -0.8222763 -0.6546441 0.01187717 -0.7558439 -0.5789902 0.0735929 -0.8120065 -0.620896 0.2884611 -0.7288885 -0.4592543 0.3247363 -0.8268203 -0.3808735 0.5500879 -0.743195 -0.2561326 0.4769365 -0.84079 -0.04861325 0.5895859 -0.8062415 -0.02461439 0.5465195 -0.8370845 0.2013762 0.6259356 -0.753427 0.2906963 0.5114361 -0.8086587 0.3918191 0.5250499 -0.7555133 0.4517088 0.2707545 -0.850089 0.628899 0.2357522 -0.7408826 0.4648228 0.0371589 -0.8846236 0.6076027 -0.08066189 -0.7901346 0.4987124 -0.263643 -0.8256987 0.3570855 -0.2515961 -0.8995496 0.3820714 -0.4826055 -0.7881075 0.1683729 -0.5429253 -0.8227288 0.1970393 -0.5779193 -0.7919501 -0.08721578 -0.6373015 -0.7656633 -0.1604071 -0.4924408 -0.8554366 -0.2647647 -0.5324581 -0.8039827 -0.3434334 -0.3737552 -0.8616035 -0.4720827 -0.3833114 -0.7938579 -0.7485921 -0.1477263 -0.6463644 -0.4954993 -0.2114565 -0.8424765 -0.5908091 0.001528263 -0.80681 -0.661404 -0.04251545 -0.7488238 -0.5560956 0.2876744 -0.7797444 -0.4484682 0.2773506 -0.8496782 -0.3159986 0.5314744 -0.7859262 -0.2511604 0.4809002 -0.8400319 -0.04561316 0.6675089 -0.7432035 0.09341806 0.525331 -0.8457543 0.07536238 0.5126177 -0.8553032 0.3231188 0.4780952 -0.8167124 0.3243428 0.395451 -0.8593139 0.5834982 0.3783103 -0.7186175 0.5240224 0.1834312 -0.8317173 0.6931399 0.01922929 -0.7205466 0.5739509 -0.08148807 -0.8148253 0.610845 -0.2949619 -0.7347556 0.4797657 -0.3206796 -0.8166943 0.4424839 -0.5048258 -0.7411876 0.2118526 -0.495999 -0.842083 0.1678697 -0.6152061 -0.7702866 0.04132848 -0.502682 -0.863483 -0.1268221 -0.4804641 -0.8677964 -0.4079084 -0.7329323 -0.5444456 -0.4257777 -0.4809569 -0.7664163 -0.399059 -0.3994717 -0.8253329 -0.7019183 -0.1490001 -0.6964983 -0.5983256 -0.1814054 -0.7804477 -0.4968104 0.05104428 -0.8663567 -0.5493398 0.09599059 -0.8300672 -0.4588841 0.3517564 -0.8159 -0.3408805 0.3187837 -0.884408 -0.2824667 0.5781642 -0.7654664 -0.08706283 0.468599 -0.8791103 0.04662853 0.6462936 -0.7616629 0.1011227 0.566251 -0.8180062 0.3732044 0.5435401 -0.7518529 0.3628224 0.3990179 -0.8421073 0.4954385 0.3358393 -0.8010947 0.4731885 0.2462416 -0.8458474 0.6376801 0.1543599 -0.7546769 0.56311 -0.08837711 -0.8216428 0.6237 -0.1503462 -0.7670687 0.401156 -0.2910227 -0.8685504 0.4198795 -0.3491421 -0.8377358 0.2085341 -0.4646146 -0.8606083 0.206238 -0.5173166 -0.8305718 -0.0627793 -0.6493457 -0.7578977 -0.1367573 -0.4186913 -0.8977723 -0.38091 -0.5250152 -0.7610958 -0.4220757 -0.2890124 -0.8592578 -0.3978535 -0.2528945 -0.8819054 -0.6728659 -0.08968538 -0.734308 -0.4554416 0.07160943 -0.887381 -0.5708752 0.2202071 -0.7909553 -0.3691805 0.3445949 -0.8631108 -0.3801096 0.4316897 -0.8180225 -0.2402256 0.5456274 -0.802859 -0.2554149 0.4900115 -0.8334579 -0.02293366 0.6546055 -0.7556227 0.05170238 0.5472181 -0.8353917 0.339012 0.5932562 -0.7301493 0.3167737 0.4408584 -0.8398203 0.4772611 0.2525156 -0.8416994 0.4753689 0.2525411 -0.8427618 0.6022447 0.02073013 -0.7980425 0.4965589 -0.03410124 -0.8673329 0.5869024 -0.2670832 -0.7643377 0.2784253 -0.2915731 -0.9151309 0.4663502 -0.3829512 -0.797412 0.1922023 -0.453985 -0.8700321 0.1636381 -0.5679077 -0.806662 -0.07435518 -0.4662753 -0.8815094 -0.134288 -0.5323619 -0.8357976 -0.3287267 -0.5178697 -0.7897783 -0.3229108 -0.3540655 -0.8777052 -0.5328654 -0.3455612 -0.772426 -0.5325765 -0.08039164 -0.8425553 -0.5009273 -0.09309846 -0.8604676 -0.5971345 0.1146974 -0.7938985 -0.4607941 0.1794534 -0.8691751 -0.4966575 0.3712431 -0.7845444 -0.3973209 0.3556982 -0.8459403 -0.2307077 0.6494055 -0.724601 -0.1499876 0.5833153 -0.7982775 0.06245803 0.6359935 -0.7691628 0.1144476 0.5286548 -0.8410862 0.2986351 0.4951515 -0.8158688 0.2947592 0.467282 -0.8335255 0.6758733 0.283798 -0.6801868 0.4859138 0.2912861 -0.824039 0.6610363 0.07140725 -0.7469485 0.5096938 0.198369 -0.837175 0.4975473 -0.1205872 -0.8590143 0.5591339 -0.1808814 -0.8091052 0.486136 -0.4019882 -0.7759365 0.2669732 -0.3658263 -0.8915697 0.2613079 -0.5240143 -0.8106338 3.42e-4 -0.6258795 -0.7799197 -0.06639587 -0.4662701 -0.8821473 -0.2479706 -0.5670329 -0.7854835 -0.3642879 -0.3270041 -0.8719877 -0.3941386 -0.3840361 -0.8349678 -0.5463886 -0.2094694 -0.8109143 -0.5259994 -0.1785416 -0.8315334 -0.6651457 0.01149374 -0.7466251 -0.5175119 0.1833584 -0.8357996 -0.4742193 0.1887251 -0.8599412 -0.4998149 0.4256499 -0.7543258 -0.2897534 0.4194349 -0.8603008 -0.2413544 0.3845929 -0.8909749 -0.1008442 0.5398386 -0.8357063 -0.0472607 0.4997245 -0.8648941 0.07444149 0.5945106 -0.8006345 0.1983622 0.4717703 -0.8591189 0.2792515 0.510673 -0.8131616 0.4203199 0.3618977 -0.8320826 0.3910357 0.2855193 -0.8749685 0.6042836 0.2209479 -0.7655217 0.5053687 -0.0597037 -0.8608356 0.4765994 -0.06519347 -0.8767 0.531174 -0.3728155 -0.7608305 0.3849861 -0.3684127 -0.8462021 0.3403328 -0.5977576 -0.7258509 0.1401543 -0.5438334 -0.8274068 0.001681864 -0.6743203 -0.7384371 -0.08389335 -0.5732737 -0.8150579 -0.2596428 -0.6052181 -0.7525268 -0.3218206 -0.4899153 -0.8101942 -0.4283496 -0.4860936 -0.7617281 -0.487512 -0.3384776 -0.8048385 -0.578288 -0.3165975 -0.751897 -0.5585674 -0.03041088 -0.8289015 -0.542732 -0.04026043 -0.8389405 -0.5585608 0.1647205 -0.8129435 -0.4845141 0.09017956 -0.8701229 -0.5218566 0.3346945 -0.7846307 -0.4100949 0.5786466 -0.7049754 -0.4834942 0.3454575 -0.8042963 -0.2215737 0.5176479 -0.8264054 -0.09968763 0.6483204 -0.7548132 -0.008362352 0.5535639 -0.8327648 0.2812988 0.6060972 -0.7439873 0.2768298 0.4784412 -0.8333423 0.4424265 0.3254947 -0.8356507 0.4442599 0.3286082 -0.8334565 0.5592966 0.08855926 -0.8242236 0.774496 -8.00006e-4 -0.6325784 0.5250811 -0.1786115 -0.8320985 0.4306086 -0.1891773 -0.8824898 0.4801578 -0.4056141 -0.7777697 0.2641174 -0.4750162 -0.8394055 0.1808906 -0.423343 -0.887727 0.1273112 -0.570872 -0.8111086 -0.1113026 -0.6148587 -0.7807437 -0.1911388 -0.3733643 -0.9077804 -0.222124 -0.5359142 -0.8145288 -0.4674053 -0.2934492 -0.8339184 -0.4614807 -0.2863894 -0.8396527 -0.515256 -0.04164981 -0.8560238 -0.5198311 -0.03958016 -0.8533518 -0.5751072 0.2004169 -0.7931486 -0.4251139 0.2439554 -0.8716443 -0.4566709 0.371404 -0.8084002 -0.2669806 0.4666111 -0.8432056 -0.2682626 0.4454624 -0.8541654 -0.08040183 0.6079776 -0.7898727 -0.03366601 0.5422029 -0.8395729 0.230486 0.6296737 -0.7418809 0.2618376 0.4539452 -0.8516895 0.4663758 0.4120681 -0.7827475 0.4153188 0.2472938 -0.8754177 0.573658 0.2061219 -0.792736 0.5699946 0.006393015 -0.8216237 0.4611979 -0.04454034 -0.8861787 0.5487918 -0.2426574 -0.7999657 0.5137951 -0.2603427 -0.8174572 0.4760727 -0.4334517 -0.765163 0.2652227 -0.4284906 -0.8637436 0.2616079 -0.4933628 -0.8295508 0.02335774 -0.5451339 -0.8380235 0.01765656 -0.5610734 -0.8275778 -0.2135856 -0.6293814 -0.7471683 -0.1731255 -0.9144131 -0.3658913 -0.6870391 -0.7005813 -0.1927776 -0.2995475 -0.1966838 -0.9335882 -0.3741664 -0.3975635 0.8378204 -0.5221965 -0.3126593 -0.793445 0.4107615 -0.2489854 -0.8770868 0.3685165 -0.5235792 0.7681539 0.203633 -0.7050118 -0.6793321 0.1338651 0.5871005 0.7983691 0.3363974 0.5261746 -0.7810105 -0.240767 -0.6136291 0.7519912 -0.4130715 -0.5023188 -0.7596367 0.2756746 -0.595145 0.754855 0.03627175 -0.7250946 -0.6876934 -0.3986756 0.2397592 -0.8851969 0.3768956 0.2647146 -0.8876239 0.1291857 -0.3516936 -0.9271585 0.08277738 -0.3232665 0.9426807 0.4392138 0.1789658 -0.8803764 0.2457298 0.4012506 0.8823916 0.2258517 -0.5150139 -0.8268928 0.2068365 0.3937883 -0.895628 -0.09826183 0.4736716 0.8752028 0.2036905 0.4599284 -0.8642778 -0.9450564 0.3115038 0.09916567 0.726736 0.09689015 -0.6800494 0.5571733 0.2411603 -0.7946066 0.695828 0.2304848 -0.6802207 0.07014846 0.05430585 -0.9960573 0.9192391 0.3500664 0.180148 0.8254229 0.4235962 -0.3731533 0.40533 0.3339682 -0.8509836 0.2094253 0.2324745 -0.9497877 0.5810136 0.5794313 -0.5715616 0.6733299 0.6123523 -0.4143086 0.6834986 0.6779466 -0.2705886 0.2324381 0.4227482 -0.8759317 0.3692348 0.6364405 -0.6772069 0.315478 0.8192723 -0.4788181 0.07916593 0.4562697 -0.886313 0.4621931 0.885346 -0.05039882 0.0829426 0.6105757 -0.7876026 0.2192931 0.7976148 -0.5618907 0.3474091 0.8782209 -0.3286866 -0.01154541 0.2274563 -0.9737198 0.01011246 0.9373551 -0.3482285 0.1188781 0.9928986 0.004520237 -0.04705572 0.7711593 -0.6349009 -0.05532377 0.9076257 -0.4161189 -0.179619 0.5184515 -0.8360294 -0.1922419 0.5775005 -0.7934333 -0.2505158 0.35813 -0.8994358 -0.21627 0.9401521 -0.2633277 -0.2592368 0.9540231 -0.1504536 -0.2724068 0.6872826 -0.6733774 -0.4637445 0.7534637 -0.4660833 -0.4669869 0.8302524 -0.3043095 -0.4434815 0.4102752 -0.796868 -0.5760607 0.6346912 -0.5150934 -0.4638443 0.2760322 -0.8418164 -0.6371964 0.7234848 0.2656135 -0.7138469 0.6494851 -0.2619006 -0.6581349 0.2712751 -0.7023307 -0.1090771 0.0173918 -0.9938812 -0.8379876 0.4442218 -0.3169289 -0.7017478 0.1615044 -0.6938779 -0.394662 -0.02783888 -0.9184045 -0.9140815 0.0594322 -0.401152 -0.4582348 -0.06651514 -0.886339 -0.9174056 -0.01808863 -0.3975422 -0.7351338 -0.1385446 -0.6636142 -0.9614929 -0.1004353 -0.2558206 -0.7759655 -0.2685526 -0.5707514 -0.9105176 -0.361707 -0.2003148 -0.9365332 -0.3395478 -0.08725267 -0.4771519 -0.2966598 -0.8272358 -0.6266581 -0.3748802 -0.6832017 -0.2865098 -0.2709972 -0.9189521 -0.7038305 -0.555597 -0.4426451 -0.6621325 -0.6482852 -0.3759081 -0.3453506 -0.5204018 -0.7809705 -0.4071566 -0.6028693 -0.6861284 -0.6659873 -0.7298541 -0.1541883 -0.1205479 -0.4772509 -0.8704596 -0.3313168 -0.8685676 -0.3685372 -0.4477379 -0.8912043 -0.07270348 -0.09235864 -0.571351 -0.8154926 -0.159561 -0.885036 -0.4373233 -0.154465 -0.890174 -0.4286384 0.1021999 -0.5258147 -0.8444373 0.09734392 -0.2932754 -0.9510593 0.03605222 -0.9279417 -0.3709777 0.2267541 -0.7721794 -0.5935668 0.2130767 -0.656892 -0.7232506 0.1994209 -0.9798915 0.006631672 0.3391988 -0.8783067 -0.3369296 0.3029369 -0.3505417 -0.8861996 0.2886615 -0.2494874 -0.9243542 0.4310021 -0.5657112 -0.7029994 0.5891237 -0.801435 -0.1031281 0.6238114 -0.6517894 -0.431312 0.3376128 -0.2533726 -0.9065428 0.7015098 -0.5513837 -0.4515085 0.6208239 -0.3640735 -0.6942825 0.878098 -0.4437597 -0.1789452 0.7543975 -0.2535377 -0.6054776 0.3382459 -0.04691749 -0.9398875 0.8677446 -0.2690564 -0.4178852 0.5185754 -0.04302567 -0.8539487 0.9646579 -0.1065349 -0.2410094 0.9211015 0.01738989 -0.3889343 -9.57674e-4 -0.002677619 -0.999996 -0.004012584 0.01667892 -0.9998529 7.02489e-4 -0.001247107 -0.9999991 0.006825268 0.007832169 -0.9999461 -0.008865952 -0.005986392 -0.9999428 0.01078563 -0.002886772 -0.9999377 0.001952767 -0.01092892 -0.9999384 -0.8631813 0.5000113 0.07004916 -0.8621323 0.5015037 0.07226395 -0.003500223 0.9973421 0.07277703 -0.002282023 0.9974496 0.07133883 0.8633171 0.4996439 0.07099086 0.8627648 0.5004346 0.07212722 0.8647312 -0.4970718 0.07183098 0.8646556 -0.4972335 0.07162147 0.001816272 -0.9974734 0.07101976 0.001841247 -0.9974712 0.07104814 -0.8664898 -0.4977379 0.03811293 -0.8654734 -0.4996936 0.03552663 0.008903682 0.006170272 0.9999414 0.006557822 0.009977638 0.9999288 3.11283e-4 0.01086574 0.999941 0.01110327 0.002338588 0.9999356 0.01133471 -0.001523137 0.9999346 0.008873641 0.004851698 0.9999489 0.009051084 -0.005027949 0.9999465 7.17999e-4 0.01120346 0.9999371 -0.005425095 0.01134568 0.999921 0.00752443 -0.008825778 0.9999328 0.009159445 -0.004973232 0.9999458 -0.00926876 0.007353425 0.99993 -0.009353995 0.005241215 0.9999426 0.003895044 -0.01098936 0.9999321 -0.01183611 0.002769172 0.9999261 3.31067e-5 -0.01029962 0.999947 -0.001410424 -0.01122188 0.9999361 -0.01190626 -0.002971172 0.9999247 -0.008606672 -0.005599915 0.9999474 -0.008102774 -0.008978962 0.9999269 -0.002583682 -0.001843214 0.9999951 0.003229618 0.00293076 0.9999905 -4.20144e-4 -0.001883804 0.9999982 9.02737e-4 -0.001114547 0.9999991 -0.999046 0.03873848 -0.02016186 -0.991052 0.1331686 0.009066045 -0.8740665 0.485795 -0.003315865 -0.8618736 0.5069555 -0.01304483 -0.6487136 0.7608518 0.0165916 -0.4921913 0.8699086 -0.03173011 -0.3336235 0.9424415 0.02234858 0.1251956 0.9920043 -0.01592564 0.07115077 0.9973105 0.01759123 0.4973369 0.8672549 -0.02291727 0.6694509 0.7419708 0.0362603 0.7732076 0.6339752 -0.01501321 0.9702605 0.2420332 0.00383526 0.9717425 0.23594 0.006994187 0.9828388 -0.1844434 -0.002922654 0.9736539 -0.2277247 0.01181823 0.8726701 -0.4880633 -0.01552987 0.7832726 -0.6212264 0.02370339 0.6321583 -0.7746183 -0.01850247 0.4314206 -0.9020016 0.01641702 0.3469067 -0.9378416 -0.01043915 -0.02849984 -0.9994398 0.01754969 -0.1194851 -0.9925433 -0.02410686 -0.5488659 -0.8356428 0.02115321 -0.6421944 -0.7662377 -0.02158999 -0.8217779 -0.5695421 0.01740878 -0.9125228 -0.4083611 -0.02331262 -0.9783286 -0.2060834 0.02007287 3.48934e-4 -4.25619e-4 -0.9999999 4.60239e-4 -2.58961e-4 -1 0.0122565 0.003691375 -0.9999181 2.856e-4 -0.009937286 -0.9999506 0.002187609 -0.005916833 -0.9999801 0.005880951 -0.001104652 -0.9999821 -0.01391953 -0.007532835 -0.9998748 -5.69897e-6 -3.24045e-5 -1 0.005700409 0.001384675 -0.9999829 -0.002779364 0.009035766 -0.9999554 0.00131011 -8.16987e-4 -0.9999989 -1.75246e-4 -1.43664e-4 -1 -8.2608e-4 -9.8697e-4 -0.9999992 -1.09332e-4 -1.86098e-4 -1 2.42756e-4 -1.65593e-4 -1 -0.001271128 -5.67235e-4 -0.9999991 -0.001501619 -0.004642546 -0.9999881 -4.00437e-6 -5.74151e-5 -1 0.03469139 0.02215987 -0.9991524 -0.005170345 2.00503e-4 -0.9999867 -0.03879898 0.01766097 -0.999091 -0.004542708 0.002671062 -0.9999862 -0.00546658 0.00965178 -0.9999386 -0.01569414 -0.001599133 -0.9998756 -0.898414 -0.4379535 0.03239309 -0.9070777 -0.4209147 -0.006403923 -0.5962516 -0.8017411 -0.04117345 -0.5331911 -0.8415216 0.08688342 -0.07305765 -0.9892953 -0.1263231 0.04077261 -0.9938672 0.1027891 0.5486962 -0.8354195 -0.03172856 0.5548996 -0.8305515 -0.04765337 0.8608776 -0.5062152 0.05134224 0.8857371 -0.4631505 -0.03100675 0.9998542 -0.007638394 -0.01528131 0.9998542 0.007638275 0.01528108 0.8651986 0.5003991 0.03212606 0.82546 0.5538741 -0.1088091 0.4326418 0.8952019 0.1069332 0.2675525 0.9493205 -0.1649431 0.002362549 0.9924629 0.1225237 -0.3692592 0.9185969 -0.1408098 -0.4954208 0.8642747 0.0871061 -0.8171074 0.5743813 -0.04921096 -0.8368926 0.5473527 0.003990471 -0.9909173 0.1344144 0.003968715 -0.9916003 0.1291812 -0.006408452 -0.9910895 0.06279647 -0.1174669 -0.9891954 0.1352357 0.05660456 -0.9039248 0.4269109 -0.02582633 -0.8896089 0.4469845 -0.09381312 -0.6843937 0.7138804 0.1482573 -0.5594834 0.8052641 -0.1962856 -0.3835338 0.9110584 0.1512427 -0.1418541 0.9765991 -0.1616528 0.0278446 0.9764444 0.2139653 0.2693117 0.9375253 -0.2202672 0.5296865 0.8314538 0.167681 0.6222801 0.7755652 -0.1061425 0.8251082 0.5490511 0.1331894 0.8864911 0.4486439 -0.1133684 0.9734451 0.2018268 0.1080306 0.9886949 0.1376232 -0.0595172 0.9638651 -0.2656095 0.02039432 0.9548735 -0.2829944 0.09017133 0.7659111 -0.6320973 -0.1176152 0.707216 -0.6999145 0.09982585 0.5196547 -0.8514519 -0.0706312 0.4228803 -0.8974432 0.1255714 0.1688292 -0.9617412 -0.2157557 -0.03170514 -0.9719315 0.2331179 -0.3194169 -0.9250317 -0.2056436 -0.4504873 -0.8788189 0.1572851 -0.7191551 -0.6784683 -0.1499893 -0.7952099 -0.5927806 0.1274853 -0.9279869 -0.3519181 -0.1224506 -0.960408 -0.2474567 0.1279906 -2.93897e-6 0 1 5.25208e-7 0 1 -3.93837e-6 0 1 1.16383e-5 0 1 -1.59488e-6 0 1 3.27904e-6 0 1 -2.12519e-6 0 1 -3.50541e-6 0 1 7.03399e-6 0 1 3.05991e-6 0 1 -4.42337e-6 0 1 5.26133e-6 0 1 2.44906e-6 0 -1 9.09612e-6 0 -1 -2.23899e-6 0 -1 -2.54488e-6 0 -1 3.17338e-6 0 -1 -1.4461e-6 0 -1 2.89238e-6 0 -1 0.6645613 0.7471909 0.00800693 0.5226542 0.852526 -0.005685031 0.1685031 0.9856984 0.00235939 0.1783943 0.9839587 0.001019477 -0.27433 0.9616335 0.002036929 -0.3456627 0.938344 -0.005306363 -0.6202237 0.7844074 0.005276918 -0.7188692 0.6951313 -0.004437506 -0.9134694 0.4068971 0.002923071 -0.9025486 0.4305882 -6.21101e-5 -0.9992833 0.03784537 8.47459e-4 -0.9992489 -0.03827112 -0.006102502 -0.9410755 -0.3381005 0.008064746 -0.8047161 -0.5935828 -0.00956422 -0.6771283 -0.7358255 0.007625937 -0.3666294 -0.9303349 -0.007738351 -0.2106841 -0.9775273 0.007253527 0.1309786 -0.9913648 -0.006354629 0.3203776 -0.9472465 0.009081244 0.5694954 -0.8219306 -0.01025009 0.8073623 -0.5899702 0.0100758 0.9072343 -0.4205775 -0.006374657 0.992393 -0.1229969 0.005275428 0.9999306 0.01023501 -0.005844593 0.9354537 0.3533725 0.007371187 0.852791 0.5221916 -0.007967174 2.57029e-5 0 -1 1.45384e-6 0 -1 -1.63121e-6 0 -1 -2.87316e-6 0 -1 6.67327e-7 0 -1 2.16325e-6 0 -1 1.92273e-6 0 -1 -2.65183e-6 0 -1 -1.64717e-6 0 -1 3.29485e-6 0 -1 -5.58895e-6 0 -1 5.7097e-6 0 -1 3.30568e-6 0 -1 1.14095e-5 0 -1 1.27942e-6 0 -1 -3.80398e-6 0 -1 4.73875e-7 0 -1 2.39089e-6 0 -1 3.84007e-6 0 -1 -1.25858e-6 0 -1 3.88928e-6 0 -1 2.05674e-6 0 -1 -8.97357e-6 0 -1 -1.24374e-7 0 -1 -1.11053e-6 0 -1 1.6547e-6 0 -1 1.4281e-5 0 -1 -2.84628e-6 0 -1 1.15286e-6 0 -1 -8.34604e-7 0 -1 -1.54965e-6 0 -1 2.09338e-6 0 -1 1.69472e-6 0 -1 3.55553e-6 0 -1 -1.38236e-5 0 -1 1.50014e-6 0 -1 -9.38081e-6 0 -1 4.90986e-6 0 -1 -1.36823e-6 0 -1 3.58049e-6 0 -1 5.73315e-6 0 -1 7.70442e-6 0 -1 4.91312e-6 0 -1 1.10456e-6 0 -1 -3.87484e-6 0 -1 -2.14878e-6 0 -1 3.27213e-6 0 -1 -2.08607e-6 0 -1 8.88712e-7 0 -1 -5.0733e-7 0 -1 -1.18664e-6 0 -1 3.15592e-7 0 -1 3.55604e-7 0 -1 1.8673e-6 0 -1 -0.5406896 0.8407644 0.02775371 -0.2961792 0.9548058 -0.02497446 0.09595417 0.995382 -0.002782464 0.02004611 0.9996094 0.0194717 0.5038173 0.8638103 7.39827e-5 0.5321366 0.8465811 0.01145261 0.8515377 0.5239155 -0.01990103 0.9128805 0.4072562 0.02813518 0.997264 -0.06990242 -0.02404427 0.9870747 -0.1600973 0.007242798 0.8342522 -0.5513788 0.002198874 0.8222109 -0.5691516 -0.005992472 0.4577321 -0.8890699 -0.006021678 0.3902156 -0.9205243 0.01915645 0.05083346 -0.9985435 -0.01808249 -0.1146202 -0.9932218 0.01930361 -0.4176676 -0.9084175 -0.01820516 -0.5345348 -0.8449806 0.01674324 -0.8026354 -0.5962038 -0.01781684 -0.8853009 -0.4643965 0.02404338 -0.9822456 -0.1862565 -0.022412 -0.9973399 0.07022953 0.01952362 -0.9699081 0.2428262 -0.01771718 -0.8704864 0.4917474 0.02092808 -0.7205665 0.6929411 -0.02483201 -0.7110899 0.7027221 -0.02308052 -0.5892541 0.8078561 0.01217371 -0.2666159 0.9637219 -0.0124917 -0.1605601 0.9868075 0.02076864 0.2431179 0.9695248 -0.03025889 0.4364227 0.8992607 0.0294215 0.7490087 0.661997 -0.02731126 0.8365792 0.5473477 0.02336913 0.9955626 0.09131634 -0.02273166 0.9990885 -0.03900969 0.01733881 0.9410212 -0.3380837 -0.01336276 0.8902079 -0.4553216 0.01456928 0.6600639 -0.7509825 -0.01847183 0.5981054 -0.8013547 0.01003253 0.1156193 -0.9932314 0.01112157 0.09189766 -0.9957684 -3.57807e-4 -0.343171 -0.9390328 -0.0212391 -0.5171058 -0.8554466 0.02850663 -0.7067036 -0.7072716 -0.01835948 -0.8918889 -0.4517602 0.02114105 -0.9382132 -0.3457576 -0.01441472 -0.9927654 0.1197158 0.009223282 -0.9829362 0.1834051 -0.01410865 -0.8361477 0.5482047 0.01813524 -0.6690378 0.7429863 -0.01896858 -0.6338084 0.7734901 -3.23989e-4 -0.2346827 0.9720082 0.01113641 -0.1030575 0.9942039 -0.03062462 0.2177743 0.9756446 0.026308 0.5172004 0.8556201 -0.02044624 0.5872372 0.809398 0.005230784 0.8933017 0.449357 -0.009508013 0.8951206 0.4457547 -0.007869005 0.99833 0.05400276 0.02051633 0.9895395 -0.1413815 -0.02868795 0.9175707 -0.3969996 0.02134048 0.779067 -0.6265383 -0.02245885 0.6433571 -0.7652345 0.02253967 0.3618464 -0.9319562 -0.02290767 0.1693354 -0.9852507 0.024634 -0.1289159 -0.9912615 -0.02795225 -0.3560247 -0.934055 0.02806925 -0.6705121 -0.7414605 -0.02549523 -0.7616901 -0.6477173 0.01704651 -0.9655942 -0.2595477 -0.01621401 -0.9879679 -0.153804 0.01624566 -0.976099 0.2165259 -0.01863837 -0.9408052 0.3382864 0.02116394 -0.6186581 0.7852328 -0.02592086 -0.3644119 0.9310928 0.0164349 -0.1692758 0.9854316 -0.01644515 0.03776937 0.9990857 0.02003353 0.2508879 0.9678257 -0.01920402 0.567199 0.8234241 0.01606941 0.5384787 0.8426341 0.002915084 0.8767595 0.4809189 -0.00311619 0.8549757 0.5182353 -0.02119022 0.9851905 0.1698144 0.02372556 0.9944776 -0.1028298 -0.02098464 0.9699565 -0.2428409 0.01458561 0.8403677 -0.5416436 -0.02011483 0.7126548 -0.7009307 0.02862215 0.4693025 -0.8825068 -0.03061097 0.1797488 -0.9829428 0.03890872 -0.07832801 -0.9963846 -0.03290253 -0.4762128 -0.8789789 0.02485054 -0.5456068 -0.8380365 -0.002846956 -0.8329216 -0.5533631 -0.005577504 -0.8733611 -0.4868168 0.01580655 -0.9774706 -0.2104812 -0.01577711 -0.9982539 -0.05733102 0.01422995 -0.9640856 0.2650979 -0.0161916 -0.9551429 0.2961055 -0.004872322 -0.7319779 0.6810179 0.02056872 0.6598185 -0.751403 0.005760252 0.4978554 -0.8672544 0.003148198 0.5329236 -0.8461503 -0.004699051 0.3315637 -0.9434329 2.29341e-5 0.3470884 -0.9378272 -0.00314176 0.2034846 -0.979075 0.002512216 0.1720252 -0.9850897 -0.002373635 0.03974205 -0.99921 -1.67325e-4 0.02245908 -0.9997429 0.003147661 -0.1760786 -0.9843683 0.003919184 -0.1350587 -0.9908336 -0.002812922 -0.2888051 -0.95738 -0.003894567 -0.3524293 -0.9358332 0.003144502 -0.473461 -0.8808112 0.002507269 -0.4361736 -0.8998574 -0.003080248 -0.5850814 -0.8109709 -0.002468049 -0.612617 -0.7903774 0.002046883 -0.6937829 -0.7201802 -0.002429783 -0.7120516 -0.702125 0.001748085 -0.8276293 -0.5612751 1.81046e-4 -0.8277563 -0.5610878 1.27238e-4 -0.9089261 -0.4169548 -0.001531541 -0.9224269 -0.3861519 0.003920018 -0.9655668 -0.260106 -0.005062758 -0.9775511 -0.2106732 0.003262162 -0.9972987 -0.07344383 0.00126183 -0.9991596 -0.04070425 -0.004826068 -0.9933469 0.1150458 0.005149185 -0.9876569 0.1565988 -0.003274738 -0.9360876 0.3517614 0.002028465 -0.9378306 0.3470926 7.82758e-4 -0.8413659 0.5404661 1.81047e-4 -0.846158 0.5329287 -0.00194478 -0.729335 0.6841546 0.001748085 -0.7004866 0.7136484 -0.004962801 -0.6321299 0.7748529 0.003852546 -0.5379877 0.8429373 -0.00510019 -0.4804211 0.8770231 0.00510621 -0.352707 0.9357164 -0.005724489 -0.2971174 0.9548285 0.004903197 -0.1020337 0.9947767 0.002921521 -0.1353816 0.9907884 -0.003192901 0.0390551 0.99923 -0.003769218 0.09616702 0.9953529 0.004963159 0.269601 0.9629688 0.002540469 0.2200331 0.9754838 -0.004087746 0.3784569 0.9256163 -0.002241969 0.4001933 0.9164296 0.001493573 0.5404018 0.8414056 -0.001630306 0.5471066 0.837063 -1.757e-4 0.6533186 0.7570821 0.001278102 0.6781865 0.7348783 -0.004125952 0.7831708 0.6217772 0.00606662 0.8210059 0.5708943 -0.005403816 0.897986 0.4400115 0.003320395 0.9073559 0.4203632 -4.24354e-4 0.9598697 0.2804457 -6.38614e-4 0.9601809 0.2793791 -4.24278e-4 0.9902676 0.1391567 0.002336084 0.9964717 0.08370685 -0.006120502 0.9998747 -0.01495057 0.005219817 0.9872868 -0.1589187 -0.003088712 0.9877991 -0.1557161 -0.002345144 0.947233 -0.3205361 0.002526819 0.937046 -0.3491926 -0.003057181 0.8731807 -0.4873892 0.002694785 0.8492863 -0.5279141 -0.004435837 0.7882825 -0.6152952 0.004741787 0.7152046 -0.6988828 -0.006732046 5.07891e-5 0 -1 3.78043e-6 0 -1 -2.96871e-6 0 -1 2.08951e-5 0 -1 2.55353e-6 0 -1 -1.5585e-6 0 -1 -3.2787e-6 0 -1 1.74107e-6 0 -1 -1.97824e-6 0 -1 3.13236e-5 0 -1 1.32399e-5 0 -1 6.16671e-6 0 -1 1.55576e-6 0 -1 -3.25508e-6 0 -1 5.8875e-6 0 -1 -2.46508e-6 0 -1 -6.82556e-6 0 -1 -5.15333e-6 0 -1 -4.03848e-6 0 -1 8.90137e-7 0 -1 0.5529165 -0.8332296 -0.003470599 0.3678787 -0.929853 0.006228625 -0.006157398 -0.9999423 -0.008806049 -0.3211631 -0.9469873 0.00834155 -0.7411255 -0.6713321 -0.006801784 -0.8057669 -0.592231 0.001477658 -0.9955388 0.09433984 -0.00161612 -0.9881847 0.1532172 0.003938794 -0.7017655 0.7123912 -0.004890143 -0.5816312 0.8134346 0.00543332 -0.2106862 0.9775454 -0.004056334 0.03087818 0.9995024 0.006441235 0.320383 0.9472617 -0.00706762 0.7000752 0.7140412 0.006335675 0.8058029 0.5921753 -0.003218412 0.9941164 0.1083166 -3.24865e-4 0.9884153 0.1517468 0.002860546 0.8858229 -0.4640208 -0.001586556 0.8473414 -0.5310357 0.003714442 1.62995e-5 0 1 7.46243e-6 0 1 -1.4387e-5 0 1 4.60155e-6 0 1 -5.39802e-6 0 1 0.563888 -0.8258193 0.007274985 0.04162698 -0.9991129 -0.006371498 -0.08618956 -0.9962748 0.002815425 -0.6276528 -0.7784929 -7.97494e-4 -0.6347181 -0.772742 -0.001640796 -0.9879354 -0.154865 7.46461e-4 -0.9903359 -0.1386885 -6.13312e-4 -0.883109 0.469157 -0.003196656 -0.9058989 0.4234938 5.6143e-4 -0.4824698 0.8758958 0.005432903 -0.3168197 0.9484685 -0.005733609 0.03774303 0.9992791 0.00410521 0.2589765 0.9658724 -0.004664719 0.5744552 0.8185138 0.006043136 0.7637637 0.6454545 -0.007324159 0.961991 0.272988 0.007132232 0.9999321 -0.009250521 -0.007098674 0.9455959 -0.3252847 0.006192982 0.7424756 -0.6698269 -0.007870078 2.06244e-5 0 1 -3.93631e-6 0 1 9.78145e-6 0 1 0.6689832 -0.7432631 0.004657149 0.2420797 -0.9702559 9.58575e-4 0.1635499 -0.9865224 -0.004997134 -0.3064929 -0.9518665 0.003501057 -0.4453097 -0.8953665 -0.004253983 -0.7529994 -0.6580006 0.005236387 -0.8994801 -0.4368936 -0.007725775 -0.9954188 -0.09529155 0.007808923 -0.9435988 0.3309638 -0.009191215 -0.8724702 0.4886595 0.002759099 -0.5233678 0.8520985 0.003805041 -0.3783161 0.925639 -0.008333683 0.1271537 0.9918657 0.005863308 0.3542055 0.9351413 -0.007024168 0.6334502 0.77376 0.006033062 0.8987127 0.4385044 -0.005427658 0.9476658 0.3192501 0.002992331 0.9857101 -0.1684284 -0.002765119 0.9561361 -0.2928977 0.00384593 0.7880532 -0.6155868 -0.005026221 2.19168e-5 0 1 -4.39566e-5 0 1 1.51745e-5 0 1 0.6770553 -0.7359259 -0.003043293 0.7249163 -0.6888362 0.001054406 0.3295166 -0.9441403 0.004264414 0.1207674 -0.9926655 -0.005524992 -0.1937344 -0.9810453 0.004153549 -0.4453066 -0.8953666 -0.004576385 -0.6476801 -0.7618895 0.005927324 -0.8994678 -0.4368934 -0.009059071 -0.9915221 -0.1296169 0.009145081 -0.9618545 0.2734758 -0.006852507 -0.8418965 0.5395967 0.00675249 -0.6525356 0.7577378 -0.005557 -0.2500076 0.9682278 0.005589783 -0.1688987 0.9856331 -8.01688e-4 0.489638 0.8719246 -0.001518249 0.5095638 0.8604328 6.41832e-4 0.9198434 0.3922809 0.00198847 0.9460775 0.3239249 -0.003199815 0.9854236 -0.1700996 0.002564549 0.9720371 -0.2348214 -0.001685321 -1.22796e-5 0 1 -3.78916e-5 0 1 8.0647e-6 0 1 0.2138387 -0.2435172 0.9460298 0.1636911 -0.2485505 0.9546874 0.157121 -0.2737047 0.9488934 0.1100596 -0.3131474 0.9433057 0.06557261 -0.3155441 0.9466426 0.02911943 -0.2971978 0.9543719 0.007120013 -0.3169415 0.9484184 -0.05711203 -0.3193019 0.9459306 -0.09070771 -0.2879463 0.953341 -0.1111366 -0.2951183 0.9489753 -0.1549121 -0.2881907 0.9449595 -0.1934423 -0.2495847 0.9488349 -0.1975156 -0.2343265 0.9518817 -0.2273969 -0.2242171 0.9476379 -0.2612548 -0.1629434 0.9514176 -0.2623335 -0.1779052 0.948436 -0.3024721 -0.1266215 0.9447104 -0.3041192 -0.06535202 0.9503898 -0.3005439 -0.05849486 0.9519726 -0.3207478 -0.02439212 0.9468505 -0.316419 0.03649818 0.9479172 -0.3049564 0.04630094 0.9512403 -0.3038905 0.1147421 0.9457721 -0.2728439 0.1374351 0.9521911 -0.2729135 0.1753109 0.9459304 -0.2313479 0.2170065 0.9483599 -0.1990573 0.2246201 0.9538984 -0.1966221 0.2410261 0.9503927 -0.1604388 0.2928871 0.9425903 -0.07086205 0.2890518 0.9546872 -0.09376978 0.3013451 0.9488933 -0.03306573 0.322386 0.9460306 0.04586434 0.3047961 0.9513127 0.03042173 0.3194763 0.9471059 0.1242477 0.2867546 0.9499129 0.08714133 0.3084027 0.9472562 0.1251162 0.2869692 0.949734 0.1774411 0.2714877 0.9459435 0.2055159 0.2295666 0.9513477 0.2043041 0.2367477 0.9498476 0.2553708 0.202112 0.9454822 0.2662131 0.1481615 0.9524593 0.2851575 0.1407139 0.9480954 0.3141067 0.09087163 0.9450289 0.3092545 0.04433476 0.9499453 0.3012014 0.03195899 0.9530249 0.3219702 -0.005678832 0.9467328 0.3180655 -0.05031913 0.9467325 0.2960778 -0.07763683 0.9520034 0.3029547 -0.1029182 0.9474315 0.2553334 -0.1681271 0.952123 0.2781528 -0.1556739 0.947838 0.2531254 -0.1971184 0.9471388 -7.3956e-6 -1.25221e-6 1 -1.28997e-5 -1.89374e-5 1 -8.49909e-6 4.21094e-6 1 -5.4916e-6 -1.10254e-6 1 -1.40128e-5 -1.84802e-5 1 0 5.31603e-6 1 -3.01931e-5 7.18036e-6 1 4.23064e-6 1.56782e-5 1 0 -5.07824e-6 1 1.58491e-6 5.21888e-5 1 -2.81445e-6 -1.05763e-5 1 -9.75224e-6 1.01767e-5 1 -3.49575e-6 -3.12599e-6 1 -8.13038e-6 0 1 -5.0177e-5 1.70035e-5 1 -7.71933e-6 -3.5894e-6 1 -1.18684e-5 5.51027e-6 1 4.90619e-6 0 1 -3.75526e-5 3.65453e-5 1 6.82664e-6 0 1 1.7609e-5 -1.16983e-5 1 -1.47587e-5 -1.61164e-5 1 -6.9602e-6 0 1 -4.43416e-5 2.01646e-5 1 0 5.49578e-5 1 3.55945e-6 0 1 2.29859e-6 -1.52921e-5 1 4.55416e-6 7.68466e-6 1 4.34005e-5 -1.79718e-5 1 2.39979e-5 5.54731e-6 1 3.26583e-5 -2.80939e-5 1 -2.08793e-6 0 1 -7.89483e-6 0 1 -4.20287e-6 0 1 4.19503e-6 0 1 1.86917e-5 7.56069e-6 1 7.54332e-6 0 1 -5.17508e-6 0 1 4.93784e-5 -8.94251e-6 1 -6.68866e-6 4.03083e-5 1 0 -6.37543e-5 1 4.98138e-6 -5.22229e-6 1 1.39683e-6 1.28844e-6 1 -1.06217e-5 -8.67602e-6 1 2.27806e-5 -7.20041e-6 1 3.56417e-6 1.60511e-5 1 4.91225e-6 -8.44106e-6 1 -2.77936e-6 -4.18511e-6 1 5.69348e-6 8.63863e-6 1 7.693e-6 -2.1607e-6 1 1.03155e-5 1.04815e-5 1 7.00208e-6 4.05541e-6 1 1.02698e-5 1.02867e-6 1 + + + + + + + + + + + + + + +

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

+
+ + + +

1064 2011 1062 2011 1063 2011 1065 2012 1062 2012 1064 2012 1066 2013 1065 2013 1064 2013 1067 2014 1064 2014 1063 2014 1068 2015 1065 2015 1066 2015 1067 2016 1063 2016 1069 2016 1067 2017 1066 2017 1064 2017 1170 2018 1169 2018 1068 2018 1071 2019 1066 2019 1067 2019 1072 2020 1067 2020 1069 2020 1074 2021 1170 2021 1068 2021 1074 2022 1068 2022 1066 2022 1070 2023 1072 2023 1069 2023 1073 2024 1170 2024 1074 2024 1073 2025 1171 2025 1170 2025 1071 2026 1067 2026 1072 2026 1071 2027 1074 2027 1066 2027 1076 2028 1072 2028 1070 2028 1077 2029 1071 2029 1072 2029 1078 2030 1076 2030 1070 2030 1078 2031 1070 2031 1075 2031 1079 2032 1074 2032 1071 2032 1073 2033 1074 2033 1079 2033 1076 2034 1077 2034 1072 2034 1079 2035 1071 2035 1077 2035 1076 2036 1078 2036 1075 2036 1082 2037 1076 2037 1075 2037 1081 2038 1077 2038 1076 2038 1082 2039 1075 2039 1080 2039 1084 2040 1073 2040 1079 2040 1082 2041 1081 2041 1076 2041 1084 2042 1079 2042 1077 2042 1084 2043 1171 2043 1073 2043 1085 2044 1084 2044 1077 2044 1088 2045 1077 2045 1081 2045 1089 2046 1082 2046 1087 2046 1087 2047 1082 2047 1080 2047 1089 2048 1081 2048 1082 2048 1090 2049 1080 2049 1083 2049 1090 2050 1087 2050 1080 2050 1088 2051 1085 2051 1077 2051 1090 2052 1083 2052 1086 2052 1095 2053 1085 2053 1088 2053 1092 2054 1090 2054 1086 2054 1089 2055 1088 2055 1081 2055 1093 2056 1087 2056 1090 2056 1093 2057 1089 2057 1087 2057 1097 2058 1084 2058 1085 2058 1092 2059 1093 2059 1090 2059 1091 2060 1092 2060 1086 2060 1095 2061 1088 2061 1089 2061 1096 2062 1092 2062 1091 2062 1097 2063 1085 2063 1095 2063 1095 2064 1089 2064 1093 2064 1096 2065 1093 2065 1092 2065 1098 2066 1095 2066 1093 2066 1099 2067 1093 2067 1096 2067 1096 2068 1091 2068 1094 2068 1098 2069 1097 2069 1095 2069 1098 2070 1093 2070 1099 2070 1102 2071 1096 2071 1094 2071 1098 2072 1101 2072 1097 2072 1103 2073 1099 2073 1096 2073 1104 2074 1098 2074 1099 2074 1104 2075 1099 2075 1103 2075 1105 2076 1096 2076 1102 2076 1102 2077 1094 2077 1100 2077 1103 2078 1096 2078 1105 2078 1101 2079 1098 2079 1104 2079 1106 2080 1102 2080 1100 2080 1106 2081 1100 2081 1107 2081 1109 2082 1101 2082 1104 2082 1109 2083 1104 2083 1108 2083 1108 2084 1104 2084 1103 2084 1106 2085 1105 2085 1102 2085 1108 2086 1103 2086 1105 2086 1112 2087 1106 2087 1107 2087 1110 2088 1113 2088 1107 2088 1112 2089 1107 2089 1113 2089 1111 2090 1105 2090 1106 2090 1112 2091 1111 2091 1106 2091 1114 2092 1108 2092 1105 2092 1109 2093 1108 2093 1114 2093 1114 2094 1105 2094 1111 2094 1116 2095 1111 2095 1112 2095 1117 2096 1112 2096 1113 2096 1115 2097 1101 2097 1109 2097 1115 2098 1109 2098 1114 2098 1116 2099 1112 2099 1117 2099 1118 2100 1113 2100 1110 2100 1119 2101 1114 2101 1111 2101 1116 2102 1119 2102 1111 2102 1118 2103 1117 2103 1113 2103 1118 2104 1110 2104 1120 2104 1119 2105 1115 2105 1114 2105 1121 2106 1116 2106 1117 2106 1124 2107 1115 2107 1119 2107 1119 2108 1116 2108 1121 2108 1125 2109 1121 2109 1117 2109 1125 2110 1117 2110 1118 2110 1120 2111 1122 2111 1123 2111 1124 2112 1119 2112 1121 2112 1125 2113 1118 2113 1120 2113 1127 2114 1120 2114 1123 2114 1123 2115 1122 2115 1126 2115 1132 2116 1115 2116 1124 2116 1125 2117 1120 2117 1127 2117 1121 2118 1125 2118 1128 2118 1128 2119 1125 2119 1127 2119 1130 2120 1123 2120 1126 2120 1132 2121 1124 2121 1121 2121 1130 2122 1127 2122 1123 2122 1133 2123 1128 2123 1127 2123 1133 2124 1127 2124 1130 2124 1128 2125 1132 2125 1121 2125 1134 2126 1126 2126 1129 2126 1134 2127 1130 2127 1126 2127 1134 2128 1135 2128 1130 2128 1135 2129 1133 2129 1130 2129 1134 2130 1129 2130 1131 2130 1138 2131 1131 2131 1136 2131 1139 2132 1132 2132 1128 2132 1142 2133 1134 2133 1131 2133 1140 2134 1133 2134 1135 2134 1139 2135 1128 2135 1133 2135 1135 2136 1134 2136 1141 2136 1142 2137 1141 2137 1134 2137 1142 2138 1131 2138 1138 2138 1137 2139 1132 2139 1139 2139 1139 2140 1133 2140 1140 2140 1138 2141 1136 2141 1143 2141 1140 2142 1135 2142 1141 2142 1138 2143 1141 2143 1142 2143 1145 2144 1139 2144 1140 2144 1146 2145 1138 2145 1143 2145 1147 2146 1140 2146 1141 2146 1146 2147 1143 2147 1144 2147 1147 2148 1145 2148 1140 2148 1137 2149 1139 2149 1145 2149 1148 2150 1138 2150 1146 2150 1148 2151 1141 2151 1138 2151 1150 2152 1141 2152 1148 2152 1150 2153 1147 2153 1141 2153 1151 2154 1137 2154 1145 2154 1152 2155 1145 2155 1147 2155 1151 2156 1145 2156 1152 2156 1148 2157 1146 2157 1144 2157 1152 2158 1147 2158 1150 2158 1154 2159 1148 2159 1144 2159 1149 2160 1154 2160 1144 2160 1155 2161 1148 2161 1154 2161 1150 2162 1148 2162 1155 2162 1158 2163 1152 2163 1150 2163 1157 2164 1154 2164 1149 2164 1157 2165 1149 2165 1153 2165 1157 2166 1153 2166 1159 2166 1155 2167 1158 2167 1150 2167 1161 2168 1154 2168 1157 2168 1161 2169 1155 2169 1154 2169 1156 2170 1159 2170 1153 2170 1162 2171 1151 2171 1152 2171 1162 2172 1152 2172 1158 2172 1158 2173 1155 2173 1161 2173 1163 2174 1156 2174 1160 2174 1163 2175 1159 2175 1156 2175 1164 2176 1158 2176 1161 2176 1161 2177 1157 2177 1159 2177 1162 2178 1158 2178 1164 2178 1165 2179 1163 2179 1160 2179 1166 2180 1161 2180 1159 2180 1166 2181 1164 2181 1161 2181 1166 2182 1159 2182 1163 2182 1065 2183 1163 2183 1165 2183 1167 2184 1164 2184 1166 2184 1168 2185 1162 2185 1164 2185 1062 2186 1065 2186 1165 2186 1169 2187 1166 2187 1163 2187 1065 2188 1169 2188 1163 2188 1168 2189 1164 2189 1167 2189 1065 2190 1068 2190 1169 2190 1169 2191 1167 2191 1166 2191 1170 2192 1168 2192 1167 2192 1170 2193 1167 2193 1169 2193 1170 2194 1171 2194 1168 2194 1062 2195 1184 2195 1063 2195 1184 2196 1172 2196 1063 2196 1063 2197 1172 2197 1069 2197 1069 2198 1172 2198 1070 2198 1172 2199 1173 2199 1070 2199 1070 2200 1173 2200 1075 2200 1075 2201 1174 2201 1080 2201 1173 2202 1174 2202 1075 2202 1080 2203 1174 2203 1083 2203 1083 2204 1174 2204 1086 2204 1174 2205 1175 2205 1086 2205 1086 2206 1175 2206 1091 2206 1091 2207 1175 2207 1094 2207 1175 2208 1176 2208 1094 2208 1094 2209 1176 2209 1100 2209 1176 2210 1177 2210 1100 2210 1100 2211 1177 2211 1107 2211 1107 2212 1177 2212 1110 2212 1177 2213 1178 2213 1110 2213 1110 2214 1178 2214 1120 2214 1178 2215 1179 2215 1120 2215 1120 2216 1179 2216 1122 2216 1122 2217 1179 2217 1126 2217 1179 2218 1180 2218 1126 2218 1126 2219 1180 2219 1129 2219 1129 2220 1180 2220 1131 2220 1180 2221 1181 2221 1131 2221 1131 2222 1181 2222 1136 2222 1136 2223 1181 2223 1143 2223 1181 2224 1182 2224 1143 2224 1143 2225 1182 2225 1144 2225 1144 2226 1182 2226 1149 2226 1149 2227 1183 2227 1153 2227 1182 2228 1183 2228 1149 2228 1153 2229 1183 2229 1156 2229 1156 2230 1183 2230 1160 2230 1183 2231 1184 2231 1160 2231 1160 2232 1184 2232 1165 2232 1165 2233 1184 2233 1062 2233 1084 2234 1186 2234 1185 2234 1171 2235 1084 2235 1185 2235 1171 2236 1185 2236 1187 2236 1097 2237 1186 2237 1084 2237 1097 2238 1188 2238 1186 2238 1171 2239 1187 2239 1189 2239 1097 2240 1190 2240 1188 2240 1171 2241 1189 2241 1191 2241 1101 2242 1190 2242 1097 2242 1168 2243 1171 2243 1191 2243 1101 2244 1192 2244 1190 2244 1168 2245 1191 2245 1193 2245 1194 2246 1192 2246 1101 2246 1162 2247 1168 2247 1193 2247 1194 2248 1101 2248 1115 2248 1195 2249 1162 2249 1193 2249 1195 2250 1151 2250 1162 2250 1196 2251 1151 2251 1195 2251 1197 2252 1194 2252 1115 2252 1197 2253 1115 2253 1132 2253 1196 2254 1137 2254 1151 2254 1198 2255 1137 2255 1196 2255 1199 2256 1197 2256 1132 2256 1200 2257 1137 2257 1198 2257 1201 2258 1199 2258 1132 2258 1201 2259 1132 2259 1137 2259 1201 2260 1137 2260 1200 2260 1204 2261 1203 2261 1202 2261 1205 2262 1202 2262 1203 2262 1204 2263 1206 2263 1203 2263 1207 2264 1205 2264 1203 2264 1208 2265 1206 2265 1204 2265 1207 2266 1203 2266 1209 2266 1208 2267 1228 2267 1206 2267 1210 2268 1207 2268 1209 2268 1213 2269 1212 2269 1211 2269 1213 2270 1214 2270 1212 2270 1215 2271 1211 2271 1212 2271 1216 2272 1214 2272 1213 2272 1215 2273 1212 2273 1217 2273 1218 2274 1215 2274 1217 2274 1216 2275 1219 2275 1214 2275 1220 2276 1219 2276 1216 2276 1221 2277 1210 2277 1209 2277 1224 2278 1210 2278 1221 2278 1220 2279 1222 2279 1219 2279 1223 2280 1222 2280 1220 2280 1222 2281 1223 2281 1225 2281 1226 2282 1222 2282 1225 2282 1227 2283 1217 2283 1228 2283 1229 2284 1227 2284 1228 2284 1227 2285 1218 2285 1217 2285 1229 2286 1228 2286 1208 2286 1230 2287 1224 2287 1221 2287 1229 2288 1208 2288 1231 2288 1227 2289 1233 2289 1218 2289 1232 674 1229 674 1231 674 1234 2290 1233 2290 1227 2290 1234 2291 1236 2291 1233 2291 1232 2292 1231 2292 1235 2292 1230 2293 1244 2293 1224 2293 1237 674 1232 674 1235 674 1237 674 1235 674 1238 674 1239 2294 1240 2294 1236 2294 1239 674 1236 674 1234 674 1241 2295 1237 2295 1238 2295 1242 2296 1243 2296 1240 2296 1242 674 1240 674 1239 674 1241 674 1238 674 1244 674 1245 2297 1225 2297 1246 2297 1245 2298 1226 2298 1225 2298 1247 2299 1241 2299 1244 2299 1242 2300 1246 2300 1243 2300 1248 2301 1246 2301 1242 2301 1247 2302 1230 2302 1249 2302 1247 2303 1244 2303 1230 2303 1248 2304 1245 2304 1246 2304 1250 2305 1245 2305 1248 2305 1251 2306 1253 2306 1252 2306 1254 674 1251 674 1252 674 1255 674 1253 674 1251 674 1254 2307 1252 2307 1247 2307 1254 2308 1247 2308 1249 2308 1256 2309 1254 2309 1249 2309 1256 2310 1249 2310 1257 2310 1255 2311 1258 2311 1253 2311 1259 2312 1258 2312 1255 2312 1262 2313 1261 2313 1263 2313 1262 674 1260 674 1261 674 1264 2314 1256 2314 1257 2314 1264 2315 1275 2315 1256 2315 1260 674 1248 674 1261 674 1260 2316 1250 2316 1248 2316 1265 2317 1250 2317 1260 2317 1265 2318 1266 2318 1250 2318 1267 2319 1262 2319 1263 2319 1259 674 1268 674 1258 674 1269 674 1268 674 1259 674 1267 674 1263 674 1270 674 1271 674 1267 674 1270 674 1272 2320 1266 2320 1265 2320 1269 2321 1274 2321 1268 2321 1293 2322 1274 2322 1269 2322 1271 674 1270 674 1273 674 1290 674 1271 674 1273 674 1290 2323 1273 2323 1274 2323 1276 2324 1272 2324 1277 2324 1276 2325 1266 2325 1272 2325 1278 2326 1275 2326 1264 2326 1276 2327 1277 2327 1279 2327 1278 2328 1282 2328 1275 2328 1280 2329 1279 2329 1281 2329 1280 2330 1276 2330 1279 2330 1283 2331 1284 2331 1282 2331 1283 2332 1282 2332 1278 2332 1280 2333 1281 2333 1285 2333 1283 2334 1288 2334 1284 2334 1286 2335 1280 2335 1285 2335 1286 2336 1285 2336 1287 2336 1289 2337 1288 2337 1283 2337 1289 2338 1293 2338 1288 2338 1286 2339 1287 2339 1290 2339 1291 2340 1293 2340 1289 2340 1292 2341 1286 2341 1290 2341 1292 2342 1290 2342 1274 2342 1291 2343 1274 2343 1293 2343 1291 2344 1292 2344 1274 2344 1294 2345 1283 2345 1278 2345 1295 2346 1294 2346 1278 2346 1295 2347 1278 2347 1264 2347 1264 2348 1296 2348 1295 2348 1297 2349 1264 2349 1257 2349 1297 2350 1296 2350 1264 2350 1298 2351 1257 2351 1249 2351 1298 2352 1297 2352 1257 2352 1299 2353 1298 2353 1249 2353 1300 2354 1249 2354 1230 2354 1300 2355 1299 2355 1249 2355 1230 2356 1301 2356 1300 2356 1221 2357 1302 2357 1301 2357 1221 2358 1301 2358 1230 2358 1302 2359 1221 2359 1209 2359 1303 2360 1302 2360 1209 2360 1209 2361 1304 2361 1303 2361 1304 2362 1209 2362 1203 2362 1305 2363 1304 2363 1203 2363 1206 2364 1306 2364 1305 2364 1206 2365 1305 2365 1203 2365 1307 2366 1306 2366 1206 2366 1308 2367 1307 2367 1206 2367 1308 2368 1206 2368 1228 2368 1309 2369 1228 2369 1217 2369 1309 2370 1308 2370 1228 2370 1217 2371 1310 2371 1309 2371 1310 2372 1217 2372 1212 2372 1311 2373 1310 2373 1212 2373 1312 2374 1311 2374 1212 2374 1312 2375 1212 2375 1214 2375 1313 2376 1312 2376 1214 2376 1313 2377 1214 2377 1219 2377 1314 2378 1313 2378 1219 2378 1222 2379 1315 2379 1314 2379 1222 2380 1314 2380 1219 2380 1315 2381 1222 2381 1226 2381 1226 2382 1316 2382 1315 2382 1316 2383 1226 2383 1245 2383 1245 2384 1317 2384 1316 2384 1317 2385 1245 2385 1250 2385 1318 2386 1317 2386 1250 2386 1319 2387 1250 2387 1266 2387 1319 2388 1318 2388 1250 2388 1320 2389 1319 2389 1266 2389 1320 2390 1266 2390 1276 2390 1321 2391 1320 2391 1276 2391 1321 2392 1276 2392 1280 2392 1322 2393 1321 2393 1280 2393 1322 2394 1280 2394 1286 2394 1323 2395 1322 2395 1286 2395 1286 2396 1324 2396 1323 2396 1324 2397 1286 2397 1292 2397 1325 2398 1292 2398 1291 2398 1325 2399 1324 2399 1292 2399 1291 2400 1326 2400 1325 2400 1326 2401 1291 2401 1289 2401 1289 2402 1327 2402 1326 2402 1327 2403 1289 2403 1283 2403 1283 2404 1328 2404 1327 2404 1328 2405 1283 2405 1294 2405 1328 2406 1294 2406 1329 2406 1328 2407 1329 2407 1330 2407 1327 2408 1328 2408 1330 2408 1327 2409 1330 2409 1331 2409 1326 2410 1327 2410 1331 2410 1326 2411 1331 2411 1332 2411 1326 2412 1332 2412 1333 2412 1325 2413 1326 2413 1333 2413 1325 2414 1333 2414 1334 2414 1324 2415 1325 2415 1334 2415 1324 2416 1334 2416 1335 2416 1323 2417 1324 2417 1335 2417 1323 2418 1335 2418 1336 2418 1322 2419 1323 2419 1336 2419 1322 2420 1336 2420 1337 2420 1321 2421 1322 2421 1337 2421 1321 2422 1337 2422 1338 2422 1320 2423 1321 2423 1338 2423 1320 2424 1338 2424 1339 2424 1319 2425 1320 2425 1339 2425 1319 2426 1339 2426 1340 2426 1318 2427 1319 2427 1340 2427 1317 2428 1340 2428 1341 2428 1317 2429 1318 2429 1340 2429 1316 2430 1317 2430 1341 2430 1316 2431 1341 2431 1342 2431 1315 2432 1316 2432 1342 2432 1315 2433 1342 2433 1343 2433 1314 2434 1315 2434 1343 2434 1314 2435 1343 2435 1344 2435 1313 2436 1314 2436 1344 2436 1313 2437 1344 2437 1345 2437 1312 2438 1313 2438 1345 2438 1312 2439 1345 2439 1346 2439 1311 2440 1312 2440 1346 2440 1311 2441 1346 2441 1347 2441 1310 2442 1311 2442 1347 2442 1310 2443 1347 2443 1348 2443 1309 2444 1310 2444 1348 2444 1308 2445 1309 2445 1348 2445 1308 2446 1348 2446 1349 2446 1307 2447 1308 2447 1349 2447 1307 2448 1349 2448 1350 2448 1306 2449 1307 2449 1350 2449 1305 2450 1306 2450 1350 2450 1305 2451 1350 2451 1351 2451 1304 2452 1305 2452 1351 2452 1304 2453 1351 2453 1352 2453 1303 2454 1304 2454 1352 2454 1303 2455 1352 2455 1353 2455 1302 2456 1303 2456 1353 2456 1302 2457 1353 2457 1354 2457 1301 2458 1302 2458 1354 2458 1300 2459 1354 2459 1355 2459 1300 2460 1301 2460 1354 2460 1299 2461 1355 2461 1356 2461 1299 2462 1300 2462 1355 2462 1298 2463 1299 2463 1356 2463 1298 2464 1356 2464 1357 2464 1297 2465 1298 2465 1357 2465 1297 2466 1357 2466 1358 2466 1296 2467 1297 2467 1358 2467 1295 2468 1296 2468 1358 2468 1295 2469 1358 2469 1359 2469 1294 2470 1295 2470 1359 2470 1294 2471 1359 2471 1329 2471 1361 2472 1362 2472 1360 2472 1363 674 1361 674 1360 674 1360 2473 1362 2473 1364 2473 1363 674 1365 674 1361 674 1366 674 1365 674 1363 674 1362 2474 1367 2474 1364 2474 1364 674 1367 674 1368 674 1366 674 1369 674 1365 674 1370 2475 1369 2475 1366 2475 1367 674 1371 674 1368 674 1368 674 1371 674 1372 674 1370 674 1373 674 1369 674 1372 2476 1374 2476 1375 2476 1371 674 1374 674 1372 674 1376 2477 1373 2477 1370 2477 1374 2478 1377 2478 1375 2478 1376 2479 1378 2479 1373 2479 1378 674 1379 674 1373 674 1374 2480 1380 2480 1377 2480 1378 674 1381 674 1379 674 1380 2481 1382 2481 1377 2481 1379 2482 1381 2482 1383 2482 1381 674 1384 674 1383 674 1385 674 1386 674 1380 674 1380 674 1386 674 1382 674 1384 674 1387 674 1383 674 1385 674 1388 674 1386 674 1389 674 1388 674 1385 674 1383 674 1387 674 1390 674 1391 674 1388 674 1389 674 1390 674 1387 674 1392 674 1387 674 1393 674 1392 674 1391 674 1394 674 1388 674 1395 2483 1394 2483 1391 2483 1393 2484 1396 2484 1392 2484 1395 2485 1396 2485 1394 2485 1392 674 1396 674 1395 674 1270 2486 1394 2486 1273 2486 1388 2487 1394 2487 1270 2487 1273 2488 1394 2488 1274 2488 1394 2489 1396 2489 1274 2489 1274 2490 1393 2490 1268 2490 1396 2491 1393 2491 1274 2491 1268 2492 1393 2492 1258 2492 1393 2493 1387 2493 1258 2493 1258 2494 1387 2494 1253 2494 1387 2495 1384 2495 1253 2495 1253 2496 1384 2496 1252 2496 1384 2497 1381 2497 1252 2497 1381 2498 1378 2498 1252 2498 1252 2499 1378 2499 1247 2499 1378 2500 1376 2500 1247 2500 1247 2501 1376 2501 1241 2501 1376 2502 1370 2502 1241 2502 1241 2503 1370 2503 1237 2503 1370 2504 1366 2504 1237 2504 1237 2505 1366 2505 1232 2505 1366 2506 1363 2506 1232 2506 1232 2507 1363 2507 1229 2507 1363 2508 1360 2508 1229 2508 1229 2509 1360 2509 1227 2509 1360 2510 1364 2510 1227 2510 1227 2511 1364 2511 1234 2511 1364 2512 1368 2512 1234 2512 1234 2513 1368 2513 1239 2513 1368 2514 1372 2514 1239 2514 1239 2515 1372 2515 1242 2515 1372 2516 1375 2516 1242 2516 1242 2517 1375 2517 1248 2517 1375 2518 1377 2518 1248 2518 1377 2519 1382 2519 1248 2519 1248 2520 1382 2520 1261 2520 1261 2521 1382 2521 1263 2521 1382 2522 1386 2522 1263 2522 1263 2523 1388 2523 1270 2523 1386 2524 1388 2524 1263 2524 1196 2525 1383 2525 1390 2525 1198 2526 1196 2526 1390 2526 1198 2527 1390 2527 1392 2527 1200 2528 1198 2528 1392 2528 1200 2529 1392 2529 1395 2529 1201 2530 1200 2530 1395 2530 1201 2531 1395 2531 1391 2531 1199 2532 1201 2532 1391 2532 1199 2533 1391 2533 1389 2533 1197 2534 1199 2534 1389 2534 1197 2535 1389 2535 1385 2535 1197 2536 1385 2536 1380 2536 1194 2537 1197 2537 1380 2537 1194 2538 1380 2538 1374 2538 1192 2539 1194 2539 1374 2539 1192 2540 1374 2540 1371 2540 1190 2541 1192 2541 1371 2541 1188 2542 1190 2542 1371 2542 1188 2543 1371 2543 1367 2543 1186 2544 1188 2544 1367 2544 1186 2545 1367 2545 1362 2545 1185 2546 1186 2546 1362 2546 1185 2547 1362 2547 1361 2547 1187 2548 1185 2548 1361 2548 1187 2549 1361 2549 1365 2549 1189 2550 1187 2550 1365 2550 1189 2551 1365 2551 1369 2551 1191 2552 1189 2552 1369 2552 1191 2553 1369 2553 1373 2553 1193 2554 1191 2554 1373 2554 1193 2555 1373 2555 1379 2555 1195 2556 1193 2556 1379 2556 1195 2557 1379 2557 1383 2557 1196 2558 1195 2558 1383 2558 1409 2559 1204 2559 1397 2559 1397 2560 1204 2560 1398 2560 1204 2561 1202 2561 1398 2561 1398 2562 1202 2562 1399 2562 1202 2563 1205 2563 1399 2563 1399 2564 1205 2564 1400 2564 1205 2565 1207 2565 1400 2565 1400 2566 1207 2566 1401 2566 1207 2567 1210 2567 1401 2567 1401 2568 1210 2568 1402 2568 1210 2569 1224 2569 1402 2569 1402 2570 1224 2570 1403 2570 1403 2571 1224 2571 1404 2571 1224 2572 1244 2572 1404 2572 1404 2573 1244 2573 1405 2573 1244 2574 1238 2574 1405 2574 1405 2575 1238 2575 1406 2575 1238 2576 1235 2576 1406 2576 1406 2577 1235 2577 1407 2577 1235 2578 1231 2578 1407 2578 1407 2579 1231 2579 1408 2579 1231 2580 1208 2580 1408 2580 1408 2581 1208 2581 1409 2581 1208 2582 1204 2582 1409 2582 1410 2583 1255 2583 1411 2583 1255 2584 1251 2584 1411 2584 1411 2585 1251 2585 1412 2585 1251 2586 1254 2586 1412 2586 1412 2587 1254 2587 1413 2587 1254 2588 1256 2588 1413 2588 1413 2589 1256 2589 1414 2589 1256 2590 1275 2590 1414 2590 1414 2591 1275 2591 1415 2591 1275 2592 1282 2592 1415 2592 1415 2593 1282 2593 1416 2593 1282 2594 1284 2594 1416 2594 1416 2595 1284 2595 1417 2595 1284 2596 1288 2596 1417 2596 1417 2597 1288 2597 1418 2597 1418 2598 1288 2598 1419 2598 1288 2599 1293 2599 1419 2599 1419 2600 1293 2600 1420 2600 1293 2601 1269 2601 1420 2601 1420 2602 1269 2602 1421 2602 1269 2603 1259 2603 1421 2603 1421 2604 1259 2604 1422 2604 1259 2605 1255 2605 1422 2605 1422 2606 1255 2606 1410 2606 1434 2607 1216 2607 1423 2607 1216 2608 1213 2608 1423 2608 1423 2609 1213 2609 1424 2609 1213 2610 1211 2610 1424 2610 1424 2611 1211 2611 1425 2611 1211 2612 1215 2612 1425 2612 1425 2613 1215 2613 1426 2613 1215 2614 1218 2614 1426 2614 1426 2615 1218 2615 1427 2615 1218 2616 1233 2616 1427 2616 1427 2617 1233 2617 1428 2617 1233 2618 1236 2618 1428 2618 1428 2619 1236 2619 1429 2619 1236 2620 1240 2620 1429 2620 1429 2621 1240 2621 1430 2621 1240 2622 1243 2622 1430 2622 1430 2623 1243 2623 1431 2623 1243 2624 1246 2624 1431 2624 1246 2625 1225 2625 1431 2625 1431 2626 1225 2626 1432 2626 1432 2627 1223 2627 1433 2627 1225 2628 1223 2628 1432 2628 1223 2629 1220 2629 1433 2629 1433 2630 1220 2630 1434 2630 1220 2631 1216 2631 1434 2631 1435 2632 1265 2632 1436 2632 1265 2633 1260 2633 1436 2633 1260 2634 1262 2634 1436 2634 1436 2635 1262 2635 1437 2635 1262 2636 1267 2636 1437 2636 1437 2637 1267 2637 1438 2637 1267 2638 1271 2638 1438 2638 1438 2639 1271 2639 1439 2639 1271 2640 1290 2640 1439 2640 1439 2641 1290 2641 1440 2641 1440 2642 1287 2642 1441 2642 1290 2643 1287 2643 1440 2643 1441 2644 1287 2644 1442 2644 1287 2645 1285 2645 1442 2645 1442 2646 1285 2646 1443 2646 1285 2647 1281 2647 1443 2647 1443 2648 1281 2648 1444 2648 1281 2649 1279 2649 1444 2649 1444 2650 1279 2650 1445 2650 1445 2651 1277 2651 1446 2651 1279 2652 1277 2652 1445 2652 1277 2653 1272 2653 1446 2653 1446 2654 1272 2654 1447 2654 1272 2655 1265 2655 1447 2655 1447 2656 1265 2656 1435 2656 1338 2657 1446 2657 1339 2657 1338 1310 1445 1310 1446 1310 1446 1310 1447 1310 1339 1310 1337 1310 1445 1310 1338 1310 1337 1310 1444 1310 1445 1310 1447 1310 1435 1310 1339 1310 1339 1310 1435 1310 1340 1310 1435 2658 1436 2658 1340 2658 1336 2659 1444 2659 1337 2659 1336 2660 1443 2660 1444 2660 1433 2661 1434 2661 1343 2661 1343 1310 1434 1310 1344 1310 1342 2662 1433 2662 1343 2662 1342 2663 1432 2663 1433 2663 1341 2664 1432 2664 1342 2664 1434 1310 1423 1310 1344 1310 1336 2665 1442 2665 1443 2665 1341 2666 1431 2666 1432 2666 1344 2667 1423 2667 1345 2667 1436 2668 1431 2668 1340 2668 1340 2669 1431 2669 1341 2669 1423 2670 1424 2670 1345 2670 1345 2671 1424 2671 1346 2671 1442 2672 1336 2672 1441 2672 1424 1310 1425 1310 1346 1310 1425 1310 1347 1310 1346 1310 1336 1310 1335 1310 1441 1310 1441 1310 1335 1310 1440 1310 1426 1310 1347 1310 1425 1310 1335 1310 1334 1310 1440 1310 1426 1310 1348 1310 1347 1310 1431 1310 1176 1310 1430 1310 1436 1310 1176 1310 1431 1310 1436 1310 1177 1310 1176 1310 1437 1310 1177 1310 1436 1310 1176 2673 1175 2673 1430 2673 1430 2674 1175 2674 1429 2674 1437 1310 1178 1310 1177 1310 1175 2675 1174 2675 1429 2675 1438 1310 1178 1310 1437 1310 1429 1310 1174 1310 1428 1310 1439 1310 1179 1310 1438 1310 1438 1310 1179 1310 1178 1310 1174 1310 1173 1310 1428 1310 1428 1310 1173 1310 1427 1310 1173 1310 1172 1310 1427 1310 1439 1310 1421 1310 1179 1310 1179 2676 1421 2676 1180 2676 1440 1310 1421 1310 1439 1310 1421 2677 1422 2677 1180 2677 1440 2678 1420 2678 1421 2678 1180 1310 1422 1310 1181 1310 1333 2679 1420 2679 1334 2679 1334 1310 1420 1310 1440 1310 1332 2680 1420 2680 1333 2680 1332 2681 1419 2681 1420 2681 1422 1310 1410 1310 1181 1310 1181 1310 1410 1310 1182 1310 1331 2682 1419 2682 1332 2682 1331 2683 1418 2683 1419 2683 1410 2684 1411 2684 1182 2684 1172 2685 1407 2685 1427 2685 1407 1310 1408 1310 1427 1310 1427 2686 1408 2686 1426 2686 1182 2687 1411 2687 1183 2687 1426 1310 1408 1310 1348 1310 1348 1310 1408 1310 1349 1310 1408 2688 1409 2688 1349 2688 1184 2689 1407 2689 1172 2689 1184 1310 1406 1310 1407 1310 1411 1310 1412 1310 1183 1310 1349 2690 1409 2690 1350 2690 1409 2691 1397 2691 1350 2691 1184 1310 1405 1310 1406 1310 1183 1310 1405 1310 1184 1310 1331 2692 1330 2692 1418 2692 1412 2693 1405 2693 1183 2693 1398 1310 1350 1310 1397 1310 1412 2694 1404 2694 1405 2694 1418 1310 1330 1310 1417 1310 1398 1310 1351 1310 1350 1310 1399 1310 1351 1310 1398 1310 1330 1310 1329 1310 1417 1310 1417 2695 1329 2695 1416 2695 1400 2696 1352 2696 1399 2696 1399 1310 1352 1310 1351 1310 1416 2697 1359 2697 1415 2697 1329 1310 1359 1310 1416 1310 1401 2698 1352 2698 1400 2698 1415 2699 1359 2699 1414 2699 1402 1310 1353 1310 1401 1310 1401 1310 1353 1310 1352 1310 1359 1310 1358 1310 1414 1310 1403 2700 1354 2700 1402 2700 1402 2701 1354 2701 1353 2701 1414 1310 1358 1310 1413 1310 1358 1310 1357 1310 1413 1310 1404 1310 1354 1310 1403 1310 1404 1310 1355 1310 1354 1310 1357 1310 1356 1310 1413 1310 1412 1310 1355 1310 1404 1310 1412 2702 1356 2702 1355 2702 1413 1310 1356 1310 1412 1310

+
+ + + +

1448 2703 1449 2703 1450 2703 1449 2704 1451 2704 1450 2704 1449 2705 1453 2705 1451 2705 1452 2706 1453 2706 1449 2706 1454 2707 1455 2707 1452 2707 1452 2708 1455 2708 1453 2708 1454 2709 1456 2709 1455 2709 1456 2710 1457 2710 1455 2710 1458 2711 1459 2711 1456 2711 1456 2712 1459 2712 1457 2712 1458 2713 1448 2713 1459 2713 1448 2714 1450 2714 1459 2714 1457 2715 1461 2715 1460 2715 1457 2716 1459 2716 1461 2716 1459 2717 1450 2717 1461 2717 1461 2718 1450 2718 1465 2718 1450 2719 1451 2719 1465 2719 1465 2720 1451 2720 1464 2720 1449 2721 1454 2721 1452 2721 1456 2722 1454 2722 1458 2722 1458 2723 1454 2723 1448 2723 1448 2724 1454 2724 1449 2724 1463 2725 2332 2725 1466 2725 1463 2726 2329 2726 2332 2726 1464 2727 1466 2727 2337 2727 1464 2728 1463 2728 1466 2728 1464 2729 2337 2729 2341 2729 1462 2730 2375 2730 2329 2730 1462 2731 2373 2731 2375 2731 1462 2732 2329 2732 1463 2732 2369 2733 2373 2733 1462 2733 1465 2734 1464 2734 2341 2734 1465 2735 2346 2735 2349 2735 1465 2736 2341 2736 2346 2736 2352 2737 1465 2737 2349 2737 1460 2738 2369 2738 1462 2738 2366 2739 2369 2739 1460 2739 2364 2740 2366 2740 1460 2740 2352 2741 1461 2741 1465 2741 2355 2742 1461 2742 2352 2742 2364 2743 1460 2743 1461 2743 2358 2744 1461 2744 2355 2744 2362 2745 2364 2745 1461 2745 2362 2746 1461 2746 2358 2746 1468 2747 1467 2747 2227 2747 1468 2748 2227 2748 1469 2748 1467 2749 1470 2749 2227 2749 1468 2750 1469 2750 1471 2750 1467 2751 1473 2751 1470 2751 1472 2752 1473 2752 1467 2752 1474 2753 1468 2753 1471 2753 1474 2754 1471 2754 1475 2754 1472 2755 2217 2755 1473 2755 1476 2756 2217 2756 1472 2756 1477 2757 1474 2757 1475 2757 1476 2758 2215 2758 2217 2758 2211 2759 2215 2759 1476 2759 1478 2760 2211 2760 1476 2760 2208 2761 2211 2761 1478 2761 2208 2762 1478 2762 1480 2762 2204 2763 2208 2763 1480 2763 2203 2764 2204 2764 1480 2764 2203 2765 1480 2765 1481 2765 1487 2766 1484 2766 1483 2766 1487 2767 1485 2767 1484 2767 1489 2768 1485 2768 1487 2768 1489 2769 1488 2769 1485 2769 1486 2770 1488 2770 1489 2770 1486 2771 1490 2771 1488 2771 1491 2772 1490 2772 1486 2772 1491 2773 1492 2773 1490 2773 1493 2774 1492 2774 1491 2774 1493 2775 1494 2775 1492 2775 1495 2776 1494 2776 1493 2776 1495 2777 1496 2777 1494 2777 1495 2778 1497 2778 1496 2778 1498 2779 1497 2779 1495 2779 1498 2780 1499 2780 1497 2780 1498 2781 1500 2781 1499 2781 1501 2782 1500 2782 1498 2782 1501 2783 1502 2783 1500 2783 1503 2784 1502 2784 1501 2784 1503 2785 1504 2785 1502 2785 1503 2786 1505 2786 1504 2786 1506 2787 1505 2787 1503 2787 1506 2788 1507 2788 1505 2788 1508 2789 1507 2789 1506 2789 1508 2790 1509 2790 1507 2790 1510 2791 1509 2791 1508 2791 1510 2792 1511 2792 1509 2792 1510 2793 1512 2793 1511 2793 1513 2794 1512 2794 1510 2794 1513 2795 1514 2795 1512 2795 1515 2796 1514 2796 1513 2796 1515 2797 1516 2797 1514 2797 1517 2798 1516 2798 1515 2798 1517 2799 1518 2799 1516 2799 1519 2800 1518 2800 1517 2800 1519 2801 1520 2801 1518 2801 1521 2802 1520 2802 1519 2802 1521 2803 1522 2803 1520 2803 1521 2804 1523 2804 1522 2804 1524 2805 1523 2805 1521 2805 1524 2806 1525 2806 1523 2806 1524 2807 1526 2807 1525 2807 1527 2808 1526 2808 1524 2808 1527 2809 1528 2809 1526 2809 1529 2810 1528 2810 1527 2810 1529 2811 1530 2811 1528 2811 1531 2812 1530 2812 1529 2812 1531 2813 1532 2813 1530 2813 1531 2814 1533 2814 1532 2814 1534 2815 1533 2815 1531 2815 1535 2816 1533 2816 1534 2816 1535 2817 1536 2817 1533 2817 1537 2818 1536 2818 1535 2818 1537 2819 1538 2819 1536 2819 1537 2820 1539 2820 1538 2820 1540 2821 1539 2821 1537 2821 1540 2822 1541 2822 1539 2822 1542 2823 1541 2823 1540 2823 1542 2824 1543 2824 1541 2824 1544 2825 1543 2825 1542 2825 1544 2826 1545 2826 1543 2826 1544 2827 1546 2827 1545 2827 1547 2828 1546 2828 1544 2828 1547 2829 1548 2829 1546 2829 1549 2830 1548 2830 1547 2830 1549 2831 1550 2831 1548 2831 1551 2832 1550 2832 1549 2832 1551 2833 1552 2833 1550 2833 1551 2834 1553 2834 1552 2834 1554 2835 1553 2835 1551 2835 1554 2836 1555 2836 1553 2836 1556 2837 1555 2837 1554 2837 1556 2838 1557 2838 1555 2838 1558 2839 1557 2839 1556 2839 1558 2840 1559 2840 1557 2840 1558 2841 1560 2841 1559 2841 1561 2842 1560 2842 1558 2842 1561 2843 1562 2843 1560 2843 1563 2844 1562 2844 1561 2844 1563 2845 1564 2845 1562 2845 1565 2846 1564 2846 1563 2846 1565 2847 1566 2847 1564 2847 1567 2848 1566 2848 1565 2848 1567 2849 1568 2849 1566 2849 1567 2850 1569 2850 1568 2850 1570 2851 1569 2851 1567 2851 1570 2852 1571 2852 1569 2852 1572 2853 1571 2853 1570 2853 1572 2854 1573 2854 1571 2854 1572 2855 1574 2855 1573 2855 1575 2856 1574 2856 1572 2856 1575 2857 1576 2857 1574 2857 1577 2858 1576 2858 1575 2858 1577 2859 1578 2859 1576 2859 1577 2860 1579 2860 1578 2860 1580 2861 1579 2861 1577 2861 1580 2862 1581 2862 1579 2862 1580 2863 1582 2863 1581 2863 1583 2864 1582 2864 1580 2864 1583 2865 1584 2865 1582 2865 1585 2866 1584 2866 1583 2866 1585 2867 1586 2867 1584 2867 1587 2868 1586 2868 1585 2868 1587 2869 1588 2869 1586 2869 1589 2870 1588 2870 1587 2870 1591 2871 1590 2871 1589 2871 1589 2872 1590 2872 1588 2872 1591 2873 1592 2873 1590 2873 1593 2874 1592 2874 1591 2874 1593 2875 1594 2875 1592 2875 1595 2876 1594 2876 1593 2876 1595 2877 1596 2877 1594 2877 1595 2878 1597 2878 1596 2878 1598 2879 1597 2879 1595 2879 1598 2880 1599 2880 1597 2880 1600 2881 1599 2881 1598 2881 1600 2882 1601 2882 1599 2882 1600 2883 1602 2883 1601 2883 1603 2884 1602 2884 1600 2884 1603 2885 1604 2885 1602 2885 1605 2886 1604 2886 1603 2886 1605 2887 1606 2887 1604 2887 1605 2888 1607 2888 1606 2888 1608 2889 1607 2889 1605 2889 1608 2890 1609 2890 1607 2890 1610 2891 1609 2891 1608 2891 1610 2892 1611 2892 1609 2892 1612 2893 1611 2893 1610 2893 1612 2894 1613 2894 1611 2894 1612 2895 1614 2895 1613 2895 1615 2896 1614 2896 1612 2896 1615 2897 1616 2897 1614 2897 1617 2898 1616 2898 1615 2898 1617 2899 1618 2899 1616 2899 1617 2900 1619 2900 1618 2900 1620 2901 1619 2901 1617 2901 1620 2902 1621 2902 1619 2902 1622 2903 1621 2903 1620 2903 1622 2904 1623 2904 1621 2904 1624 2905 1623 2905 1622 2905 1624 2906 1625 2906 1623 2906 1626 2907 1627 2907 1624 2907 1624 2908 1627 2908 1625 2908 1628 2909 1629 2909 1626 2909 1626 2910 1629 2910 1627 2910 1628 2911 1630 2911 1629 2911 1631 2912 1630 2912 1628 2912 1631 2913 1632 2913 1630 2913 1631 2914 1633 2914 1632 2914 1634 2915 1633 2915 1631 2915 1634 2916 1635 2916 1633 2916 1636 2917 1635 2917 1634 2917 1636 2918 1637 2918 1635 2918 1638 2919 1637 2919 1636 2919 1638 2920 1639 2920 1637 2920 1638 2921 1640 2921 1639 2921 1641 2922 1640 2922 1638 2922 1641 2923 1642 2923 1640 2923 1643 2924 1642 2924 1641 2924 1643 2925 1644 2925 1642 2925 1645 2926 1644 2926 1643 2926 1645 2927 1646 2927 1644 2927 1645 2928 1647 2928 1646 2928 1648 2929 1647 2929 1645 2929 1648 2930 1649 2930 1647 2930 1650 2931 1649 2931 1648 2931 1650 2932 1651 2932 1649 2932 1652 2933 1653 2933 1650 2933 1650 2934 1653 2934 1651 2934 1654 2935 1653 2935 1652 2935 1654 2936 1655 2936 1653 2936 1656 2937 1655 2937 1654 2937 1656 2938 1657 2938 1655 2938 1658 2939 1657 2939 1656 2939 1658 2940 1659 2940 1657 2940 1658 2941 1660 2941 1659 2941 1661 2942 1660 2942 1658 2942 1661 2943 1662 2943 1660 2943 1663 2944 1662 2944 1661 2944 1663 2945 1664 2945 1662 2945 1665 2946 1664 2946 1663 2946 1665 2947 1666 2947 1664 2947 1667 2948 1666 2948 1665 2948 1667 2949 1668 2949 1666 2949 1669 2950 1668 2950 1667 2950 1669 2951 1670 2951 1668 2951 1669 2952 1671 2952 1670 2952 1672 2953 1671 2953 1669 2953 1672 2954 1673 2954 1671 2954 1674 2955 1673 2955 1672 2955 1674 2956 1675 2956 1673 2956 1676 2957 1675 2957 1674 2957 1676 2958 1677 2958 1675 2958 1678 2959 1677 2959 1676 2959 1678 2960 1679 2960 1677 2960 1680 2961 1679 2961 1678 2961 1680 2962 1681 2962 1679 2962 1680 2963 1682 2963 1681 2963 1683 2964 1682 2964 1680 2964 1683 2965 1684 2965 1682 2965 1685 2966 1684 2966 1683 2966 1685 2967 1686 2967 1684 2967 1687 2968 1686 2968 1685 2968 1687 2969 1688 2969 1686 2969 1689 2970 1688 2970 1687 2970 1689 2971 1690 2971 1688 2971 1689 2972 1691 2972 1690 2972 1692 2973 1691 2973 1689 2973 1692 2974 1693 2974 1691 2974 1694 2975 1693 2975 1692 2975 1694 2976 1695 2976 1693 2976 1696 2977 1695 2977 1694 2977 1696 2978 1697 2978 1695 2978 1696 2979 1698 2979 1697 2979 1699 2980 1698 2980 1696 2980 1699 2981 1700 2981 1698 2981 1701 2982 1700 2982 1699 2982 1701 2983 1702 2983 1700 2983 1703 2984 1702 2984 1701 2984 1703 2985 1704 2985 1702 2985 1703 2986 1705 2986 1704 2986 1706 2987 1705 2987 1703 2987 1706 2988 1707 2988 1705 2988 1706 2989 1708 2989 1707 2989 1709 2990 1708 2990 1706 2990 1709 2991 1710 2991 1708 2991 1711 2992 1710 2992 1709 2992 1711 2993 1712 2993 1710 2993 1713 2994 1712 2994 1711 2994 1713 2995 1714 2995 1712 2995 1715 2996 1714 2996 1713 2996 1715 2997 1716 2997 1714 2997 1717 2998 1716 2998 1715 2998 1717 2999 1718 2999 1716 2999 1719 3000 1718 3000 1717 3000 1719 3001 1720 3001 1718 3001 1719 3002 1721 3002 1720 3002 1722 3003 1721 3003 1719 3003 1722 3004 1723 3004 1721 3004 1724 3005 1723 3005 1722 3005 1724 3006 1725 3006 1723 3006 1726 3007 1725 3007 1724 3007 1726 3008 1727 3008 1725 3008 1726 3009 1728 3009 1727 3009 1729 3010 1728 3010 1726 3010 1729 3011 1730 3011 1728 3011 1729 3012 1731 3012 1730 3012 1732 3013 1731 3013 1729 3013 1732 3014 1733 3014 1731 3014 1734 3015 1733 3015 1732 3015 1734 3016 1735 3016 1733 3016 1736 3017 1735 3017 1734 3017 1736 3018 1737 3018 1735 3018 1736 3019 1738 3019 1737 3019 1739 3020 1738 3020 1736 3020 1739 3021 1740 3021 1738 3021 1741 3022 1740 3022 1739 3022 1741 3023 1742 3023 1740 3023 1743 3024 1742 3024 1741 3024 1743 3025 1744 3025 1742 3025 1745 3026 1744 3026 1743 3026 1745 3027 1746 3027 1744 3027 1747 3028 1746 3028 1745 3028 1747 3029 1748 3029 1746 3029 1747 3030 1749 3030 1748 3030 1750 3031 1749 3031 1747 3031 1750 3032 1751 3032 1749 3032 1752 3033 1751 3033 1750 3033 1752 3034 1753 3034 1751 3034 1754 3035 1753 3035 1752 3035 1754 3036 1755 3036 1753 3036 1756 3037 1755 3037 1754 3037 1756 3038 1757 3038 1755 3038 1758 3039 1757 3039 1756 3039 1758 3040 1759 3040 1757 3040 1760 3041 1759 3041 1758 3041 1760 3042 1761 3042 1759 3042 1763 3043 1762 3043 1760 3043 1760 3044 1762 3044 1761 3044 1763 3045 1764 3045 1762 3045 1765 3046 1764 3046 1763 3046 1765 3047 1766 3047 1764 3047 1765 3048 1767 3048 1766 3048 1768 3049 1767 3049 1765 3049 1768 3050 1769 3050 1767 3050 1770 3051 1769 3051 1768 3051 1770 3052 1771 3052 1769 3052 1772 3053 1771 3053 1770 3053 1772 3054 1773 3054 1771 3054 1772 3055 1774 3055 1773 3055 1775 3056 1774 3056 1772 3056 1775 3057 1776 3057 1774 3057 1777 3058 1776 3058 1775 3058 1777 3059 1778 3059 1776 3059 1779 3060 1778 3060 1777 3060 1779 3061 1780 3061 1778 3061 1781 3062 1780 3062 1779 3062 1781 3063 1782 3063 1780 3063 1783 3064 1782 3064 1781 3064 1783 3065 1784 3065 1782 3065 1785 3066 1784 3066 1783 3066 1785 3067 1786 3067 1784 3067 1787 3068 1786 3068 1785 3068 1787 3069 1788 3069 1786 3069 1789 3070 1788 3070 1787 3070 1789 3071 1790 3071 1788 3071 1789 3072 1791 3072 1790 3072 1792 3073 1791 3073 1789 3073 1792 3074 1793 3074 1791 3074 1794 3075 1793 3075 1792 3075 1794 3076 1795 3076 1793 3076 1796 3077 1795 3077 1794 3077 1796 3078 1797 3078 1795 3078 1798 3079 1797 3079 1796 3079 1798 3080 1799 3080 1797 3080 1800 3081 1799 3081 1798 3081 1800 3082 1801 3082 1799 3082 1802 3083 1801 3083 1800 3083 1802 3084 1803 3084 1801 3084 1802 3085 1804 3085 1803 3085 1805 3086 1804 3086 1802 3086 1805 3087 1806 3087 1804 3087 1807 3088 1806 3088 1805 3088 1807 3089 1808 3089 1806 3089 1809 3090 1808 3090 1807 3090 1809 3091 1810 3091 1808 3091 1811 3092 1810 3092 1809 3092 1811 3093 1812 3093 1810 3093 1813 3094 1812 3094 1811 3094 1813 3095 1814 3095 1812 3095 1813 3096 1815 3096 1814 3096 1816 3097 1815 3097 1813 3097 1816 3098 1817 3098 1815 3098 1818 3099 1817 3099 1816 3099 1818 3100 1819 3100 1817 3100 1820 3101 1819 3101 1818 3101 1820 3102 1821 3102 1819 3102 1822 3103 1821 3103 1820 3103 1822 3104 1823 3104 1821 3104 1824 3105 1823 3105 1822 3105 1824 3106 1825 3106 1823 3106 1826 3107 1825 3107 1824 3107 1826 3108 1827 3108 1825 3108 1826 3109 1828 3109 1827 3109 1829 3110 1828 3110 1826 3110 1829 3111 1830 3111 1828 3111 1829 3112 1831 3112 1830 3112 1832 3113 1831 3113 1829 3113 1832 3114 1833 3114 1831 3114 1834 3115 1833 3115 1832 3115 1834 3116 1835 3116 1833 3116 1836 3117 1835 3117 1834 3117 1836 3118 1837 3118 1835 3118 1838 3119 1837 3119 1836 3119 1838 3120 1839 3120 1837 3120 1838 3121 1840 3121 1839 3121 1841 3122 1840 3122 1838 3122 1841 3123 1842 3123 1840 3123 1843 3124 1842 3124 1841 3124 1843 3125 1844 3125 1842 3125 1843 3126 1845 3126 1844 3126 1846 3127 1845 3127 1843 3127 1846 3128 1847 3128 1845 3128 1848 3129 1847 3129 1846 3129 1848 3130 1849 3130 1847 3130 1848 3131 1850 3131 1849 3131 1851 3132 1850 3132 1848 3132 1851 3133 1852 3133 1850 3133 1853 3134 1852 3134 1851 3134 1853 3135 1854 3135 1852 3135 1855 3136 1854 3136 1853 3136 1855 3137 1856 3137 1854 3137 1857 3138 1856 3138 1855 3138 1857 3139 1858 3139 1856 3139 1857 3140 1859 3140 1858 3140 1860 3141 1859 3141 1857 3141 1860 3142 1861 3142 1859 3142 1862 3143 1861 3143 1860 3143 1862 3144 1863 3144 1861 3144 1864 3145 1863 3145 1862 3145 1864 3146 1865 3146 1863 3146 1866 3147 1865 3147 1864 3147 1866 3148 1867 3148 1865 3148 1866 3149 1868 3149 1867 3149 1869 3150 1868 3150 1866 3150 1869 3151 1870 3151 1868 3151 1871 3152 1870 3152 1869 3152 1871 3153 1872 3153 1870 3153 1873 3154 1872 3154 1871 3154 1873 3155 1874 3155 1872 3155 1875 3156 1874 3156 1873 3156 1875 3157 1876 3157 1874 3157 1877 3158 1876 3158 1875 3158 1877 3159 1878 3159 1876 3159 1879 3160 1878 3160 1877 3160 1879 3161 1880 3161 1878 3161 1881 3162 1880 3162 1879 3162 1881 3163 1882 3163 1880 3163 1883 3164 1882 3164 1881 3164 1883 3165 1884 3165 1882 3165 1885 3166 1884 3166 1883 3166 1885 3167 1886 3167 1884 3167 1887 3168 1886 3168 1885 3168 1887 3169 1888 3169 1886 3169 1889 3170 1888 3170 1887 3170 1889 3171 1890 3171 1888 3171 1889 3172 1891 3172 1890 3172 1892 3173 1891 3173 1889 3173 1892 3174 1893 3174 1891 3174 1892 3175 1894 3175 1893 3175 1895 3176 1894 3176 1892 3176 1895 3177 1896 3177 1894 3177 1895 3178 1897 3178 1896 3178 1898 3179 1897 3179 1895 3179 1898 3180 1899 3180 1897 3180 1898 3181 1900 3181 1899 3181 1901 3182 1900 3182 1898 3182 1901 3183 1902 3183 1900 3183 1903 3184 1902 3184 1901 3184 1903 3185 1904 3185 1902 3185 1903 3186 1905 3186 1904 3186 1906 3187 1905 3187 1903 3187 1906 3188 1907 3188 1905 3188 1906 3189 1908 3189 1907 3189 1909 3190 1908 3190 1906 3190 1909 3191 1910 3191 1908 3191 1911 3192 1910 3192 1909 3192 1911 3193 1912 3193 1910 3193 1913 3194 1912 3194 1911 3194 1913 3195 1914 3195 1912 3195 1915 3196 1914 3196 1913 3196 1915 3197 1916 3197 1914 3197 1915 3198 1917 3198 1916 3198 1918 3199 1917 3199 1915 3199 1918 3200 1919 3200 1917 3200 1920 3201 1919 3201 1918 3201 1920 3202 1921 3202 1919 3202 1922 3203 1921 3203 1920 3203 1922 3204 1923 3204 1921 3204 1922 3205 1924 3205 1923 3205 1925 3206 1924 3206 1922 3206 1925 3207 1926 3207 1924 3207 1927 3208 1926 3208 1925 3208 1927 3209 1928 3209 1926 3209 1927 3210 1929 3210 1928 3210 1930 3211 1929 3211 1927 3211 1930 3212 1931 3212 1929 3212 1932 3213 1931 3213 1930 3213 1932 3214 1933 3214 1931 3214 1932 3215 1934 3215 1933 3215 1935 3216 1934 3216 1932 3216 1935 3217 1936 3217 1934 3217 1937 3218 1936 3218 1935 3218 1937 3219 1938 3219 1936 3219 1937 3220 1939 3220 1938 3220 1940 3221 1939 3221 1937 3221 1940 3222 1941 3222 1939 3222 1942 3223 1941 3223 1940 3223 1942 3224 1943 3224 1941 3224 1944 3225 1943 3225 1942 3225 1944 3226 1945 3226 1943 3226 1946 3227 1945 3227 1944 3227 1946 3228 1947 3228 1945 3228 1946 3229 1948 3229 1947 3229 1949 3230 1948 3230 1946 3230 1949 3231 1950 3231 1948 3231 1951 3232 1950 3232 1949 3232 1951 3233 1952 3233 1950 3233 1951 3234 1953 3234 1952 3234 1954 3235 1953 3235 1951 3235 1954 3236 1955 3236 1953 3236 1956 3237 1955 3237 1954 3237 1956 3238 1957 3238 1955 3238 1958 3239 1957 3239 1956 3239 1958 3240 1959 3240 1957 3240 1960 3241 1959 3241 1958 3241 1960 3242 1961 3242 1959 3242 1962 3243 1961 3243 1960 3243 1962 3244 1963 3244 1961 3244 1964 3245 1963 3245 1962 3245 1964 3246 1965 3246 1963 3246 1964 3247 1966 3247 1965 3247 1967 3248 1966 3248 1964 3248 1967 3249 1968 3249 1966 3249 1969 3250 1968 3250 1967 3250 1969 3251 2241 3251 1968 3251 1969 3252 1479 3252 2241 3252 1970 3253 1479 3253 1969 3253 1970 3254 1477 3254 1479 3254 1971 3255 1477 3255 1970 3255 1971 3256 1474 3256 1477 3256 1972 3257 1474 3257 1971 3257 1972 3258 1468 3258 1474 3258 1495 3259 1493 3259 1973 3259 1974 3260 1495 3260 1973 3260 1498 3261 1495 3261 1974 3261 1975 3262 1498 3262 1974 3262 1501 3263 1498 3263 1975 3263 1503 3264 1501 3264 1975 3264 1976 3265 1503 3265 1975 3265 1977 3266 1503 3266 1976 3266 1506 3267 1503 3267 1977 3267 1508 3268 1506 3268 1977 3268 1978 3269 1508 3269 1977 3269 1510 3270 1508 3270 1978 3270 1979 3271 1510 3271 1978 3271 1980 3272 1510 3272 1979 3272 1513 3273 1510 3273 1980 3273 1515 3274 1513 3274 1980 3274 1981 3275 1515 3275 1980 3275 1517 3276 1515 3276 1981 3276 1982 3277 1517 3277 1981 3277 1519 3278 1517 3278 1982 3278 1521 3279 1519 3279 1982 3279 1983 3280 1521 3280 1982 3280 1524 3281 1521 3281 1983 3281 1984 3282 1524 3282 1983 3282 1985 3283 1524 3283 1984 3283 1527 3284 1524 3284 1985 3284 1529 3285 1527 3285 1985 3285 1986 3286 1529 3286 1985 3286 1531 3287 1529 3287 1986 3287 1987 3288 1531 3288 1986 3288 1534 3289 1531 3289 1987 3289 1988 3290 1534 3290 1987 3290 1535 3291 1534 3291 1988 3291 1537 3292 1535 3292 1988 3292 1989 3293 1537 3293 1988 3293 1990 3294 1537 3294 1989 3294 1540 3295 1537 3295 1990 3295 1542 3296 1540 3296 1990 3296 1991 3297 1542 3297 1990 3297 1992 3298 1542 3298 1991 3298 1544 3299 1542 3299 1992 3299 1993 3300 1544 3300 1992 3300 1547 3301 1544 3301 1993 3301 1549 3302 1547 3302 1993 3302 1994 3303 1549 3303 1993 3303 1551 3304 1549 3304 1994 3304 1995 3305 1551 3305 1994 3305 1554 3306 1551 3306 1995 3306 1556 3307 1554 3307 1996 3307 1997 3308 1556 3308 1996 3308 1558 3309 1556 3309 1997 3309 1998 3310 1558 3310 1997 3310 1561 3311 1558 3311 1998 3311 1563 3312 1561 3312 1998 3312 1999 3313 1563 3313 1998 3313 1565 3314 1563 3314 1999 3314 2000 3315 1565 3315 1999 3315 1567 3316 1565 3316 2000 3316 2001 3317 1567 3317 2000 3317 1570 3318 1567 3318 2001 3318 2002 3319 1570 3319 2001 3319 1570 3320 2002 3320 2003 3320 1572 3321 1570 3321 2003 3321 2004 3322 1572 3322 2003 3322 1575 3323 1572 3323 2004 3323 1577 3324 1575 3324 2004 3324 2005 3325 1577 3325 2004 3325 2006 3326 1577 3326 2005 3326 1580 3327 1577 3327 2006 3327 2007 3328 1580 3328 2006 3328 1583 3329 1580 3329 2007 3329 2008 3330 1583 3330 2007 3330 1585 3331 1583 3331 2008 3331 2009 3332 1587 3332 1585 3332 1589 3333 1587 3333 2009 3333 2010 3334 1589 3334 2009 3334 1591 3335 1589 3335 2010 3335 2011 3336 1591 3336 2010 3336 1593 3337 1591 3337 2011 3337 2012 3338 1593 3338 2011 3338 1595 3339 1593 3339 2012 3339 2013 3340 1595 3340 2012 3340 1598 3341 1595 3341 2013 3341 1600 3342 1598 3342 2013 3342 2014 3343 1600 3343 2013 3343 2015 3344 1600 3344 2014 3344 1603 3345 1600 3345 2015 3345 1605 3346 1603 3346 2015 3346 2016 3347 1605 3347 2015 3347 1608 3348 1605 3348 2016 3348 2017 3349 1608 3349 2016 3349 2018 3350 1608 3350 2017 3350 1610 3351 1608 3351 2018 3351 2019 3352 1610 3352 2018 3352 1612 3353 1610 3353 2019 3353 2020 3354 1612 3354 2019 3354 1615 3355 1612 3355 2020 3355 2021 3356 1615 3356 2020 3356 1617 3357 1615 3357 2021 3357 2022 3358 1617 3358 2021 3358 1620 3359 1617 3359 2022 3359 1622 3360 1620 3360 2022 3360 2023 3361 1622 3361 2022 3361 1624 3362 1622 3362 2023 3362 2024 3363 1624 3363 2023 3363 1626 3364 1624 3364 2024 3364 2025 3365 1626 3365 2024 3365 1628 3366 1626 3366 2025 3366 2026 3367 1628 3367 2025 3367 1631 3368 1628 3368 2026 3368 2027 3369 1631 3369 2026 3369 1634 3370 1631 3370 2027 3370 2028 3371 1634 3371 2027 3371 1636 3372 1634 3372 2028 3372 2029 3373 1636 3373 2028 3373 1638 3374 1636 3374 2029 3374 2030 3375 1638 3375 2029 3375 1641 3376 1638 3376 2030 3376 2031 3377 1641 3377 2030 3377 1643 3378 1641 3378 2031 3378 2032 3379 1643 3379 2031 3379 1645 3380 1643 3380 2032 3380 2033 3381 1645 3381 2032 3381 2034 3382 1645 3382 2033 3382 1648 3383 1645 3383 2034 3383 2035 3384 1648 3384 2034 3384 1650 3385 1648 3385 2035 3385 2036 3386 1650 3386 2035 3386 1652 3387 1650 3387 2036 3387 2037 3388 1652 3388 2036 3388 1654 3389 1652 3389 2037 3389 1656 3390 1654 3390 2037 3390 2038 3391 1656 3391 2037 3391 1658 3392 1656 3392 2038 3392 2039 3393 1658 3393 2038 3393 1661 3394 1658 3394 2039 3394 1663 3395 1661 3395 2040 3395 1665 3396 1663 3396 2040 3396 2041 3397 1665 3397 2040 3397 1667 3398 1665 3398 2041 3398 2042 3399 1667 3399 2041 3399 2043 3400 1667 3400 2042 3400 1669 3401 1667 3401 2043 3401 2044 3402 1669 3402 2043 3402 1672 3403 1669 3403 2044 3403 2045 3404 1672 3404 2044 3404 1674 3405 1672 3405 2045 3405 2046 3406 1676 3406 1674 3406 1678 3407 1676 3407 2046 3407 2047 3408 1678 3408 2046 3408 1680 3409 1678 3409 2047 3409 2048 3410 1680 3410 2047 3410 1683 3411 1680 3411 2048 3411 2049 3412 1683 3412 2048 3412 1685 3413 1683 3413 2049 3413 2050 3414 1685 3414 2049 3414 1687 3415 1685 3415 2050 3415 1689 3416 2050 3416 2051 3416 1689 3417 1687 3417 2050 3417 2052 3418 1689 3418 2051 3418 1692 3419 1689 3419 2052 3419 2053 3420 1692 3420 2052 3420 2054 3421 1692 3421 2053 3421 1694 3422 1692 3422 2054 3422 2055 3423 1694 3423 2054 3423 1696 3424 1694 3424 2055 3424 1699 3425 1696 3425 2055 3425 2056 3426 1699 3426 2055 3426 1701 3427 1699 3427 2056 3427 2057 3428 1701 3428 2056 3428 1703 3429 1701 3429 2057 3429 2058 3430 1703 3430 2057 3430 1706 3431 1703 3431 2058 3431 2059 3432 1706 3432 2058 3432 1709 3433 1706 3433 2059 3433 2060 3434 1709 3434 2059 3434 1711 3435 1709 3435 2060 3435 2061 3436 1711 3436 2060 3436 1713 3437 1711 3437 2061 3437 2062 3438 1713 3438 2061 3438 1715 3439 1713 3439 2062 3439 2063 3440 1715 3440 2062 3440 1717 3441 1715 3441 2063 3441 2064 3442 1717 3442 2063 3442 1719 3443 1717 3443 2064 3443 2065 3444 1719 3444 2064 3444 1722 3445 1719 3445 2065 3445 2066 3446 1722 3446 2065 3446 1724 3447 1722 3447 2066 3447 1726 3448 1724 3448 2066 3448 2067 3449 1726 3449 2066 3449 2068 3450 1726 3450 2067 3450 1729 3451 1726 3451 2068 3451 2069 3452 1729 3452 2068 3452 1732 3453 1729 3453 2069 3453 1734 3454 1732 3454 2069 3454 2070 3455 1734 3455 2069 3455 1736 3456 1734 3456 2070 3456 2071 3457 1736 3457 2070 3457 2072 3458 1736 3458 2071 3458 1739 3459 1736 3459 2072 3459 1741 3460 1739 3460 2072 3460 2073 3461 1741 3461 2072 3461 1743 3462 1741 3462 2073 3462 2074 3463 1743 3463 2073 3463 1745 3464 1743 3464 2074 3464 2075 3465 1745 3465 2074 3465 1747 3466 1745 3466 2075 3466 2076 3467 1747 3467 2075 3467 1750 3468 1747 3468 2076 3468 2077 3469 1750 3469 2076 3469 1752 3470 1750 3470 2077 3470 1754 3471 1752 3471 2077 3471 1756 3472 1754 3472 2078 3472 1758 3473 1756 3473 2078 3473 2079 3474 1758 3474 2078 3474 1760 3475 1758 3475 2079 3475 2080 3476 1760 3476 2079 3476 2081 3477 1760 3477 2080 3477 1763 3478 1760 3478 2081 3478 2082 3479 1763 3479 2081 3479 1765 3480 1763 3480 2082 3480 2083 3481 1765 3481 2082 3481 1768 3482 1765 3482 2083 3482 1770 3483 1768 3483 2083 3483 2084 3484 1770 3484 2083 3484 1772 3485 1770 3485 2084 3485 1775 3486 1772 3486 2085 3486 1777 3487 1775 3487 2085 3487 2086 3488 1777 3488 2085 3488 1779 3489 1777 3489 2086 3489 2087 3490 1779 3490 2086 3490 1781 3491 1779 3491 2087 3491 2088 3492 1781 3492 2087 3492 1783 3493 1781 3493 2088 3493 1785 3494 1783 3494 2088 3494 1785 3495 2088 3495 2089 3495 2090 3496 1785 3496 2089 3496 1787 3497 1785 3497 2090 3497 1789 3498 1787 3498 2090 3498 2091 3499 1789 3499 2090 3499 2092 3500 1789 3500 2091 3500 1792 3501 1789 3501 2092 3501 1794 3502 1792 3502 2092 3502 2093 3503 1794 3503 2092 3503 2094 3504 1794 3504 2093 3504 1796 3505 1794 3505 2094 3505 2095 3506 1796 3506 2094 3506 1798 3507 1796 3507 2095 3507 2096 3508 1798 3508 2095 3508 1800 3509 1798 3509 2096 3509 1802 3510 1800 3510 2096 3510 2097 3511 1802 3511 2096 3511 1805 3512 1802 3512 2097 3512 2098 3513 1805 3513 2097 3513 1807 3514 1805 3514 2098 3514 2099 3515 1807 3515 2098 3515 1809 3516 1807 3516 2099 3516 1811 3517 1809 3517 2099 3517 2100 3518 1811 3518 2099 3518 1813 3519 1811 3519 2100 3519 2101 3520 1813 3520 2100 3520 1816 3521 1813 3521 2101 3521 1818 3522 1816 3522 2101 3522 2102 3523 1818 3523 2101 3523 1820 3524 1818 3524 2102 3524 2103 3525 1820 3525 2102 3525 1822 3526 1820 3526 2103 3526 2104 3527 1824 3527 1822 3527 1826 3528 1824 3528 2104 3528 2105 3529 1826 3529 2104 3529 1829 3530 1826 3530 2105 3530 2106 3531 1829 3531 2105 3531 1832 3532 1829 3532 2106 3532 1834 3533 1832 3533 2106 3533 2107 3534 1834 3534 2106 3534 2108 3535 1834 3535 2107 3535 1836 3536 1834 3536 2108 3536 1838 3537 1836 3537 2108 3537 2109 3538 1838 3538 2108 3538 1841 3539 1838 3539 2109 3539 2110 3540 1841 3540 2109 3540 2111 3541 1841 3541 2110 3541 1843 3542 1841 3542 2111 3542 2112 3543 1843 3543 2111 3543 1846 3544 1843 3544 2112 3544 2113 3545 1846 3545 2112 3545 1848 3546 1846 3546 2113 3546 1851 3547 1848 3547 2113 3547 2114 3548 1851 3548 2113 3548 1853 3549 1851 3549 2114 3549 2115 3550 1855 3550 1853 3550 1857 3551 2115 3551 2116 3551 1857 3552 1855 3552 2115 3552 2117 3553 1857 3553 2116 3553 1860 3554 1857 3554 2117 3554 2118 3555 1860 3555 2117 3555 1862 3556 1860 3556 2118 3556 1864 3557 1862 3557 2118 3557 2119 3558 1864 3558 2118 3558 1866 3559 1864 3559 2119 3559 2120 3560 1866 3560 2119 3560 2121 3561 1866 3561 2120 3561 1869 3562 1866 3562 2121 3562 1871 3563 1869 3563 2121 3563 2122 3564 1871 3564 2121 3564 1873 3565 1871 3565 2122 3565 2123 3566 1873 3566 2122 3566 1875 3567 1873 3567 2123 3567 2124 3568 1875 3568 2123 3568 1877 3569 1875 3569 2124 3569 2125 3570 1877 3570 2124 3570 1879 3571 1877 3571 2125 3571 2126 3572 1879 3572 2125 3572 1881 3573 1879 3573 2126 3573 1883 3574 1881 3574 2126 3574 2127 3575 1883 3575 2126 3575 1885 3576 1883 3576 2127 3576 2128 3577 1885 3577 2127 3577 1887 3578 1885 3578 2128 3578 2129 3579 1887 3579 2128 3579 2130 3580 1887 3580 2129 3580 1889 3581 1887 3581 2130 3581 1892 3582 1889 3582 2130 3582 2131 3583 1892 3583 2130 3583 1895 3584 1892 3584 2131 3584 2132 3585 1895 3585 2131 3585 1898 3586 1895 3586 2132 3586 2133 3587 1898 3587 2132 3587 2134 3588 1898 3588 2133 3588 1901 3589 1898 3589 2134 3589 2135 3590 1901 3590 2134 3590 1903 3591 1901 3591 2135 3591 2136 3592 1903 3592 2135 3592 1906 3593 1903 3593 2136 3593 2137 3594 1906 3594 2136 3594 1906 3595 2137 3595 2138 3595 1909 3596 1906 3596 2138 3596 1911 3597 1909 3597 2138 3597 2139 3598 1911 3598 2138 3598 1913 3599 1911 3599 2139 3599 2140 3600 1913 3600 2139 3600 1915 3601 1913 3601 2140 3601 2141 3602 1915 3602 2140 3602 1918 3603 1915 3603 2141 3603 1920 3604 1918 3604 2142 3604 1922 3605 1920 3605 2142 3605 2143 3606 1922 3606 2142 3606 2144 3607 1922 3607 2143 3607 1925 3608 1922 3608 2144 3608 1927 3609 1925 3609 2144 3609 2145 3610 1927 3610 2144 3610 2146 3611 1927 3611 2145 3611 1930 3612 1927 3612 2146 3612 2147 3613 1930 3613 2146 3613 1932 3614 1930 3614 2147 3614 2148 3615 1932 3615 2147 3615 1935 3616 1932 3616 2148 3616 2149 3617 1935 3617 2148 3617 2150 3618 1935 3618 2149 3618 1937 3619 1935 3619 2150 3619 2151 3620 1937 3620 2150 3620 1940 3621 1937 3621 2151 3621 2152 3622 1940 3622 2151 3622 1942 3623 1940 3623 2152 3623 2153 3624 1942 3624 2152 3624 1944 3625 1942 3625 2153 3625 2154 3626 1944 3626 2153 3626 1946 3627 1944 3627 2154 3627 2155 3628 1946 3628 2154 3628 1949 3629 1946 3629 2155 3629 1951 3630 1949 3630 2155 3630 2156 3631 1951 3631 2155 3631 2157 3632 1951 3632 2156 3632 1954 3633 1951 3633 2157 3633 2158 3634 1954 3634 2157 3634 1956 3635 1954 3635 2158 3635 1958 3636 1956 3636 2158 3636 2159 3637 1958 3637 2158 3637 1960 3638 1958 3638 2159 3638 2160 3639 1960 3639 2159 3639 1962 3640 1960 3640 2160 3640 2161 3641 1962 3641 2160 3641 1964 3642 1962 3642 2161 3642 2162 3643 1964 3643 2161 3643 1967 3644 1964 3644 2162 3644 2163 3645 1967 3645 2162 3645 1969 3646 1967 3646 2163 3646 2164 3647 1970 3647 1969 3647 1971 3648 1970 3648 2164 3648 2165 3649 1971 3649 2164 3649 1972 3650 1971 3650 2165 3650 1972 3651 2165 3651 2166 3651 1468 3652 1972 3652 2166 3652 2167 3653 1468 3653 2166 3653 1467 3654 1468 3654 2167 3654 2168 3655 1467 3655 2167 3655 1472 3656 1467 3656 2168 3656 2169 3657 1975 3657 1974 3657 2171 3658 1975 3658 2169 3658 2171 3659 1976 3659 1975 3659 2171 3660 1977 3660 1976 3660 2170 3661 1977 3661 2171 3661 2170 3662 1978 3662 1977 3662 2172 3663 1978 3663 2170 3663 2172 3664 1979 3664 1978 3664 1482 3665 1979 3665 2172 3665 1482 3666 1980 3666 1979 3666 2173 3667 1980 3667 1482 3667 1484 3668 1980 3668 2173 3668 1484 3669 1981 3669 1980 3669 1485 3670 1981 3670 1484 3670 1488 3671 1981 3671 1485 3671 1488 3672 1982 3672 1981 3672 1490 3673 1982 3673 1488 3673 1492 3674 1982 3674 1490 3674 1492 3675 1983 3675 1982 3675 1494 3676 1983 3676 1492 3676 1494 3677 1984 3677 1983 3677 1496 3678 1984 3678 1494 3678 1496 3679 1985 3679 1984 3679 1497 3680 1985 3680 1496 3680 1499 3681 1985 3681 1497 3681 1499 3682 1986 3682 1985 3682 1500 3683 1986 3683 1499 3683 1502 3684 1986 3684 1500 3684 1502 3685 1987 3685 1986 3685 1504 3686 1987 3686 1502 3686 1504 3687 1988 3687 1987 3687 1505 3688 1988 3688 1504 3688 1507 3689 1988 3689 1505 3689 1507 3690 1989 3690 1988 3690 1509 3691 1989 3691 1507 3691 1509 3692 1990 3692 1989 3692 1511 3693 1990 3693 1509 3693 1512 3694 1990 3694 1511 3694 1512 3695 1991 3695 1990 3695 1514 3696 1991 3696 1512 3696 1514 3697 1992 3697 1991 3697 1516 3698 1992 3698 1514 3698 1516 3699 1993 3699 1992 3699 1518 3700 1993 3700 1516 3700 1520 3701 1993 3701 1518 3701 1520 3702 1994 3702 1993 3702 1522 3703 1994 3703 1520 3703 1522 3704 1995 3704 1994 3704 1523 3705 1995 3705 1522 3705 1523 3706 1554 3706 1995 3706 1525 3707 1554 3707 1523 3707 1525 3708 1996 3708 1554 3708 1526 3709 1996 3709 1525 3709 1528 3710 1996 3710 1526 3710 1528 3711 1997 3711 1996 3711 1530 3712 1997 3712 1528 3712 1532 3713 1997 3713 1530 3713 1532 3714 1998 3714 1997 3714 1533 3715 1998 3715 1532 3715 1533 3716 1999 3716 1998 3716 1536 3717 1999 3717 1533 3717 1538 3718 1999 3718 1536 3718 1538 3719 2000 3719 1999 3719 1539 3720 2000 3720 1538 3720 1539 3721 2001 3721 2000 3721 1539 3722 2002 3722 2001 3722 1541 3723 2002 3723 1539 3723 1541 3724 2003 3724 2002 3724 1543 3725 2003 3725 1541 3725 1545 3726 2003 3726 1543 3726 1545 3727 2004 3727 2003 3727 1546 3728 2004 3728 1545 3728 1548 3729 2004 3729 1546 3729 1548 3730 2005 3730 2004 3730 1550 3731 2005 3731 1548 3731 1550 3732 2006 3732 2005 3732 1552 3733 2006 3733 1550 3733 1552 3734 2007 3734 2006 3734 1553 3735 2007 3735 1552 3735 1553 3736 2008 3736 2007 3736 1555 3737 2008 3737 1553 3737 1555 3738 1585 3738 2008 3738 1557 3739 1585 3739 1555 3739 1557 3740 2009 3740 1585 3740 1559 3741 2009 3741 1557 3741 1559 3742 2010 3742 2009 3742 1560 3743 2010 3743 1559 3743 1560 3744 2011 3744 2010 3744 1562 3745 2011 3745 1560 3745 1564 3746 2011 3746 1562 3746 1564 3747 2012 3747 2011 3747 1566 3748 2012 3748 1564 3748 1566 3749 2013 3749 2012 3749 1568 3750 2013 3750 1566 3750 2174 3751 2013 3751 1568 3751 2174 3752 2014 3752 2013 3752 2175 3753 2014 3753 2174 3753 2175 3754 2015 3754 2014 3754 1574 3755 2015 3755 2175 3755 1574 3756 2016 3756 2015 3756 1576 3757 2016 3757 1574 3757 1576 3758 2017 3758 2016 3758 1578 3759 2017 3759 1576 3759 1579 3760 2017 3760 1578 3760 1579 3761 2018 3761 2017 3761 1581 3762 2018 3762 1579 3762 1581 3763 2019 3763 2018 3763 1582 3764 2019 3764 1581 3764 1582 3765 2020 3765 2019 3765 1584 3766 2020 3766 1582 3766 1586 3767 2020 3767 1584 3767 1586 3768 2021 3768 2020 3768 1588 3769 2021 3769 1586 3769 1588 3770 2022 3770 2021 3770 1590 3771 2022 3771 1588 3771 1592 3772 2022 3772 1590 3772 1592 3773 2023 3773 2022 3773 1596 3774 2023 3774 1592 3774 1596 3775 2024 3775 2023 3775 1597 3776 2024 3776 1596 3776 1597 3777 2025 3777 2024 3777 1599 3778 2025 3778 1597 3778 1601 3779 2026 3779 1599 3779 1599 3780 2026 3780 2025 3780 1602 3781 2027 3781 1601 3781 1601 3782 2027 3782 2026 3782 1604 3783 2027 3783 1602 3783 1604 3784 2028 3784 2027 3784 1606 3785 2028 3785 1604 3785 1607 3786 2028 3786 1606 3786 1607 3787 2029 3787 2028 3787 1609 3788 2029 3788 1607 3788 1609 3789 2030 3789 2029 3789 1611 3790 2030 3790 1609 3790 1611 3791 2031 3791 2030 3791 1613 3792 2031 3792 1611 3792 1613 3793 2032 3793 2031 3793 1614 3794 2032 3794 1613 3794 1614 3795 2033 3795 2032 3795 1616 3796 2033 3796 1614 3796 1616 3797 2034 3797 2033 3797 1618 3798 2034 3798 1616 3798 1619 3799 2034 3799 1618 3799 1619 3800 2035 3800 2034 3800 1621 3801 2035 3801 1619 3801 1623 3802 2035 3802 1621 3802 1623 3803 2036 3803 2035 3803 1625 3804 2036 3804 1623 3804 1625 3805 2037 3805 2036 3805 1627 3806 2037 3806 1625 3806 1627 3807 2038 3807 2037 3807 1629 3808 2038 3808 1627 3808 1629 3809 2039 3809 2038 3809 1630 3810 2039 3810 1629 3810 1632 3811 2039 3811 1630 3811 1632 3812 1661 3812 2039 3812 1633 3813 1661 3813 1632 3813 1633 3814 2040 3814 1661 3814 2176 3815 2040 3815 1633 3815 2176 3816 2041 3816 2040 3816 1637 3817 2041 3817 2176 3817 1639 3818 2041 3818 1637 3818 1639 3819 2042 3819 2041 3819 1640 3820 2042 3820 1639 3820 1640 3821 2043 3821 2042 3821 1642 3822 2043 3822 1640 3822 1642 3823 2044 3823 2043 3823 1644 3824 2044 3824 1642 3824 1644 3825 2045 3825 2044 3825 2177 3826 2045 3826 1644 3826 2177 3827 1674 3827 2045 3827 2177 3828 2046 3828 1674 3828 1647 3829 2046 3829 2177 3829 1649 3830 2046 3830 1647 3830 1649 3831 2047 3831 2046 3831 1651 3832 2047 3832 1649 3832 2178 3833 2047 3833 1651 3833 2178 3834 2048 3834 2047 3834 1655 3835 2048 3835 2178 3835 1655 3836 2049 3836 2048 3836 1657 3837 2049 3837 1655 3837 1657 3838 2050 3838 2049 3838 1659 3839 2050 3839 1657 3839 1660 3840 2050 3840 1659 3840 1660 3841 2051 3841 2050 3841 1662 3842 2051 3842 1660 3842 1662 3843 2052 3843 2051 3843 1664 3844 2053 3844 1662 3844 1662 3845 2053 3845 2052 3845 1664 3846 2054 3846 2053 3846 2179 3847 2054 3847 1664 3847 2179 3848 2055 3848 2054 3848 1670 3849 2055 3849 2179 3849 1671 3850 2055 3850 1670 3850 1671 3851 2056 3851 2055 3851 1673 3852 2056 3852 1671 3852 1673 3853 2057 3853 2056 3853 1675 3854 2057 3854 1673 3854 1677 3855 2057 3855 1675 3855 1677 3856 2058 3856 2057 3856 1679 3857 2058 3857 1677 3857 1679 3858 2059 3858 2058 3858 2180 3859 2059 3859 1679 3859 2180 3860 2060 3860 2059 3860 1681 3861 2060 3861 2180 3861 1682 3862 2060 3862 1681 3862 1682 3863 2061 3863 2060 3863 2181 3864 2061 3864 1682 3864 2181 3865 2062 3865 2061 3865 1686 3866 2062 3866 2181 3866 1686 3867 2063 3867 2062 3867 1688 3868 2063 3868 1686 3868 1688 3869 2064 3869 2063 3869 1690 3870 2064 3870 1688 3870 1690 3871 2065 3871 2064 3871 1691 3872 2065 3872 1690 3872 1691 3873 2066 3873 2065 3873 1693 3874 2066 3874 1691 3874 1695 3875 2066 3875 1693 3875 1695 3876 2067 3876 2066 3876 1697 3877 2067 3877 1695 3877 1697 3878 2068 3878 2067 3878 1698 3879 2068 3879 1697 3879 1700 3880 2068 3880 1698 3880 1700 3881 2069 3881 2068 3881 1702 3882 2069 3882 1700 3882 1704 3883 2069 3883 1702 3883 1704 3884 2070 3884 2069 3884 1705 3885 2070 3885 1704 3885 1705 3886 2071 3886 2070 3886 1707 3887 2071 3887 1705 3887 1707 3888 2072 3888 2071 3888 1708 3889 2072 3889 1707 3889 1710 3890 2072 3890 1708 3890 1710 3891 2073 3891 2072 3891 1712 3892 2073 3892 1710 3892 1712 3893 2074 3893 2073 3893 1714 3894 2074 3894 1712 3894 1714 3895 2075 3895 2074 3895 1716 3896 2075 3896 1714 3896 1720 3897 2075 3897 1716 3897 1720 3898 2076 3898 2075 3898 2182 3899 2076 3899 1720 3899 2182 3900 2077 3900 2076 3900 2183 3901 2077 3901 2182 3901 2183 3902 1754 3902 2077 3902 1723 3903 1754 3903 2183 3903 1723 3904 2078 3904 1754 3904 1727 3905 2078 3905 1723 3905 1727 3906 2079 3906 2078 3906 1728 3907 2079 3907 1727 3907 1730 3908 2079 3908 1728 3908 1730 3909 2080 3909 2079 3909 1731 3910 2080 3910 1730 3910 1731 3911 2081 3911 2080 3911 1733 3912 2081 3912 1731 3912 1733 3913 2082 3913 2081 3913 1735 3914 2082 3914 1733 3914 1735 3915 2083 3915 2082 3915 1737 3916 2083 3916 1735 3916 1738 3917 2083 3917 1737 3917 1738 3918 2084 3918 2083 3918 1740 3919 2084 3919 1738 3919 1740 3920 1772 3920 2084 3920 1742 3921 1772 3921 1740 3921 1742 3922 2085 3922 1772 3922 1744 3923 2085 3923 1742 3923 1744 3924 2086 3924 2085 3924 1746 3925 2086 3925 1744 3925 1746 3926 2087 3926 2086 3926 1748 3927 2087 3927 1746 3927 1749 3928 2087 3928 1748 3928 1749 3929 2088 3929 2087 3929 1751 3930 2088 3930 1749 3930 1753 3931 2088 3931 1751 3931 1753 3932 2089 3932 2088 3932 1753 3933 2090 3933 2089 3933 1755 3934 2090 3934 1753 3934 1757 3935 2090 3935 1755 3935 1757 3936 2091 3936 2090 3936 1759 3937 2091 3937 1757 3937 1759 3938 2092 3938 2091 3938 1761 3939 2092 3939 1759 3939 1762 3940 2092 3940 1761 3940 1762 3941 2093 3941 2092 3941 1762 3942 2094 3942 2093 3942 1764 3943 2094 3943 1762 3943 1766 3944 2094 3944 1764 3944 1766 3945 2095 3945 2094 3945 1767 3946 2095 3946 1766 3946 1767 3947 2096 3947 2095 3947 1769 3948 2096 3948 1767 3948 1771 3949 2096 3949 1769 3949 1771 3950 2097 3950 2096 3950 1773 3951 2097 3951 1771 3951 1773 3952 2098 3952 2097 3952 1774 3953 2098 3953 1773 3953 1774 3954 2099 3954 2098 3954 1778 3955 2099 3955 1774 3955 2184 3956 2099 3956 1778 3956 1780 3957 2100 3957 2184 3957 2184 3958 2100 3958 2099 3958 1782 3959 2100 3959 1780 3959 1782 3960 2101 3960 2100 3960 1784 3961 2101 3961 1782 3961 1786 3962 2101 3962 1784 3962 1786 3963 2102 3963 2101 3963 1788 3964 2102 3964 1786 3964 1788 3965 2103 3965 2102 3965 1790 3966 2103 3966 1788 3966 1790 3967 1822 3967 2103 3967 1791 3968 1822 3968 1790 3968 1791 3969 2104 3969 1822 3969 1793 3970 2104 3970 1791 3970 1795 3971 2104 3971 1793 3971 1795 3972 2105 3972 2104 3972 1797 3973 2105 3973 1795 3973 1799 3974 2105 3974 1797 3974 1799 3975 2106 3975 2105 3975 1801 3976 2106 3976 1799 3976 1801 3977 2107 3977 2106 3977 1803 3978 2107 3978 1801 3978 1803 3979 2108 3979 2107 3979 1804 3980 2108 3980 1803 3980 1806 3981 2108 3981 1804 3981 1806 3982 2109 3982 2108 3982 1808 3983 2109 3983 1806 3983 1810 3984 2109 3984 1808 3984 1810 3985 2110 3985 2109 3985 2185 3986 2110 3986 1810 3986 2185 3987 2111 3987 2110 3987 1812 3988 2111 3988 2185 3988 1812 3989 2112 3989 2111 3989 1814 3990 2112 3990 1812 3990 1815 3991 2112 3991 1814 3991 1817 3992 2112 3992 1815 3992 1817 3993 2113 3993 2112 3993 1819 3994 2113 3994 1817 3994 1819 3995 2114 3995 2113 3995 1821 3996 2114 3996 1819 3996 1821 3997 1853 3997 2114 3997 1823 3998 1853 3998 1821 3998 1823 3999 2115 3999 1853 3999 1825 4000 2115 4000 1823 4000 1825 4001 2116 4001 2115 4001 1827 4002 2116 4002 1825 4002 1828 4003 2116 4003 1827 4003 1828 4004 2117 4004 2116 4004 1830 4005 2117 4005 1828 4005 1830 4006 2118 4006 2117 4006 1831 4007 2118 4007 1830 4007 1831 4008 2119 4008 2118 4008 1833 4009 2119 4009 1831 4009 1835 4010 2119 4010 1833 4010 1835 4011 2120 4011 2119 4011 1835 4012 2121 4012 2120 4012 1839 4013 2121 4013 1835 4013 1840 4014 2121 4014 1839 4014 1840 4015 2122 4015 2121 4015 1842 4016 2122 4016 1840 4016 1842 4017 2123 4017 2122 4017 1842 4018 2124 4018 2123 4018 1844 4019 2124 4019 1842 4019 1845 4020 2124 4020 1844 4020 1847 4021 2124 4021 1845 4021 1847 4022 2125 4022 2124 4022 1849 4023 2125 4023 1847 4023 1850 4024 2125 4024 1849 4024 1850 4025 2126 4025 2125 4025 1850 4026 2127 4026 2126 4026 1852 4027 2127 4027 1850 4027 1854 4028 2127 4028 1852 4028 1854 4029 2128 4029 2127 4029 2186 4030 2128 4030 1854 4030 1856 4031 2128 4031 2186 4031 1856 4032 2129 4032 2128 4032 1858 4033 2129 4033 1856 4033 1858 4034 2130 4034 2129 4034 1859 4035 2130 4035 1858 4035 1861 4036 2130 4036 1859 4036 1861 4037 2131 4037 2130 4037 1863 4038 2131 4038 1861 4038 1865 4039 2131 4039 1863 4039 1865 4040 2132 4040 2131 4040 1867 4041 2132 4041 1865 4041 1867 4042 2133 4042 2132 4042 1868 4043 2133 4043 1867 4043 1870 4044 2133 4044 1868 4044 1870 4045 2134 4045 2133 4045 1872 4046 2134 4046 1870 4046 1872 4047 2135 4047 2134 4047 1874 4048 2135 4048 1872 4048 1874 4049 2136 4049 2135 4049 1876 4050 2136 4050 1874 4050 1876 4051 2137 4051 2136 4051 1878 4052 2137 4052 1876 4052 1878 4053 2138 4053 2137 4053 1880 4054 2138 4054 1878 4054 1882 4055 2138 4055 1880 4055 1882 4056 2139 4056 2138 4056 1884 4057 2139 4057 1882 4057 1884 4058 2140 4058 2139 4058 1886 4059 2140 4059 1884 4059 1886 4060 2141 4060 2140 4060 1888 4061 2141 4061 1886 4061 1888 4062 1918 4062 2141 4062 1890 4063 1918 4063 1888 4063 1890 4064 2142 4064 1918 4064 1891 4065 2142 4065 1890 4065 1893 4066 2142 4066 1891 4066 1893 4067 2143 4067 2142 4067 1894 4068 2143 4068 1893 4068 1894 4069 2144 4069 2143 4069 2187 4070 2144 4070 1894 4070 1899 4071 2144 4071 2187 4071 1899 4072 2145 4072 2144 4072 1900 4073 2145 4073 1899 4073 1900 4074 2146 4074 2145 4074 1900 4075 2147 4075 2146 4075 1902 4076 2147 4076 1900 4076 1902 4077 2148 4077 2147 4077 1905 4078 2148 4078 1902 4078 1905 4079 2149 4079 2148 4079 1907 4080 2149 4080 1905 4080 1907 4081 2150 4081 2149 4081 1908 4082 2150 4082 1907 4082 1910 4083 2150 4083 1908 4083 1910 4084 2151 4084 2150 4084 1912 4085 2151 4085 1910 4085 1912 4086 2152 4086 2151 4086 1914 4087 2152 4087 1912 4087 1914 4088 2153 4088 2152 4088 1916 4089 2153 4089 1914 4089 1916 4090 2154 4090 2153 4090 1917 4091 2154 4091 1916 4091 1917 4092 2155 4092 2154 4092 2188 4093 2155 4093 1917 4093 2189 4094 2155 4094 2188 4094 2189 4095 2156 4095 2155 4095 1921 4096 2156 4096 2189 4096 1923 4097 2156 4097 1921 4097 1923 4098 2157 4098 2156 4098 1924 4099 2157 4099 1923 4099 1926 4100 2158 4100 1924 4100 1924 4101 2158 4101 2157 4101 1928 4102 2158 4102 1926 4102 1928 4103 2159 4103 2158 4103 1929 4104 2159 4104 1928 4104 1931 4105 2159 4105 1929 4105 1931 4106 2160 4106 2159 4106 1933 4107 2160 4107 1931 4107 1933 4108 2161 4108 2160 4108 1934 4109 2161 4109 1933 4109 1934 4110 2162 4110 2161 4110 1936 4111 2162 4111 1934 4111 1936 4112 2163 4112 2162 4112 1938 4113 2163 4113 1936 4113 1938 4114 1969 4114 2163 4114 1939 4115 1969 4115 1938 4115 1939 4116 2164 4116 1969 4116 1941 4117 2164 4117 1939 4117 1943 4118 2164 4118 1941 4118 1943 4119 2165 4119 2164 4119 1945 4120 2165 4120 1943 4120 1945 4121 2166 4121 2165 4121 1947 4122 2166 4122 1945 4122 1948 4123 2166 4123 1947 4123 1948 4124 2167 4124 2166 4124 1948 4125 2168 4125 2167 4125 1950 4126 2168 4126 1948 4126 1952 4127 2168 4127 1950 4127 1952 4128 1472 4128 2168 4128 1953 4129 1472 4129 1952 4129 1953 4130 1476 4130 1472 4130 1955 4131 1476 4131 1953 4131 1955 4132 1478 4132 1476 4132 1959 4133 1478 4133 1955 4133 2190 4134 1478 4134 1959 4134 2190 4135 1480 4135 1478 4135 1963 4136 1480 4136 2190 4136 1963 4137 1481 4137 1480 4137 1965 4138 1481 4138 1963 4138 1965 4139 2197 4139 1481 4139 2173 4140 1482 4140 1483 4140 1484 4141 2173 4141 1483 4141 2174 4142 1568 4142 1569 4142 1571 4143 2174 4143 1569 4143 2175 4144 2174 4144 1571 4144 1573 4145 2175 4145 1571 4145 1574 4146 2175 4146 1573 4146 1596 4147 1592 4147 1594 4147 1635 4148 2176 4148 1633 4148 1637 4149 2176 4149 1635 4149 2177 4150 1644 4150 1646 4150 1647 4151 2177 4151 1646 4151 2178 4152 1651 4152 1653 4152 1655 4153 2178 4153 1653 4153 2179 4154 1664 4154 1666 4154 1668 4155 2179 4155 1666 4155 1670 4156 2179 4156 1668 4156 1681 4157 2180 4157 1679 4157 2181 4158 1682 4158 1684 4158 1686 4159 2181 4159 1684 4159 1720 4160 1716 4160 1718 4160 1721 4161 2182 4161 1720 4161 2183 4162 2182 4162 1721 4162 1723 4163 2183 4163 1721 4163 1727 4164 1723 4164 1725 4164 1778 4165 1774 4165 1776 4165 1780 4166 2184 4166 1778 4166 1812 4167 2185 4167 1810 4167 1839 4168 1835 4168 1837 4168 1856 4169 2186 4169 1854 4169 2187 4170 1894 4170 1896 4170 1897 4171 2187 4171 1896 4171 1899 4172 2187 4172 1897 4172 1905 4173 1902 4173 1904 4173 1919 4174 2188 4174 1917 4174 2189 4175 2188 4175 1919 4175 1921 4176 2189 4176 1919 4176 1959 4177 1955 4177 1957 4177 1961 4178 2190 4178 1959 4178 1963 4179 2190 4179 1961 4179 1966 4180 2197 4180 1965 4180 2195 4181 2197 4181 1966 4181 1968 4182 2195 4182 1966 4182 2192 4183 2239 4183 2191 4183 2195 4184 2192 4184 2191 4184 2193 4185 2191 4185 2194 4185 2193 4186 2195 4186 2191 4186 2195 4187 1968 4187 2192 4187 2196 4188 2195 4188 2193 4188 2196 4189 2193 4189 2194 4189 2196 4190 2197 4190 2195 4190 2198 4191 2196 4191 2194 4191 2198 4192 2197 4192 2196 4192 2199 4193 2198 4193 2194 4193 2198 4194 1481 4194 2197 4194 2200 4195 2198 4195 2199 4195 1481 4196 2198 4196 2200 4196 2202 4197 2200 4197 2199 4197 2203 4198 2200 4198 2202 4198 2203 4199 1481 4199 2200 4199 2201 4200 2202 4200 2199 4200 2204 4201 2203 4201 2202 4201 2204 4202 2202 4202 2201 4202 2206 4203 2204 4203 2201 4203 2206 4204 2201 4204 2207 4204 2207 4205 2201 4205 2205 4205 2206 4206 2208 4206 2204 4206 2208 4207 2206 4207 2207 4207 2209 4208 2208 4208 2207 4208 2209 4209 2207 4209 2205 4209 2210 4210 2209 4210 2205 4210 2211 4211 2208 4211 2209 4211 2211 4212 2209 4212 2210 4212 2210 4213 2205 4213 2212 4213 2213 4214 2211 4214 2210 4214 2214 4215 2210 4215 2212 4215 2214 4216 2213 4216 2210 4216 2215 4217 2211 4217 2213 4217 2216 4218 2214 4218 2212 4218 2215 4219 2213 4219 2214 4219 2217 4220 2215 4220 2214 4220 2216 4221 2217 4221 2214 4221 2218 4222 2216 4222 2212 4222 2219 4223 2217 4223 2216 4223 2220 4224 2219 4224 2216 4224 2219 4225 1473 4225 2217 4225 2221 4226 2220 4226 2216 4226 2221 4227 2216 4227 2218 4227 1473 4228 2219 4228 2220 4228 2222 4229 2221 4229 2218 4229 2223 4230 2220 4230 2221 4230 1473 4231 2220 4231 2223 4231 2224 4232 2221 4232 2222 4232 2224 4233 2223 4233 2221 4233 1470 4234 1473 4234 2223 4234 2227 4235 1470 4235 2223 4235 2226 4236 2224 4236 2222 4236 2227 4237 2223 4237 2224 4237 2226 4238 2227 4238 2224 4238 2225 4239 2226 4239 2222 4239 2229 4240 2227 4240 2226 4240 2228 4241 2226 4241 2225 4241 2229 4242 2226 4242 2228 4242 1469 4243 2227 4243 2229 4243 2230 4244 2229 4244 2228 4244 1471 4245 1469 4245 2229 4245 1471 4246 2229 4246 2230 4246 2231 4247 2228 4247 2225 4247 2232 4248 2230 4248 2228 4248 2233 4249 2232 4249 2228 4249 2233 4250 2228 4250 2231 4250 1471 4251 2230 4251 2232 4251 1475 4252 1471 4252 2232 4252 2234 4253 2232 4253 2233 4253 1475 4254 2232 4254 2234 4254 2234 4255 2233 4255 2231 4255 2234 4256 1477 4256 1475 4256 2236 4257 2234 4257 2231 4257 2235 4258 2236 4258 2231 4258 1477 4259 2234 4259 2236 4259 2235 4260 2231 4260 2237 4260 2238 4261 2236 4261 2235 4261 1479 4262 1477 4262 2236 4262 2237 4263 2238 4263 2235 4263 1479 4264 2236 4264 2238 4264 2240 4265 2238 4265 2237 4265 2240 4266 2237 4266 2239 4266 2240 4267 1479 4267 2238 4267 2241 4268 1479 4268 2240 4268 2239 4269 2237 4269 2191 4269 2241 4270 2240 4270 2239 4270 2192 4271 2241 4271 2239 4271 1968 4272 2241 4272 2192 4272 2191 4273 2237 4273 2231 4273 2201 4274 2199 4274 2194 4274 2205 4275 2191 4275 2231 4275 2205 4276 2194 4276 2191 4276 2205 4277 2218 4277 2212 4277 2205 4278 2225 4278 2222 4278 2205 4279 2231 4279 2225 4279 2205 4280 2222 4280 2218 4280 2205 4281 2201 4281 2194 4281 2242 4282 2308 4282 2307 4282 2243 4283 2308 4283 2242 4283 2244 4284 2306 4284 2243 4284 2245 4285 2243 4285 2242 4285 2244 4286 2243 4286 2245 4286 2246 4287 2245 4287 2242 4287 2248 4288 2244 4288 2245 4288 2248 4289 2245 4289 2246 4289 2248 4290 2246 4290 2247 4290 2250 4291 2248 4291 2247 4291 2251 4292 2244 4292 2248 4292 2251 4293 2248 4293 2250 4293 2250 4294 2247 4294 2249 4294 2252 4295 2250 4295 2249 4295 2252 4296 2251 4296 2250 4296 2252 4297 2249 4297 2253 4297 2254 4298 2252 4298 2253 4298 2255 4299 2251 4299 2252 4299 2255 4300 2252 4300 2254 4300 2256 4301 2254 4301 2257 4301 2255 4302 2254 4302 2256 4302 2258 4303 2255 4303 2256 4303 2258 4304 2256 4304 2257 4304 2258 4305 2257 4305 2259 4305 2260 4306 2255 4306 2258 4306 2261 4307 2258 4307 2259 4307 2260 4308 2258 4308 2261 4308 2262 4309 2261 4309 2259 4309 2263 4310 2261 4310 2262 4310 2265 4311 2260 4311 2261 4311 2263 4312 2265 4312 2261 4312 2263 4313 2262 4313 2264 4313 2265 4314 2263 4314 2264 4314 2265 4315 2264 4315 2266 4315 2267 4316 2265 4316 2266 4316 2269 4317 2266 4317 2268 4317 2267 4318 2266 4318 2269 4318 2270 4319 2269 4319 2268 4319 2271 4320 2269 4320 2270 4320 2272 4321 2267 4321 2269 4321 2272 4322 2269 4322 2271 4322 2273 4323 2271 4323 2274 4323 2273 4324 2272 4324 2271 4324 2275 4325 2272 4325 2273 4325 2275 4326 2273 4326 2274 4326 2277 4327 2272 4327 2275 4327 2276 4328 2275 4328 2274 4328 2279 4329 2276 4329 2278 4329 2279 4330 2275 4330 2276 4330 2277 4331 2275 4331 2279 4331 2281 4332 2278 4332 2280 4332 2281 4333 2279 4333 2278 4333 2282 4334 2277 4334 2279 4334 2282 4335 2279 4335 2281 4335 2283 4336 2281 4336 2280 4336 2284 4337 2281 4337 2283 4337 2284 4338 2282 4338 2281 4338 2285 4339 2282 4339 2284 4339 2286 4340 2285 4340 2284 4340 2286 4341 2284 4341 2287 4341 2288 4342 2285 4342 2286 4342 2289 4343 2286 4343 2287 4343 2289 4344 2288 4344 2286 4344 2290 4345 2289 4345 2287 4345 2291 4346 2288 4346 2289 4346 2292 4347 2289 4347 2290 4347 2291 4348 2289 4348 2292 4348 2293 4349 2292 4349 2290 4349 2294 4350 2292 4350 2293 4350 2294 4351 2293 4351 2295 4351 2296 4352 2292 4352 2294 4352 2296 4353 2291 4353 2292 4353 2297 4354 2294 4354 2295 4354 2296 4355 2294 4355 2297 4355 2298 4356 2296 4356 2297 4356 2298 4357 2297 4357 2299 4357 2300 4358 2298 4358 2299 4358 2300 4359 2299 4359 2301 4359 2302 4360 2298 4360 2300 4360 2302 4361 2300 4361 2301 4361 2304 4362 2302 4362 2301 4362 2303 4363 2304 4363 2301 4363 2305 4364 2304 4364 2303 4364 2306 4365 2302 4365 2304 4365 2306 4366 2304 4366 2305 4366 2308 4367 2305 4367 2307 4367 2308 4368 2306 4368 2305 4368 2306 4369 2308 4369 2243 4369 2242 4370 2307 4370 2309 4370 2242 4371 2309 4371 2310 4371 2242 4372 2310 4372 2311 4372 2246 4373 2242 4373 2311 4373 2246 4374 2311 4374 2312 4374 2247 4375 2246 4375 2312 4375 2249 4376 2247 4376 2312 4376 2249 4377 2312 4377 2313 4377 2249 4378 2313 4378 2314 4378 2253 4379 2249 4379 2314 4379 2253 4380 2314 4380 2368 4380 2254 4381 2253 4381 2368 4381 2254 4382 2368 4382 2315 4382 2257 4383 2254 4383 2315 4383 2257 4384 2315 4384 2316 4384 2259 4385 2257 4385 2316 4385 2259 4386 2316 4386 2317 4386 2262 4387 2259 4387 2317 4387 2262 4388 2317 4388 2363 4388 2264 4389 2262 4389 2363 4389 2264 4390 2363 4390 2361 4390 2266 4391 2264 4391 2361 4391 2266 4392 2361 4392 2318 4392 2268 4393 2266 4393 2318 4393 2268 4394 2318 4394 2359 4394 2270 4395 2268 4395 2359 4395 2270 4396 2359 4396 2319 4396 2271 4397 2270 4397 2319 4397 2271 4398 2319 4398 2320 4398 2274 4399 2271 4399 2320 4399 2274 4400 2320 4400 2354 4400 2276 4401 2274 4401 2354 4401 2276 4402 2354 4402 2321 4402 2278 4403 2276 4403 2321 4403 2278 4404 2321 4404 2350 4404 2280 4405 2278 4405 2350 4405 2280 4406 2350 4406 2348 4406 2283 4407 2280 4407 2348 4407 2283 4408 2348 4408 2345 4408 2284 4409 2283 4409 2345 4409 2287 4410 2284 4410 2345 4410 2287 4411 2345 4411 2343 4411 2290 4412 2343 4412 2322 4412 2290 4413 2287 4413 2343 4413 2293 4414 2290 4414 2322 4414 2293 4415 2322 4415 2340 4415 2295 4416 2293 4416 2340 4416 2295 4417 2340 4417 2338 4417 2295 4418 2338 4418 2335 4418 2297 4419 2295 4419 2335 4419 2297 4420 2335 4420 2323 4420 2299 4421 2323 4421 2324 4421 2299 4422 2297 4422 2323 4422 2301 4423 2324 4423 2325 4423 2301 4424 2299 4424 2324 4424 2303 4425 2301 4425 2325 4425 2303 4426 2325 4426 2326 4426 2305 4427 2326 4427 2330 4427 2305 4428 2303 4428 2326 4428 2307 4429 2305 4429 2330 4429 2307 4430 2330 4430 2327 4430 2307 4431 2327 4431 2309 4431 1973 4432 2282 4432 2285 4432 1973 4433 2285 4433 2288 4433 1493 4434 2277 4434 2282 4434 1493 4435 2282 4435 1973 4435 1974 4436 1973 4436 2288 4436 1974 4437 2288 4437 2291 4437 1491 4438 2277 4438 1493 4438 1974 4439 2291 4439 2296 4439 2169 4440 1974 4440 2296 4440 1486 4441 2277 4441 1491 4441 1486 4442 2272 4442 2277 4442 2169 4443 2296 4443 2298 4443 1486 4444 2267 4444 2272 4444 2171 4445 2169 4445 2298 4445 1489 4446 2267 4446 1486 4446 2171 4447 2298 4447 2302 4447 2306 4448 2171 4448 2302 4448 2267 4449 1489 4449 1487 4449 2265 4450 2267 4450 1487 4450 2306 4451 2170 4451 2171 4451 2260 4452 2265 4452 1487 4452 2260 4453 1487 4453 1483 4453 2244 4454 2170 4454 2306 4454 2255 4455 2260 4455 1483 4455 2255 4456 1483 4456 1482 4456 2244 4457 2172 4457 2170 4457 2251 4458 2172 4458 2244 4458 2251 4459 2255 4459 1482 4459 2251 4460 1482 4460 2172 4460 2329 4461 2309 4461 2328 4461 2328 4462 2309 4462 2327 4462 2330 4463 2328 4463 2327 4463 2331 4464 2328 4464 2330 4464 2332 4465 2328 4465 2331 4465 2332 4466 2329 4466 2328 4466 2326 4467 2331 4467 2330 4467 2333 4468 2331 4468 2326 4468 2333 4469 2332 4469 2331 4469 2325 4470 2333 4470 2326 4470 2334 4471 2333 4471 2325 4471 1466 4472 2332 4472 2333 4472 2334 4473 2325 4473 2324 4473 1466 4474 2333 4474 2334 4474 2323 4475 2334 4475 2324 4475 2336 4476 2334 4476 2323 4476 1466 4477 2334 4477 2336 4477 2336 4478 2323 4478 2335 4478 2337 4479 1466 4479 2336 4479 2338 4480 2336 4480 2335 4480 2339 4481 2336 4481 2338 4481 2337 4482 2336 4482 2339 4482 2340 4483 2339 4483 2338 4483 2341 4484 2337 4484 2339 4484 2322 4485 2339 4485 2340 4485 2342 4486 2339 4486 2322 4486 2341 4487 2339 4487 2342 4487 2343 4488 2342 4488 2322 4488 2341 4489 2342 4489 2344 4489 2344 4490 2342 4490 2343 4490 2344 4491 2343 4491 2345 4491 2346 4492 2341 4492 2344 4492 2347 4493 2344 4493 2345 4493 2346 4494 2344 4494 2347 4494 2347 4495 2345 4495 2348 4495 2349 4496 2346 4496 2347 4496 2347 4497 2348 4497 2350 4497 2349 4498 2347 4498 2350 4498 2351 4499 2349 4499 2350 4499 2351 4500 2350 4500 2321 4500 2352 4501 2349 4501 2351 4501 2353 4502 2351 4502 2321 4502 2352 4503 2351 4503 2353 4503 2353 4504 2321 4504 2354 4504 2320 4505 2353 4505 2354 4505 2355 4506 2352 4506 2353 4506 2355 4507 2353 4507 2320 4507 2356 4508 2355 4508 2320 4508 2356 4509 2320 4509 2319 4509 2357 4510 2356 4510 2319 4510 2357 4511 2355 4511 2356 4511 2358 4512 2355 4512 2357 4512 2359 4513 2357 4513 2319 4513 2318 4514 2357 4514 2359 4514 2360 4515 2358 4515 2357 4515 2360 4516 2357 4516 2318 4516 2360 4517 2318 4517 2361 4517 2362 4518 2358 4518 2360 4518 2362 4519 2360 4519 2361 4519 2363 4520 2362 4520 2361 4520 2364 4521 2362 4521 2363 4521 2364 4522 2363 4522 2317 4522 2365 4523 2317 4523 2316 4523 2365 4524 2364 4524 2317 4524 2366 4525 2364 4525 2365 4525 2315 4526 2365 4526 2316 4526 2367 4527 2365 4527 2315 4527 2366 4528 2365 4528 2367 4528 2368 4529 2367 4529 2315 4529 2369 4530 2366 4530 2367 4530 2369 4531 2367 4531 2368 4531 2370 4532 2369 4532 2368 4532 2314 4533 2370 4533 2368 4533 2371 4534 2369 4534 2370 4534 2371 4535 2370 4535 2314 4535 2313 4536 2371 4536 2314 4536 2372 4537 2371 4537 2313 4537 2372 4538 2313 4538 2312 4538 2373 4539 2369 4539 2371 4539 2373 4540 2371 4540 2372 4540 2374 4541 2372 4541 2312 4541 2373 4542 2372 4542 2374 4542 2374 4543 2312 4543 2311 4543 2310 4544 2374 4544 2311 4544 2375 4545 2373 4545 2374 4545 2375 4546 2374 4546 2310 4546 2375 4547 2310 4547 2309 4547 2329 4548 2375 4548 2309 4548 1455 4549 1457 4549 1462 4549 1462 4550 1457 4550 1460 4550 1453 4551 1462 4551 1463 4551 1453 4552 1455 4552 1462 4552 1451 4553 1463 4553 1464 4553 1451 4554 1453 4554 1463 4554

+
+ + + +

2376 4555 2377 4555 2378 4555 2377 4556 2379 4556 2378 4556 2377 4557 2381 4557 2379 4557 2380 4558 2381 4558 2377 4558 2382 4559 2383 4559 2380 4559 2380 4560 2383 4560 2381 4560 2384 4561 2385 4561 2382 4561 2382 4562 2385 4562 2383 4562 2384 4563 2386 4563 2385 4563 2386 4564 2387 4564 2385 4564 2376 4565 2378 4565 2386 4565 2386 4566 2378 4566 2387 4566 2385 4567 2387 4567 2388 4567 2388 4568 2387 4568 2389 4568 2387 4569 2378 4569 2389 4569 2389 4570 2378 4570 2393 4570 2378 4571 2392 4571 2393 4571 2378 4572 2379 4572 2392 4572 2376 4573 2386 4573 2377 4573 2386 4574 2380 4574 2377 4574 2386 4575 2384 4575 2380 4575 2384 4576 2382 4576 2380 4576 2391 4577 3268 4577 3270 4577 2391 4578 3263 4578 3268 4578 2392 4579 3277 4579 3281 4579 2392 4580 3274 4580 3277 4580 2392 4581 2391 4581 3270 4581 2392 4582 3270 4582 3274 4582 2390 4583 3311 4583 3263 4583 2390 4584 3308 4584 3311 4584 2390 4585 3263 4585 2391 4585 2393 4586 2392 4586 3281 4586 2393 4587 3281 4587 3286 4587 3303 4588 3308 4588 2390 4588 3289 4589 2393 4589 3286 4589 2388 4590 3303 4590 2390 4590 3291 4591 2393 4591 3289 4591 3301 4592 3303 4592 2388 4592 3291 4593 2389 4593 2393 4593 3293 4594 2389 4594 3291 4594 3301 4595 2388 4595 2389 4595 3298 4596 3301 4596 2389 4596 3293 4597 3298 4597 2389 4597 2396 4598 2394 4598 2395 4598 2396 4599 2395 4599 2397 4599 2394 4600 2398 4600 2395 4600 2399 4601 2398 4601 2394 4601 2399 4602 2400 4602 2398 4602 2396 4603 2397 4603 2401 4603 2402 4604 2396 4604 2401 4604 2399 4605 3147 4605 2400 4605 2403 4606 3147 4606 2399 4606 2405 4607 3147 4607 2403 4607 2406 4608 3147 4608 2405 4608 2408 4609 2406 4609 2405 4609 2408 4610 2405 4610 2409 4610 2410 4611 2408 4611 2409 4611 2411 4612 2410 4612 2409 4612 2411 4613 2409 4613 2412 4613 2416 4614 2414 4614 3124 4614 2416 4615 2415 4615 2414 4615 2419 4616 2415 4616 2416 4616 2419 4617 2417 4617 2415 4617 2421 4618 2417 4618 2419 4618 2421 4619 2420 4619 2417 4619 2418 4620 2420 4620 2421 4620 2418 4621 2422 4621 2420 4621 2423 4622 2422 4622 2418 4622 2423 4623 2424 4623 2422 4623 2425 4624 2424 4624 2423 4624 2425 4625 2426 4625 2424 4625 2425 4626 2427 4626 2426 4626 2428 4627 2427 4627 2425 4627 2428 4628 2429 4628 2427 4628 2430 4629 2429 4629 2428 4629 2430 4630 2431 4630 2429 4630 2430 4631 2432 4631 2431 4631 2433 4632 2432 4632 2430 4632 2433 4633 2434 4633 2432 4633 2435 4634 2434 4634 2433 4634 2435 4635 2436 4635 2434 4635 2435 4636 2437 4636 2436 4636 2438 4637 2437 4637 2435 4637 2438 4638 2439 4638 2437 4638 2438 4639 2440 4639 2439 4639 2441 4640 2440 4640 2438 4640 2441 4641 2442 4641 2440 4641 2443 4642 2442 4642 2441 4642 2443 4643 2444 4643 2442 4643 2445 4644 2444 4644 2443 4644 2445 4645 2446 4645 2444 4645 2445 4646 2447 4646 2446 4646 2448 4647 2447 4647 2445 4647 2448 4648 2449 4648 2447 4648 2450 4649 2449 4649 2448 4649 2450 4650 2451 4650 2449 4650 2452 4651 2451 4651 2450 4651 2452 4652 2453 4652 2451 4652 2452 4653 2454 4653 2453 4653 2455 4654 2454 4654 2452 4654 2455 4655 2456 4655 2454 4655 2455 4656 2457 4656 2456 4656 2458 4657 2457 4657 2455 4657 2458 4658 2459 4658 2457 4658 2460 4659 2459 4659 2458 4659 2460 4660 2461 4660 2459 4660 2462 4661 2461 4661 2460 4661 2462 4662 2463 4662 2461 4662 2462 4663 2464 4663 2463 4663 2465 4664 2464 4664 2462 4664 2466 4665 2464 4665 2465 4665 2466 4666 2467 4666 2464 4666 2466 4667 2468 4667 2467 4667 2469 4668 2468 4668 2466 4668 2469 4669 2470 4669 2468 4669 2471 4670 2470 4670 2469 4670 2471 4671 2472 4671 2470 4671 2473 4672 2472 4672 2471 4672 2473 4673 2474 4673 2472 4673 2475 4674 2474 4674 2473 4674 2475 4675 2476 4675 2474 4675 2477 4676 2478 4676 2475 4676 2475 4677 2478 4677 2476 4677 2477 4678 2479 4678 2478 4678 2480 4679 2479 4679 2477 4679 2480 4680 2481 4680 2479 4680 2482 4681 2481 4681 2480 4681 2482 4682 2483 4682 2481 4682 2484 4683 2483 4683 2482 4683 2484 4684 2485 4684 2483 4684 2486 4685 2487 4685 2484 4685 2484 4686 2487 4686 2485 4686 2486 4687 2488 4687 2487 4687 2486 4688 2489 4688 2488 4688 2490 4689 2489 4689 2486 4689 2490 4690 2491 4690 2489 4690 2492 4691 2491 4691 2490 4691 2492 4692 2493 4692 2491 4692 2494 4693 2493 4693 2492 4693 2494 4694 2495 4694 2493 4694 2496 4695 2495 4695 2494 4695 2496 4696 2497 4696 2495 4696 2498 4697 2497 4697 2496 4697 2498 4698 2499 4698 2497 4698 2498 4699 2500 4699 2499 4699 2501 4700 2500 4700 2498 4700 2501 4701 2502 4701 2500 4701 2501 4702 2503 4702 2502 4702 2504 4703 2503 4703 2501 4703 2504 4704 2505 4704 2503 4704 2506 4705 2505 4705 2504 4705 2506 4706 2507 4706 2505 4706 2508 4707 2507 4707 2506 4707 2508 4708 2509 4708 2507 4708 2510 4709 2509 4709 2508 4709 2510 4710 2511 4710 2509 4710 2512 4711 2511 4711 2510 4711 2512 4712 2513 4712 2511 4712 2514 4713 2513 4713 2512 4713 2514 4714 2515 4714 2513 4714 2516 4715 2515 4715 2514 4715 2516 4716 2517 4716 2515 4716 2518 4717 2517 4717 2516 4717 2518 4718 2519 4718 2517 4718 2520 4719 2519 4719 2518 4719 2520 4720 2521 4720 2519 4720 2520 4721 2522 4721 2521 4721 2524 4722 2523 4722 2520 4722 2520 4723 2523 4723 2522 4723 2524 4724 2525 4724 2523 4724 2526 4725 2525 4725 2524 4725 2526 4726 2527 4726 2525 4726 2528 4727 2527 4727 2526 4727 2528 4728 2529 4728 2527 4728 2528 4729 2530 4729 2529 4729 2528 4730 2531 4730 2530 4730 2532 4731 2531 4731 2528 4731 2532 4732 2533 4732 2531 4732 2534 4733 2533 4733 2532 4733 2534 4734 2535 4734 2533 4734 2534 4735 2536 4735 2535 4735 2537 4736 2536 4736 2534 4736 2537 4737 2538 4737 2536 4737 2539 4738 2538 4738 2537 4738 2539 4739 2540 4739 2538 4739 2539 4740 2541 4740 2540 4740 2542 4741 2541 4741 2539 4741 2542 4742 2543 4742 2541 4742 2544 4743 2543 4743 2542 4743 2544 4744 2545 4744 2543 4744 2546 4745 2545 4745 2544 4745 2546 4746 2547 4746 2545 4746 2546 4747 2548 4747 2547 4747 2549 4748 2548 4748 2546 4748 2549 4749 2550 4749 2548 4749 2551 4750 2550 4750 2549 4750 2551 4751 2552 4751 2550 4751 2553 4752 2552 4752 2551 4752 2553 4753 2554 4753 2552 4753 2555 4754 2554 4754 2553 4754 2555 4755 2556 4755 2554 4755 2557 4756 2556 4756 2555 4756 2557 4757 2558 4757 2556 4757 2559 4758 2560 4758 2557 4758 2557 4759 2560 4759 2558 4759 2561 4760 2562 4760 2559 4760 2559 4761 2562 4761 2560 4761 2561 4762 2563 4762 2562 4762 2564 4763 2563 4763 2561 4763 2564 4764 2565 4764 2563 4764 2564 4765 2566 4765 2565 4765 2567 4766 2566 4766 2564 4766 2567 4767 2568 4767 2566 4767 2569 4768 2568 4768 2567 4768 2569 4769 2570 4769 2568 4769 2571 4770 2570 4770 2569 4770 2571 4771 2572 4771 2570 4771 2573 4772 2572 4772 2571 4772 2573 4773 2574 4773 2572 4773 2573 4774 2575 4774 2574 4774 2576 4775 2575 4775 2573 4775 2576 4776 2577 4776 2575 4776 2576 4777 2578 4777 2577 4777 2579 4778 2578 4778 2576 4778 2579 4779 2580 4779 2578 4779 2579 4780 2581 4780 2580 4780 2582 4781 2581 4781 2579 4781 2582 4782 2583 4782 2581 4782 2584 4783 2583 4783 2582 4783 2584 4784 2585 4784 2583 4784 2586 4785 2585 4785 2584 4785 2586 4786 2587 4786 2585 4786 2586 4787 2588 4787 2587 4787 2586 4788 2589 4788 2588 4788 2590 4789 2589 4789 2586 4789 2590 4790 2591 4790 2589 4790 2592 4791 2591 4791 2590 4791 2592 4792 2593 4792 2591 4792 2594 4793 2593 4793 2592 4793 2594 4794 2595 4794 2593 4794 2596 4795 2595 4795 2594 4795 2596 4796 2597 4796 2595 4796 2598 4797 2597 4797 2596 4797 2598 4798 2599 4798 2597 4798 2600 4799 2599 4799 2598 4799 2600 4800 2601 4800 2599 4800 2602 4801 2601 4801 2600 4801 2602 4802 2603 4802 2601 4802 2602 4803 2604 4803 2603 4803 2605 4804 2604 4804 2602 4804 2605 4805 2606 4805 2604 4805 2607 4806 2606 4806 2605 4806 2607 4807 2608 4807 2606 4807 2609 4808 2608 4808 2607 4808 2609 4809 2610 4809 2608 4809 2611 4810 2610 4810 2609 4810 2611 4811 2612 4811 2610 4811 2613 4812 2612 4812 2611 4812 2613 4813 2614 4813 2612 4813 2613 4814 2615 4814 2614 4814 2616 4815 2615 4815 2613 4815 2616 4816 2617 4816 2615 4816 2618 4817 2617 4817 2616 4817 2618 4818 2619 4818 2617 4818 2620 4819 2619 4819 2618 4819 2620 4820 2621 4820 2619 4820 2622 4821 2621 4821 2620 4821 2622 4822 2623 4822 2621 4822 2624 4823 2623 4823 2622 4823 2624 4824 2625 4824 2623 4824 2624 4825 2626 4825 2625 4825 2627 4826 2626 4826 2624 4826 2627 4827 2628 4827 2626 4827 2627 4828 2629 4828 2628 4828 2630 4829 2629 4829 2627 4829 2630 4830 2631 4830 2629 4830 2630 4831 2632 4831 2631 4831 2633 4832 2632 4832 2630 4832 2633 4833 2634 4833 2632 4833 2635 4834 2634 4834 2633 4834 2635 4835 2636 4835 2634 4835 2637 4836 2636 4836 2635 4836 2637 4837 2638 4837 2636 4837 2639 4838 2638 4838 2637 4838 2639 4839 2640 4839 2638 4839 2641 4840 2640 4840 2639 4840 2641 4841 2642 4841 2640 4841 2643 4842 2642 4842 2641 4842 2643 4843 2644 4843 2642 4843 2643 4844 2645 4844 2644 4844 2646 4845 2645 4845 2643 4845 2646 4846 2647 4846 2645 4846 2648 4847 2647 4847 2646 4847 2648 4848 2649 4848 2647 4848 2650 4849 2649 4849 2648 4849 2650 4850 2651 4850 2649 4850 2652 4851 2651 4851 2650 4851 2652 4852 2653 4852 2651 4852 2654 4853 2653 4853 2652 4853 2654 4854 2655 4854 2653 4854 2654 4855 2656 4855 2655 4855 2657 4856 2656 4856 2654 4856 2657 4857 2658 4857 2656 4857 2657 4858 2659 4858 2658 4858 2660 4859 2659 4859 2657 4859 2661 4860 2662 4860 2660 4860 2660 4861 2662 4861 2659 4861 2661 4862 2663 4862 2662 4862 2664 4863 2663 4863 2661 4863 2664 4864 2665 4864 2663 4864 2666 4865 2665 4865 2664 4865 2666 4866 2667 4866 2665 4866 2666 4867 2668 4867 2667 4867 2669 4868 2668 4868 2666 4868 2669 4869 2670 4869 2668 4869 2671 4870 2670 4870 2669 4870 2671 4871 2672 4871 2670 4871 2673 4872 2672 4872 2671 4872 2673 4873 2674 4873 2672 4873 2675 4874 2674 4874 2673 4874 2675 4875 2676 4875 2674 4875 2677 4876 2676 4876 2675 4876 2677 4877 2678 4877 2676 4877 2679 4878 2678 4878 2677 4878 2679 4879 2680 4879 2678 4879 2681 4880 2680 4880 2679 4880 2681 4881 2682 4881 2680 4881 2681 4882 2683 4882 2682 4882 2684 4883 2683 4883 2681 4883 2684 4884 2685 4884 2683 4884 2686 4885 2685 4885 2684 4885 2686 4886 2687 4886 2685 4886 2686 4887 2688 4887 2687 4887 2689 4888 2688 4888 2686 4888 2689 4889 2690 4889 2688 4889 2691 4890 2690 4890 2689 4890 2691 4891 2692 4891 2690 4891 2691 4892 2693 4892 2692 4892 2694 4893 2693 4893 2691 4893 2694 4894 2695 4894 2693 4894 2696 4895 2695 4895 2694 4895 2698 4896 2697 4896 2696 4896 2696 4897 2697 4897 2695 4897 2698 4898 2699 4898 2697 4898 2700 4899 2699 4899 2698 4899 2700 4900 2701 4900 2699 4900 2700 4901 2702 4901 2701 4901 2703 4902 2702 4902 2700 4902 2703 4903 2704 4903 2702 4903 2705 4904 2704 4904 2703 4904 2705 4905 2706 4905 2704 4905 2707 4906 2706 4906 2705 4906 2707 4907 2708 4907 2706 4907 2709 4908 2708 4908 2707 4908 2709 4909 2710 4909 2708 4909 2711 4910 2712 4910 2709 4910 2709 4911 2712 4911 2710 4911 2713 4912 2714 4912 2711 4912 2711 4913 2714 4913 2712 4913 2715 4914 2714 4914 2713 4914 2715 4915 2716 4915 2714 4915 2715 4916 2717 4916 2716 4916 2718 4917 2717 4917 2715 4917 2718 4918 2719 4918 2717 4918 2720 4919 2719 4919 2718 4919 2720 4920 2721 4920 2719 4920 2722 4921 2721 4921 2720 4921 2722 4922 2723 4922 2721 4922 2724 4923 2723 4923 2722 4923 2724 4924 2725 4924 2723 4924 2726 4925 2725 4925 2724 4925 2726 4926 2727 4926 2725 4926 2728 4927 2729 4927 2726 4927 2726 4928 2729 4928 2727 4928 2730 4929 2729 4929 2728 4929 2730 4930 2731 4930 2729 4930 2732 4931 2731 4931 2730 4931 2732 4932 2733 4932 2731 4932 2732 4933 2734 4933 2733 4933 2735 4934 2734 4934 2732 4934 2735 4935 2736 4935 2734 4935 2735 4936 2737 4936 2736 4936 2738 4937 2737 4937 2735 4937 2738 4938 2739 4938 2737 4938 2738 4939 2740 4939 2739 4939 2741 4940 2740 4940 2738 4940 2741 4941 2742 4941 2740 4941 2741 4942 2743 4942 2742 4942 2744 4943 2743 4943 2741 4943 2744 4944 2745 4944 2743 4944 2746 4945 2745 4945 2744 4945 2746 4946 2747 4946 2745 4946 2746 4947 2748 4947 2747 4947 2749 4948 2748 4948 2746 4948 2749 4949 2750 4949 2748 4949 2749 4950 2751 4950 2750 4950 2752 4951 2751 4951 2749 4951 2752 4952 2753 4952 2751 4952 2754 4953 2753 4953 2752 4953 2754 4954 2755 4954 2753 4954 2754 4955 2756 4955 2755 4955 2757 4956 2756 4956 2754 4956 2758 4957 2756 4957 2757 4957 2758 4958 2759 4958 2756 4958 2760 4959 2761 4959 2758 4959 2758 4960 2761 4960 2759 4960 2760 4961 2762 4961 2761 4961 2763 4962 2762 4962 2760 4962 2763 4963 2764 4963 2762 4963 2765 4964 2764 4964 2763 4964 2765 4965 2766 4965 2764 4965 2767 4966 2766 4966 2765 4966 2767 4967 2768 4967 2766 4967 2767 4968 2769 4968 2768 4968 2770 4969 2769 4969 2767 4969 2770 4970 2771 4970 2769 4970 2772 4971 2771 4971 2770 4971 2772 4972 2773 4972 2771 4972 2774 4973 2773 4973 2772 4973 2774 4974 2775 4974 2773 4974 2776 4975 2775 4975 2774 4975 2776 4976 2777 4976 2775 4976 2778 4977 2777 4977 2776 4977 2778 4978 2779 4978 2777 4978 2780 4979 2779 4979 2778 4979 2780 4980 2781 4980 2779 4980 2780 4981 2782 4981 2781 4981 2783 4982 2782 4982 2780 4982 2783 4983 2784 4983 2782 4983 2785 4984 2784 4984 2783 4984 2785 4985 2786 4985 2784 4985 2787 4986 2786 4986 2785 4986 2787 4987 2788 4987 2786 4987 2789 4988 2788 4988 2787 4988 2789 4989 2790 4989 2788 4989 2791 4990 2790 4990 2789 4990 2791 4991 2792 4991 2790 4991 2793 4992 2792 4992 2791 4992 2793 4993 2794 4993 2792 4993 2793 4994 2795 4994 2794 4994 2796 4995 2795 4995 2793 4995 2796 4996 2797 4996 2795 4996 2798 4997 2797 4997 2796 4997 2798 4998 2799 4998 2797 4998 2800 4999 2799 4999 2798 4999 2800 5000 2801 5000 2799 5000 2802 5001 2801 5001 2800 5001 2802 5002 2803 5002 2801 5002 2802 5003 2804 5003 2803 5003 2805 5004 2804 5004 2802 5004 2805 5005 2806 5005 2804 5005 2807 5006 2806 5006 2805 5006 2807 5007 2808 5007 2806 5007 2809 5008 2808 5008 2807 5008 2809 5009 2810 5009 2808 5009 2811 5010 2810 5010 2809 5010 2811 5011 2812 5011 2810 5011 2811 5012 2813 5012 2812 5012 2814 5013 2813 5013 2811 5013 2814 5014 2815 5014 2813 5014 2814 5015 2816 5015 2815 5015 2817 5016 2816 5016 2814 5016 2817 5017 2818 5017 2816 5017 2819 5018 2818 5018 2817 5018 2819 5019 2820 5019 2818 5019 2821 5020 2820 5020 2819 5020 2821 5021 2822 5021 2820 5021 2823 5022 2822 5022 2821 5022 2823 5023 2824 5023 2822 5023 2825 5024 2824 5024 2823 5024 2825 5025 2826 5025 2824 5025 2825 5026 2827 5026 2826 5026 2828 5027 2827 5027 2825 5027 2828 5028 2829 5028 2827 5028 2830 5029 2829 5029 2828 5029 2830 5030 2831 5030 2829 5030 2830 5031 2832 5031 2831 5031 2833 5032 2832 5032 2830 5032 2833 5033 2834 5033 2832 5033 2835 5034 2834 5034 2833 5034 2835 5035 2836 5035 2834 5035 2835 5036 2837 5036 2836 5036 2838 5037 2837 5037 2835 5037 2838 5038 2839 5038 2837 5038 2840 5039 2839 5039 2838 5039 2840 5040 2841 5040 2839 5040 2840 5041 2842 5041 2841 5041 2840 5042 2843 5042 2842 5042 2844 5043 2843 5043 2840 5043 2844 5044 2845 5044 2843 5044 2844 5045 2846 5045 2845 5045 2847 5046 2846 5046 2844 5046 2847 5047 2848 5047 2846 5047 2849 5048 2848 5048 2847 5048 2850 5049 2848 5049 2849 5049 2850 5050 2851 5050 2848 5050 2852 5051 2851 5051 2850 5051 2852 5052 2853 5052 2851 5052 2852 5053 2854 5053 2853 5053 2855 5054 2854 5054 2852 5054 2855 5055 2856 5055 2854 5055 2857 5056 2856 5056 2855 5056 2857 5057 2858 5057 2856 5057 2859 5058 2858 5058 2857 5058 2859 5059 2860 5059 2858 5059 2859 5060 2861 5060 2860 5060 2862 5061 2861 5061 2859 5061 2862 5062 2863 5062 2861 5062 2864 5063 2863 5063 2862 5063 2864 5064 2865 5064 2863 5064 2864 5065 2866 5065 2865 5065 2867 5066 2866 5066 2864 5066 2867 5067 2868 5067 2866 5067 2867 5068 2869 5068 2868 5068 2870 5069 2869 5069 2867 5069 2872 5070 2871 5070 2870 5070 2870 5071 2871 5071 2869 5071 2872 5072 2873 5072 2871 5072 2874 5073 2873 5073 2872 5073 2874 5074 2875 5074 2873 5074 2876 5075 2875 5075 2874 5075 2876 5076 2877 5076 2875 5076 2876 5077 2878 5077 2877 5077 2879 5078 2878 5078 2876 5078 2879 5079 2880 5079 2878 5079 2881 5080 2880 5080 2879 5080 2881 5081 2882 5081 2880 5081 2883 5082 2882 5082 2881 5082 2883 5083 2884 5083 2882 5083 2883 5084 2885 5084 2884 5084 2886 5085 2885 5085 2883 5085 2886 5086 2887 5086 2885 5086 2888 5087 2887 5087 2886 5087 2888 5088 2889 5088 2887 5088 2888 5089 2890 5089 2889 5089 2891 5090 2890 5090 2888 5090 2891 5091 2892 5091 2890 5091 2893 5092 2892 5092 2891 5092 2893 5093 2894 5093 2892 5093 2895 5094 2894 5094 2893 5094 2895 5095 2896 5095 2894 5095 2897 5096 2896 5096 2895 5096 2897 5097 2898 5097 2896 5097 2899 5098 2898 5098 2897 5098 2899 5099 2900 5099 2898 5099 2901 5100 2900 5100 2899 5100 2901 5101 2407 5101 2900 5101 2902 5102 2407 5102 2901 5102 2902 5103 2404 5103 2407 5103 2903 5104 2404 5104 2902 5104 2903 5105 2402 5105 2404 5105 2904 5106 2402 5106 2903 5106 2904 5107 2396 5107 2402 5107 2905 5108 2428 5108 2425 5108 2906 5109 2428 5109 2905 5109 2430 5110 2428 5110 2906 5110 2907 5111 2430 5111 2906 5111 2433 5112 2430 5112 2907 5112 2908 5113 2433 5113 2907 5113 2435 5114 2433 5114 2908 5114 2909 5115 2435 5115 2908 5115 2438 5116 2435 5116 2909 5116 2910 5117 2438 5117 2909 5117 2441 5118 2438 5118 2910 5118 2911 5119 2441 5119 2910 5119 2443 5120 2441 5120 2911 5120 2445 5121 2443 5121 2911 5121 2912 5122 2445 5122 2911 5122 2913 5123 2445 5123 2912 5123 2448 5124 2445 5124 2913 5124 2914 5125 2448 5125 2913 5125 2450 5126 2448 5126 2914 5126 2915 5127 2450 5127 2914 5127 2452 5128 2450 5128 2915 5128 2455 5129 2452 5129 2915 5129 2916 5130 2455 5130 2915 5130 2917 5131 2455 5131 2916 5131 2458 5132 2455 5132 2917 5132 2918 5133 2458 5133 2917 5133 2460 5134 2458 5134 2918 5134 2919 5135 2460 5135 2918 5135 2462 5136 2460 5136 2919 5136 2920 5137 2462 5137 2919 5137 2465 5138 2462 5138 2920 5138 2921 5139 2465 5139 2920 5139 2466 5140 2465 5140 2921 5140 2922 5141 2466 5141 2921 5141 2469 5142 2466 5142 2922 5142 2923 5143 2469 5143 2922 5143 2471 5144 2469 5144 2923 5144 2473 5145 2471 5145 2923 5145 2924 5146 2473 5146 2923 5146 2475 5147 2473 5147 2924 5147 2925 5148 2475 5148 2924 5148 2477 5149 2475 5149 2925 5149 2926 5150 2477 5150 2925 5150 2480 5151 2477 5151 2926 5151 2927 5152 2480 5152 2926 5152 2482 5153 2480 5153 2927 5153 2928 5154 2482 5154 2927 5154 2484 5155 2482 5155 2928 5155 2929 5156 2484 5156 2928 5156 2486 5157 2484 5157 2929 5157 2930 5158 2486 5158 2929 5158 2490 5159 2486 5159 2930 5159 2931 5160 2490 5160 2930 5160 2492 5161 2490 5161 2931 5161 2932 5162 2492 5162 2931 5162 2494 5163 2492 5163 2932 5163 2933 5164 2494 5164 2932 5164 2496 5165 2494 5165 2933 5165 2934 5166 2496 5166 2933 5166 2498 5167 2496 5167 2934 5167 2935 5168 2498 5168 2934 5168 2501 5169 2498 5169 2935 5169 2936 5170 2501 5170 2935 5170 2504 5171 2501 5171 2936 5171 2937 5172 2504 5172 2936 5172 2506 5173 2504 5173 2937 5173 2938 5174 2506 5174 2937 5174 2508 5175 2506 5175 2938 5175 2939 5176 2508 5176 2938 5176 2510 5177 2508 5177 2939 5177 2512 5178 2510 5178 2939 5178 2940 5179 2512 5179 2939 5179 2514 5180 2512 5180 2940 5180 2941 5181 2516 5181 2514 5181 2518 5182 2516 5182 2941 5182 2942 5183 2518 5183 2941 5183 2520 5184 2518 5184 2942 5184 2943 5185 2520 5185 2942 5185 2524 5186 2520 5186 2943 5186 2944 5187 2524 5187 2943 5187 2526 5188 2524 5188 2944 5188 2945 5189 2526 5189 2944 5189 2528 5190 2526 5190 2945 5190 2946 5191 2528 5191 2945 5191 2532 5192 2528 5192 2946 5192 2947 5193 2532 5193 2946 5193 2948 5194 2532 5194 2947 5194 2534 5195 2532 5195 2948 5195 2949 5196 2534 5196 2948 5196 2537 5197 2534 5197 2949 5197 2950 5198 2537 5198 2949 5198 2539 5199 2537 5199 2950 5199 2951 5200 2539 5200 2950 5200 2542 5201 2539 5201 2951 5201 2952 5202 2542 5202 2951 5202 2953 5203 2542 5203 2952 5203 2544 5204 2542 5204 2953 5204 2954 5205 2544 5205 2953 5205 2546 5206 2544 5206 2954 5206 2955 5207 2546 5207 2954 5207 2549 5208 2546 5208 2955 5208 2956 5209 2549 5209 2955 5209 2551 5210 2549 5210 2956 5210 2957 5211 2551 5211 2956 5211 2553 5212 2551 5212 2957 5212 2555 5213 2553 5213 2957 5213 2958 5214 2555 5214 2957 5214 2557 5215 2555 5215 2958 5215 2959 5216 2557 5216 2958 5216 2559 5217 2557 5217 2959 5217 2561 5218 2559 5218 2959 5218 2960 5219 2561 5219 2959 5219 2564 5220 2561 5220 2960 5220 2961 5221 2564 5221 2960 5221 2567 5222 2564 5222 2961 5222 2962 5223 2567 5223 2961 5223 2963 5224 2567 5224 2962 5224 2569 5225 2567 5225 2963 5225 2964 5226 2569 5226 2963 5226 2571 5227 2569 5227 2964 5227 2965 5228 2571 5228 2964 5228 2573 5229 2571 5229 2965 5229 2966 5230 2573 5230 2965 5230 2576 5231 2573 5231 2966 5231 2967 5232 2576 5232 2966 5232 2579 5233 2576 5233 2967 5233 2968 5234 2579 5234 2967 5234 2582 5235 2579 5235 2968 5235 2969 5236 2582 5236 2968 5236 2584 5237 2582 5237 2969 5237 2970 5238 2584 5238 2969 5238 2586 5239 2584 5239 2970 5239 2971 5240 2586 5240 2970 5240 2590 5241 2586 5241 2971 5241 2972 5242 2590 5242 2971 5242 2973 5243 2590 5243 2972 5243 2592 5244 2590 5244 2973 5244 2594 5245 2592 5245 2973 5245 2596 5246 2594 5246 2974 5246 2598 5247 2596 5247 2974 5247 2975 5248 2598 5248 2974 5248 2600 5249 2598 5249 2975 5249 2976 5250 2600 5250 2975 5250 2977 5251 2600 5251 2976 5251 2602 5252 2600 5252 2977 5252 2978 5253 2602 5253 2977 5253 2605 5254 2602 5254 2978 5254 2979 5255 2605 5255 2978 5255 2607 5256 2605 5256 2979 5256 2609 5257 2607 5257 2979 5257 2980 5258 2609 5258 2979 5258 2981 5259 2609 5259 2980 5259 2611 5260 2609 5260 2981 5260 2982 5261 2611 5261 2981 5261 2613 5262 2611 5262 2982 5262 2983 5263 2613 5263 2982 5263 2616 5264 2613 5264 2983 5264 2618 5265 2616 5265 2983 5265 2984 5266 2618 5266 2983 5266 2620 5267 2618 5267 2984 5267 2985 5268 2620 5268 2984 5268 2622 5269 2620 5269 2985 5269 2624 5270 2622 5270 2985 5270 2624 5271 2985 5271 2986 5271 2987 5272 2624 5272 2986 5272 2627 5273 2624 5273 2987 5273 2988 5274 2627 5274 2987 5274 2630 5275 2627 5275 2988 5275 2989 5276 2630 5276 2988 5276 2633 5277 2630 5277 2989 5277 2635 5278 2633 5278 2989 5278 2990 5279 2635 5279 2989 5279 2637 5280 2635 5280 2990 5280 2991 5281 2637 5281 2990 5281 2639 5282 2637 5282 2991 5282 2992 5283 2639 5283 2991 5283 2641 5284 2639 5284 2992 5284 2643 5285 2641 5285 2992 5285 2993 5286 2643 5286 2992 5286 2646 5287 2643 5287 2993 5287 2994 5288 2646 5288 2993 5288 2648 5289 2646 5289 2994 5289 2995 5290 2648 5290 2994 5290 2650 5291 2648 5291 2995 5291 2996 5292 2650 5292 2995 5292 2652 5293 2650 5293 2996 5293 2997 5294 2652 5294 2996 5294 2654 5295 2652 5295 2997 5295 2998 5296 2654 5296 2997 5296 2657 5297 2654 5297 2998 5297 2999 5298 2657 5298 2998 5298 2660 5299 2657 5299 2999 5299 2661 5300 2660 5300 2999 5300 3000 5301 2661 5301 2999 5301 2664 5302 2661 5302 3000 5302 3001 5303 2664 5303 3000 5303 2666 5304 2664 5304 3001 5304 3002 5305 2666 5305 3001 5305 2669 5306 2666 5306 3002 5306 3003 5307 2669 5307 3002 5307 2671 5308 2669 5308 3003 5308 3004 5309 2671 5309 3003 5309 2673 5310 2671 5310 3004 5310 3005 5311 2673 5311 3004 5311 2675 5312 2673 5312 3005 5312 2677 5313 2675 5313 3005 5313 3006 5314 2677 5314 3005 5314 2679 5315 2677 5315 3006 5315 3007 5316 2681 5316 2679 5316 2684 5317 2681 5317 3007 5317 3008 5318 2684 5318 3007 5318 2686 5319 2684 5319 3008 5319 3009 5320 2686 5320 3008 5320 3010 5321 2686 5321 3009 5321 2689 5322 2686 5322 3010 5322 2691 5323 2689 5323 3010 5323 3011 5324 2691 5324 3010 5324 2694 5325 2691 5325 3011 5325 3012 5326 2694 5326 3011 5326 2696 5327 2694 5327 3012 5327 3013 5328 2696 5328 3012 5328 2698 5329 2696 5329 3013 5329 3014 5330 2698 5330 3013 5330 2700 5331 2698 5331 3014 5331 3015 5332 2700 5332 3014 5332 2703 5333 2700 5333 3015 5333 3016 5334 2703 5334 3015 5334 2705 5335 2703 5335 3016 5335 2707 5336 2705 5336 3016 5336 3017 5337 2707 5337 3016 5337 2709 5338 2707 5338 3017 5338 3018 5339 2709 5339 3017 5339 2711 5340 2709 5340 3018 5340 3019 5341 2711 5341 3018 5341 2713 5342 2711 5342 3019 5342 3020 5343 2715 5343 2713 5343 2718 5344 2715 5344 3020 5344 3021 5345 2718 5345 3020 5345 2720 5346 2718 5346 3021 5346 3022 5347 2720 5347 3021 5347 2722 5348 2720 5348 3022 5348 2724 5349 2722 5349 3022 5349 3023 5350 2724 5350 3022 5350 2726 5351 2724 5351 3023 5351 3024 5352 2726 5352 3023 5352 2728 5353 2726 5353 3024 5353 3025 5354 2728 5354 3024 5354 2730 5355 2728 5355 3025 5355 3026 5356 2730 5356 3025 5356 2732 5357 2730 5357 3026 5357 3027 5358 2732 5358 3026 5358 2735 5359 2732 5359 3027 5359 3028 5360 2735 5360 3027 5360 2738 5361 2735 5361 3028 5361 3029 5362 2738 5362 3028 5362 2741 5363 2738 5363 3029 5363 3030 5364 2741 5364 3029 5364 3031 5365 2741 5365 3030 5365 2744 5366 2741 5366 3031 5366 3032 5367 2744 5367 3031 5367 2746 5368 2744 5368 3032 5368 3033 5369 2746 5369 3032 5369 2749 5370 2746 5370 3033 5370 3034 5371 2749 5371 3033 5371 2752 5372 2749 5372 3034 5372 3035 5373 2752 5373 3034 5373 2754 5374 2752 5374 3035 5374 3036 5375 2754 5375 3035 5375 2757 5376 2754 5376 3036 5376 3037 5377 2757 5377 3036 5377 2758 5378 2757 5378 3037 5378 3038 5379 2758 5379 3037 5379 2760 5380 2758 5380 3038 5380 3039 5381 2760 5381 3038 5381 2763 5382 2760 5382 3039 5382 2765 5383 2763 5383 3039 5383 3040 5384 2765 5384 3039 5384 2767 5385 2765 5385 3040 5385 3041 5386 2767 5386 3040 5386 3042 5387 2767 5387 3041 5387 2770 5388 2767 5388 3042 5388 2772 5389 2770 5389 3042 5389 3043 5390 2772 5390 3042 5390 2774 5391 2772 5391 3043 5391 3044 5392 2774 5392 3043 5392 2776 5393 2774 5393 3044 5393 3045 5394 2776 5394 3044 5394 2778 5395 2776 5395 3045 5395 3046 5396 2778 5396 3045 5396 2780 5397 2778 5397 3046 5397 3047 5398 2780 5398 3046 5398 2783 5399 2780 5399 3047 5399 3048 5400 2783 5400 3047 5400 3049 5401 2783 5401 3048 5401 2785 5402 2783 5402 3049 5402 2787 5403 2785 5403 3049 5403 3050 5404 2787 5404 3049 5404 2789 5405 2787 5405 3050 5405 3051 5406 2789 5406 3050 5406 2791 5407 2789 5407 3051 5407 3052 5408 2791 5408 3051 5408 2793 5409 2791 5409 3052 5409 3053 5410 2793 5410 3052 5410 2796 5411 2793 5411 3053 5411 2798 5412 2796 5412 3054 5412 3055 5413 2798 5413 3054 5413 2800 5414 2798 5414 3055 5414 2802 5415 2800 5415 3055 5415 3056 5416 2802 5416 3055 5416 2805 5417 2802 5417 3056 5417 3057 5418 2805 5418 3056 5418 2807 5419 2805 5419 3057 5419 3058 5420 2807 5420 3057 5420 2809 5421 2807 5421 3058 5421 3059 5422 2809 5422 3058 5422 2811 5423 2809 5423 3059 5423 2814 5424 2811 5424 3059 5424 3060 5425 2814 5425 3059 5425 3061 5426 2814 5426 3060 5426 2817 5427 2814 5427 3061 5427 3062 5428 2817 5428 3061 5428 2819 5429 2817 5429 3062 5429 3063 5430 2819 5430 3062 5430 2821 5431 2819 5431 3063 5431 2823 5432 2821 5432 3063 5432 3064 5433 2823 5433 3063 5433 2825 5434 2823 5434 3064 5434 3065 5435 2825 5435 3064 5435 2828 5436 2825 5436 3065 5436 3066 5437 2828 5437 3065 5437 2830 5438 2828 5438 3066 5438 3067 5439 2830 5439 3066 5439 3068 5440 2830 5440 3067 5440 2833 5441 2830 5441 3068 5441 2835 5442 2833 5442 3068 5442 3069 5443 2835 5443 3068 5443 2838 5444 2835 5444 3069 5444 3070 5445 2838 5445 3069 5445 2840 5446 2838 5446 3070 5446 3071 5447 2840 5447 3070 5447 3072 5448 2840 5448 3071 5448 2844 5449 2840 5449 3072 5449 3073 5450 2844 5450 3072 5450 2847 5451 2844 5451 3073 5451 2849 5452 2847 5452 3073 5452 3074 5453 2849 5453 3073 5453 2850 5454 2849 5454 3074 5454 3075 5455 2850 5455 3074 5455 2852 5456 2850 5456 3075 5456 3076 5457 2852 5457 3075 5457 2855 5458 2852 5458 3076 5458 3077 5459 2855 5459 3076 5459 2857 5460 2855 5460 3077 5460 3078 5461 2857 5461 3077 5461 2859 5462 2857 5462 3078 5462 3079 5463 2859 5463 3078 5463 2862 5464 2859 5464 3079 5464 2864 5465 2862 5465 3080 5465 3081 5466 2864 5466 3080 5466 2867 5467 2864 5467 3081 5467 3082 5468 2867 5468 3081 5468 2870 5469 2867 5469 3082 5469 2872 5470 2870 5470 3082 5470 3083 5471 2872 5471 3082 5471 2874 5472 2872 5472 3083 5472 3084 5473 2874 5473 3083 5473 2876 5474 2874 5474 3084 5474 2879 5475 2876 5475 3084 5475 3085 5476 2879 5476 3084 5476 3086 5477 2879 5477 3085 5477 2881 5478 2879 5478 3086 5478 2883 5479 2881 5479 3086 5479 3087 5480 2883 5480 3086 5480 2886 5481 2883 5481 3087 5481 3088 5482 2886 5482 3087 5482 2888 5483 2886 5483 3088 5483 3089 5484 2888 5484 3088 5484 2891 5485 2888 5485 3089 5485 3090 5486 2891 5486 3089 5486 2893 5487 2891 5487 3090 5487 3091 5488 2893 5488 3090 5488 2895 5489 2893 5489 3091 5489 3092 5490 2895 5490 3091 5490 2897 5491 2895 5491 3092 5491 3093 5492 2897 5492 3092 5492 2899 5493 2897 5493 3093 5493 3094 5494 2899 5494 3093 5494 2901 5495 2899 5495 3094 5495 2902 5496 2901 5496 3094 5496 3095 5497 2902 5497 3094 5497 2903 5498 2902 5498 3095 5498 2904 5499 2903 5499 3095 5499 3096 5500 2904 5500 3095 5500 2396 5501 2904 5501 3096 5501 3097 5502 2396 5502 3096 5502 2394 5503 2396 5503 3097 5503 3098 5504 2394 5504 3097 5504 2399 5505 2394 5505 3098 5505 3099 5506 2907 5506 2906 5506 3101 5507 2907 5507 3099 5507 3101 5508 2908 5508 2907 5508 3101 5509 2909 5509 2908 5509 3100 5510 2909 5510 3101 5510 3102 5511 2909 5511 3100 5511 3102 5512 2910 5512 2909 5512 3103 5513 2910 5513 3102 5513 3103 5514 2911 5514 2910 5514 2414 5515 2911 5515 3103 5515 2414 5516 2912 5516 2911 5516 2415 5517 2912 5517 2414 5517 2415 5518 2913 5518 2912 5518 2417 5519 2913 5519 2415 5519 2420 5520 2913 5520 2417 5520 2420 5521 2914 5521 2913 5521 2420 5522 2915 5522 2914 5522 2422 5523 2915 5523 2420 5523 2424 5524 2915 5524 2422 5524 2424 5525 2916 5525 2915 5525 2426 5526 2916 5526 2424 5526 2426 5527 2917 5527 2916 5527 2429 5528 2917 5528 2426 5528 2429 5529 2918 5529 2917 5529 2431 5530 2918 5530 2429 5530 2431 5531 2919 5531 2918 5531 3104 5532 2919 5532 2431 5532 3104 5533 2920 5533 2919 5533 2436 5534 2920 5534 3104 5534 2436 5535 2921 5535 2920 5535 2437 5536 2921 5536 2436 5536 2439 5537 2921 5537 2437 5537 2439 5538 2922 5538 2921 5538 2440 5539 2922 5539 2439 5539 2440 5540 2923 5540 2922 5540 2442 5541 2923 5541 2440 5541 2444 5542 2923 5542 2442 5542 2444 5543 2924 5543 2923 5543 3105 5544 2924 5544 2444 5544 3105 5545 2925 5545 2924 5545 2447 5546 2925 5546 3105 5546 2447 5547 2926 5547 2925 5547 2449 5548 2926 5548 2447 5548 2451 5549 2926 5549 2449 5549 2451 5550 2927 5550 2926 5550 2453 5551 2927 5551 2451 5551 2453 5552 2928 5552 2927 5552 2454 5553 2928 5553 2453 5553 2454 5554 2929 5554 2928 5554 2456 5555 2929 5555 2454 5555 2456 5556 2930 5556 2929 5556 2457 5557 2930 5557 2456 5557 2459 5558 2930 5558 2457 5558 2459 5559 2931 5559 2930 5559 2461 5560 2931 5560 2459 5560 2463 5561 2931 5561 2461 5561 2463 5562 2932 5562 2931 5562 2464 5563 2932 5563 2463 5563 2464 5564 2933 5564 2932 5564 2467 5565 2933 5565 2464 5565 2467 5566 2934 5566 2933 5566 2468 5567 2934 5567 2467 5567 2468 5568 2935 5568 2934 5568 2470 5569 2935 5569 2468 5569 2472 5570 2935 5570 2470 5570 2472 5571 2936 5571 2935 5571 2474 5572 2936 5572 2472 5572 2476 5573 2936 5573 2474 5573 2476 5574 2937 5574 2936 5574 2478 5575 2937 5575 2476 5575 2478 5576 2938 5576 2937 5576 3106 5577 2938 5577 2478 5577 3106 5578 2939 5578 2938 5578 2481 5579 2939 5579 3106 5579 2481 5580 2940 5580 2939 5580 2483 5581 2940 5581 2481 5581 2483 5582 2514 5582 2940 5582 2485 5583 2514 5583 2483 5583 2485 5584 2941 5584 2514 5584 2487 5585 2941 5585 2485 5585 2488 5586 2941 5586 2487 5586 2488 5587 2942 5587 2941 5587 2489 5588 2942 5588 2488 5588 2491 5589 2942 5589 2489 5589 2491 5590 2943 5590 2942 5590 2491 5591 2944 5591 2943 5591 2493 5592 2944 5592 2491 5592 2495 5593 2944 5593 2493 5593 2495 5594 2945 5594 2944 5594 2497 5595 2945 5595 2495 5595 2497 5596 2946 5596 2945 5596 2499 5597 2946 5597 2497 5597 2500 5598 2946 5598 2499 5598 2500 5599 2947 5599 2946 5599 2502 5600 2947 5600 2500 5600 2502 5601 2948 5601 2947 5601 2503 5602 2948 5602 2502 5602 2503 5603 2949 5603 2948 5603 2505 5604 2949 5604 2503 5604 2507 5605 2950 5605 2505 5605 2505 5606 2950 5606 2949 5606 2509 5607 2951 5607 2507 5607 2507 5608 2951 5608 2950 5608 2511 5609 2951 5609 2509 5609 2511 5610 2952 5610 2951 5610 2513 5611 2952 5611 2511 5611 2513 5612 2953 5612 2952 5612 2515 5613 2953 5613 2513 5613 2515 5614 2954 5614 2953 5614 2517 5615 2954 5615 2515 5615 2519 5616 2954 5616 2517 5616 2519 5617 2955 5617 2954 5617 2521 5618 2955 5618 2519 5618 2521 5619 2956 5619 2955 5619 2522 5620 2956 5620 2521 5620 2522 5621 2957 5621 2956 5621 2523 5622 2957 5622 2522 5622 2525 5623 2957 5623 2523 5623 2525 5624 2958 5624 2957 5624 2529 5625 2958 5625 2525 5625 2530 5626 2958 5626 2529 5626 2530 5627 2959 5627 2958 5627 2531 5628 2959 5628 2530 5628 2531 5629 2960 5629 2959 5629 2533 5630 2960 5630 2531 5630 2533 5631 2961 5631 2960 5631 2535 5632 2961 5632 2533 5632 2535 5633 2962 5633 2961 5633 2536 5634 2962 5634 2535 5634 2536 5635 2963 5635 2962 5635 2540 5636 2963 5636 2536 5636 2540 5637 2964 5637 2963 5637 2541 5638 2964 5638 2540 5638 2541 5639 2965 5639 2964 5639 2543 5640 2965 5640 2541 5640 2545 5641 2965 5641 2543 5641 2545 5642 2966 5642 2965 5642 2547 5643 2966 5643 2545 5643 2547 5644 2967 5644 2966 5644 2548 5645 2967 5645 2547 5645 2548 5646 2968 5646 2967 5646 2550 5647 2968 5647 2548 5647 2552 5648 2968 5648 2550 5648 2552 5649 2969 5649 2968 5649 2554 5650 2969 5650 2552 5650 2554 5651 2970 5651 2969 5651 2556 5652 2970 5652 2554 5652 2556 5653 2971 5653 2970 5653 2558 5654 2971 5654 2556 5654 2560 5655 2971 5655 2558 5655 2560 5656 2972 5656 2971 5656 2562 5657 2972 5657 2560 5657 2562 5658 2973 5658 2972 5658 2563 5659 2973 5659 2562 5659 2565 5660 2973 5660 2563 5660 2565 5661 2594 5661 2973 5661 3107 5662 2594 5662 2565 5662 3107 5663 2974 5663 2594 5663 3108 5664 2974 5664 3107 5664 3108 5665 2975 5665 2974 5665 2570 5666 2975 5666 3108 5666 2572 5667 2975 5667 2570 5667 2572 5668 2976 5668 2975 5668 2574 5669 2977 5669 2572 5669 2572 5670 2977 5670 2976 5670 2575 5671 2977 5671 2574 5671 2575 5672 2978 5672 2977 5672 2577 5673 2978 5673 2575 5673 2577 5674 2979 5674 2978 5674 2578 5675 2979 5675 2577 5675 2580 5676 2979 5676 2578 5676 2580 5677 2980 5677 2979 5677 2581 5678 2980 5678 2580 5678 2581 5679 2981 5679 2980 5679 2583 5680 2981 5680 2581 5680 2583 5681 2982 5681 2981 5681 2585 5682 2982 5682 2583 5682 2585 5683 2983 5683 2982 5683 2587 5684 2983 5684 2585 5684 2587 5685 2984 5685 2983 5685 2588 5686 2984 5686 2587 5686 2589 5687 2984 5687 2588 5687 2589 5688 2985 5688 2984 5688 2591 5689 2985 5689 2589 5689 2593 5690 2985 5690 2591 5690 2593 5691 2986 5691 2985 5691 2595 5692 2986 5692 2593 5692 2595 5693 2987 5693 2986 5693 2597 5694 2987 5694 2595 5694 2597 5695 2988 5695 2987 5695 2599 5696 2988 5696 2597 5696 3109 5697 2988 5697 2599 5697 3109 5698 2989 5698 2988 5698 3110 5699 2989 5699 3109 5699 2604 5700 2989 5700 3110 5700 2604 5701 2990 5701 2989 5701 2606 5702 2990 5702 2604 5702 2606 5703 2991 5703 2990 5703 2608 5704 2991 5704 2606 5704 2608 5705 2992 5705 2991 5705 2610 5706 2992 5706 2608 5706 2612 5707 2992 5707 2610 5707 2612 5708 2993 5708 2992 5708 2614 5709 2993 5709 2612 5709 2615 5710 2993 5710 2614 5710 2617 5711 2994 5711 2615 5711 2615 5712 2994 5712 2993 5712 2619 5713 2994 5713 2617 5713 2621 5714 2995 5714 2619 5714 2619 5715 2995 5715 2994 5715 2623 5716 2995 5716 2621 5716 2623 5717 2996 5717 2995 5717 2625 5718 2996 5718 2623 5718 2625 5719 2997 5719 2996 5719 2626 5720 2997 5720 2625 5720 2628 5721 2997 5721 2626 5721 2628 5722 2998 5722 2997 5722 2628 5723 2999 5723 2998 5723 2631 5724 2999 5724 2628 5724 2632 5725 2999 5725 2631 5725 2632 5726 3000 5726 2999 5726 2634 5727 3000 5727 2632 5727 2634 5728 3001 5728 3000 5728 2636 5729 3001 5729 2634 5729 2636 5730 3002 5730 3001 5730 2638 5731 3002 5731 2636 5731 2640 5732 3002 5732 2638 5732 2640 5733 3003 5733 3002 5733 2642 5734 3003 5734 2640 5734 2642 5735 3004 5735 3003 5735 2644 5736 3004 5736 2642 5736 2644 5737 3005 5737 3004 5737 2645 5738 3005 5738 2644 5738 3111 5739 3005 5739 2645 5739 3111 5740 3006 5740 3005 5740 3112 5741 3006 5741 3111 5741 3112 5742 2679 5742 3006 5742 2649 5743 2679 5743 3112 5743 2649 5744 3007 5744 2679 5744 2651 5745 3007 5745 2649 5745 2653 5746 3007 5746 2651 5746 2653 5747 3008 5747 3007 5747 2655 5748 3008 5748 2653 5748 2655 5749 3009 5749 3008 5749 2656 5750 3009 5750 2655 5750 2658 5751 3009 5751 2656 5751 2658 5752 3010 5752 3009 5752 2659 5753 3010 5753 2658 5753 2662 5754 3010 5754 2659 5754 2662 5755 3011 5755 3010 5755 2663 5756 3011 5756 2662 5756 2665 5757 3011 5757 2663 5757 2665 5758 3012 5758 3011 5758 3113 5759 3012 5759 2665 5759 3113 5760 3013 5760 3012 5760 2667 5761 3013 5761 3113 5761 2668 5762 3013 5762 2667 5762 2668 5763 3014 5763 3013 5763 2670 5764 3014 5764 2668 5764 2670 5765 3015 5765 3014 5765 2672 5766 3015 5766 2670 5766 2674 5767 3015 5767 2672 5767 2674 5768 3016 5768 3015 5768 3114 5769 3016 5769 2674 5769 3114 5770 3017 5770 3016 5770 2676 5771 3017 5771 3114 5771 2676 5772 3018 5772 3017 5772 2678 5773 3018 5773 2676 5773 2678 5774 3019 5774 3018 5774 2680 5775 3019 5775 2678 5775 2682 5776 3019 5776 2680 5776 2682 5777 2713 5777 3019 5777 2683 5778 2713 5778 2682 5778 2683 5779 3020 5779 2713 5779 2685 5780 3020 5780 2683 5780 2687 5781 3020 5781 2685 5781 2687 5782 3021 5782 3020 5782 2688 5783 3021 5783 2687 5783 2690 5784 3021 5784 2688 5784 2690 5785 3022 5785 3021 5785 3115 5786 3022 5786 2690 5786 2692 5787 3022 5787 3115 5787 2692 5788 3023 5788 3022 5788 3116 5789 3023 5789 2692 5789 3116 5790 3024 5790 3023 5790 2697 5791 3024 5791 3116 5791 2697 5792 3025 5792 3024 5792 2699 5793 3025 5793 2697 5793 2701 5794 3025 5794 2699 5794 2701 5795 3026 5795 3025 5795 2702 5796 3026 5796 2701 5796 2704 5797 3026 5797 2702 5797 2704 5798 3027 5798 3026 5798 2706 5799 3027 5799 2704 5799 2708 5800 3027 5800 2706 5800 2708 5801 3028 5801 3027 5801 2710 5802 3028 5802 2708 5802 2710 5803 3029 5803 3028 5803 2712 5804 3029 5804 2710 5804 2712 5805 3030 5805 3029 5805 2712 5806 3031 5806 3030 5806 2714 5807 3031 5807 2712 5807 2716 5808 3031 5808 2714 5808 2716 5809 3032 5809 3031 5809 2717 5810 3032 5810 2716 5810 2717 5811 3033 5811 3032 5811 2719 5812 3033 5812 2717 5812 2721 5813 3033 5813 2719 5813 2721 5814 3034 5814 3033 5814 2723 5815 3034 5815 2721 5815 2723 5816 3035 5816 3034 5816 2725 5817 3035 5817 2723 5817 2725 5818 3036 5818 3035 5818 3117 5819 3036 5819 2725 5819 2727 5820 3036 5820 3117 5820 2727 5821 3037 5821 3036 5821 2729 5822 3037 5822 2727 5822 2731 5823 3037 5823 2729 5823 2731 5824 3038 5824 3037 5824 2733 5825 3038 5825 2731 5825 2733 5826 3039 5826 3038 5826 2734 5827 3039 5827 2733 5827 2734 5828 3040 5828 3039 5828 2736 5829 3040 5829 2734 5829 2736 5830 3041 5830 3040 5830 2737 5831 3041 5831 2736 5831 2739 5832 3041 5832 2737 5832 2739 5833 3042 5833 3041 5833 2740 5834 3042 5834 2739 5834 2742 5835 3042 5835 2740 5835 2742 5836 3043 5836 3042 5836 2743 5837 3043 5837 2742 5837 2743 5838 3044 5838 3043 5838 2745 5839 3044 5839 2743 5839 2745 5840 3045 5840 3044 5840 2747 5841 3045 5841 2745 5841 2750 5842 3045 5842 2747 5842 2750 5843 3046 5843 3045 5843 2751 5844 3046 5844 2750 5844 2751 5845 3047 5845 3046 5845 2753 5846 3047 5846 2751 5846 2753 5847 3048 5847 3047 5847 2755 5848 3048 5848 2753 5848 2755 5849 3049 5849 3048 5849 2756 5850 3049 5850 2755 5850 2759 5851 3049 5851 2756 5851 2759 5852 3050 5852 3049 5852 2761 5853 3050 5853 2759 5853 2762 5854 3050 5854 2761 5854 2762 5855 3051 5855 3050 5855 2764 5856 3051 5856 2762 5856 2764 5857 3052 5857 3051 5857 2766 5858 3052 5858 2764 5858 2766 5859 3053 5859 3052 5859 2768 5860 3053 5860 2766 5860 2768 5861 2796 5861 3053 5861 2769 5862 2796 5862 2768 5862 2769 5863 3054 5863 2796 5863 2771 5864 3054 5864 2769 5864 2771 5865 3055 5865 3054 5865 2773 5866 3055 5866 2771 5866 2775 5867 3055 5867 2773 5867 2775 5868 3056 5868 3055 5868 2777 5869 3056 5869 2775 5869 2777 5870 3057 5870 3056 5870 2779 5871 3057 5871 2777 5871 3118 5872 3057 5872 2779 5872 3118 5873 3058 5873 3057 5873 3118 5874 3059 5874 3058 5874 2782 5875 3059 5875 3118 5875 3119 5876 3059 5876 2782 5876 3119 5877 3060 5877 3059 5877 3120 5878 3060 5878 3119 5878 3120 5879 3061 5879 3060 5879 2788 5880 3061 5880 3120 5880 2788 5881 3062 5881 3061 5881 3121 5882 3062 5882 2788 5882 3121 5883 3063 5883 3062 5883 2792 5884 3063 5884 3121 5884 2792 5885 3064 5885 3063 5885 2794 5886 3064 5886 2792 5886 2795 5887 3064 5887 2794 5887 2795 5888 3065 5888 3064 5888 2797 5889 3065 5889 2795 5889 2797 5890 3066 5890 3065 5890 2799 5891 3066 5891 2797 5891 2801 5892 3066 5892 2799 5892 2801 5893 3067 5893 3066 5893 2803 5894 3067 5894 2801 5894 2803 5895 3068 5895 3067 5895 2804 5896 3068 5896 2803 5896 2804 5897 3069 5897 3068 5897 2806 5898 3069 5898 2804 5898 2808 5899 3069 5899 2806 5899 2808 5900 3070 5900 3069 5900 2810 5901 3070 5901 2808 5901 2810 5902 3071 5902 3070 5902 2812 5903 3071 5903 2810 5903 2812 5904 3072 5904 3071 5904 2813 5905 3072 5905 2812 5905 2815 5906 3072 5906 2813 5906 2815 5907 3073 5907 3072 5907 2816 5908 3073 5908 2815 5908 2818 5909 3073 5909 2816 5909 2818 5910 3074 5910 3073 5910 2820 5911 3074 5911 2818 5911 2822 5912 3074 5912 2820 5912 2822 5913 3075 5913 3074 5913 2824 5914 3075 5914 2822 5914 2824 5915 3076 5915 3075 5915 2826 5916 3076 5916 2824 5916 2826 5917 3077 5917 3076 5917 2827 5918 3077 5918 2826 5918 2829 5919 3077 5919 2827 5919 2829 5920 3078 5920 3077 5920 2831 5921 3078 5921 2829 5921 2831 5922 3079 5922 3078 5922 2832 5923 3079 5923 2831 5923 2832 5924 2862 5924 3079 5924 2834 5925 2862 5925 2832 5925 2834 5926 3080 5926 2862 5926 2836 5927 3080 5927 2834 5927 2837 5928 3080 5928 2836 5928 2837 5929 3081 5929 3080 5929 2839 5930 3081 5930 2837 5930 2839 5931 3082 5931 3081 5931 2841 5932 3082 5932 2839 5932 2842 5933 3082 5933 2841 5933 2842 5934 3083 5934 3082 5934 2843 5935 3083 5935 2842 5935 2845 5936 3083 5936 2843 5936 2845 5937 3084 5937 3083 5937 2846 5938 3084 5938 2845 5938 3122 5939 3084 5939 2846 5939 3122 5940 3085 5940 3084 5940 2851 5941 3085 5941 3122 5941 2851 5942 3086 5942 3085 5942 2853 5943 3086 5943 2851 5943 2853 5944 3087 5944 3086 5944 2854 5945 3087 5945 2853 5945 2854 5946 3088 5946 3087 5946 2856 5947 3088 5947 2854 5947 2858 5948 3088 5948 2856 5948 2858 5949 3089 5949 3088 5949 2860 5950 3089 5950 2858 5950 2861 5951 3089 5951 2860 5951 2861 5952 3090 5952 3089 5952 2863 5953 3090 5953 2861 5953 2863 5954 3091 5954 3090 5954 2866 5955 3091 5955 2863 5955 2866 5956 3092 5956 3091 5956 2868 5957 3092 5957 2866 5957 2868 5958 3093 5958 3092 5958 2869 5959 3093 5959 2868 5959 2871 5960 3093 5960 2869 5960 2871 5961 3094 5961 3093 5961 2873 5962 3094 5962 2871 5962 2873 5963 3095 5963 3094 5963 2875 5964 3095 5964 2873 5964 2877 5965 3095 5965 2875 5965 2877 5966 3096 5966 3095 5966 3123 5967 3096 5967 2877 5967 2878 5968 3096 5968 3123 5968 2878 5969 3097 5969 3096 5969 2880 5970 3097 5970 2878 5970 2882 5971 3098 5971 2880 5971 2880 5972 3098 5972 3097 5972 2884 5973 3098 5973 2882 5973 2884 5974 2399 5974 3098 5974 2885 5975 2399 5975 2884 5975 2885 5976 2403 5976 2399 5976 2887 5977 2403 5977 2885 5977 2887 5978 2405 5978 2403 5978 2889 5979 2405 5979 2887 5979 2890 5980 2405 5980 2889 5980 2890 5981 2409 5981 2405 5981 2892 5982 2409 5982 2890 5982 2894 5983 2409 5983 2892 5983 2894 5984 2412 5984 2409 5984 2896 5985 2412 5985 2894 5985 2896 5986 2413 5986 2412 5986 3103 5987 3102 5987 3124 5987 2414 5988 3103 5988 3124 5988 2429 5989 2426 5989 2427 5989 3104 5990 2431 5990 2432 5990 2434 5991 3104 5991 2432 5991 2436 5992 3104 5992 2434 5992 2446 5993 3105 5993 2444 5993 2447 5994 3105 5994 2446 5994 3106 5995 2478 5995 2479 5995 2481 5996 3106 5996 2479 5996 2529 5997 2525 5997 2527 5997 2540 5998 2536 5998 2538 5998 2566 5999 3107 5999 2565 5999 3108 6000 3107 6000 2566 6000 2568 6001 3108 6001 2566 6001 2570 6002 3108 6002 2568 6002 2601 6003 3109 6003 2599 6003 3110 6004 3109 6004 2601 6004 2603 6005 3110 6005 2601 6005 2604 6006 3110 6006 2603 6006 2631 6007 2628 6007 2629 6007 2647 6008 3111 6008 2645 6008 3112 6009 3111 6009 2647 6009 2649 6010 3112 6010 2647 6010 2667 6011 3113 6011 2665 6011 2676 6012 3114 6012 2674 6012 2692 6013 3115 6013 2690 6013 3116 6014 2692 6014 2693 6014 2695 6015 3116 6015 2693 6015 2697 6016 3116 6016 2695 6016 2727 6017 3117 6017 2725 6017 2750 6018 2747 6018 2748 6018 2781 6019 3118 6019 2779 6019 2782 6020 3118 6020 2781 6020 2784 6021 3119 6021 2782 6021 3120 6022 3119 6022 2784 6022 2786 6023 3120 6023 2784 6023 2788 6024 3120 6024 2786 6024 2790 6025 3121 6025 2788 6025 2792 6026 3121 6026 2790 6026 2848 6027 3122 6027 2846 6027 2851 6028 3122 6028 2848 6028 2866 6029 2863 6029 2865 6029 2878 6030 3123 6030 2877 6030 2413 6031 2896 6031 2898 6031 3130 6032 2413 6032 2898 6032 2900 6033 3126 6033 2898 6033 3126 6034 3171 6034 3125 6034 3127 6035 3126 6035 3125 6035 2898 6036 3126 6036 3127 6036 3129 6037 3127 6037 3125 6037 3129 6038 3125 6038 3128 6038 3130 6039 3127 6039 3129 6039 3130 6040 2898 6040 3127 6040 3131 6041 3129 6041 3128 6041 3132 6042 3130 6042 3129 6042 3132 6043 3129 6043 3131 6043 2413 6044 3130 6044 3132 6044 2412 6045 3132 6045 3131 6045 2412 6046 2413 6046 3132 6046 3134 6047 3131 6047 3128 6047 2412 6048 3131 6048 3134 6048 3134 6049 3128 6049 3133 6049 3135 6050 2412 6050 3134 6050 2411 6051 2412 6051 3135 6051 3135 6052 3134 6052 3133 6052 3135 6053 3133 6053 3137 6053 3136 6054 3137 6054 3133 6054 3138 6055 3135 6055 3137 6055 2411 6056 3135 6056 3138 6056 2410 6057 2411 6057 3138 6057 3139 6058 3138 6058 3137 6058 3139 6059 3137 6059 3136 6059 2410 6060 3138 6060 3139 6060 3140 6061 3139 6061 3136 6061 2408 6062 2410 6062 3139 6062 3141 6063 3139 6063 3140 6063 2408 6064 3139 6064 3141 6064 3143 6065 3140 6065 3136 6065 3142 6066 3140 6066 3143 6066 3142 6067 3141 6067 3140 6067 2406 6068 2408 6068 3141 6068 3144 6069 3141 6069 3142 6069 3143 6070 3136 6070 3145 6070 2406 6071 3141 6071 3144 6071 3146 6072 3142 6072 3143 6072 3144 6073 3147 6073 2406 6073 3146 6074 3144 6074 3142 6074 3146 6075 3143 6075 3145 6075 3147 6076 3144 6076 3146 6076 3148 6077 3146 6077 3145 6077 3148 6078 3147 6078 3146 6078 2400 6079 3147 6079 3148 6079 3151 6080 3148 6080 3145 6080 3151 6081 3150 6081 3148 6081 2400 6082 3148 6082 3150 6082 3151 6083 3145 6083 3149 6083 3152 6084 3151 6084 3149 6084 3153 6085 3150 6085 3151 6085 3153 6086 3151 6086 3152 6086 3153 6087 2398 6087 2400 6087 3153 6088 2400 6088 3150 6088 3155 6089 3153 6089 3152 6089 3152 6090 3149 6090 3154 6090 3155 6091 2398 6091 3153 6091 3156 6092 3152 6092 3154 6092 3156 6093 3155 6093 3152 6093 2395 6094 2398 6094 3155 6094 3156 6095 2395 6095 3155 6095 3158 6096 3156 6096 3154 6096 3159 6097 3156 6097 3158 6097 3157 6098 3158 6098 3154 6098 3159 6099 2395 6099 3156 6099 3159 6100 3158 6100 3160 6100 3160 6101 3158 6101 3157 6101 3160 6102 2395 6102 3159 6102 2397 6103 2395 6103 3160 6103 2397 6104 3160 6104 3161 6104 3163 6105 3160 6105 3157 6105 3163 6106 3161 6106 3160 6106 3162 6107 3163 6107 3157 6107 3164 6108 3161 6108 3163 6108 3164 6109 2397 6109 3161 6109 2401 6110 2397 6110 3164 6110 3165 6111 3163 6111 3162 6111 3165 6112 3164 6112 3163 6112 2402 6113 3164 6113 3165 6113 2402 6114 2401 6114 3164 6114 3167 6115 3165 6115 3162 6115 3167 6116 3162 6116 3166 6116 3168 6117 2402 6117 3165 6117 3168 6118 3165 6118 3167 6118 2404 6119 2402 6119 3168 6119 3169 6120 3168 6120 3167 6120 3169 6121 3167 6121 3166 6121 2404 6122 3168 6122 3169 6122 3170 6123 3169 6123 3166 6123 3169 6124 2407 6124 2404 6124 3171 6125 3170 6125 3166 6125 3171 6126 3166 6126 3125 6126 2407 6127 3169 6127 3170 6127 3172 6128 3170 6128 3171 6128 3173 6129 2407 6129 3170 6129 3173 6130 3170 6130 3172 6130 3173 6131 2900 6131 2407 6131 3172 6132 3171 6132 3126 6132 3126 6133 3173 6133 3172 6133 2900 6134 3173 6134 3126 6134 3136 6135 3125 6135 3166 6135 3136 6136 3128 6136 3125 6136 3136 6137 3149 6137 3145 6137 3136 6138 3166 6138 3162 6138 3136 6139 3157 6139 3154 6139 3136 6140 3162 6140 3157 6140 3136 6141 3154 6141 3149 6141 3136 6142 3133 6142 3128 6142 3175 6143 3243 6143 3174 6143 3175 6144 3174 6144 3176 6144 3175 6145 3241 6145 3243 6145 3177 6146 3175 6146 3176 6146 3178 6147 3241 6147 3175 6147 3178 6148 3175 6148 3177 6148 3179 6149 3177 6149 3180 6149 3179 6150 3178 6150 3177 6150 3181 6151 3178 6151 3179 6151 3181 6152 3179 6152 3180 6152 3182 6153 3181 6153 3180 6153 3183 6154 3178 6154 3181 6154 3184 6155 3181 6155 3182 6155 3185 6156 3184 6156 3182 6156 3183 6157 3188 6157 3178 6157 3183 6158 3181 6158 3184 6158 3186 6159 3184 6159 3185 6159 3188 6160 3183 6160 3184 6160 3187 6161 3184 6161 3186 6161 3188 6162 3184 6162 3187 6162 3190 6163 3188 6163 3187 6163 3190 6164 3187 6164 3189 6164 3191 6165 3190 6165 3189 6165 3192 6166 3190 6166 3191 6166 3193 6167 3188 6167 3190 6167 3193 6168 3190 6168 3192 6168 3192 6169 3191 6169 3194 6169 3196 6170 3192 6170 3194 6170 3193 6171 3192 6171 3196 6171 3196 6172 3194 6172 3195 6172 3196 6173 3195 6173 3197 6173 3199 6174 3196 6174 3197 6174 3199 6175 3197 6175 3198 6175 3196 6176 3201 6176 3193 6176 3202 6177 3196 6177 3199 6177 3201 6178 3196 6178 3202 6178 3202 6179 3199 6179 3198 6179 3202 6180 3198 6180 3200 6180 3203 6181 3202 6181 3200 6181 3204 6182 3203 6182 3200 6182 3201 6183 3202 6183 3203 6183 3206 6184 3201 6184 3203 6184 3205 6185 3203 6185 3204 6185 3205 6186 3204 6186 3207 6186 3206 6187 3203 6187 3205 6187 3208 6188 3205 6188 3207 6188 3209 6189 3205 6189 3208 6189 3206 6190 3205 6190 3209 6190 3210 6191 3209 6191 3208 6191 3206 6192 3209 6192 3211 6192 3211 6193 3209 6193 3210 6193 3212 6194 3211 6194 3210 6194 3212 6195 3210 6195 3213 6195 3214 6196 3212 6196 3213 6196 3215 6197 3214 6197 3213 6197 3216 6198 3212 6198 3214 6198 3216 6199 3211 6199 3212 6199 3217 6200 3216 6200 3214 6200 3218 6201 3214 6201 3215 6201 3217 6202 3214 6202 3218 6202 3219 6203 3216 6203 3217 6203 3219 6204 3217 6204 3218 6204 3220 6205 3219 6205 3218 6205 3220 6206 3218 6206 3221 6206 3220 6207 3221 6207 3222 6207 3223 6208 3219 6208 3220 6208 3222 6209 3223 6209 3220 6209 3223 6210 3222 6210 3224 6210 3225 6211 3223 6211 3224 6211 3226 6212 3225 6212 3224 6212 3228 6213 3223 6213 3225 6213 3228 6214 3225 6214 3226 6214 3228 6215 3226 6215 3227 6215 3230 6216 3228 6216 3227 6216 3230 6217 3227 6217 3229 6217 3234 6218 3228 6218 3230 6218 3232 6219 3229 6219 3231 6219 3232 6220 3230 6220 3229 6220 3234 6221 3230 6221 3232 6221 3232 6222 3231 6222 3233 6222 3236 6223 3232 6223 3233 6223 3234 6224 3232 6224 3236 6224 3236 6225 3233 6225 3235 6225 3239 6226 3234 6226 3236 6226 3237 6227 3236 6227 3235 6227 3239 6228 3236 6228 3237 6228 3238 6229 3239 6229 3237 6229 3242 6230 3238 6230 3240 6230 3242 6231 3239 6231 3238 6231 3241 6232 3239 6232 3242 6232 3174 6233 3242 6233 3240 6233 3241 6234 3242 6234 3243 6234 3243 6235 3242 6235 3174 6235 3176 6236 3174 6236 3244 6236 3176 6237 3244 6237 3310 6237 3177 6238 3176 6238 3310 6238 3177 6239 3310 6239 3245 6239 3180 6240 3177 6240 3245 6240 3180 6241 3245 6241 3246 6241 3182 6242 3180 6242 3246 6242 3182 6243 3246 6243 3247 6243 3185 6244 3182 6244 3247 6244 3185 6245 3247 6245 3248 6245 3186 6246 3185 6246 3248 6246 3187 6247 3186 6247 3248 6247 3187 6248 3248 6248 3249 6248 3189 6249 3187 6249 3249 6249 3189 6250 3249 6250 3250 6250 3191 6251 3189 6251 3250 6251 3191 6252 3250 6252 3251 6252 3194 6253 3191 6253 3251 6253 3194 6254 3251 6254 3252 6254 3195 6255 3194 6255 3252 6255 3195 6256 3252 6256 3253 6256 3197 6257 3195 6257 3253 6257 3198 6258 3197 6258 3253 6258 3198 6259 3253 6259 3295 6259 3198 6260 3295 6260 3254 6260 3200 6261 3198 6261 3254 6261 3204 6262 3200 6262 3254 6262 3204 6263 3254 6263 3255 6263 3207 6264 3204 6264 3255 6264 3207 6265 3255 6265 3290 6265 3208 6266 3290 6266 3256 6266 3208 6267 3207 6267 3290 6267 3210 6268 3208 6268 3256 6268 3210 6269 3256 6269 3257 6269 3213 6270 3210 6270 3257 6270 3215 6271 3213 6271 3257 6271 3215 6272 3257 6272 3285 6272 3215 6273 3285 6273 3258 6273 3218 6274 3215 6274 3258 6274 3221 6275 3258 6275 3283 6275 3221 6276 3218 6276 3258 6276 3221 6277 3283 6277 3280 6277 3222 6278 3221 6278 3280 6278 3224 6279 3222 6279 3280 6279 3224 6280 3280 6280 3278 6280 3226 6281 3224 6281 3278 6281 3226 6282 3278 6282 3275 6282 3227 6283 3226 6283 3275 6283 3227 6284 3275 6284 3259 6284 3229 6285 3227 6285 3259 6285 3231 6286 3259 6286 3272 6286 3231 6287 3229 6287 3259 6287 3231 6288 3272 6288 3269 6288 3233 6289 3231 6289 3269 6289 3235 6290 3269 6290 3266 6290 3235 6291 3233 6291 3269 6291 3237 6292 3235 6292 3266 6292 3237 6293 3266 6293 3264 6293 3238 6294 3237 6294 3264 6294 3238 6295 3264 6295 3260 6295 3240 6296 3238 6296 3260 6296 3174 6297 3260 6297 3261 6297 3174 6298 3240 6298 3260 6298 3174 6299 3261 6299 3244 6299 2425 6300 3216 6300 2905 6300 2905 6301 3216 6301 3219 6301 2906 6302 2905 6302 3219 6302 2906 6303 3219 6303 3223 6303 2423 6304 3216 6304 2425 6304 2423 6305 3211 6305 3216 6305 2906 6306 3223 6306 3228 6306 3099 6307 2906 6307 3228 6307 2423 6308 3206 6308 3211 6308 2418 6309 3206 6309 2423 6309 3099 6310 3228 6310 3234 6310 3101 6311 3099 6311 3234 6311 2418 6312 3201 6312 3206 6312 2421 6313 3201 6313 2418 6313 3101 6314 3234 6314 3239 6314 3193 6315 3201 6315 2421 6315 3193 6316 2421 6316 2419 6316 3241 6317 3100 6317 3101 6317 3241 6318 3101 6318 3239 6318 3193 6319 2419 6319 2416 6319 3188 6320 3193 6320 2416 6320 3178 6321 3100 6321 3241 6321 3178 6322 3102 6322 3100 6322 3188 6323 2416 6323 3124 6323 3178 6324 3124 6324 3102 6324 3178 6325 3188 6325 3124 6325 3262 6326 3261 6326 3260 6326 3263 6327 3262 6327 3260 6327 3263 6328 3260 6328 3264 6328 3265 6329 3263 6329 3264 6329 3268 6330 3263 6330 3265 6330 3265 6331 3264 6331 3266 6331 3267 6332 3265 6332 3266 6332 3268 6333 3265 6333 3267 6333 3267 6334 3266 6334 3269 6334 3270 6335 3268 6335 3267 6335 3271 6336 3267 6336 3269 6336 3270 6337 3267 6337 3271 6337 3272 6338 3271 6338 3269 6338 3273 6339 3270 6339 3271 6339 3259 6340 3271 6340 3272 6340 3273 6341 3271 6341 3259 6341 3274 6342 3273 6342 3259 6342 3274 6343 3270 6343 3273 6343 3275 6344 3274 6344 3259 6344 3276 6345 3274 6345 3275 6345 3276 6346 3275 6346 3278 6346 3277 6347 3274 6347 3276 6347 3279 6348 3276 6348 3278 6348 3279 6349 3277 6349 3276 6349 3279 6350 3278 6350 3280 6350 3281 6351 3277 6351 3279 6351 3282 6352 3279 6352 3280 6352 3281 6353 3279 6353 3282 6353 3283 6354 3282 6354 3280 6354 3281 6355 3282 6355 3284 6355 3284 6356 3282 6356 3283 6356 3284 6357 3283 6357 3258 6357 3285 6358 3284 6358 3258 6358 3286 6359 3281 6359 3284 6359 3286 6360 3284 6360 3285 6360 3287 6361 3285 6361 3257 6361 3287 6362 3286 6362 3285 6362 3289 6363 3286 6363 3287 6363 3288 6364 3287 6364 3257 6364 3288 6365 3257 6365 3256 6365 3289 6366 3287 6366 3288 6366 3290 6367 3288 6367 3256 6367 3291 6368 3289 6368 3288 6368 3291 6369 3288 6369 3290 6369 3292 6370 3290 6370 3255 6370 3292 6371 3291 6371 3290 6371 3293 6372 3291 6372 3292 6372 3294 6373 3292 6373 3255 6373 3294 6374 3293 6374 3292 6374 3294 6375 3255 6375 3254 6375 3295 6376 3294 6376 3254 6376 3296 6377 3293 6377 3294 6377 3296 6378 3294 6378 3295 6378 3253 6379 3296 6379 3295 6379 3297 6380 3296 6380 3253 6380 3298 6381 3293 6381 3296 6381 3298 6382 3296 6382 3297 6382 3297 6383 3253 6383 3252 6383 3299 6384 3297 6384 3252 6384 3299 6385 3298 6385 3297 6385 3301 6386 3298 6386 3299 6386 3251 6387 3299 6387 3252 6387 3300 6388 3299 6388 3251 6388 3300 6389 3251 6389 3250 6389 3300 6390 3301 6390 3299 6390 3249 6391 3300 6391 3250 6391 3302 6392 3300 6392 3249 6392 3303 6393 3300 6393 3302 6393 3303 6394 3301 6394 3300 6394 3304 6395 3249 6395 3248 6395 3304 6396 3302 6396 3249 6396 3304 6397 3303 6397 3302 6397 3247 6398 3304 6398 3248 6398 3305 6399 3304 6399 3247 6399 3306 6400 3304 6400 3305 6400 3306 6401 3303 6401 3304 6401 3307 6402 3305 6402 3247 6402 3307 6403 3247 6403 3246 6403 3307 6404 3306 6404 3305 6404 3308 6405 3303 6405 3306 6405 3308 6406 3306 6406 3307 6406 3309 6407 3307 6407 3246 6407 3309 6408 3308 6408 3307 6408 3309 6409 3246 6409 3245 6409 3310 6410 3309 6410 3245 6410 3311 6411 3309 6411 3310 6411 3308 6412 3309 6412 3311 6412 3244 6413 3311 6413 3310 6413 3244 6414 3261 6414 3262 6414 3262 6415 3311 6415 3244 6415 3262 6416 3263 6416 3311 6416 2383 6417 2385 6417 2390 6417 2390 6418 2385 6418 2388 6418 2381 6419 2383 6419 2391 6419 2391 6420 2383 6420 2390 6420 2379 6421 2381 6421 2392 6421 2392 6422 2381 6422 2391 6422

+
+ + + +

3313 6423 3314 6423 3312 6423 3312 6424 3314 6424 3315 6424 3313 6425 3316 6425 3314 6425 3316 6426 3317 6426 3314 6426 3316 6427 3318 6427 3317 6427 3318 6428 3319 6428 3317 6428 3320 6429 3321 6429 3318 6429 3318 6430 3321 6430 3319 6430 3320 6431 3322 6431 3321 6431 3322 6432 3323 6432 3321 6432 3322 6433 3312 6433 3323 6433 3312 6434 3315 6434 3323 6434 3321 6435 3323 6435 3324 6435 3324 6436 3323 6436 3325 6436 3323 6437 3315 6437 3325 6437 3325 6438 3315 6438 3329 6438 3315 6439 3314 6439 3329 6439 3329 6440 3314 6440 3328 6440 3312 6441 3322 6441 3313 6441 3322 6442 3316 6442 3313 6442 3322 6443 3320 6443 3316 6443 3320 6444 3318 6444 3316 6444 3327 6445 4218 6445 4221 6445 3327 6446 4215 6446 4218 6446 3327 6447 4212 6447 4215 6447 3328 6448 4221 6448 4224 6448 3328 6449 4226 6449 4230 6449 3328 6450 3327 6450 4221 6450 3328 6451 4224 6451 4226 6451 3326 6452 4254 6452 4212 6452 3326 6453 4250 6453 4254 6453 3326 6454 4212 6454 3327 6454 4248 6455 4250 6455 3326 6455 3329 6456 3328 6456 4230 6456 3329 6457 4230 6457 4232 6457 4233 6458 3329 6458 4232 6458 3324 6459 4248 6459 3326 6459 4236 6460 3329 6460 4233 6460 4246 6461 4248 6461 3324 6461 4236 6462 3325 6462 3329 6462 4238 6463 3325 6463 4236 6463 4245 6464 4246 6464 3324 6464 4245 6465 3324 6465 3325 6465 4240 6466 3325 6466 4238 6466 4240 6467 4245 6467 3325 6467 3330 6468 3331 6468 4101 6468 3332 6469 3330 6469 4101 6469 3332 6470 4101 6470 3333 6470 3330 6471 4097 6471 3331 6471 3334 6472 4097 6472 3330 6472 3335 6473 3332 6473 3333 6473 3335 6474 3333 6474 3336 6474 3334 6475 4091 6475 4097 6475 3337 6476 4091 6476 3334 6476 3337 6477 4087 6477 4091 6477 3338 6478 3335 6478 3336 6478 4109 6479 3335 6479 3338 6479 4082 6480 4087 6480 3337 6480 3339 6481 3335 6481 4109 6481 3340 6482 4082 6482 3337 6482 4078 6483 4082 6483 3340 6483 4078 6484 3340 6484 3342 6484 4077 6485 4078 6485 3342 6485 4077 6486 3342 6486 3343 6486 4071 6487 4077 6487 3343 6487 4071 6488 3343 6488 3344 6488 3350 6489 3347 6489 3346 6489 3350 6490 3348 6490 3347 6490 3352 6491 3348 6491 3350 6491 3352 6492 3351 6492 3348 6492 3349 6493 3351 6493 3352 6493 3349 6494 3353 6494 3351 6494 3349 6495 3354 6495 3353 6495 3355 6496 3354 6496 3349 6496 3355 6497 3356 6497 3354 6497 3357 6498 3356 6498 3355 6498 3357 6499 3358 6499 3356 6499 3357 6500 3359 6500 3358 6500 3360 6501 3359 6501 3357 6501 3360 6502 3361 6502 3359 6502 3362 6503 3363 6503 3360 6503 3360 6504 3363 6504 3361 6504 3362 6505 3364 6505 3363 6505 3365 6506 3364 6506 3362 6506 3365 6507 3366 6507 3364 6507 3367 6508 3366 6508 3365 6508 3367 6509 3368 6509 3366 6509 3369 6510 3368 6510 3367 6510 3369 6511 3370 6511 3368 6511 3369 6512 3371 6512 3370 6512 3372 6513 3371 6513 3369 6513 3372 6514 3373 6514 3371 6514 3372 6515 3374 6515 3373 6515 3375 6516 3374 6516 3372 6516 3375 6517 3376 6517 3374 6517 3377 6518 3376 6518 3375 6518 3377 6519 3378 6519 3376 6519 3379 6520 3378 6520 3377 6520 3379 6521 3380 6521 3378 6521 3379 6522 3381 6522 3380 6522 3382 6523 3381 6523 3379 6523 3382 6524 3383 6524 3381 6524 3384 6525 3383 6525 3382 6525 3384 6526 3385 6526 3383 6526 3386 6527 3385 6527 3384 6527 3386 6528 3387 6528 3385 6528 3388 6529 3387 6529 3386 6529 3388 6530 3389 6530 3387 6530 3388 6531 3390 6531 3389 6531 3391 6532 3390 6532 3388 6532 3391 6533 3392 6533 3390 6533 3393 6534 3392 6534 3391 6534 3393 6535 3394 6535 3392 6535 3395 6536 3396 6536 3393 6536 3393 6537 3396 6537 3394 6537 3395 6538 3397 6538 3396 6538 3395 6539 3398 6539 3397 6539 3399 6540 3398 6540 3395 6540 3399 6541 3400 6541 3398 6541 3401 6542 3400 6542 3399 6542 3401 6543 3402 6543 3400 6543 3403 6544 3402 6544 3401 6544 3403 6545 3404 6545 3402 6545 3403 6546 3405 6546 3404 6546 3406 6547 3405 6547 3403 6547 3407 6548 3408 6548 3406 6548 3406 6549 3408 6549 3405 6549 3409 6550 3410 6550 3407 6550 3407 6551 3410 6551 3408 6551 3409 6552 3411 6552 3410 6552 3412 6553 3411 6553 3409 6553 3412 6554 3413 6554 3411 6554 3412 6555 3414 6555 3413 6555 3415 6556 3414 6556 3412 6556 3415 6557 3416 6557 3414 6557 3417 6558 3416 6558 3415 6558 3417 6559 3418 6559 3416 6559 3417 6560 3419 6560 3418 6560 3420 6561 3419 6561 3417 6561 3420 6562 3421 6562 3419 6562 3422 6563 3421 6563 3420 6563 3422 6564 3423 6564 3421 6564 3422 6565 3424 6565 3423 6565 3425 6566 3424 6566 3422 6566 3425 6567 3426 6567 3424 6567 3427 6568 3426 6568 3425 6568 3427 6569 3428 6569 3426 6569 3427 6570 3429 6570 3428 6570 3430 6571 3429 6571 3427 6571 3430 6572 3431 6572 3429 6572 3432 6573 3431 6573 3430 6573 3432 6574 3433 6574 3431 6574 3432 6575 3434 6575 3433 6575 3435 6576 3434 6576 3432 6576 3435 6577 3436 6577 3434 6577 3437 6578 3436 6578 3435 6578 3437 6579 3438 6579 3436 6579 3439 6580 3438 6580 3437 6580 3439 6581 3440 6581 3438 6581 3439 6582 3441 6582 3440 6582 3442 6583 3441 6583 3439 6583 3442 6584 3443 6584 3441 6584 3442 6585 3444 6585 3443 6585 3445 6586 3444 6586 3442 6586 3445 6587 3446 6587 3444 6587 3447 6588 3446 6588 3445 6588 3447 6589 3448 6589 3446 6589 3449 6590 3448 6590 3447 6590 3449 6591 3450 6591 3448 6591 3449 6592 3451 6592 3450 6592 3452 6593 3451 6593 3449 6593 3452 6594 3453 6594 3451 6594 3452 6595 3454 6595 3453 6595 3455 6596 3454 6596 3452 6596 3455 6597 3456 6597 3454 6597 3457 6598 3456 6598 3455 6598 3457 6599 3458 6599 3456 6599 3457 6600 3459 6600 3458 6600 3460 6601 3459 6601 3457 6601 3460 6602 3461 6602 3459 6602 3462 6603 3461 6603 3460 6603 3462 6604 3463 6604 3461 6604 3464 6605 3463 6605 3462 6605 3464 6606 3465 6606 3463 6606 3464 6607 3466 6607 3465 6607 3467 6608 3466 6608 3464 6608 3467 6609 3468 6609 3466 6609 3467 6610 3469 6610 3468 6610 3470 6611 3469 6611 3467 6611 3470 6612 3471 6612 3469 6612 3472 6613 3471 6613 3470 6613 3472 6614 3473 6614 3471 6614 3474 6615 3473 6615 3472 6615 3474 6616 3475 6616 3473 6616 3476 6617 3475 6617 3474 6617 3476 6618 3477 6618 3475 6618 3478 6619 3477 6619 3476 6619 3478 6620 3479 6620 3477 6620 3478 6621 3480 6621 3479 6621 3481 6622 3480 6622 3478 6622 3481 6623 3482 6623 3480 6623 3483 6624 3482 6624 3481 6624 3483 6625 3484 6625 3482 6625 3483 6626 3485 6626 3484 6626 3486 6627 3485 6627 3483 6627 3486 6628 3487 6628 3485 6628 3488 6629 3487 6629 3486 6629 3488 6630 3489 6630 3487 6630 3490 6631 3491 6631 3488 6631 3488 6632 3491 6632 3489 6632 3490 6633 3492 6633 3491 6633 3493 6634 3492 6634 3490 6634 3493 6635 3494 6635 3492 6635 3495 6636 3494 6636 3493 6636 3495 6637 3496 6637 3494 6637 3497 6638 3498 6638 3495 6638 3495 6639 3498 6639 3496 6639 3499 6640 3498 6640 3497 6640 3499 6641 3500 6641 3498 6641 3501 6642 3500 6642 3499 6642 3501 6643 3502 6643 3500 6643 3501 6644 3503 6644 3502 6644 3504 6645 3503 6645 3501 6645 3504 6646 3505 6646 3503 6646 3504 6647 3506 6647 3505 6647 3507 6648 3506 6648 3504 6648 3508 6649 3506 6649 3507 6649 3508 6650 3509 6650 3506 6650 3508 6651 3510 6651 3509 6651 3511 6652 3510 6652 3508 6652 3511 6653 3512 6653 3510 6653 3513 6654 3512 6654 3511 6654 3513 6655 3514 6655 3512 6655 3513 6656 3515 6656 3514 6656 3516 6657 3515 6657 3513 6657 3516 6658 3517 6658 3515 6658 3518 6659 3519 6659 3516 6659 3516 6660 3519 6660 3517 6660 3518 6661 3520 6661 3519 6661 3518 6662 3521 6662 3520 6662 3522 6663 3521 6663 3518 6663 3522 6664 3523 6664 3521 6664 3524 6665 3523 6665 3522 6665 3524 6666 3525 6666 3523 6666 3526 6667 3525 6667 3524 6667 3526 6668 3527 6668 3525 6668 3526 6669 3528 6669 3527 6669 3529 6670 3528 6670 3526 6670 3529 6671 3530 6671 3528 6671 3531 6672 3530 6672 3529 6672 3531 6673 3532 6673 3530 6673 3533 6674 3532 6674 3531 6674 3533 6675 3534 6675 3532 6675 3533 6676 3535 6676 3534 6676 3536 6677 3535 6677 3533 6677 3536 6678 3537 6678 3535 6678 3538 6679 3537 6679 3536 6679 3538 6680 3539 6680 3537 6680 3540 6681 3539 6681 3538 6681 3540 6682 3541 6682 3539 6682 3540 6683 3542 6683 3541 6683 3543 6684 3542 6684 3540 6684 3543 6685 3544 6685 3542 6685 3545 6686 3544 6686 3543 6686 3545 6687 3546 6687 3544 6687 3547 6688 3546 6688 3545 6688 3547 6689 3548 6689 3546 6689 3547 6690 3549 6690 3548 6690 3550 6691 3549 6691 3547 6691 3550 6692 3551 6692 3549 6692 3552 6693 3551 6693 3550 6693 3552 6694 3553 6694 3551 6694 3554 6695 3555 6695 3552 6695 3552 6696 3555 6696 3553 6696 3554 6697 3556 6697 3555 6697 3554 6698 3557 6698 3556 6698 3558 6699 3557 6699 3554 6699 3558 6700 3559 6700 3557 6700 3560 6701 3559 6701 3558 6701 3560 6702 3561 6702 3559 6702 3562 6703 3561 6703 3560 6703 3562 6704 3563 6704 3561 6704 3564 6705 3563 6705 3562 6705 3564 6706 3565 6706 3563 6706 3566 6707 3565 6707 3564 6707 3566 6708 3567 6708 3565 6708 3568 6709 3567 6709 3566 6709 3568 6710 3569 6710 3567 6710 3568 6711 3570 6711 3569 6711 3571 6712 3570 6712 3568 6712 3572 6713 3570 6713 3571 6713 3572 6714 3573 6714 3570 6714 3572 6715 3574 6715 3573 6715 3575 6716 3574 6716 3572 6716 3575 6717 3576 6717 3574 6717 3577 6718 3576 6718 3575 6718 3577 6719 3578 6719 3576 6719 3579 6720 3578 6720 3577 6720 3579 6721 3580 6721 3578 6721 3579 6722 3581 6722 3580 6722 3579 6723 3582 6723 3581 6723 3583 6724 3582 6724 3579 6724 3584 6725 3582 6725 3583 6725 3584 6726 3585 6726 3582 6726 3584 6727 3586 6727 3585 6727 3587 6728 3586 6728 3584 6728 3587 6729 3588 6729 3586 6729 3589 6730 3588 6730 3587 6730 3589 6731 3590 6731 3588 6731 3591 6732 3590 6732 3589 6732 3591 6733 3592 6733 3590 6733 3593 6734 3594 6734 3591 6734 3591 6735 3594 6735 3592 6735 3593 6736 3595 6736 3594 6736 3596 6737 3595 6737 3593 6737 3596 6738 3597 6738 3595 6738 3598 6739 3597 6739 3596 6739 3598 6740 3599 6740 3597 6740 3600 6741 3599 6741 3598 6741 3600 6742 3601 6742 3599 6742 3600 6743 3602 6743 3601 6743 3603 6744 3602 6744 3600 6744 3603 6745 3604 6745 3602 6745 3603 6746 3605 6746 3604 6746 3606 6747 3605 6747 3603 6747 3606 6748 3607 6748 3605 6748 3608 6749 3607 6749 3606 6749 3610 6750 3609 6750 3608 6750 3608 6751 3609 6751 3607 6751 3610 6752 3611 6752 3609 6752 3612 6753 3611 6753 3610 6753 3612 6754 3613 6754 3611 6754 3612 6755 3614 6755 3613 6755 3615 6756 3614 6756 3612 6756 3615 6757 3616 6757 3614 6757 3615 6758 3617 6758 3616 6758 3618 6759 3617 6759 3615 6759 3618 6760 3619 6760 3617 6760 3620 6761 3619 6761 3618 6761 3620 6762 3621 6762 3619 6762 3622 6763 3621 6763 3620 6763 3622 6764 3623 6764 3621 6764 3622 6765 3624 6765 3623 6765 3625 6766 3624 6766 3622 6766 3625 6767 3626 6767 3624 6767 3625 6768 3627 6768 3626 6768 3628 6769 3627 6769 3625 6769 3628 6770 3629 6770 3627 6770 3630 6771 3629 6771 3628 6771 3630 6772 3631 6772 3629 6772 3632 6773 3631 6773 3630 6773 3632 6774 3633 6774 3631 6774 3632 6775 3634 6775 3633 6775 3635 6776 3634 6776 3632 6776 3635 6777 3636 6777 3634 6777 3637 6778 3636 6778 3635 6778 3637 6779 3638 6779 3636 6779 3637 6780 3639 6780 3638 6780 3640 6781 3639 6781 3637 6781 3640 6782 3641 6782 3639 6782 3642 6783 3641 6783 3640 6783 3642 6784 3643 6784 3641 6784 3642 6785 3644 6785 3643 6785 3645 6786 3644 6786 3642 6786 3645 6787 3646 6787 3644 6787 3647 6788 3646 6788 3645 6788 3647 6789 3648 6789 3646 6789 3649 6790 3648 6790 3647 6790 3649 6791 3650 6791 3648 6791 3649 6792 3651 6792 3650 6792 3652 6793 3651 6793 3649 6793 3652 6794 3653 6794 3651 6794 3652 6795 3654 6795 3653 6795 3655 6796 3654 6796 3652 6796 3656 6797 3654 6797 3655 6797 3656 6798 3657 6798 3654 6798 3656 6799 3658 6799 3657 6799 3659 6800 3658 6800 3656 6800 3660 6801 3658 6801 3659 6801 3660 6802 3661 6802 3658 6802 3660 6803 3662 6803 3661 6803 3663 6804 3662 6804 3660 6804 3663 6805 3664 6805 3662 6805 3663 6806 3665 6806 3664 6806 3666 6807 3665 6807 3663 6807 3666 6808 3667 6808 3665 6808 3668 6809 3667 6809 3666 6809 3668 6810 3669 6810 3667 6810 3668 6811 3670 6811 3669 6811 3671 6812 3670 6812 3668 6812 3671 6813 3672 6813 3670 6813 3673 6814 3674 6814 3671 6814 3671 6815 3674 6815 3672 6815 3673 6816 3675 6816 3674 6816 3676 6817 3675 6817 3673 6817 3676 6818 3677 6818 3675 6818 3678 6819 3677 6819 3676 6819 3678 6820 3679 6820 3677 6820 3678 6821 3680 6821 3679 6821 3678 6822 3681 6822 3680 6822 3682 6823 3681 6823 3678 6823 3682 6824 3683 6824 3681 6824 3684 6825 3683 6825 3682 6825 3684 6826 3685 6826 3683 6826 3686 6827 3685 6827 3684 6827 3686 6828 3687 6828 3685 6828 3688 6829 3687 6829 3686 6829 3688 6830 3689 6830 3687 6830 3690 6831 3689 6831 3688 6831 3690 6832 3691 6832 3689 6832 3690 6833 3692 6833 3691 6833 3693 6834 3692 6834 3690 6834 3694 6835 3695 6835 3693 6835 3693 6836 3695 6836 3692 6836 3694 6837 3696 6837 3695 6837 3694 6838 3697 6838 3696 6838 3698 6839 3697 6839 3694 6839 3698 6840 3699 6840 3697 6840 3700 6841 3699 6841 3698 6841 3700 6842 3701 6842 3699 6842 3700 6843 3702 6843 3701 6843 3703 6844 3702 6844 3700 6844 3703 6845 3704 6845 3702 6845 3705 6846 3704 6846 3703 6846 3705 6847 3706 6847 3704 6847 3707 6848 3706 6848 3705 6848 3707 6849 3708 6849 3706 6849 3709 6850 3708 6850 3707 6850 3709 6851 3710 6851 3708 6851 3709 6852 3711 6852 3710 6852 3712 6853 3711 6853 3709 6853 3712 6854 3713 6854 3711 6854 3714 6855 3713 6855 3712 6855 3714 6856 3715 6856 3713 6856 3716 6857 3715 6857 3714 6857 3716 6858 3717 6858 3715 6858 3716 6859 3718 6859 3717 6859 3719 6860 3718 6860 3716 6860 3719 6861 3720 6861 3718 6861 3721 6862 3720 6862 3719 6862 3721 6863 3722 6863 3720 6863 3723 6864 3722 6864 3721 6864 3723 6865 3724 6865 3722 6865 3725 6866 3724 6866 3723 6866 3725 6867 3726 6867 3724 6867 3727 6868 3726 6868 3725 6868 3727 6869 3728 6869 3726 6869 3727 6870 3729 6870 3728 6870 3730 6871 3729 6871 3727 6871 3730 6872 3731 6872 3729 6872 3732 6873 3731 6873 3730 6873 3732 6874 3733 6874 3731 6874 3732 6875 3734 6875 3733 6875 3735 6876 3734 6876 3732 6876 3735 6877 3736 6877 3734 6877 3737 6878 3736 6878 3735 6878 3737 6879 3738 6879 3736 6879 3737 6880 3739 6880 3738 6880 3740 6881 3739 6881 3737 6881 3740 6882 3741 6882 3739 6882 3742 6883 3741 6883 3740 6883 3742 6884 3743 6884 3741 6884 3744 6885 3743 6885 3742 6885 3744 6886 3745 6886 3743 6886 3746 6887 3745 6887 3744 6887 3746 6888 3747 6888 3745 6888 3748 6889 3747 6889 3746 6889 3748 6890 3749 6890 3747 6890 3748 6891 3750 6891 3749 6891 3751 6892 3750 6892 3748 6892 3751 6893 3752 6893 3750 6893 3751 6894 3753 6894 3752 6894 3754 6895 3753 6895 3751 6895 3754 6896 3755 6896 3753 6896 3756 6897 3755 6897 3754 6897 3756 6898 3757 6898 3755 6898 3758 6899 3757 6899 3756 6899 3758 6900 3759 6900 3757 6900 3758 6901 3760 6901 3759 6901 3761 6902 3760 6902 3758 6902 3761 6903 3762 6903 3760 6903 3763 6904 3762 6904 3761 6904 3763 6905 3764 6905 3762 6905 3765 6906 3764 6906 3763 6906 3765 6907 3766 6907 3764 6907 3765 6908 3767 6908 3766 6908 3768 6909 3767 6909 3765 6909 3768 6910 3769 6910 3767 6910 3770 6911 3769 6911 3768 6911 3770 6912 3771 6912 3769 6912 3772 6913 3771 6913 3770 6913 3773 6914 3771 6914 3772 6914 3773 6915 3774 6915 3771 6915 3773 6916 3775 6916 3774 6916 3776 6917 3775 6917 3773 6917 3776 6918 3777 6918 3775 6918 3776 6919 3778 6919 3777 6919 3779 6920 3778 6920 3776 6920 3779 6921 3780 6921 3778 6921 3781 6922 3780 6922 3779 6922 3781 6923 3782 6923 3780 6923 3781 6924 3783 6924 3782 6924 3784 6925 3783 6925 3781 6925 3784 6926 3785 6926 3783 6926 3786 6927 3785 6927 3784 6927 3787 6928 3788 6928 3786 6928 3786 6929 3788 6929 3785 6929 3787 6930 3789 6930 3788 6930 3790 6931 3789 6931 3787 6931 3790 6932 3791 6932 3789 6932 3792 6933 3791 6933 3790 6933 3792 6934 3793 6934 3791 6934 3794 6935 3793 6935 3792 6935 3794 6936 3795 6936 3793 6936 3794 6937 3796 6937 3795 6937 3797 6938 3796 6938 3794 6938 3797 6939 3798 6939 3796 6939 3799 6940 3798 6940 3797 6940 3799 6941 3800 6941 3798 6941 3801 6942 3800 6942 3799 6942 3801 6943 3802 6943 3800 6943 3803 6944 3802 6944 3801 6944 3803 6945 3804 6945 3802 6945 3805 6946 3804 6946 3803 6946 3805 6947 3806 6947 3804 6947 3805 6948 3807 6948 3806 6948 3808 6949 3807 6949 3805 6949 3808 6950 3809 6950 3807 6950 3810 6951 3809 6951 3808 6951 3810 6952 3811 6952 3809 6952 3812 6953 3811 6953 3810 6953 3812 6954 3813 6954 3811 6954 3812 6955 3814 6955 3813 6955 3815 6956 3814 6956 3812 6956 3815 6957 3816 6957 3814 6957 3817 6958 3816 6958 3815 6958 3817 6959 3818 6959 3816 6959 3817 6960 3819 6960 3818 6960 3820 6961 3819 6961 3817 6961 3820 6962 3821 6962 3819 6962 3822 6963 3821 6963 3820 6963 3822 6964 3823 6964 3821 6964 3824 6965 3823 6965 3822 6965 3824 6966 3825 6966 3823 6966 3824 6967 3826 6967 3825 6967 3827 6968 3826 6968 3824 6968 3827 6969 3341 6969 3826 6969 3828 6970 3341 6970 3827 6970 3828 6971 3339 6971 3341 6971 3828 6972 3335 6972 3339 6972 3829 6973 3335 6973 3828 6973 3830 6974 3335 6974 3829 6974 3830 6975 3332 6975 3335 6975 3831 6976 3360 6976 3357 6976 3832 6977 3360 6977 3831 6977 3362 6978 3360 6978 3832 6978 3833 6979 3362 6979 3832 6979 3365 6980 3362 6980 3833 6980 3834 6981 3365 6981 3833 6981 3367 6982 3365 6982 3834 6982 3835 6983 3367 6983 3834 6983 3369 6984 3367 6984 3835 6984 3836 6985 3369 6985 3835 6985 3372 6986 3369 6986 3836 6986 3837 6987 3372 6987 3836 6987 3838 6988 3372 6988 3837 6988 3375 6989 3372 6989 3838 6989 3839 6990 3375 6990 3838 6990 3377 6991 3375 6991 3839 6991 3379 6992 3377 6992 3839 6992 3840 6993 3379 6993 3839 6993 3382 6994 3379 6994 3840 6994 3841 6995 3382 6995 3840 6995 3384 6996 3382 6996 3841 6996 3842 6997 3384 6997 3841 6997 3386 6998 3384 6998 3842 6998 3843 6999 3386 6999 3842 6999 3388 7000 3386 7000 3843 7000 3844 7001 3388 7001 3843 7001 3845 7002 3388 7002 3844 7002 3391 7003 3388 7003 3845 7003 3393 7004 3391 7004 3845 7004 3393 7005 3845 7005 3846 7005 3395 7006 3393 7006 3846 7006 3847 7007 3395 7007 3846 7007 3848 7008 3395 7008 3847 7008 3399 7009 3395 7009 3848 7009 3849 7010 3399 7010 3848 7010 3401 7011 3399 7011 3849 7011 3850 7012 3401 7012 3849 7012 3403 7013 3401 7013 3850 7013 3851 7014 3403 7014 3850 7014 3406 7015 3403 7015 3851 7015 3852 7016 3406 7016 3851 7016 3407 7017 3406 7017 3852 7017 3853 7018 3407 7018 3852 7018 3409 7019 3407 7019 3853 7019 3854 7020 3409 7020 3853 7020 3412 7021 3409 7021 3854 7021 3855 7022 3412 7022 3854 7022 3415 7023 3412 7023 3855 7023 3856 7024 3415 7024 3855 7024 3417 7025 3415 7025 3856 7025 3420 7026 3417 7026 3856 7026 3857 7027 3420 7027 3856 7027 3858 7028 3420 7028 3857 7028 3422 7029 3420 7029 3858 7029 3859 7030 3422 7030 3858 7030 3425 7031 3422 7031 3859 7031 3860 7032 3425 7032 3859 7032 3427 7033 3425 7033 3860 7033 3861 7034 3427 7034 3860 7034 3430 7035 3427 7035 3861 7035 3862 7036 3430 7036 3861 7036 3432 7037 3430 7037 3862 7037 3863 7038 3432 7038 3862 7038 3435 7039 3432 7039 3863 7039 3864 7040 3435 7040 3863 7040 3437 7041 3435 7041 3864 7041 3865 7042 3437 7042 3864 7042 3439 7043 3437 7043 3865 7043 3866 7044 3439 7044 3865 7044 3442 7045 3439 7045 3866 7045 3867 7046 3442 7046 3866 7046 3445 7047 3442 7047 3867 7047 3447 7048 3445 7048 3868 7048 3449 7049 3447 7049 3868 7049 3869 7050 3449 7050 3868 7050 3870 7051 3449 7051 3869 7051 3452 7052 3449 7052 3870 7052 3871 7053 3452 7053 3870 7053 3455 7054 3452 7054 3871 7054 3872 7055 3455 7055 3871 7055 3873 7056 3455 7056 3872 7056 3457 7057 3455 7057 3873 7057 3874 7058 3457 7058 3873 7058 3460 7059 3457 7059 3874 7059 3875 7060 3460 7060 3874 7060 3462 7061 3460 7061 3875 7061 3464 7062 3462 7062 3875 7062 3876 7063 3464 7063 3875 7063 3877 7064 3464 7064 3876 7064 3467 7065 3464 7065 3877 7065 3878 7066 3467 7066 3877 7066 3470 7067 3467 7067 3878 7067 3879 7068 3470 7068 3878 7068 3472 7069 3470 7069 3879 7069 3474 7070 3472 7070 3879 7070 3880 7071 3474 7071 3879 7071 3476 7072 3474 7072 3880 7072 3478 7073 3476 7073 3880 7073 3881 7074 3478 7074 3880 7074 3882 7075 3478 7075 3881 7075 3481 7076 3478 7076 3882 7076 3483 7077 3481 7077 3882 7077 3883 7078 3483 7078 3882 7078 3486 7079 3483 7079 3883 7079 3884 7080 3486 7080 3883 7080 3488 7081 3486 7081 3884 7081 3885 7082 3488 7082 3884 7082 3490 7083 3488 7083 3885 7083 3886 7084 3490 7084 3885 7084 3493 7085 3490 7085 3886 7085 3887 7086 3493 7086 3886 7086 3495 7087 3493 7087 3887 7087 3888 7088 3495 7088 3887 7088 3889 7089 3495 7089 3888 7089 3497 7090 3495 7090 3889 7090 3499 7091 3497 7091 3889 7091 3890 7092 3499 7092 3889 7092 3501 7093 3499 7093 3890 7093 3891 7094 3501 7094 3890 7094 3504 7095 3501 7095 3891 7095 3892 7096 3504 7096 3891 7096 3507 7097 3504 7097 3892 7097 3893 7098 3507 7098 3892 7098 3508 7099 3507 7099 3893 7099 3894 7100 3508 7100 3893 7100 3511 7101 3508 7101 3894 7101 3895 7102 3511 7102 3894 7102 3513 7103 3511 7103 3895 7103 3896 7104 3513 7104 3895 7104 3516 7105 3513 7105 3896 7105 3897 7106 3516 7106 3896 7106 3518 7107 3516 7107 3897 7107 3898 7108 3518 7108 3897 7108 3899 7109 3518 7109 3898 7109 3522 7110 3518 7110 3899 7110 3524 7111 3522 7111 3899 7111 3900 7112 3524 7112 3899 7112 3526 7113 3524 7113 3900 7113 3901 7114 3526 7114 3900 7114 3902 7115 3526 7115 3901 7115 3529 7116 3526 7116 3902 7116 3903 7117 3529 7117 3902 7117 3531 7118 3529 7118 3903 7118 3904 7119 3531 7119 3903 7119 3533 7120 3531 7120 3904 7120 3905 7121 3533 7121 3904 7121 3536 7122 3533 7122 3905 7122 3538 7123 3536 7123 3906 7123 3907 7124 3538 7124 3906 7124 3540 7125 3538 7125 3907 7125 3908 7126 3540 7126 3907 7126 3543 7127 3540 7127 3908 7127 3909 7128 3543 7128 3908 7128 3545 7129 3543 7129 3909 7129 3910 7130 3545 7130 3909 7130 3547 7131 3545 7131 3910 7131 3911 7132 3547 7132 3910 7132 3550 7133 3547 7133 3911 7133 3912 7134 3550 7134 3911 7134 3552 7135 3550 7135 3912 7135 3913 7136 3552 7136 3912 7136 3554 7137 3552 7137 3913 7137 3914 7138 3554 7138 3913 7138 3558 7139 3554 7139 3914 7139 3915 7140 3558 7140 3914 7140 3560 7141 3558 7141 3915 7141 3916 7142 3560 7142 3915 7142 3562 7143 3560 7143 3916 7143 3917 7144 3562 7144 3916 7144 3564 7145 3562 7145 3917 7145 3918 7146 3564 7146 3917 7146 3566 7147 3564 7147 3918 7147 3919 7148 3566 7148 3918 7148 3568 7149 3566 7149 3919 7149 3920 7150 3568 7150 3919 7150 3571 7151 3568 7151 3920 7151 3921 7152 3571 7152 3920 7152 3572 7153 3571 7153 3921 7153 3575 7154 3572 7154 3921 7154 3922 7155 3575 7155 3921 7155 3923 7156 3575 7156 3922 7156 3577 7157 3575 7157 3923 7157 3924 7158 3577 7158 3923 7158 3579 7159 3577 7159 3924 7159 3925 7160 3579 7160 3924 7160 3583 7161 3579 7161 3925 7161 3926 7162 3583 7162 3925 7162 3584 7163 3583 7163 3926 7163 3927 7164 3584 7164 3926 7164 3587 7165 3584 7165 3927 7165 3928 7166 3587 7166 3927 7166 3589 7167 3587 7167 3928 7167 3929 7168 3589 7168 3928 7168 3591 7169 3589 7169 3929 7169 3930 7170 3591 7170 3929 7170 3593 7171 3591 7171 3930 7171 3931 7172 3593 7172 3930 7172 3596 7173 3593 7173 3931 7173 3932 7174 3596 7174 3931 7174 3598 7175 3596 7175 3932 7175 3933 7176 3598 7176 3932 7176 3600 7177 3598 7177 3933 7177 3934 7178 3600 7178 3933 7178 3603 7179 3600 7179 3934 7179 3935 7180 3603 7180 3934 7180 3606 7181 3603 7181 3935 7181 3936 7182 3606 7182 3935 7182 3608 7183 3606 7183 3936 7183 3937 7184 3608 7184 3936 7184 3610 7185 3608 7185 3937 7185 3938 7186 3610 7186 3937 7186 3612 7187 3610 7187 3938 7187 3939 7188 3612 7188 3938 7188 3615 7189 3612 7189 3939 7189 3940 7190 3615 7190 3939 7190 3618 7191 3615 7191 3940 7191 3941 7192 3618 7192 3940 7192 3620 7193 3618 7193 3941 7193 3942 7194 3620 7194 3941 7194 3622 7195 3620 7195 3942 7195 3625 7196 3622 7196 3942 7196 3943 7197 3625 7197 3942 7197 3628 7198 3625 7198 3943 7198 3944 7199 3628 7199 3943 7199 3630 7200 3628 7200 3944 7200 3945 7201 3630 7201 3944 7201 3946 7202 3630 7202 3945 7202 3632 7203 3630 7203 3946 7203 3632 7204 3946 7204 3947 7204 3635 7205 3632 7205 3947 7205 3948 7206 3635 7206 3947 7206 3637 7207 3635 7207 3948 7207 3949 7208 3637 7208 3948 7208 3640 7209 3637 7209 3949 7209 3950 7210 3640 7210 3949 7210 3642 7211 3640 7211 3950 7211 3951 7212 3642 7212 3950 7212 3952 7213 3642 7213 3951 7213 3645 7214 3642 7214 3952 7214 3953 7215 3645 7215 3952 7215 3647 7216 3645 7216 3953 7216 3954 7217 3647 7217 3953 7217 3649 7218 3647 7218 3954 7218 3955 7219 3649 7219 3954 7219 3652 7220 3649 7220 3955 7220 3956 7221 3652 7221 3955 7221 3957 7222 3652 7222 3956 7222 3655 7223 3652 7223 3957 7223 3656 7224 3655 7224 3957 7224 3958 7225 3656 7225 3957 7225 3656 7226 3958 7226 3959 7226 3659 7227 3656 7227 3959 7227 3960 7228 3659 7228 3959 7228 3660 7229 3659 7229 3960 7229 3961 7230 3660 7230 3960 7230 3663 7231 3660 7231 3961 7231 3962 7232 3663 7232 3961 7232 3666 7233 3663 7233 3962 7233 3963 7234 3666 7234 3962 7234 3668 7235 3666 7235 3963 7235 3964 7236 3668 7236 3963 7236 3671 7237 3668 7237 3964 7237 3965 7238 3671 7238 3964 7238 3673 7239 3671 7239 3965 7239 3966 7240 3673 7240 3965 7240 3676 7241 3673 7241 3966 7241 3967 7242 3676 7242 3966 7242 3678 7243 3676 7243 3967 7243 3968 7244 3678 7244 3967 7244 3682 7245 3678 7245 3968 7245 3684 7246 3682 7246 3968 7246 3684 7247 3968 7247 3969 7247 3686 7248 3684 7248 3969 7248 3970 7249 3688 7249 3686 7249 3690 7250 3688 7250 3970 7250 3971 7251 3690 7251 3970 7251 3972 7252 3690 7252 3971 7252 3693 7253 3690 7253 3972 7253 3694 7254 3693 7254 3972 7254 3973 7255 3694 7255 3972 7255 3974 7256 3694 7256 3973 7256 3698 7257 3694 7257 3974 7257 3700 7258 3698 7258 3974 7258 3975 7259 3700 7259 3974 7259 3976 7260 3700 7260 3975 7260 3703 7261 3700 7261 3976 7261 3705 7262 3703 7262 3976 7262 3977 7263 3705 7263 3976 7263 3707 7264 3705 7264 3977 7264 3709 7265 3707 7265 3977 7265 3978 7266 3709 7266 3977 7266 3979 7267 3709 7267 3978 7267 3712 7268 3709 7268 3979 7268 3714 7269 3712 7269 3979 7269 3980 7270 3714 7270 3979 7270 3716 7271 3714 7271 3980 7271 3981 7272 3716 7272 3980 7272 3719 7273 3716 7273 3981 7273 3982 7274 3719 7274 3981 7274 3721 7275 3719 7275 3982 7275 3983 7276 3721 7276 3982 7276 3723 7277 3721 7277 3983 7277 3725 7278 3723 7278 3983 7278 3984 7279 3725 7279 3983 7279 3727 7280 3725 7280 3984 7280 3985 7281 3727 7281 3984 7281 3730 7282 3727 7282 3985 7282 3986 7283 3730 7283 3985 7283 3732 7284 3730 7284 3986 7284 3987 7285 3732 7285 3986 7285 3735 7286 3732 7286 3987 7286 3988 7287 3735 7287 3987 7287 3737 7288 3735 7288 3988 7288 3989 7289 3737 7289 3988 7289 3990 7290 3737 7290 3989 7290 3740 7291 3737 7291 3990 7291 3991 7292 3740 7292 3990 7292 3742 7293 3740 7293 3991 7293 3992 7294 3742 7294 3991 7294 3744 7295 3742 7295 3992 7295 3746 7296 3744 7296 3992 7296 3993 7297 3746 7297 3992 7297 3748 7298 3746 7298 3993 7298 3994 7299 3748 7299 3993 7299 3751 7300 3748 7300 3994 7300 3995 7301 3751 7301 3994 7301 3996 7302 3751 7302 3995 7302 3754 7303 3751 7303 3996 7303 3997 7304 3754 7304 3996 7304 3756 7305 3754 7305 3997 7305 3998 7306 3756 7306 3997 7306 3999 7307 3756 7307 3998 7307 3758 7308 3756 7308 3999 7308 4000 7309 3758 7309 3999 7309 3761 7310 3758 7310 4000 7310 4001 7311 3761 7311 4000 7311 3763 7312 3761 7312 4001 7312 3765 7313 3763 7313 4001 7313 3765 7314 4001 7314 4002 7314 3768 7315 3765 7315 4002 7315 4003 7316 3768 7316 4002 7316 3770 7317 3768 7317 4003 7317 4004 7318 3770 7318 4003 7318 3772 7319 3770 7319 4004 7319 3773 7320 3772 7320 4004 7320 4005 7321 3773 7321 4004 7321 3776 7322 3773 7322 4005 7322 4006 7323 3776 7323 4005 7323 3779 7324 3776 7324 4006 7324 4007 7325 3779 7325 4006 7325 3781 7326 3779 7326 4007 7326 4008 7327 3781 7327 4007 7327 3784 7328 3781 7328 4008 7328 4009 7329 3784 7329 4008 7329 3786 7330 3784 7330 4009 7330 3787 7331 3786 7331 4009 7331 4010 7332 3787 7332 4009 7332 3790 7333 3787 7333 4010 7333 4011 7334 3790 7334 4010 7334 3792 7335 3790 7335 4011 7335 3792 7336 4011 7336 4012 7336 3794 7337 3792 7337 4012 7337 3797 7338 3794 7338 4012 7338 4013 7339 3797 7339 4012 7339 4014 7340 3797 7340 4013 7340 3799 7341 3797 7341 4014 7341 3801 7342 3799 7342 4014 7342 4015 7343 3801 7343 4014 7343 3803 7344 3801 7344 4015 7344 4016 7345 3803 7345 4015 7345 3805 7346 3803 7346 4016 7346 4017 7347 3805 7347 4016 7347 3808 7348 3805 7348 4017 7348 4018 7349 3808 7349 4017 7349 4019 7350 3808 7350 4018 7350 3810 7351 3808 7351 4019 7351 3812 7352 3810 7352 4019 7352 4020 7353 3812 7353 4019 7353 3815 7354 3812 7354 4020 7354 4021 7355 3815 7355 4020 7355 3817 7356 3815 7356 4021 7356 3820 7357 3817 7357 4021 7357 4022 7358 3820 7358 4021 7358 4023 7359 3820 7359 4022 7359 3822 7360 3820 7360 4023 7360 3824 7361 3822 7361 4023 7361 4024 7362 3824 7362 4023 7362 3827 7363 3824 7363 4024 7363 4025 7364 3827 7364 4024 7364 3828 7365 3827 7365 4025 7365 4026 7366 3828 7366 4025 7366 4027 7367 3828 7367 4026 7367 3829 7368 3828 7368 4027 7368 4028 7369 3829 7369 4027 7369 3830 7370 3829 7370 4028 7370 3830 7371 4028 7371 4029 7371 3332 7372 3830 7372 4029 7372 4030 7373 3332 7373 4029 7373 3330 7374 3332 7374 4030 7374 3330 7375 4030 7375 3334 7375 4032 7376 3833 7376 3832 7376 4032 7377 3834 7377 3833 7377 4033 7378 3834 7378 4032 7378 4033 7379 3835 7379 3834 7379 4031 7380 3835 7380 4033 7380 4031 7381 3836 7381 3835 7381 4034 7382 3836 7382 4031 7382 4034 7383 3837 7383 3836 7383 4035 7384 3837 7384 4034 7384 4035 7385 3838 7385 3837 7385 3347 7386 3839 7386 4035 7386 4035 7387 3839 7387 3838 7387 4036 7388 3839 7388 3347 7388 4036 7389 3840 7389 3839 7389 3351 7390 3840 7390 4036 7390 3353 7391 3840 7391 3351 7391 3353 7392 3841 7392 3840 7392 3354 7393 3841 7393 3353 7393 3354 7394 3842 7394 3841 7394 3356 7395 3842 7395 3354 7395 3356 7396 3843 7396 3842 7396 3358 7397 3843 7397 3356 7397 3359 7398 3843 7398 3358 7398 3359 7399 3844 7399 3843 7399 3361 7400 3844 7400 3359 7400 3361 7401 3845 7401 3844 7401 3363 7402 3845 7402 3361 7402 3364 7403 3845 7403 3363 7403 3364 7404 3846 7404 3845 7404 4037 7405 3846 7405 3364 7405 4037 7406 3847 7406 3846 7406 3368 7407 3847 7407 4037 7407 3368 7408 3848 7408 3847 7408 3370 7409 3848 7409 3368 7409 3370 7410 3849 7410 3848 7410 3371 7411 3849 7411 3370 7411 3371 7412 3850 7412 3849 7412 3373 7413 3850 7413 3371 7413 3374 7414 3850 7414 3373 7414 3374 7415 3851 7415 3850 7415 3376 7416 3851 7416 3374 7416 3376 7417 3852 7417 3851 7417 3378 7418 3852 7418 3376 7418 3378 7419 3853 7419 3852 7419 3380 7420 3853 7420 3378 7420 3381 7421 3853 7421 3380 7421 3381 7422 3854 7422 3853 7422 3383 7423 3854 7423 3381 7423 3383 7424 3855 7424 3854 7424 3387 7425 3855 7425 3383 7425 3387 7426 3856 7426 3855 7426 3389 7427 3856 7427 3387 7427 3389 7428 3857 7428 3856 7428 4038 7429 3857 7429 3389 7429 4038 7430 3858 7430 3857 7430 3392 7431 3858 7431 4038 7431 3392 7432 3859 7432 3858 7432 3394 7433 3859 7433 3392 7433 3396 7434 3859 7434 3394 7434 3396 7435 3860 7435 3859 7435 3398 7436 3860 7436 3396 7436 3400 7437 3860 7437 3398 7437 3400 7438 3861 7438 3860 7438 3402 7439 3861 7439 3400 7439 3402 7440 3862 7440 3861 7440 3402 7441 3863 7441 3862 7441 4039 7442 3863 7442 3402 7442 3405 7443 3863 7443 4039 7443 3405 7444 3864 7444 3863 7444 3408 7445 3864 7445 3405 7445 3408 7446 3865 7446 3864 7446 3410 7447 3865 7447 3408 7447 3410 7448 3866 7448 3865 7448 3411 7449 3866 7449 3410 7449 3411 7450 3867 7450 3866 7450 3413 7451 3867 7451 3411 7451 3414 7452 3867 7452 3413 7452 3414 7453 3445 7453 3867 7453 3416 7454 3445 7454 3414 7454 3416 7455 3868 7455 3445 7455 3418 7456 3868 7456 3416 7456 3419 7457 3868 7457 3418 7457 3419 7458 3869 7458 3868 7458 3421 7459 3869 7459 3419 7459 3421 7460 3870 7460 3869 7460 3423 7461 3870 7461 3421 7461 3423 7462 3871 7462 3870 7462 3424 7463 3871 7463 3423 7463 3424 7464 3872 7464 3871 7464 3426 7465 3872 7465 3424 7465 3426 7466 3873 7466 3872 7466 3428 7467 3873 7467 3426 7467 3428 7468 3874 7468 3873 7468 3429 7469 3874 7469 3428 7469 3431 7470 3874 7470 3429 7470 3431 7471 3875 7471 3874 7471 3433 7472 3875 7472 3431 7472 3434 7473 3875 7473 3433 7473 3434 7474 3876 7474 3875 7474 3436 7475 3876 7475 3434 7475 3436 7476 3877 7476 3876 7476 3438 7477 3877 7477 3436 7477 3438 7478 3878 7478 3877 7478 3440 7479 3878 7479 3438 7479 3441 7480 3878 7480 3440 7480 3441 7481 3879 7481 3878 7481 3443 7482 3879 7482 3441 7482 3444 7483 3879 7483 3443 7483 3444 7484 3880 7484 3879 7484 4040 7485 3880 7485 3444 7485 3450 7486 3880 7486 4040 7486 3450 7487 3881 7487 3880 7487 4041 7488 3881 7488 3450 7488 4041 7489 3882 7489 3881 7489 3451 7490 3882 7490 4041 7490 3451 7491 3883 7491 3882 7491 3453 7492 3883 7492 3451 7492 3454 7493 3883 7493 3453 7493 3454 7494 3884 7494 3883 7494 3456 7495 3884 7495 3454 7495 3458 7496 3884 7496 3456 7496 3458 7497 3885 7497 3884 7497 3459 7498 3885 7498 3458 7498 3459 7499 3886 7499 3885 7499 3461 7500 3886 7500 3459 7500 3463 7501 3886 7501 3461 7501 3463 7502 3887 7502 3886 7502 3465 7503 3887 7503 3463 7503 3465 7504 3888 7504 3887 7504 3466 7505 3888 7505 3465 7505 3466 7506 3889 7506 3888 7506 3468 7507 3889 7507 3466 7507 4042 7508 3889 7508 3468 7508 4042 7509 3890 7509 3889 7509 3469 7510 3890 7510 4042 7510 3471 7511 3890 7511 3469 7511 3471 7512 3891 7512 3890 7512 3473 7513 3891 7513 3471 7513 3473 7514 3892 7514 3891 7514 3475 7515 3892 7515 3473 7515 3477 7516 3892 7516 3475 7516 3477 7517 3893 7517 3892 7517 3479 7518 3893 7518 3477 7518 3479 7519 3894 7519 3893 7519 3480 7520 3894 7520 3479 7520 3482 7521 3894 7521 3480 7521 3482 7522 3895 7522 3894 7522 3484 7523 3895 7523 3482 7523 3485 7524 3895 7524 3484 7524 3485 7525 3896 7525 3895 7525 3487 7526 3896 7526 3485 7526 3487 7527 3897 7527 3896 7527 3489 7528 3897 7528 3487 7528 3491 7529 3897 7529 3489 7529 3491 7530 3898 7530 3897 7530 3492 7531 3898 7531 3491 7531 3492 7532 3899 7532 3898 7532 3494 7533 3899 7533 3492 7533 3494 7534 3900 7534 3899 7534 3496 7535 3900 7535 3494 7535 4043 7536 3900 7536 3496 7536 4043 7537 3901 7537 3900 7537 4044 7538 3901 7538 4043 7538 4044 7539 3902 7539 3901 7539 3500 7540 3902 7540 4044 7540 3500 7541 3903 7541 3902 7541 3502 7542 3903 7542 3500 7542 3503 7543 3903 7543 3502 7543 3505 7544 3903 7544 3503 7544 3505 7545 3904 7545 3903 7545 3506 7546 3904 7546 3505 7546 3506 7547 3905 7547 3904 7547 3509 7548 3905 7548 3506 7548 3509 7549 3536 7549 3905 7549 3510 7550 3536 7550 3509 7550 3510 7551 3906 7551 3536 7551 3512 7552 3906 7552 3510 7552 3512 7553 3907 7553 3906 7553 3514 7554 3907 7554 3512 7554 3515 7555 3907 7555 3514 7555 3515 7556 3908 7556 3907 7556 3517 7557 3908 7557 3515 7557 3519 7558 3908 7558 3517 7558 3519 7559 3909 7559 3908 7559 3520 7560 3909 7560 3519 7560 3520 7561 3910 7561 3909 7561 3521 7562 3910 7562 3520 7562 3521 7563 3911 7563 3910 7563 3523 7564 3911 7564 3521 7564 4045 7565 3911 7565 3523 7565 4045 7566 3912 7566 3911 7566 4045 7567 3913 7567 3912 7567 3527 7568 3913 7568 4045 7568 4046 7569 3913 7569 3527 7569 4046 7570 3914 7570 3913 7570 4046 7571 3915 7571 3914 7571 3530 7572 3915 7572 4046 7572 3532 7573 3915 7573 3530 7573 3532 7574 3916 7574 3915 7574 3534 7575 3916 7575 3532 7575 3534 7576 3917 7576 3916 7576 3535 7577 3917 7577 3534 7577 3535 7578 3918 7578 3917 7578 3537 7579 3918 7579 3535 7579 3537 7580 3919 7580 3918 7580 3539 7581 3919 7581 3537 7581 3541 7582 3919 7582 3539 7582 3541 7583 3920 7583 3919 7583 3541 7584 3921 7584 3920 7584 3542 7585 3921 7585 3541 7585 4047 7586 3921 7586 3542 7586 4047 7587 3922 7587 3921 7587 4048 7588 3922 7588 4047 7588 4049 7589 3922 7589 4048 7589 4049 7590 3923 7590 3922 7590 4049 7591 3924 7591 3923 7591 3549 7592 3924 7592 4049 7592 3551 7593 3924 7593 3549 7593 3551 7594 3925 7594 3924 7594 3553 7595 3925 7595 3551 7595 3553 7596 3926 7596 3925 7596 3555 7597 3926 7597 3553 7597 3555 7598 3927 7598 3926 7598 3556 7599 3927 7599 3555 7599 3557 7600 3927 7600 3556 7600 3557 7601 3928 7601 3927 7601 4050 7602 3928 7602 3557 7602 4050 7603 3929 7603 3928 7603 3559 7604 3929 7604 4050 7604 3561 7605 3929 7605 3559 7605 3561 7606 3930 7606 3929 7606 3563 7607 3930 7607 3561 7607 3565 7608 3930 7608 3563 7608 3565 7609 3931 7609 3930 7609 3567 7610 3931 7610 3565 7610 3567 7611 3932 7611 3931 7611 3569 7612 3932 7612 3567 7612 3570 7613 3932 7613 3569 7613 3570 7614 3933 7614 3932 7614 3573 7615 3933 7615 3570 7615 3573 7616 3934 7616 3933 7616 3574 7617 3934 7617 3573 7617 3574 7618 3935 7618 3934 7618 3576 7619 3935 7619 3574 7619 3576 7620 3936 7620 3935 7620 3578 7621 3936 7621 3576 7621 3578 7622 3937 7622 3936 7622 3580 7623 3937 7623 3578 7623 3581 7624 3937 7624 3580 7624 3581 7625 3938 7625 3937 7625 3582 7626 3938 7626 3581 7626 3582 7627 3939 7627 3938 7627 3585 7628 3939 7628 3582 7628 3586 7629 3939 7629 3585 7629 3586 7630 3940 7630 3939 7630 3588 7631 3940 7631 3586 7631 3588 7632 3941 7632 3940 7632 3590 7633 3941 7633 3588 7633 3590 7634 3942 7634 3941 7634 4051 7635 3942 7635 3590 7635 4052 7636 3942 7636 4051 7636 4052 7637 3943 7637 3942 7637 3595 7638 3943 7638 4052 7638 3595 7639 3944 7639 3943 7639 3597 7640 3944 7640 3595 7640 3597 7641 3945 7641 3944 7641 3599 7642 3945 7642 3597 7642 3599 7643 3946 7643 3945 7643 3601 7644 3946 7644 3599 7644 3601 7645 3947 7645 3946 7645 3602 7646 3947 7646 3601 7646 3604 7647 3947 7647 3602 7647 3605 7648 3947 7648 3604 7648 3605 7649 3948 7649 3947 7649 3607 7650 3949 7650 3605 7650 3605 7651 3949 7651 3948 7651 3609 7652 3949 7652 3607 7652 3611 7653 3949 7653 3609 7653 3611 7654 3950 7654 3949 7654 3613 7655 3950 7655 3611 7655 3613 7656 3951 7656 3950 7656 3614 7657 3951 7657 3613 7657 3614 7658 3952 7658 3951 7658 3616 7659 3952 7659 3614 7659 3616 7660 3953 7660 3952 7660 3617 7661 3953 7661 3616 7661 3617 7662 3954 7662 3953 7662 3621 7663 3954 7663 3617 7663 3623 7664 3954 7664 3621 7664 3623 7665 3955 7665 3954 7665 3624 7666 3955 7666 3623 7666 3624 7667 3956 7667 3955 7667 3626 7668 3956 7668 3624 7668 3626 7669 3957 7669 3956 7669 3627 7670 3957 7670 3626 7670 3627 7671 3958 7671 3957 7671 3629 7672 3958 7672 3627 7672 3629 7673 3959 7673 3958 7673 3631 7674 3959 7674 3629 7674 3631 7675 3960 7675 3959 7675 3633 7676 3960 7676 3631 7676 3633 7677 3961 7677 3960 7677 3634 7678 3961 7678 3633 7678 3636 7679 3961 7679 3634 7679 3636 7680 3962 7680 3961 7680 3638 7681 3962 7681 3636 7681 4053 7682 3962 7682 3638 7682 4053 7683 3963 7683 3962 7683 3643 7684 3963 7684 4053 7684 3643 7685 3964 7685 3963 7685 3644 7686 3964 7686 3643 7686 3644 7687 3965 7687 3964 7687 3646 7688 3965 7688 3644 7688 3646 7689 3966 7689 3965 7689 3648 7690 3966 7690 3646 7690 3648 7691 3967 7691 3966 7691 3650 7692 3967 7692 3648 7692 3651 7693 3967 7693 3650 7693 3651 7694 3968 7694 3967 7694 3653 7695 3968 7695 3651 7695 3654 7696 3969 7696 3653 7696 3653 7697 3969 7697 3968 7697 3657 7698 3969 7698 3654 7698 3657 7699 3686 7699 3969 7699 4054 7700 3686 7700 3657 7700 4054 7701 3970 7701 3686 7701 3661 7702 3970 7702 4054 7702 3661 7703 3971 7703 3970 7703 3662 7704 3971 7704 3661 7704 3662 7705 3972 7705 3971 7705 3664 7706 3972 7706 3662 7706 3665 7707 3972 7707 3664 7707 3665 7708 3973 7708 3972 7708 3667 7709 3973 7709 3665 7709 3667 7710 3974 7710 3973 7710 3669 7711 3974 7711 3667 7711 3670 7712 3974 7712 3669 7712 3670 7713 3975 7713 3974 7713 3672 7714 3975 7714 3670 7714 3672 7715 3976 7715 3975 7715 3674 7716 3976 7716 3672 7716 3675 7717 3976 7717 3674 7717 3677 7718 3976 7718 3675 7718 3677 7719 3977 7719 3976 7719 3679 7720 3977 7720 3677 7720 3679 7721 3978 7721 3977 7721 3680 7722 3978 7722 3679 7722 3681 7723 3979 7723 3680 7723 3680 7724 3979 7724 3978 7724 3683 7725 3979 7725 3681 7725 3683 7726 3980 7726 3979 7726 3685 7727 3980 7727 3683 7727 3687 7728 3980 7728 3685 7728 3687 7729 3981 7729 3980 7729 3689 7730 3981 7730 3687 7730 3689 7731 3982 7731 3981 7731 3691 7732 3982 7732 3689 7732 3691 7733 3983 7733 3982 7733 3692 7734 3983 7734 3691 7734 3695 7735 3983 7735 3692 7735 3695 7736 3984 7736 3983 7736 3697 7737 3984 7737 3695 7737 3697 7738 3985 7738 3984 7738 3699 7739 3985 7739 3697 7739 3701 7740 3985 7740 3699 7740 3701 7741 3986 7741 3985 7741 4055 7742 3986 7742 3701 7742 3702 7743 3986 7743 4055 7743 3702 7744 3987 7744 3986 7744 3702 7745 3988 7745 3987 7745 3704 7746 3988 7746 3702 7746 3704 7747 3989 7747 3988 7747 3706 7748 3989 7748 3704 7748 3706 7749 3990 7749 3989 7749 3708 7750 3990 7750 3706 7750 3710 7751 3990 7751 3708 7751 3710 7752 3991 7752 3990 7752 3711 7753 3991 7753 3710 7753 3711 7754 3992 7754 3991 7754 4056 7755 3992 7755 3711 7755 3717 7756 3992 7756 4056 7756 3717 7757 3993 7757 3992 7757 3718 7758 3993 7758 3717 7758 3718 7759 3994 7759 3993 7759 3720 7760 3994 7760 3718 7760 3720 7761 3995 7761 3994 7761 3720 7762 3996 7762 3995 7762 4057 7763 3996 7763 3720 7763 4057 7764 3997 7764 3996 7764 3724 7765 3997 7765 4057 7765 3726 7766 3997 7766 3724 7766 3726 7767 3998 7767 3997 7767 3728 7768 3998 7768 3726 7768 3728 7769 3999 7769 3998 7769 3729 7770 3999 7770 3728 7770 3729 7771 4000 7771 3999 7771 3731 7772 4000 7772 3729 7772 3733 7773 4000 7773 3731 7773 3733 7774 4001 7774 4000 7774 3736 7775 4001 7775 3733 7775 3736 7776 4002 7776 4001 7776 3738 7777 4002 7777 3736 7777 3738 7778 4003 7778 4002 7778 3739 7779 4003 7779 3738 7779 3741 7780 4003 7780 3739 7780 4058 7781 4004 7781 3741 7781 3741 7782 4004 7782 4003 7782 4059 7783 4004 7783 4058 7783 4059 7784 4005 7784 4004 7784 3745 7785 4005 7785 4059 7785 3747 7786 4005 7786 3745 7786 3747 7787 4006 7787 4005 7787 3749 7788 4006 7788 3747 7788 3749 7789 4007 7789 4006 7789 3750 7790 4007 7790 3749 7790 3752 7791 4007 7791 3750 7791 3752 7792 4008 7792 4007 7792 3753 7793 4008 7793 3752 7793 3755 7794 4008 7794 3753 7794 3755 7795 4009 7795 4008 7795 3757 7796 4009 7796 3755 7796 3759 7797 4009 7797 3757 7797 3759 7798 4010 7798 4009 7798 3760 7799 4010 7799 3759 7799 3760 7800 4011 7800 4010 7800 3762 7801 4011 7801 3760 7801 3762 7802 4012 7802 4011 7802 3764 7803 4012 7803 3762 7803 3766 7804 4012 7804 3764 7804 3766 7805 4013 7805 4012 7805 4060 7806 4013 7806 3766 7806 4060 7807 4014 7807 4013 7807 4061 7808 4014 7808 4060 7808 4061 7809 4015 7809 4014 7809 3771 7810 4015 7810 4061 7810 3774 7811 4015 7811 3771 7811 3774 7812 4016 7812 4015 7812 3775 7813 4016 7813 3774 7813 3775 7814 4017 7814 4016 7814 3777 7815 4017 7815 3775 7815 3777 7816 4018 7816 4017 7816 3778 7817 4018 7817 3777 7817 3778 7818 4019 7818 4018 7818 3780 7819 4019 7819 3778 7819 3780 7820 4020 7820 4019 7820 3782 7821 4020 7821 3780 7821 3783 7822 4020 7822 3782 7822 3783 7823 4021 7823 4020 7823 3785 7824 4021 7824 3783 7824 3788 7825 4021 7825 3785 7825 3788 7826 4022 7826 4021 7826 3789 7827 4022 7827 3788 7827 3789 7828 4023 7828 4022 7828 3791 7829 4023 7829 3789 7829 3793 7830 4023 7830 3791 7830 3793 7831 4024 7831 4023 7831 3795 7832 4024 7832 3793 7832 3796 7833 4024 7833 3795 7833 3796 7834 4025 7834 4024 7834 3798 7835 4025 7835 3796 7835 3798 7836 4026 7836 4025 7836 3800 7837 4026 7837 3798 7837 3800 7838 4027 7838 4026 7838 3802 7839 4027 7839 3800 7839 3804 7840 4027 7840 3802 7840 3804 7841 4028 7841 4027 7841 3806 7842 4028 7842 3804 7842 3806 7843 4029 7843 4028 7843 3807 7844 4029 7844 3806 7844 3807 7845 4030 7845 4029 7845 3809 7846 4030 7846 3807 7846 3809 7847 3334 7847 4030 7847 3811 7848 3334 7848 3809 7848 3811 7849 3337 7849 3334 7849 3813 7850 3337 7850 3811 7850 3814 7851 3337 7851 3813 7851 3814 7852 3340 7852 3337 7852 3816 7853 3340 7853 3814 7853 3818 7854 3340 7854 3816 7854 3818 7855 3342 7855 3340 7855 4062 7856 3342 7856 3818 7856 4062 7857 3343 7857 3342 7857 3821 7858 3343 7858 4062 7858 3821 7859 3344 7859 3343 7859 4035 7860 4034 7860 3345 7860 3346 7861 4035 7861 3345 7861 3347 7862 4035 7862 3346 7862 3348 7863 4036 7863 3347 7863 3351 7864 4036 7864 3348 7864 3366 7865 4037 7865 3364 7865 3368 7866 4037 7866 3366 7866 3387 7867 3383 7867 3385 7867 4038 7868 3389 7868 3390 7868 3392 7869 4038 7869 3390 7869 3398 7870 3396 7870 3397 7870 4039 7871 3402 7871 3404 7871 3405 7872 4039 7872 3404 7872 4040 7873 3444 7873 3446 7873 3448 7874 4040 7874 3446 7874 3450 7875 4040 7875 3448 7875 3451 7876 4041 7876 3450 7876 3469 7877 4042 7877 3468 7877 3498 7878 4043 7878 3496 7878 4044 7879 4043 7879 3498 7879 3500 7880 4044 7880 3498 7880 3525 7881 4045 7881 3523 7881 3527 7882 4045 7882 3525 7882 4046 7883 3527 7883 3528 7883 3530 7884 4046 7884 3528 7884 3544 7885 4047 7885 3542 7885 4048 7886 4047 7886 3544 7886 3546 7887 4048 7887 3544 7887 4049 7888 4048 7888 3546 7888 3548 7889 4049 7889 3546 7889 3549 7890 4049 7890 3548 7890 3559 7891 4050 7891 3557 7891 4051 7892 3590 7892 3592 7892 3594 7893 4051 7893 3592 7893 4052 7894 4051 7894 3594 7894 3595 7895 4052 7895 3594 7895 3621 7896 3617 7896 3619 7896 4053 7897 3638 7897 3639 7897 3641 7898 4053 7898 3639 7898 3643 7899 4053 7899 3641 7899 3658 7900 4054 7900 3657 7900 3661 7901 4054 7901 3658 7901 3697 7902 3695 7902 3696 7902 3702 7903 4055 7903 3701 7903 4056 7904 3711 7904 3713 7904 3715 7905 4056 7905 3713 7905 3717 7906 4056 7906 3715 7906 4057 7907 3720 7907 3722 7907 3724 7908 4057 7908 3722 7908 3736 7909 3733 7909 3734 7909 3743 7910 4058 7910 3741 7910 4059 7911 4058 7911 3743 7911 3745 7912 4059 7912 3743 7912 4060 7913 3766 7913 3767 7913 3769 7914 4060 7914 3767 7914 4061 7915 4060 7915 3769 7915 3771 7916 4061 7916 3769 7916 3819 7917 4062 7917 3818 7917 3821 7918 4062 7918 3819 7918 3823 7919 3344 7919 3821 7919 3825 7920 3344 7920 3823 7920 3826 7921 4064 7921 3825 7921 4065 7922 4064 7922 4063 7922 4065 7923 4063 7923 4066 7923 3825 7924 4064 7924 4065 7924 4067 7925 3825 7925 4065 7925 4067 7926 4065 7926 4066 7926 4068 7927 4067 7927 4066 7927 3344 7928 3825 7928 4067 7928 4068 7929 4066 7929 4069 7929 3344 7930 4067 7930 4068 7930 4070 7931 4069 7931 4066 7931 4068 7932 4069 7932 4072 7932 4071 7933 3344 7933 4068 7933 4071 7934 4068 7934 4072 7934 4072 7935 4069 7935 4070 7935 4074 7936 4072 7936 4070 7936 4073 7937 4071 7937 4072 7937 4075 7938 4074 7938 4070 7938 4073 7939 4072 7939 4074 7939 4075 7940 4070 7940 4076 7940 4077 7941 4073 7941 4074 7941 4077 7942 4071 7942 4073 7942 4078 7943 4077 7943 4074 7943 4079 7944 4075 7944 4076 7944 4080 7945 4074 7945 4075 7945 4080 7946 4075 7946 4079 7946 4080 7947 4078 7947 4074 7947 4080 7948 4082 7948 4078 7948 4081 7949 4079 7949 4076 7949 4082 7950 4080 7950 4079 7950 4083 7951 4079 7951 4081 7951 4083 7952 4082 7952 4079 7952 4085 7953 4083 7953 4081 7953 4084 7954 4083 7954 4085 7954 4082 7955 4083 7955 4084 7955 4084 7956 4087 7956 4082 7956 4086 7957 4084 7957 4085 7957 4087 7958 4084 7958 4086 7958 4088 7959 4086 7959 4085 7959 4088 7960 4085 7960 4089 7960 4090 7961 4087 7961 4086 7961 4090 7962 4086 7962 4088 7962 4091 7963 4087 7963 4090 7963 4092 7964 4090 7964 4088 7964 4093 7965 4091 7965 4090 7965 4092 7966 4088 7966 4089 7966 4093 7967 4090 7967 4092 7967 4093 7968 4097 7968 4091 7968 4094 7969 4092 7969 4089 7969 4094 7970 4089 7970 4095 7970 4096 7971 4092 7971 4094 7971 4096 7972 4093 7972 4092 7972 4097 7973 4093 7973 4096 7973 3331 7974 4097 7974 4096 7974 4099 7975 4094 7975 4095 7975 4098 7976 4096 7976 4094 7976 4098 7977 4094 7977 4099 7977 3331 7978 4096 7978 4098 7978 4100 7979 4099 7979 4095 7979 4101 7980 3331 7980 4098 7980 4101 7981 4098 7981 4099 7981 4102 7982 4100 7982 4095 7982 4103 7983 4101 7983 4099 7983 4104 7984 4099 7984 4100 7984 4103 7985 4099 7985 4104 7985 4102 7986 4104 7986 4100 7986 4103 7987 3333 7987 4101 7987 3336 7988 3333 7988 4103 7988 3336 7989 4103 7989 4104 7989 4105 7990 4104 7990 4102 7990 4106 7991 4104 7991 4105 7991 4106 7992 3336 7992 4104 7992 4107 7993 4105 7993 4102 7993 4108 7994 4105 7994 4107 7994 3338 7995 3336 7995 4106 7995 4108 7996 4106 7996 4105 7996 3338 7997 4106 7997 4108 7997 4108 7998 4107 7998 4110 7998 4109 7999 3338 7999 4108 7999 4110 8000 4107 8000 4111 8000 4110 8001 4109 8001 4108 8001 3339 8002 4109 8002 4110 8002 4112 8003 4110 8003 4111 8003 4113 8004 4110 8004 4112 8004 4113 8005 3339 8005 4110 8005 4113 8006 3341 8006 3339 8006 4114 8007 4113 8007 4112 8007 4114 8008 3341 8008 4113 8008 4115 8009 4114 8009 4112 8009 4115 8010 4112 8010 4111 8010 3341 8011 4114 8011 4115 8011 3826 8012 3341 8012 4115 8012 4063 8013 4115 8013 4111 8013 4115 8014 4063 8014 4064 8014 3826 8015 4115 8015 4064 8015 4076 8016 4066 8016 4063 8016 4076 8017 4063 8017 4111 8017 4076 8018 4070 8018 4066 8018 4076 8019 4085 8019 4081 8019 4076 8020 4089 8020 4085 8020 4076 8021 4102 8021 4095 8021 4076 8022 4107 8022 4102 8022 4076 8023 4111 8023 4107 8023 4076 8024 4095 8024 4089 8024 4119 8025 4117 8025 4116 8025 4118 8026 4117 8026 4119 8026 4119 8027 4116 8027 4120 8027 4121 8028 4118 8028 4119 8028 4122 8029 4119 8029 4120 8029 4123 8030 4119 8030 4122 8030 4123 8031 4121 8031 4119 8031 4124 8032 4123 8032 4122 8032 4125 8033 4121 8033 4123 8033 4126 8034 4123 8034 4124 8034 4125 8035 4123 8035 4126 8035 4126 8036 4124 8036 4127 8036 4128 8037 4126 8037 4127 8037 4128 8038 4125 8038 4126 8038 4129 8039 4125 8039 4128 8039 4128 8040 4127 8040 4130 8040 4132 8041 4125 8041 4129 8041 4131 8042 4128 8042 4130 8042 4129 8043 4128 8043 4131 8043 4133 8044 4131 8044 4130 8044 4132 8045 4129 8045 4131 8045 4132 8046 4131 8046 4134 8046 4134 8047 4131 8047 4133 8047 4134 8048 4133 8048 4135 8048 4137 8049 4132 8049 4134 8049 4136 8050 4134 8050 4135 8050 4137 8051 4134 8051 4136 8051 4141 8052 4132 8052 4137 8052 4139 8053 4137 8053 4136 8053 4139 8054 4136 8054 4138 8054 4139 8055 4141 8055 4137 8055 4140 8056 4139 8056 4138 8056 4142 8057 4139 8057 4140 8057 4142 8058 4141 8058 4139 8058 4143 8059 4142 8059 4140 8059 4144 8060 4141 8060 4142 8060 4145 8061 4142 8061 4143 8061 4144 8062 4142 8062 4145 8062 4145 8063 4143 8063 4146 8063 4147 8064 4145 8064 4146 8064 4148 8065 4144 8065 4145 8065 4149 8066 4147 8066 4146 8066 4147 8067 4148 8067 4145 8067 4148 8068 4147 8068 4149 8068 4151 8069 4148 8069 4149 8069 4151 8070 4149 8070 4150 8070 4151 8071 4150 8071 4152 8071 4153 8072 4151 8072 4152 8072 4153 8073 4152 8073 4154 8073 4155 8074 4151 8074 4153 8074 4155 8075 4153 8075 4154 8075 4157 8076 4155 8076 4154 8076 4157 8077 4154 8077 4156 8077 4160 8078 4155 8078 4157 8078 4159 8079 4156 8079 4158 8079 4159 8080 4157 8080 4156 8080 4160 8081 4157 8081 4159 8081 4162 8082 4160 8082 4159 8082 4161 8083 4159 8083 4158 8083 4162 8084 4159 8084 4161 8084 4164 8085 4160 8085 4162 8085 4165 8086 4161 8086 4163 8086 4165 8087 4162 8087 4161 8087 4164 8088 4162 8088 4165 8088 4166 8089 4165 8089 4163 8089 4164 8090 4165 8090 4167 8090 4167 8091 4165 8091 4166 8091 4168 8092 4167 8092 4166 8092 4169 8093 4164 8093 4167 8093 4169 8094 4167 8094 4170 8094 4170 8095 4167 8095 4168 8095 4171 8096 4170 8096 4168 8096 4173 8097 4169 8097 4170 8097 4173 8098 4171 8098 4172 8098 4173 8099 4170 8099 4171 8099 4174 8100 4169 8100 4173 8100 4174 8101 4173 8101 4172 8101 4174 8102 4172 8102 4175 8102 4177 8103 4174 8103 4175 8103 4177 8104 4175 8104 4176 8104 4179 8105 4174 8105 4177 8105 4178 8106 4177 8106 4176 8106 4179 8107 4177 8107 4178 8107 4180 8108 4178 8108 4176 8108 4181 8109 4178 8109 4180 8109 4181 8110 4179 8110 4178 8110 4181 8111 4180 8111 4182 8111 4183 8112 4181 8112 4182 8112 4184 8113 4179 8113 4181 8113 4184 8114 4181 8114 4183 8114 4185 8115 4183 8115 4182 8115 4186 8116 4184 8116 4183 8116 4186 8117 4183 8117 4185 8117 4117 8118 4186 8118 4185 8118 4117 8119 4185 8119 4187 8119 4118 8120 4184 8120 4186 8120 4187 8121 4116 8121 4117 8121 4118 8122 4186 8122 4117 8122 4120 8123 4116 8123 4188 8123 4120 8124 4188 8124 4189 8124 4122 8125 4120 8125 4189 8125 4122 8126 4189 8126 4190 8126 4124 8127 4122 8127 4190 8127 4124 8128 4190 8128 4251 8128 4127 8129 4124 8129 4251 8129 4127 8130 4251 8130 4191 8130 4130 8131 4191 8131 4192 8131 4130 8132 4127 8132 4191 8132 4133 8133 4130 8133 4192 8133 4133 8134 4192 8134 4247 8134 4135 8135 4133 8135 4247 8135 4135 8136 4247 8136 4193 8136 4136 8137 4135 8137 4193 8137 4136 8138 4193 8138 4194 8138 4138 8139 4136 8139 4194 8139 4138 8140 4194 8140 4195 8140 4140 8141 4138 8141 4195 8141 4140 8142 4195 8142 4196 8142 4143 8143 4140 8143 4196 8143 4143 8144 4196 8144 4197 8144 4146 8145 4143 8145 4197 8145 4146 8146 4197 8146 4241 8146 4149 8147 4146 8147 4241 8147 4149 8148 4241 8148 4198 8148 4149 8149 4198 8149 4199 8149 4150 8150 4149 8150 4199 8150 4152 8151 4199 8151 4237 8151 4152 8152 4150 8152 4199 8152 4154 8153 4152 8153 4237 8153 4154 8154 4237 8154 4235 8154 4154 8155 4235 8155 4200 8155 4156 8156 4154 8156 4200 8156 4156 8157 4200 8157 4201 8157 4158 8158 4156 8158 4201 8158 4158 8159 4201 8159 4202 8159 4161 8160 4202 8160 4203 8160 4161 8161 4158 8161 4202 8161 4163 8162 4161 8162 4203 8162 4163 8163 4203 8163 4204 8163 4163 8164 4204 8164 4205 8164 4166 8165 4163 8165 4205 8165 4168 8166 4166 8166 4205 8166 4168 8167 4205 8167 4206 8167 4168 8168 4206 8168 4227 8168 4171 8169 4168 8169 4227 8169 4171 8170 4227 8170 4225 8170 4172 8171 4171 8171 4225 8171 4172 8172 4225 8172 4223 8172 4175 8173 4172 8173 4223 8173 4175 8174 4223 8174 4207 8174 4176 8175 4175 8175 4207 8175 4176 8176 4207 8176 4219 8176 4180 8177 4176 8177 4219 8177 4180 8178 4219 8178 4208 8178 4182 8179 4180 8179 4208 8179 4182 8180 4208 8180 4209 8180 4185 8181 4182 8181 4209 8181 4185 8182 4209 8182 4210 8182 4187 8183 4210 8183 4211 8183 4187 8184 4185 8184 4210 8184 4116 8185 4187 8185 4211 8185 4116 8186 4211 8186 4188 8186 3831 8187 4160 8187 4164 8187 3357 8188 4160 8188 3831 8188 3832 8189 3831 8189 4164 8189 3832 8190 4164 8190 4169 8190 3355 8191 4160 8191 3357 8191 3355 8192 4155 8192 4160 8192 4032 8193 3832 8193 4169 8193 3349 8194 4155 8194 3355 8194 4032 8195 4169 8195 4174 8195 3349 8196 4151 8196 4155 8196 3349 8197 4148 8197 4151 8197 4032 8198 4174 8198 4179 8198 3352 8199 4148 8199 3349 8199 4033 8200 4032 8200 4179 8200 4144 8201 4148 8201 3352 8201 4144 8202 3352 8202 3350 8202 4184 8203 4033 8203 4179 8203 4141 8204 4144 8204 3350 8204 4118 8205 4033 8205 4184 8205 4118 8206 4031 8206 4033 8206 4141 8207 3350 8207 3346 8207 4132 8208 4141 8208 3346 8208 4121 8209 4031 8209 4118 8209 4121 8210 4034 8210 4031 8210 4132 8211 3346 8211 3345 8211 4125 8212 4034 8212 4121 8212 4125 8213 4132 8213 3345 8213 4125 8214 3345 8214 4034 8214 4213 8215 4212 8215 4211 8215 4213 8216 4211 8216 4210 8216 4214 8217 4213 8217 4210 8217 4209 8218 4214 8218 4210 8218 4215 8219 4212 8219 4213 8219 4215 8220 4213 8220 4214 8220 4216 8221 4214 8221 4209 8221 4216 8222 4209 8222 4208 8222 4215 8223 4214 8223 4216 8223 4218 8224 4215 8224 4216 8224 4217 8225 4216 8225 4208 8225 4217 8226 4208 8226 4219 8226 4218 8227 4216 8227 4217 8227 4220 8228 4217 8228 4219 8228 4221 8229 4217 8229 4220 8229 4221 8230 4218 8230 4217 8230 4207 8231 4220 8231 4219 8231 4222 8232 4220 8232 4207 8232 4222 8233 4221 8233 4220 8233 4223 8234 4222 8234 4207 8234 4224 8235 4221 8235 4222 8235 4225 8236 4222 8236 4223 8236 4224 8237 4222 8237 4225 8237 4226 8238 4224 8238 4225 8238 4226 8239 4225 8239 4227 8239 4228 8240 4226 8240 4227 8240 4206 8241 4228 8241 4227 8241 4229 8242 4226 8242 4228 8242 4228 8243 4206 8243 4205 8243 4230 8244 4226 8244 4229 8244 4230 8245 4229 8245 4228 8245 4204 8246 4228 8246 4205 8246 4230 8247 4228 8247 4204 8247 4231 8248 4230 8248 4204 8248 4231 8249 4204 8249 4203 8249 4232 8250 4230 8250 4231 8250 4232 8251 4231 8251 4203 8251 4232 8252 4203 8252 4202 8252 4233 8253 4232 8253 4202 8253 4234 8254 4233 8254 4202 8254 4234 8255 4202 8255 4201 8255 4234 8256 4201 8256 4200 8256 4235 8257 4234 8257 4200 8257 4236 8258 4233 8258 4234 8258 4236 8259 4234 8259 4235 8259 4237 8260 4236 8260 4235 8260 4238 8261 4236 8261 4237 8261 4239 8262 4237 8262 4199 8262 4239 8263 4238 8263 4237 8263 4198 8264 4239 8264 4199 8264 4241 8265 4239 8265 4198 8265 4240 8266 4238 8266 4239 8266 4240 8267 4239 8267 4241 8267 4242 8268 4241 8268 4197 8268 4242 8269 4240 8269 4241 8269 4243 8270 4240 8270 4242 8270 4242 8271 4197 8271 4196 8271 4245 8272 4240 8272 4243 8272 4195 8273 4242 8273 4196 8273 4195 8274 4243 8274 4242 8274 4244 8275 4243 8275 4195 8275 4245 8276 4243 8276 4244 8276 4244 8277 4195 8277 4194 8277 4246 8278 4245 8278 4244 8278 4193 8279 4244 8279 4194 8279 4246 8280 4244 8280 4193 8280 4248 8281 4193 8281 4247 8281 4248 8282 4246 8282 4193 8282 4192 8283 4248 8283 4247 8283 4249 8284 4248 8284 4192 8284 4191 8285 4249 8285 4192 8285 4250 8286 4248 8286 4249 8286 4251 8287 4249 8287 4191 8287 4250 8288 4249 8288 4251 8288 4252 8289 4250 8289 4251 8289 4252 8290 4251 8290 4190 8290 4253 8291 4252 8291 4190 8291 4254 8292 4252 8292 4253 8292 4250 8293 4252 8293 4254 8293 4189 8294 4253 8294 4190 8294 4255 8295 4253 8295 4189 8295 4255 8296 4189 8296 4188 8296 4254 8297 4253 8297 4255 8297 4211 8298 4255 8298 4188 8298 4212 8299 4254 8299 4255 8299 4212 8300 4255 8300 4211 8300 3319 8301 3321 8301 3326 8301 3326 8302 3321 8302 3324 8302 3317 8303 3319 8303 3327 8303 3327 8304 3319 8304 3326 8304 3314 8305 3317 8305 3328 8305 3328 8306 3317 8306 3327 8306

+
+ + + +

4257 8307 4258 8307 4256 8307 4256 8308 4258 8308 4259 8308 4257 8309 4260 8309 4258 8309 4260 8310 4261 8310 4258 8310 4260 8311 4262 8311 4261 8311 4262 8312 4263 8312 4261 8312 4264 8313 4265 8313 4262 8313 4262 8314 4265 8314 4263 8314 4264 8315 4266 8315 4265 8315 4266 8316 4267 8316 4265 8316 4256 8317 4259 8317 4266 8317 4266 8318 4259 8318 4267 8318 4265 8319 4267 8319 4268 8319 4268 8320 4267 8320 4269 8320 4267 8321 4259 8321 4269 8321 4269 8322 4259 8322 4273 8322 4259 8323 4258 8323 4273 8323 4273 8324 4258 8324 4272 8324 4257 8325 4262 8325 4260 8325 4264 8326 4262 8326 4266 8326 4266 8327 4262 8327 4256 8327 4256 8328 4262 8328 4257 8328 4271 8329 5139 8329 5142 8329 4271 8330 5137 8330 5139 8330 4272 8331 4271 8331 5142 8331 4272 8332 5146 8332 5150 8332 4272 8333 5142 8333 5146 8333 5151 8334 4272 8334 5150 8334 4270 8335 5183 8335 5137 8335 4270 8336 5180 8336 5183 8336 4270 8337 5137 8337 4271 8337 5176 8338 5180 8338 4270 8338 4273 8339 4272 8339 5151 8339 4273 8340 5151 8340 5155 8340 5158 8341 4273 8341 5155 8341 4268 8342 5176 8342 4270 8342 5174 8343 5176 8343 4268 8343 5163 8344 4269 8344 4273 8344 5163 8345 4273 8345 5158 8345 5169 8346 5174 8346 4268 8346 5168 8347 4269 8347 5163 8347 5169 8348 4268 8348 4269 8348 5169 8349 4269 8349 5168 8349 4274 8350 5028 8350 4275 8350 4276 8351 5026 8351 5028 8351 4276 8352 5028 8352 4274 8352 4274 8353 4275 8353 5032 8353 4277 8354 4274 8354 5032 8354 4276 8355 5022 8355 5026 8355 4277 8356 5032 8356 4278 8356 4279 8357 5022 8357 4276 8357 4279 8358 5018 8358 5022 8358 4280 8359 4277 8359 4278 8359 4279 8360 5016 8360 5018 8360 4281 8361 4277 8361 4280 8361 4282 8362 5016 8362 4279 8362 4283 8363 5016 8363 4282 8363 4283 8364 4282 8364 4285 8364 5009 8365 4283 8365 4285 8365 4286 8366 5009 8366 4285 8366 4286 8367 4285 8367 4287 8367 4288 8368 4286 8368 4287 8368 4293 8369 4291 8369 4290 8369 4293 8370 4292 8370 4291 8370 4296 8371 4292 8371 4293 8371 4296 8372 4294 8372 4292 8372 4298 8373 4294 8373 4296 8373 4298 8374 4297 8374 4294 8374 4295 8375 4297 8375 4298 8375 4295 8376 4299 8376 4297 8376 4300 8377 4299 8377 4295 8377 4300 8378 4301 8378 4299 8378 4302 8379 4301 8379 4300 8379 4302 8380 4303 8380 4301 8380 4302 8381 4304 8381 4303 8381 4305 8382 4304 8382 4302 8382 4305 8383 4306 8383 4304 8383 4307 8384 4306 8384 4305 8384 4307 8385 4308 8385 4306 8385 4307 8386 4309 8386 4308 8386 4310 8387 4309 8387 4307 8387 4310 8388 4311 8388 4309 8388 4310 8389 4312 8389 4311 8389 4313 8390 4312 8390 4310 8390 4313 8391 4314 8391 4312 8391 4315 8392 4314 8392 4313 8392 4315 8393 4316 8393 4314 8393 4317 8394 4316 8394 4315 8394 4317 8395 4318 8395 4316 8395 4319 8396 4318 8396 4317 8396 4319 8397 4320 8397 4318 8397 4321 8398 4320 8398 4319 8398 4321 8399 4322 8399 4320 8399 4321 8400 4323 8400 4322 8400 4324 8401 4323 8401 4321 8401 4324 8402 4325 8402 4323 8402 4326 8403 4325 8403 4324 8403 4326 8404 4327 8404 4325 8404 4328 8405 4327 8405 4326 8405 4328 8406 4329 8406 4327 8406 4328 8407 4330 8407 4329 8407 4331 8408 4330 8408 4328 8408 4331 8409 4332 8409 4330 8409 4333 8410 4332 8410 4331 8410 4333 8411 4334 8411 4332 8411 4333 8412 4335 8412 4334 8412 4336 8413 4335 8413 4333 8413 4336 8414 4337 8414 4335 8414 4338 8415 4337 8415 4336 8415 4338 8416 4339 8416 4337 8416 4340 8417 4341 8417 4338 8417 4338 8418 4341 8418 4339 8418 4340 8419 4342 8419 4341 8419 4343 8420 4342 8420 4340 8420 4343 8421 4344 8421 4342 8421 4345 8422 4344 8422 4343 8422 4345 8423 4346 8423 4344 8423 4347 8424 4346 8424 4345 8424 4347 8425 4348 8425 4346 8425 4347 8426 4349 8426 4348 8426 4350 8427 4349 8427 4347 8427 4350 8428 4351 8428 4349 8428 4352 8429 4351 8429 4350 8429 4352 8430 4353 8430 4351 8430 4352 8431 4354 8431 4353 8431 4355 8432 4354 8432 4352 8432 4355 8433 4356 8433 4354 8433 4357 8434 4356 8434 4355 8434 4357 8435 4358 8435 4356 8435 4357 8436 4359 8436 4358 8436 4360 8437 4359 8437 4357 8437 4360 8438 4361 8438 4359 8438 4362 8439 4361 8439 4360 8439 4362 8440 4363 8440 4361 8440 4362 8441 4364 8441 4363 8441 4365 8442 4364 8442 4362 8442 4365 8443 4366 8443 4364 8443 4365 8444 4367 8444 4366 8444 4368 8445 4367 8445 4365 8445 4368 8446 4369 8446 4367 8446 4370 8447 4369 8447 4368 8447 4370 8448 4371 8448 4369 8448 4370 8449 4372 8449 4371 8449 4373 8450 4372 8450 4370 8450 4373 8451 4374 8451 4372 8451 4375 8452 4374 8452 4373 8452 4375 8453 4376 8453 4374 8453 4377 8454 4376 8454 4375 8454 4377 8455 4378 8455 4376 8455 4379 8456 4378 8456 4377 8456 4379 8457 4380 8457 4378 8457 4379 8458 4381 8458 4380 8458 4382 8459 4381 8459 4379 8459 4382 8460 4383 8460 4381 8460 4384 8461 4383 8461 4382 8461 4384 8462 4385 8462 4383 8462 4384 8463 4386 8463 4385 8463 4387 8464 4386 8464 4384 8464 4387 8465 4388 8465 4386 8465 4387 8466 4389 8466 4388 8466 4390 8467 4389 8467 4387 8467 4390 8468 4391 8468 4389 8468 4392 8469 4391 8469 4390 8469 4392 8470 4393 8470 4391 8470 4394 8471 4395 8471 4392 8471 4392 8472 4395 8472 4393 8472 4394 8473 4396 8473 4395 8473 4397 8474 4396 8474 4394 8474 4397 8475 4398 8475 4396 8475 4399 8476 4398 8476 4397 8476 4399 8477 4400 8477 4398 8477 4399 8478 4401 8478 4400 8478 4402 8479 4401 8479 4399 8479 4402 8480 4403 8480 4401 8480 4404 8481 4403 8481 4402 8481 4404 8482 4405 8482 4403 8482 4406 8483 4405 8483 4404 8483 4406 8484 4407 8484 4405 8484 4408 8485 4407 8485 4406 8485 4408 8486 4409 8486 4407 8486 4408 8487 4410 8487 4409 8487 4411 8488 4410 8488 4408 8488 4411 8489 4412 8489 4410 8489 4411 8490 4413 8490 4412 8490 4414 8491 4413 8491 4411 8491 4415 8492 4413 8492 4414 8492 4415 8493 4416 8493 4413 8493 4417 8494 4416 8494 4415 8494 4417 8495 4418 8495 4416 8495 4417 8496 4419 8496 4418 8496 4420 8497 4419 8497 4417 8497 4420 8498 4421 8498 4419 8498 4420 8499 4422 8499 4421 8499 4423 8500 4422 8500 4420 8500 4423 8501 4424 8501 4422 8501 4423 8502 4425 8502 4424 8502 4426 8503 4425 8503 4423 8503 4426 8504 4427 8504 4425 8504 4428 8505 4427 8505 4426 8505 4428 8506 4429 8506 4427 8506 4428 8507 4430 8507 4429 8507 4431 8508 4430 8508 4428 8508 4432 8509 4433 8509 4431 8509 4431 8510 4433 8510 4430 8510 4432 8511 4434 8511 4433 8511 4435 8512 4434 8512 4432 8512 4435 8513 4436 8513 4434 8513 4435 8514 4437 8514 4436 8514 4438 8515 4437 8515 4435 8515 4438 8516 4439 8516 4437 8516 4440 8517 4439 8517 4438 8517 4440 8518 4441 8518 4439 8518 4440 8519 4442 8519 4441 8519 4443 8520 4442 8520 4440 8520 4443 8521 4444 8521 4442 8521 4443 8522 4445 8522 4444 8522 4446 8523 4445 8523 4443 8523 4446 8524 4447 8524 4445 8524 4448 8525 4447 8525 4446 8525 4448 8526 4449 8526 4447 8526 4450 8527 4449 8527 4448 8527 4450 8528 4451 8528 4449 8528 4452 8529 4451 8529 4450 8529 4452 8530 4453 8530 4451 8530 4454 8531 4453 8531 4452 8531 4454 8532 4455 8532 4453 8532 4456 8533 4455 8533 4454 8533 4456 8534 4457 8534 4455 8534 4456 8535 4458 8535 4457 8535 4459 8536 4458 8536 4456 8536 4459 8537 4460 8537 4458 8537 4461 8538 4460 8538 4459 8538 4461 8539 4462 8539 4460 8539 4463 8540 4462 8540 4461 8540 4463 8541 4464 8541 4462 8541 4463 8542 4465 8542 4464 8542 4466 8543 4465 8543 4463 8543 4466 8544 4467 8544 4465 8544 4468 8545 4467 8545 4466 8545 4468 8546 4469 8546 4467 8546 4470 8547 4469 8547 4468 8547 4470 8548 4471 8548 4469 8548 4472 8549 4471 8549 4470 8549 4472 8550 4473 8550 4471 8550 4472 8551 4474 8551 4473 8551 4475 8552 4474 8552 4472 8552 4475 8553 4476 8553 4474 8553 4477 8554 4476 8554 4475 8554 4477 8555 4478 8555 4476 8555 4477 8556 4479 8556 4478 8556 4480 8557 4479 8557 4477 8557 4480 8558 4481 8558 4479 8558 4482 8559 4481 8559 4480 8559 4482 8560 4483 8560 4481 8560 4484 8561 4483 8561 4482 8561 4484 8562 4485 8562 4483 8562 4486 8563 4485 8563 4484 8563 4486 8564 4487 8564 4485 8564 4488 8565 4487 8565 4486 8565 4488 8566 4489 8566 4487 8566 4488 8567 4490 8567 4489 8567 4491 8568 4490 8568 4488 8568 4491 8569 4492 8569 4490 8569 4493 8570 4492 8570 4491 8570 4493 8571 4494 8571 4492 8571 4495 8572 4494 8572 4493 8572 4495 8573 4496 8573 4494 8573 4497 8574 4496 8574 4495 8574 4497 8575 4498 8575 4496 8575 4499 8576 4498 8576 4497 8576 4499 8577 4500 8577 4498 8577 4501 8578 4500 8578 4499 8578 4501 8579 4502 8579 4500 8579 4501 8580 4503 8580 4502 8580 4504 8581 4503 8581 4501 8581 4504 8582 4505 8582 4503 8582 4506 8583 4505 8583 4504 8583 4506 8584 4507 8584 4505 8584 4508 8585 4507 8585 4506 8585 4508 8586 4509 8586 4507 8586 4510 8587 4509 8587 4508 8587 4510 8588 4511 8588 4509 8588 4510 8589 4512 8589 4511 8589 4513 8590 4512 8590 4510 8590 4513 8591 4514 8591 4512 8591 4515 8592 4514 8592 4513 8592 4515 8593 4516 8593 4514 8593 4517 8594 4516 8594 4515 8594 4518 8595 4516 8595 4517 8595 4518 8596 4519 8596 4516 8596 4520 8597 4519 8597 4518 8597 4520 8598 4521 8598 4519 8598 4520 8599 4522 8599 4521 8599 4523 8600 4522 8600 4520 8600 4523 8601 4524 8601 4522 8601 4525 8602 4524 8602 4523 8602 4525 8603 4526 8603 4524 8603 4527 8604 4526 8604 4525 8604 4527 8605 4528 8605 4526 8605 4529 8606 4528 8606 4527 8606 4529 8607 4530 8607 4528 8607 4531 8608 4530 8608 4529 8608 4531 8609 4532 8609 4530 8609 4533 8610 4532 8610 4531 8610 4533 8611 4534 8611 4532 8611 4533 8612 4535 8612 4534 8612 4536 8613 4535 8613 4533 8613 4536 8614 4537 8614 4535 8614 4538 8615 4537 8615 4536 8615 4538 8616 4539 8616 4537 8616 4540 8617 4541 8617 4538 8617 4538 8618 4541 8618 4539 8618 4542 8619 4543 8619 4540 8619 4540 8620 4543 8620 4541 8620 4542 8621 4544 8621 4543 8621 4545 8622 4546 8622 4542 8622 4542 8623 4546 8623 4544 8623 4545 8624 4547 8624 4546 8624 4548 8625 4547 8625 4545 8625 4548 8626 4549 8626 4547 8626 4550 8627 4549 8627 4548 8627 4550 8628 4551 8628 4549 8628 4552 8629 4551 8629 4550 8629 4552 8630 4553 8630 4551 8630 4552 8631 4554 8631 4553 8631 4555 8632 4554 8632 4552 8632 4555 8633 4556 8633 4554 8633 4557 8634 4556 8634 4555 8634 4557 8635 4558 8635 4556 8635 4557 8636 4559 8636 4558 8636 4560 8637 4559 8637 4557 8637 4560 8638 4561 8638 4559 8638 4560 8639 4562 8639 4561 8639 4563 8640 4562 8640 4560 8640 4563 8641 4564 8641 4562 8641 4565 8642 4564 8642 4563 8642 4565 8643 4566 8643 4564 8643 4565 8644 4567 8644 4566 8644 4568 8645 4567 8645 4565 8645 4568 8646 4569 8646 4567 8646 4568 8647 4570 8647 4569 8647 4571 8648 4570 8648 4568 8648 4571 8649 4572 8649 4570 8649 4571 8650 4573 8650 4572 8650 4574 8651 4573 8651 4571 8651 4574 8652 4575 8652 4573 8652 4576 8653 4575 8653 4574 8653 4576 8654 4577 8654 4575 8654 4578 8655 4577 8655 4576 8655 4578 8656 4579 8656 4577 8656 4580 8657 4579 8657 4578 8657 4580 8658 4581 8658 4579 8658 4582 8659 4581 8659 4580 8659 4582 8660 4583 8660 4581 8660 4584 8661 4585 8661 4582 8661 4582 8662 4585 8662 4583 8662 4584 8663 4586 8663 4585 8663 4587 8664 4586 8664 4584 8664 4587 8665 4588 8665 4586 8665 4589 8666 4588 8666 4587 8666 4589 8667 4590 8667 4588 8667 4591 8668 4590 8668 4589 8668 4591 8669 4592 8669 4590 8669 4591 8670 4593 8670 4592 8670 4594 8671 4593 8671 4591 8671 4594 8672 4595 8672 4593 8672 4594 8673 4596 8673 4595 8673 4597 8674 4596 8674 4594 8674 4597 8675 4598 8675 4596 8675 4599 8676 4598 8676 4597 8676 4599 8677 4600 8677 4598 8677 4601 8678 4600 8678 4599 8678 4601 8679 4602 8679 4600 8679 4603 8680 4602 8680 4601 8680 4603 8681 4604 8681 4602 8681 4605 8682 4604 8682 4603 8682 4606 8683 4607 8683 4605 8683 4605 8684 4607 8684 4604 8684 4608 8685 4609 8685 4606 8685 4606 8686 4609 8686 4607 8686 4610 8687 4609 8687 4608 8687 4610 8688 4611 8688 4609 8688 4610 8689 4612 8689 4611 8689 4613 8690 4612 8690 4610 8690 4613 8691 4614 8691 4612 8691 4615 8692 4614 8692 4613 8692 4615 8693 4616 8693 4614 8693 4617 8694 4616 8694 4615 8694 4617 8695 4618 8695 4616 8695 4617 8696 4619 8696 4618 8696 4620 8697 4619 8697 4617 8697 4620 8698 4621 8698 4619 8698 4622 8699 4621 8699 4620 8699 4622 8700 4623 8700 4621 8700 4624 8701 4623 8701 4622 8701 4624 8702 4625 8702 4623 8702 4626 8703 4625 8703 4624 8703 4626 8704 4627 8704 4625 8704 4626 8705 4628 8705 4627 8705 4629 8706 4628 8706 4626 8706 4629 8707 4630 8707 4628 8707 4631 8708 4630 8708 4629 8708 4631 8709 4632 8709 4630 8709 4631 8710 4633 8710 4632 8710 4634 8711 4633 8711 4631 8711 4634 8712 4635 8712 4633 8712 4636 8713 4635 8713 4634 8713 4636 8714 4637 8714 4635 8714 4636 8715 4638 8715 4637 8715 4639 8716 4638 8716 4636 8716 4640 8717 4641 8717 4639 8717 4639 8718 4641 8718 4638 8718 4640 8719 4642 8719 4641 8719 4643 8720 4642 8720 4640 8720 4643 8721 4644 8721 4642 8721 4645 8722 4644 8722 4643 8722 4645 8723 4646 8723 4644 8723 4645 8724 4647 8724 4646 8724 4648 8725 4647 8725 4645 8725 4648 8726 4649 8726 4647 8726 4648 8727 4650 8727 4649 8727 4651 8728 4650 8728 4648 8728 4651 8729 4652 8729 4650 8729 4653 8730 4652 8730 4651 8730 4653 8731 4654 8731 4652 8731 4655 8732 4654 8732 4653 8732 4655 8733 4656 8733 4654 8733 4657 8734 4656 8734 4655 8734 4657 8735 4658 8735 4656 8735 4659 8736 4658 8736 4657 8736 4659 8737 4660 8737 4658 8737 4661 8738 4660 8738 4659 8738 4661 8739 4662 8739 4660 8739 4663 8740 4662 8740 4661 8740 4663 8741 4664 8741 4662 8741 4663 8742 4665 8742 4664 8742 4666 8743 4665 8743 4663 8743 4666 8744 4667 8744 4665 8744 4666 8745 4668 8745 4667 8745 4669 8746 4668 8746 4666 8746 4669 8747 4670 8747 4668 8747 4671 8748 4670 8748 4669 8748 4671 8749 4672 8749 4670 8749 4671 8750 4673 8750 4672 8750 4674 8751 4673 8751 4671 8751 4674 8752 4675 8752 4673 8752 4676 8753 4675 8753 4674 8753 4676 8754 4677 8754 4675 8754 4678 8755 4677 8755 4676 8755 4678 8756 4679 8756 4677 8756 4678 8757 4680 8757 4679 8757 4681 8758 4680 8758 4678 8758 4681 8759 4682 8759 4680 8759 4683 8760 4682 8760 4681 8760 4683 8761 4684 8761 4682 8761 4685 8762 4684 8762 4683 8762 4685 8763 4686 8763 4684 8763 4687 8764 4686 8764 4685 8764 4687 8765 4688 8765 4686 8765 4687 8766 4689 8766 4688 8766 4690 8767 4689 8767 4687 8767 4690 8768 4691 8768 4689 8768 4692 8769 4691 8769 4690 8769 4692 8770 4693 8770 4691 8770 4692 8771 4694 8771 4693 8771 4695 8772 4694 8772 4692 8772 4695 8773 4696 8773 4694 8773 4697 8774 4696 8774 4695 8774 4697 8775 4698 8775 4696 8775 4699 8776 4698 8776 4697 8776 4699 8777 4700 8777 4698 8777 4701 8778 4700 8778 4699 8778 4701 8779 4702 8779 4700 8779 4701 8780 4703 8780 4702 8780 4704 8781 4703 8781 4701 8781 4704 8782 4705 8782 4703 8782 4704 8783 4706 8783 4705 8783 4707 8784 4706 8784 4704 8784 4707 8785 4708 8785 4706 8785 4707 8786 4709 8786 4708 8786 4710 8787 4709 8787 4707 8787 4710 8788 4711 8788 4709 8788 4712 8789 4713 8789 4710 8789 4710 8790 4713 8790 4711 8790 4714 8791 4715 8791 4712 8791 4712 8792 4715 8792 4713 8792 4714 8793 4716 8793 4715 8793 4717 8794 4716 8794 4714 8794 4717 8795 4718 8795 4716 8795 4717 8796 4719 8796 4718 8796 4720 8797 4719 8797 4717 8797 4720 8798 4721 8798 4719 8798 4722 8799 4721 8799 4720 8799 4722 8800 4723 8800 4721 8800 4724 8801 4723 8801 4722 8801 4724 8802 4725 8802 4723 8802 4724 8803 4726 8803 4725 8803 4727 8804 4726 8804 4724 8804 4728 8805 4726 8805 4727 8805 4728 8806 4729 8806 4726 8806 4728 8807 4730 8807 4729 8807 4731 8808 4730 8808 4728 8808 4732 8809 4730 8809 4731 8809 4732 8810 4733 8810 4730 8810 4732 8811 4734 8811 4733 8811 4735 8812 4734 8812 4732 8812 4735 8813 4736 8813 4734 8813 4737 8814 4736 8814 4735 8814 4737 8815 4738 8815 4736 8815 4737 8816 4739 8816 4738 8816 4740 8817 4739 8817 4737 8817 4741 8818 4739 8818 4740 8818 4741 8819 4742 8819 4739 8819 4741 8820 4743 8820 4742 8820 4744 8821 4743 8821 4741 8821 4744 8822 4745 8822 4743 8822 4744 8823 4746 8823 4745 8823 4747 8824 4746 8824 4744 8824 4747 8825 4748 8825 4746 8825 4749 8826 4748 8826 4747 8826 4749 8827 4750 8827 4748 8827 4751 8828 4750 8828 4749 8828 4751 8829 4752 8829 4750 8829 4753 8830 4752 8830 4751 8830 4753 8831 4754 8831 4752 8831 4755 8832 4754 8832 4753 8832 4755 8833 4756 8833 4754 8833 4755 8834 4757 8834 4756 8834 4758 8835 4757 8835 4755 8835 4758 8836 4759 8836 4757 8836 4760 8837 4759 8837 4758 8837 4760 8838 4761 8838 4759 8838 4762 8839 4761 8839 4760 8839 4762 8840 4763 8840 4761 8840 4764 8841 4763 8841 4762 8841 4764 8842 4765 8842 4763 8842 4764 8843 4766 8843 4765 8843 4767 8844 4766 8844 4764 8844 4768 8845 4766 8845 4767 8845 4768 8846 4769 8846 4766 8846 4768 8847 4284 8847 4769 8847 4770 8848 4284 8848 4768 8848 4770 8849 4281 8849 4284 8849 4770 8850 4277 8850 4281 8850 4771 8851 4277 8851 4770 8851 4772 8852 4277 8852 4771 8852 4772 8853 4274 8853 4277 8853 4773 8854 4302 8854 4300 8854 4305 8855 4302 8855 4773 8855 4774 8856 4305 8856 4773 8856 4307 8857 4305 8857 4774 8857 4775 8858 4307 8858 4774 8858 4310 8859 4307 8859 4775 8859 4776 8860 4310 8860 4775 8860 4777 8861 4310 8861 4776 8861 4313 8862 4310 8862 4777 8862 4315 8863 4313 8863 4777 8863 4778 8864 4315 8864 4777 8864 4317 8865 4315 8865 4778 8865 4779 8866 4317 8866 4778 8866 4319 8867 4317 8867 4779 8867 4321 8868 4319 8868 4779 8868 4780 8869 4321 8869 4779 8869 4324 8870 4321 8870 4780 8870 4781 8871 4324 8871 4780 8871 4326 8872 4324 8872 4781 8872 4782 8873 4326 8873 4781 8873 4328 8874 4326 8874 4782 8874 4783 8875 4328 8875 4782 8875 4331 8876 4328 8876 4783 8876 4784 8877 4331 8877 4783 8877 4785 8878 4331 8878 4784 8878 4333 8879 4331 8879 4785 8879 4786 8880 4333 8880 4785 8880 4336 8881 4333 8881 4786 8881 4338 8882 4336 8882 4786 8882 4338 8883 4786 8883 4787 8883 4340 8884 4338 8884 4787 8884 4788 8885 4343 8885 4340 8885 4789 8886 4343 8886 4788 8886 4345 8887 4343 8887 4789 8887 4790 8888 4345 8888 4789 8888 4347 8889 4345 8889 4790 8889 4791 8890 4347 8890 4790 8890 4350 8891 4347 8891 4791 8891 4792 8892 4350 8892 4791 8892 4352 8893 4350 8893 4792 8893 4793 8894 4352 8894 4792 8894 4794 8895 4352 8895 4793 8895 4355 8896 4352 8896 4794 8896 4795 8897 4355 8897 4794 8897 4357 8898 4355 8898 4795 8898 4796 8899 4357 8899 4795 8899 4360 8900 4357 8900 4796 8900 4797 8901 4360 8901 4796 8901 4362 8902 4360 8902 4797 8902 4798 8903 4362 8903 4797 8903 4365 8904 4362 8904 4798 8904 4799 8905 4365 8905 4798 8905 4800 8906 4365 8906 4799 8906 4368 8907 4365 8907 4800 8907 4801 8908 4368 8908 4800 8908 4370 8909 4368 8909 4801 8909 4802 8910 4370 8910 4801 8910 4373 8911 4370 8911 4802 8911 4375 8912 4373 8912 4802 8912 4803 8913 4375 8913 4802 8913 4377 8914 4375 8914 4803 8914 4377 8915 4803 8915 4804 8915 4379 8916 4377 8916 4804 8916 4805 8917 4379 8917 4804 8917 4382 8918 4379 8918 4805 8918 4384 8919 4382 8919 4805 8919 4806 8920 4384 8920 4805 8920 4807 8921 4384 8921 4806 8921 4387 8922 4384 8922 4807 8922 4808 8923 4387 8923 4807 8923 4390 8924 4387 8924 4808 8924 4809 8925 4390 8925 4808 8925 4392 8926 4390 8926 4809 8926 4810 8927 4392 8927 4809 8927 4394 8928 4392 8928 4810 8928 4811 8929 4394 8929 4810 8929 4397 8930 4394 8930 4811 8930 4812 8931 4397 8931 4811 8931 4399 8932 4397 8932 4812 8932 4813 8933 4399 8933 4812 8933 4402 8934 4399 8934 4813 8934 4814 8935 4404 8935 4402 8935 4406 8936 4404 8936 4814 8936 4815 8937 4406 8937 4814 8937 4408 8938 4406 8938 4815 8938 4816 8939 4408 8939 4815 8939 4411 8940 4408 8940 4816 8940 4817 8941 4411 8941 4816 8941 4414 8942 4411 8942 4817 8942 4818 8943 4414 8943 4817 8943 4415 8944 4414 8944 4818 8944 4417 8945 4415 8945 4818 8945 4417 8946 4818 8946 4819 8946 4820 8947 4417 8947 4819 8947 4420 8948 4417 8948 4820 8948 4423 8949 4420 8949 4820 8949 4821 8950 4423 8950 4820 8950 4822 8951 4423 8951 4821 8951 4426 8952 4423 8952 4822 8952 4823 8953 4426 8953 4822 8953 4428 8954 4426 8954 4823 8954 4824 8955 4428 8955 4823 8955 4431 8956 4428 8956 4824 8956 4432 8957 4431 8957 4824 8957 4825 8958 4432 8958 4824 8958 4826 8959 4432 8959 4825 8959 4435 8960 4432 8960 4826 8960 4827 8961 4435 8961 4826 8961 4438 8962 4435 8962 4827 8962 4828 8963 4438 8963 4827 8963 4440 8964 4438 8964 4828 8964 4829 8965 4440 8965 4828 8965 4443 8966 4440 8966 4829 8966 4830 8967 4443 8967 4829 8967 4446 8968 4443 8968 4830 8968 4831 8969 4446 8969 4830 8969 4448 8970 4446 8970 4831 8970 4832 8971 4448 8971 4831 8971 4450 8972 4448 8972 4832 8972 4833 8973 4450 8973 4832 8973 4452 8974 4450 8974 4833 8974 4834 8975 4452 8975 4833 8975 4454 8976 4452 8976 4834 8976 4835 8977 4454 8977 4834 8977 4456 8978 4454 8978 4835 8978 4836 8979 4456 8979 4835 8979 4459 8980 4456 8980 4836 8980 4837 8981 4459 8981 4836 8981 4461 8982 4459 8982 4837 8982 4838 8983 4461 8983 4837 8983 4463 8984 4461 8984 4838 8984 4839 8985 4463 8985 4838 8985 4466 8986 4463 8986 4839 8986 4468 8987 4466 8987 4839 8987 4840 8988 4468 8988 4839 8988 4841 8989 4468 8989 4840 8989 4470 8990 4468 8990 4841 8990 4842 8991 4470 8991 4841 8991 4472 8992 4470 8992 4842 8992 4843 8993 4472 8993 4842 8993 4475 8994 4472 8994 4843 8994 4844 8995 4475 8995 4843 8995 4477 8996 4475 8996 4844 8996 4845 8997 4477 8997 4844 8997 4480 8998 4477 8998 4845 8998 4846 8999 4480 8999 4845 8999 4482 9000 4480 9000 4846 9000 4847 9001 4482 9001 4846 9001 4484 9002 4482 9002 4847 9002 4848 9003 4484 9003 4847 9003 4486 9004 4484 9004 4848 9004 4488 9005 4486 9005 4848 9005 4849 9006 4488 9006 4848 9006 4491 9007 4488 9007 4849 9007 4850 9008 4493 9008 4491 9008 4495 9009 4493 9009 4850 9009 4497 9010 4495 9010 4851 9010 4499 9011 4497 9011 4851 9011 4852 9012 4499 9012 4851 9012 4501 9013 4499 9013 4852 9013 4853 9014 4501 9014 4852 9014 4504 9015 4501 9015 4853 9015 4506 9016 4504 9016 4853 9016 4854 9017 4506 9017 4853 9017 4508 9018 4506 9018 4854 9018 4510 9019 4508 9019 4855 9019 4513 9020 4510 9020 4855 9020 4515 9021 4513 9021 4856 9021 4517 9022 4515 9022 4856 9022 4857 9023 4517 9023 4856 9023 4518 9024 4517 9024 4857 9024 4858 9025 4518 9025 4857 9025 4520 9026 4518 9026 4858 9026 4859 9027 4520 9027 4858 9027 4523 9028 4520 9028 4859 9028 4860 9029 4523 9029 4859 9029 4525 9030 4523 9030 4860 9030 4861 9031 4525 9031 4860 9031 4527 9032 4525 9032 4861 9032 4529 9033 4527 9033 4861 9033 4862 9034 4529 9034 4861 9034 4531 9035 4529 9035 4862 9035 4533 9036 4531 9036 4862 9036 4863 9037 4533 9037 4862 9037 4864 9038 4533 9038 4863 9038 4536 9039 4533 9039 4864 9039 4538 9040 4536 9040 4864 9040 4865 9041 4538 9041 4864 9041 4540 9042 4538 9042 4865 9042 4542 9043 4540 9043 4865 9043 4866 9044 4542 9044 4865 9044 4867 9045 4542 9045 4866 9045 4545 9046 4542 9046 4867 9046 4868 9047 4545 9047 4867 9047 4548 9048 4545 9048 4868 9048 4869 9049 4548 9049 4868 9049 4550 9050 4548 9050 4869 9050 4870 9051 4550 9051 4869 9051 4552 9052 4550 9052 4870 9052 4871 9053 4552 9053 4870 9053 4555 9054 4552 9054 4871 9054 4872 9055 4555 9055 4871 9055 4557 9056 4555 9056 4872 9056 4873 9057 4557 9057 4872 9057 4560 9058 4557 9058 4873 9058 4874 9059 4560 9059 4873 9059 4875 9060 4560 9060 4874 9060 4563 9061 4560 9061 4875 9061 4876 9062 4563 9062 4875 9062 4565 9063 4563 9063 4876 9063 4877 9064 4565 9064 4876 9064 4568 9065 4565 9065 4877 9065 4878 9066 4568 9066 4877 9066 4571 9067 4568 9067 4878 9067 4879 9068 4571 9068 4878 9068 4880 9069 4571 9069 4879 9069 4574 9070 4571 9070 4880 9070 4576 9071 4574 9071 4880 9071 4881 9072 4576 9072 4880 9072 4578 9073 4881 9073 4882 9073 4578 9074 4576 9074 4881 9074 4580 9075 4578 9075 4882 9075 4883 9076 4580 9076 4882 9076 4582 9077 4580 9077 4883 9077 4884 9078 4582 9078 4883 9078 4584 9079 4582 9079 4884 9079 4885 9080 4584 9080 4884 9080 4587 9081 4584 9081 4885 9081 4886 9082 4587 9082 4885 9082 4589 9083 4587 9083 4886 9083 4887 9084 4589 9084 4886 9084 4591 9085 4589 9085 4887 9085 4888 9086 4591 9086 4887 9086 4889 9087 4591 9087 4888 9087 4594 9088 4591 9088 4889 9088 4890 9089 4594 9089 4889 9089 4597 9090 4594 9090 4890 9090 4891 9091 4597 9091 4890 9091 4599 9092 4597 9092 4891 9092 4892 9093 4599 9093 4891 9093 4601 9094 4599 9094 4892 9094 4893 9095 4601 9095 4892 9095 4894 9096 4601 9096 4893 9096 4603 9097 4601 9097 4894 9097 4605 9098 4603 9098 4894 9098 4895 9099 4605 9099 4894 9099 4606 9100 4605 9100 4895 9100 4896 9101 4606 9101 4895 9101 4608 9102 4606 9102 4896 9102 4897 9103 4608 9103 4896 9103 4610 9104 4608 9104 4897 9104 4898 9105 4610 9105 4897 9105 4613 9106 4610 9106 4898 9106 4899 9107 4613 9107 4898 9107 4615 9108 4613 9108 4899 9108 4900 9109 4615 9109 4899 9109 4617 9110 4615 9110 4900 9110 4901 9111 4617 9111 4900 9111 4620 9112 4617 9112 4901 9112 4902 9113 4620 9113 4901 9113 4622 9114 4620 9114 4902 9114 4903 9115 4622 9115 4902 9115 4624 9116 4622 9116 4903 9116 4904 9117 4624 9117 4903 9117 4626 9118 4624 9118 4904 9118 4905 9119 4626 9119 4904 9119 4629 9120 4626 9120 4905 9120 4906 9121 4629 9121 4905 9121 4631 9122 4629 9122 4906 9122 4907 9123 4631 9123 4906 9123 4634 9124 4631 9124 4907 9124 4636 9125 4634 9125 4907 9125 4908 9126 4636 9126 4907 9126 4639 9127 4636 9127 4908 9127 4909 9128 4639 9128 4908 9128 4640 9129 4639 9129 4909 9129 4910 9130 4640 9130 4909 9130 4643 9131 4640 9131 4910 9131 4643 9132 4910 9132 4911 9132 4645 9133 4643 9133 4911 9133 4912 9134 4645 9134 4911 9134 4648 9135 4645 9135 4912 9135 4913 9136 4648 9136 4912 9136 4914 9137 4648 9137 4913 9137 4651 9138 4648 9138 4914 9138 4653 9139 4651 9139 4914 9139 4915 9140 4655 9140 4653 9140 4657 9141 4655 9141 4915 9141 4916 9142 4657 9142 4915 9142 4659 9143 4657 9143 4916 9143 4917 9144 4659 9144 4916 9144 4661 9145 4659 9145 4917 9145 4663 9146 4661 9146 4917 9146 4918 9147 4663 9147 4917 9147 4919 9148 4663 9148 4918 9148 4666 9149 4663 9149 4919 9149 4920 9150 4666 9150 4919 9150 4669 9151 4666 9151 4920 9151 4921 9152 4669 9152 4920 9152 4671 9153 4669 9153 4921 9153 4922 9154 4671 9154 4921 9154 4674 9155 4671 9155 4922 9155 4923 9156 4674 9156 4922 9156 4676 9157 4674 9157 4923 9157 4924 9158 4676 9158 4923 9158 4678 9159 4676 9159 4924 9159 4925 9160 4678 9160 4924 9160 4926 9161 4678 9161 4925 9161 4681 9162 4678 9162 4926 9162 4683 9163 4681 9163 4926 9163 4927 9164 4683 9164 4926 9164 4683 9165 4927 9165 4928 9165 4685 9166 4683 9166 4928 9166 4929 9167 4685 9167 4928 9167 4687 9168 4685 9168 4929 9168 4930 9169 4687 9169 4929 9169 4690 9170 4687 9170 4930 9170 4931 9171 4690 9171 4930 9171 4692 9172 4690 9172 4931 9172 4932 9173 4692 9173 4931 9173 4695 9174 4692 9174 4932 9174 4933 9175 4697 9175 4695 9175 4699 9176 4697 9176 4933 9176 4934 9177 4699 9177 4933 9177 4701 9178 4699 9178 4934 9178 4935 9179 4701 9179 4934 9179 4936 9180 4701 9180 4935 9180 4704 9181 4701 9181 4936 9181 4937 9182 4704 9182 4936 9182 4707 9183 4704 9183 4937 9183 4938 9184 4707 9184 4937 9184 4939 9185 4707 9185 4938 9185 4710 9186 4707 9186 4939 9186 4940 9187 4710 9187 4939 9187 4712 9188 4710 9188 4940 9188 4714 9189 4712 9189 4940 9189 4941 9190 4717 9190 4714 9190 4942 9191 4717 9191 4941 9191 4720 9192 4717 9192 4942 9192 4943 9193 4720 9193 4942 9193 4722 9194 4720 9194 4943 9194 4944 9195 4722 9195 4943 9195 4724 9196 4722 9196 4944 9196 4727 9197 4724 9197 4944 9197 4728 9198 4727 9198 4945 9198 4731 9199 4728 9199 4945 9199 4946 9200 4732 9200 4731 9200 4947 9201 4732 9201 4946 9201 4735 9202 4732 9202 4947 9202 4737 9203 4735 9203 4947 9203 4737 9204 4947 9204 4948 9204 4740 9205 4737 9205 4948 9205 4949 9206 4740 9206 4948 9206 4741 9207 4740 9207 4949 9207 4950 9208 4741 9208 4949 9208 4744 9209 4741 9209 4950 9209 4951 9210 4744 9210 4950 9210 4952 9211 4744 9211 4951 9211 4747 9212 4744 9212 4952 9212 4953 9213 4747 9213 4952 9213 4749 9214 4747 9214 4953 9214 4954 9215 4749 9215 4953 9215 4751 9216 4749 9216 4954 9216 4955 9217 4751 9217 4954 9217 4753 9218 4751 9218 4955 9218 4956 9219 4753 9219 4955 9219 4755 9220 4753 9220 4956 9220 4957 9221 4755 9221 4956 9221 4758 9222 4755 9222 4957 9222 4958 9223 4758 9223 4957 9223 4760 9224 4758 9224 4958 9224 4762 9225 4760 9225 4958 9225 4959 9226 4762 9226 4958 9226 4960 9227 4762 9227 4959 9227 4764 9228 4762 9228 4960 9228 4961 9229 4764 9229 4960 9229 4767 9230 4764 9230 4961 9230 4768 9231 4767 9231 4961 9231 4962 9232 4768 9232 4961 9232 4770 9233 4768 9233 4962 9233 4963 9234 4770 9234 4962 9234 4771 9235 4770 9235 4963 9235 4964 9236 4771 9236 4963 9236 4772 9237 4771 9237 4964 9237 4274 9238 4772 9238 4964 9238 4965 9239 4274 9239 4964 9239 4276 9240 4274 9240 4965 9240 4966 9241 4276 9241 4965 9241 4279 9242 4276 9242 4966 9242 4968 9243 4775 9243 4774 9243 4968 9244 4776 9244 4775 9244 4969 9245 4776 9245 4968 9245 4969 9246 4777 9246 4776 9246 4967 9247 4777 9247 4969 9247 4967 9248 4778 9248 4777 9248 4970 9249 4778 9249 4967 9249 4971 9250 4778 9250 4970 9250 4971 9251 4779 9251 4778 9251 4291 9252 4779 9252 4971 9252 4291 9253 4780 9253 4779 9253 4292 9254 4780 9254 4291 9254 4294 9255 4780 9255 4292 9255 4294 9256 4781 9256 4780 9256 4297 9257 4781 9257 4294 9257 4972 9258 4782 9258 4297 9258 4297 9259 4782 9259 4781 9259 4973 9260 4782 9260 4972 9260 4973 9261 4783 9261 4782 9261 4301 9262 4783 9262 4973 9262 4301 9263 4784 9263 4783 9263 4303 9264 4784 9264 4301 9264 4303 9265 4785 9265 4784 9265 4304 9266 4785 9266 4303 9266 4304 9267 4786 9267 4785 9267 4306 9268 4786 9268 4304 9268 4308 9269 4786 9269 4306 9269 4308 9270 4787 9270 4786 9270 4309 9271 4787 9271 4308 9271 4309 9272 4340 9272 4787 9272 4311 9273 4340 9273 4309 9273 4311 9274 4788 9274 4340 9274 4312 9275 4788 9275 4311 9275 4974 9276 4788 9276 4312 9276 4974 9277 4789 9277 4788 9277 4974 9278 4790 9278 4789 9278 4316 9279 4790 9279 4974 9279 4318 9280 4790 9280 4316 9280 4318 9281 4791 9281 4790 9281 4320 9282 4791 9282 4318 9282 4322 9283 4791 9283 4320 9283 4322 9284 4792 9284 4791 9284 4323 9285 4792 9285 4322 9285 4323 9286 4793 9286 4792 9286 4325 9287 4793 9287 4323 9287 4325 9288 4794 9288 4793 9288 4327 9289 4794 9289 4325 9289 4329 9290 4794 9290 4327 9290 4329 9291 4795 9291 4794 9291 4329 9292 4796 9292 4795 9292 4330 9293 4796 9293 4329 9293 4332 9294 4796 9294 4330 9294 4332 9295 4797 9295 4796 9295 4334 9296 4797 9296 4332 9296 4334 9297 4798 9297 4797 9297 4335 9298 4798 9298 4334 9298 4337 9299 4798 9299 4335 9299 4337 9300 4799 9300 4798 9300 4339 9301 4799 9301 4337 9301 4339 9302 4800 9302 4799 9302 4341 9303 4800 9303 4339 9303 4342 9304 4801 9304 4341 9304 4341 9305 4801 9305 4800 9305 4342 9306 4802 9306 4801 9306 4344 9307 4802 9307 4342 9307 4346 9308 4802 9308 4344 9308 4346 9309 4803 9309 4802 9309 4348 9310 4803 9310 4346 9310 4349 9311 4803 9311 4348 9311 4349 9312 4804 9312 4803 9312 4351 9313 4804 9313 4349 9313 4975 9314 4804 9314 4351 9314 4975 9315 4805 9315 4804 9315 4354 9316 4805 9316 4975 9316 4354 9317 4806 9317 4805 9317 4356 9318 4807 9318 4354 9318 4354 9319 4807 9319 4806 9319 4358 9320 4807 9320 4356 9320 4358 9321 4808 9321 4807 9321 4359 9322 4808 9322 4358 9322 4359 9323 4809 9323 4808 9323 4361 9324 4809 9324 4359 9324 4363 9325 4809 9325 4361 9325 4363 9326 4810 9326 4809 9326 4364 9327 4810 9327 4363 9327 4364 9328 4811 9328 4810 9328 4366 9329 4811 9329 4364 9329 4366 9330 4812 9330 4811 9330 4367 9331 4812 9331 4366 9331 4369 9332 4812 9332 4367 9332 4369 9333 4813 9333 4812 9333 4371 9334 4813 9334 4369 9334 4371 9335 4402 9335 4813 9335 4372 9336 4402 9336 4371 9336 4372 9337 4814 9337 4402 9337 4374 9338 4814 9338 4372 9338 4376 9339 4814 9339 4374 9339 4378 9340 4814 9340 4376 9340 4378 9341 4815 9341 4814 9341 4380 9342 4815 9342 4378 9342 4380 9343 4816 9343 4815 9343 4381 9344 4816 9344 4380 9344 4381 9345 4817 9345 4816 9345 4383 9346 4817 9346 4381 9346 4385 9347 4817 9347 4383 9347 4385 9348 4818 9348 4817 9348 4386 9349 4818 9349 4385 9349 4388 9350 4818 9350 4386 9350 4388 9351 4819 9351 4818 9351 4389 9352 4819 9352 4388 9352 4389 9353 4820 9353 4819 9353 4391 9354 4820 9354 4389 9354 4393 9355 4821 9355 4391 9355 4391 9356 4821 9356 4820 9356 4395 9357 4821 9357 4393 9357 4395 9358 4822 9358 4821 9358 4396 9359 4822 9359 4395 9359 4396 9360 4823 9360 4822 9360 4398 9361 4823 9361 4396 9361 4400 9362 4823 9362 4398 9362 4400 9363 4824 9363 4823 9363 4401 9364 4824 9364 4400 9364 4401 9365 4825 9365 4824 9365 4405 9366 4825 9366 4401 9366 4407 9367 4825 9367 4405 9367 4407 9368 4826 9368 4825 9368 4407 9369 4827 9369 4826 9369 4409 9370 4827 9370 4407 9370 4410 9371 4827 9371 4409 9371 4410 9372 4828 9372 4827 9372 4412 9373 4828 9373 4410 9373 4976 9374 4828 9374 4412 9374 4976 9375 4829 9375 4828 9375 4416 9376 4829 9376 4976 9376 4416 9377 4830 9377 4829 9377 4418 9378 4830 9378 4416 9378 4418 9379 4831 9379 4830 9379 4419 9380 4831 9380 4418 9380 4421 9381 4831 9381 4419 9381 4421 9382 4832 9382 4831 9382 4421 9383 4833 9383 4832 9383 4422 9384 4833 9384 4421 9384 4424 9385 4833 9385 4422 9385 4424 9386 4834 9386 4833 9386 4425 9387 4834 9387 4424 9387 4425 9388 4835 9388 4834 9388 4427 9389 4835 9389 4425 9389 4427 9390 4836 9390 4835 9390 4429 9391 4836 9391 4427 9391 4429 9392 4837 9392 4836 9392 4430 9393 4837 9393 4429 9393 4433 9394 4837 9394 4430 9394 4433 9395 4838 9395 4837 9395 4434 9396 4838 9396 4433 9396 4434 9397 4839 9397 4838 9397 4436 9398 4839 9398 4434 9398 4437 9399 4839 9399 4436 9399 4437 9400 4840 9400 4839 9400 4439 9401 4840 9401 4437 9401 4439 9402 4841 9402 4840 9402 4441 9403 4841 9403 4439 9403 4441 9404 4842 9404 4841 9404 4442 9405 4842 9405 4441 9405 4442 9406 4843 9406 4842 9406 4444 9407 4843 9407 4442 9407 4445 9408 4843 9408 4444 9408 4447 9409 4843 9409 4445 9409 4447 9410 4844 9410 4843 9410 4449 9411 4844 9411 4447 9411 4449 9412 4845 9412 4844 9412 4451 9413 4845 9413 4449 9413 4451 9414 4846 9414 4845 9414 4453 9415 4846 9415 4451 9415 4455 9416 4846 9416 4453 9416 4455 9417 4847 9417 4846 9417 4977 9418 4847 9418 4455 9418 4977 9419 4848 9419 4847 9419 4457 9420 4848 9420 4977 9420 4460 9421 4848 9421 4457 9421 4460 9422 4849 9422 4848 9422 4462 9423 4849 9423 4460 9423 4462 9424 4491 9424 4849 9424 4464 9425 4491 9425 4462 9425 4464 9426 4850 9426 4491 9426 4465 9427 4850 9427 4464 9427 4465 9428 4495 9428 4850 9428 4465 9429 4851 9429 4495 9429 4978 9430 4851 9430 4465 9430 4469 9431 4851 9431 4978 9431 4469 9432 4852 9432 4851 9432 4471 9433 4852 9433 4469 9433 4473 9434 4852 9434 4471 9434 4473 9435 4853 9435 4852 9435 4473 9436 4854 9436 4853 9436 4474 9437 4854 9437 4473 9437 4476 9438 4854 9438 4474 9438 4476 9439 4508 9439 4854 9439 4478 9440 4508 9440 4476 9440 4478 9441 4855 9441 4508 9441 4479 9442 4855 9442 4478 9442 4481 9443 4855 9443 4479 9443 4481 9444 4513 9444 4855 9444 4483 9445 4513 9445 4481 9445 4483 9446 4856 9446 4513 9446 4485 9447 4856 9447 4483 9447 4487 9448 4856 9448 4485 9448 4487 9449 4857 9449 4856 9449 4489 9450 4858 9450 4487 9450 4487 9451 4858 9451 4857 9451 4490 9452 4858 9452 4489 9452 4490 9453 4859 9453 4858 9453 4492 9454 4859 9454 4490 9454 4494 9455 4859 9455 4492 9455 4494 9456 4860 9456 4859 9456 4496 9457 4860 9457 4494 9457 4496 9458 4861 9458 4860 9458 4498 9459 4861 9459 4496 9459 4500 9460 4861 9460 4498 9460 4500 9461 4862 9461 4861 9461 4502 9462 4862 9462 4500 9462 4503 9463 4862 9463 4502 9463 4503 9464 4863 9464 4862 9464 4505 9465 4863 9465 4503 9465 4507 9466 4864 9466 4505 9466 4505 9467 4864 9467 4863 9467 4509 9468 4864 9468 4507 9468 4509 9469 4865 9469 4864 9469 4511 9470 4865 9470 4509 9470 4512 9471 4865 9471 4511 9471 4512 9472 4866 9472 4865 9472 4514 9473 4866 9473 4512 9473 4514 9474 4867 9474 4866 9474 4979 9475 4867 9475 4514 9475 4979 9476 4868 9476 4867 9476 4516 9477 4868 9477 4979 9477 4516 9478 4869 9478 4868 9478 4519 9479 4869 9479 4516 9479 4521 9480 4869 9480 4519 9480 4521 9481 4870 9481 4869 9481 4522 9482 4870 9482 4521 9482 4522 9483 4871 9483 4870 9483 4524 9484 4871 9484 4522 9484 4526 9485 4871 9485 4524 9485 4526 9486 4872 9486 4871 9486 4528 9487 4872 9487 4526 9487 4528 9488 4873 9488 4872 9488 4530 9489 4873 9489 4528 9489 4532 9490 4873 9490 4530 9490 4532 9491 4874 9491 4873 9491 4534 9492 4874 9492 4532 9492 4534 9493 4875 9493 4874 9493 4535 9494 4876 9494 4534 9494 4534 9495 4876 9495 4875 9495 4537 9496 4876 9496 4535 9496 4539 9497 4876 9497 4537 9497 4539 9498 4877 9498 4876 9498 4541 9499 4877 9499 4539 9499 4541 9500 4878 9500 4877 9500 4543 9501 4878 9501 4541 9501 4544 9502 4878 9502 4543 9502 4544 9503 4879 9503 4878 9503 4546 9504 4879 9504 4544 9504 4546 9505 4880 9505 4879 9505 4980 9506 4880 9506 4546 9506 4980 9507 4881 9507 4880 9507 4980 9508 4882 9508 4881 9508 4549 9509 4882 9509 4980 9509 4551 9510 4882 9510 4549 9510 4551 9511 4883 9511 4882 9511 4553 9512 4883 9512 4551 9512 4553 9513 4884 9513 4883 9513 4554 9514 4884 9514 4553 9514 4556 9515 4885 9515 4554 9515 4554 9516 4885 9516 4884 9516 4558 9517 4885 9517 4556 9517 4558 9518 4886 9518 4885 9518 4559 9519 4886 9519 4558 9519 4559 9520 4887 9520 4886 9520 4561 9521 4887 9521 4559 9521 4562 9522 4887 9522 4561 9522 4562 9523 4888 9523 4887 9523 4562 9524 4889 9524 4888 9524 4564 9525 4889 9525 4562 9525 4564 9526 4890 9526 4889 9526 4567 9527 4890 9527 4564 9527 4567 9528 4891 9528 4890 9528 4569 9529 4891 9529 4567 9529 4569 9530 4892 9530 4891 9530 4570 9531 4892 9531 4569 9531 4572 9532 4892 9532 4570 9532 4572 9533 4893 9533 4892 9533 4573 9534 4893 9534 4572 9534 4573 9535 4894 9535 4893 9535 4575 9536 4894 9536 4573 9536 4981 9537 4894 9537 4575 9537 4981 9538 4895 9538 4894 9538 4982 9539 4895 9539 4981 9539 4982 9540 4896 9540 4895 9540 4982 9541 4897 9541 4896 9541 4581 9542 4897 9542 4982 9542 4581 9543 4898 9543 4897 9543 4583 9544 4898 9544 4581 9544 4583 9545 4899 9545 4898 9545 4983 9546 4899 9546 4583 9546 4983 9547 4900 9547 4899 9547 4586 9548 4900 9548 4983 9548 4588 9549 4900 9549 4586 9549 4588 9550 4901 9550 4900 9550 4590 9551 4901 9551 4588 9551 4590 9552 4902 9552 4901 9552 4592 9553 4902 9553 4590 9553 4592 9554 4903 9554 4902 9554 4593 9555 4903 9555 4592 9555 4595 9556 4904 9556 4593 9556 4593 9557 4904 9557 4903 9557 4596 9558 4904 9558 4595 9558 4596 9559 4905 9559 4904 9559 4598 9560 4905 9560 4596 9560 4598 9561 4906 9561 4905 9561 4600 9562 4906 9562 4598 9562 4602 9563 4906 9563 4600 9563 4602 9564 4907 9564 4906 9564 4984 9565 4907 9565 4602 9565 4607 9566 4907 9566 4984 9566 4607 9567 4908 9567 4907 9567 4985 9568 4908 9568 4607 9568 4985 9569 4909 9569 4908 9569 4611 9570 4909 9570 4985 9570 4611 9571 4910 9571 4909 9571 4612 9572 4910 9572 4611 9572 4612 9573 4911 9573 4910 9573 4614 9574 4911 9574 4612 9574 4616 9575 4911 9575 4614 9575 4616 9576 4912 9576 4911 9576 4618 9577 4912 9577 4616 9577 4618 9578 4913 9578 4912 9578 4619 9579 4913 9579 4618 9579 4619 9580 4914 9580 4913 9580 4621 9581 4914 9581 4619 9581 4623 9582 4914 9582 4621 9582 4623 9583 4653 9583 4914 9583 4625 9584 4653 9584 4623 9584 4625 9585 4915 9585 4653 9585 4627 9586 4915 9586 4625 9586 4630 9587 4915 9587 4627 9587 4630 9588 4916 9588 4915 9588 4632 9589 4916 9589 4630 9589 4632 9590 4917 9590 4916 9590 4633 9591 4917 9591 4632 9591 4633 9592 4918 9592 4917 9592 4635 9593 4918 9593 4633 9593 4635 9594 4919 9594 4918 9594 4986 9595 4919 9595 4635 9595 4986 9596 4920 9596 4919 9596 4638 9597 4920 9597 4986 9597 4638 9598 4921 9598 4920 9598 4987 9599 4921 9599 4638 9599 4642 9600 4921 9600 4987 9600 4642 9601 4922 9601 4921 9601 4988 9602 4922 9602 4642 9602 4988 9603 4923 9603 4922 9603 4988 9604 4924 9604 4923 9604 4647 9605 4924 9605 4988 9605 4649 9606 4924 9606 4647 9606 4649 9607 4925 9607 4924 9607 4649 9608 4926 9608 4925 9608 4650 9609 4926 9609 4649 9609 4652 9610 4926 9610 4650 9610 4652 9611 4927 9611 4926 9611 4654 9612 4927 9612 4652 9612 4654 9613 4928 9613 4927 9613 4654 9614 4929 9614 4928 9614 4656 9615 4929 9615 4654 9615 4656 9616 4930 9616 4929 9616 4660 9617 4930 9617 4656 9617 4660 9618 4931 9618 4930 9618 4662 9619 4931 9619 4660 9619 4664 9620 4931 9620 4662 9620 4664 9621 4932 9621 4931 9621 4665 9622 4932 9622 4664 9622 4665 9623 4695 9623 4932 9623 4667 9624 4695 9624 4665 9624 4667 9625 4933 9625 4695 9625 4668 9626 4933 9626 4667 9626 4989 9627 4933 9627 4668 9627 4989 9628 4934 9628 4933 9628 4670 9629 4934 9629 4989 9629 4670 9630 4935 9630 4934 9630 4672 9631 4935 9631 4670 9631 4672 9632 4936 9632 4935 9632 4673 9633 4936 9633 4672 9633 4675 9634 4936 9634 4673 9634 4675 9635 4937 9635 4936 9635 4990 9636 4937 9636 4675 9636 4990 9637 4938 9637 4937 9637 4680 9638 4938 9638 4990 9638 4680 9639 4939 9639 4938 9639 4991 9640 4939 9640 4680 9640 4991 9641 4940 9641 4939 9641 4684 9642 4940 9642 4991 9642 4684 9643 4714 9643 4940 9643 4686 9644 4714 9644 4684 9644 4686 9645 4941 9645 4714 9645 4688 9646 4941 9646 4686 9646 4689 9647 4941 9647 4688 9647 4689 9648 4942 9648 4941 9648 4691 9649 4942 9649 4689 9649 4691 9650 4943 9650 4942 9650 4693 9651 4943 9651 4691 9651 4693 9652 4944 9652 4943 9652 4694 9653 4944 9653 4693 9653 4696 9654 4944 9654 4694 9654 4696 9655 4727 9655 4944 9655 4698 9656 4727 9656 4696 9656 4698 9657 4945 9657 4727 9657 4700 9658 4945 9658 4698 9658 4700 9659 4731 9659 4945 9659 4702 9660 4731 9660 4700 9660 4703 9661 4946 9661 4702 9661 4702 9662 4946 9662 4731 9662 4703 9663 4947 9663 4946 9663 4705 9664 4947 9664 4703 9664 4706 9665 4947 9665 4705 9665 4706 9666 4948 9666 4947 9666 4708 9667 4948 9667 4706 9667 4709 9668 4948 9668 4708 9668 4709 9669 4949 9669 4948 9669 4711 9670 4949 9670 4709 9670 4711 9671 4950 9671 4949 9671 4713 9672 4950 9672 4711 9672 4715 9673 4950 9673 4713 9673 4715 9674 4951 9674 4950 9674 4716 9675 4951 9675 4715 9675 4716 9676 4952 9676 4951 9676 4718 9677 4952 9677 4716 9677 4718 9678 4953 9678 4952 9678 4719 9679 4953 9679 4718 9679 4719 9680 4954 9680 4953 9680 4721 9681 4954 9681 4719 9681 4723 9682 4954 9682 4721 9682 4723 9683 4955 9683 4954 9683 4725 9684 4955 9684 4723 9684 4725 9685 4956 9685 4955 9685 4726 9686 4956 9686 4725 9686 4729 9687 4957 9687 4726 9687 4726 9688 4957 9688 4956 9688 4730 9689 4958 9689 4729 9689 4729 9690 4958 9690 4957 9690 4733 9691 4958 9691 4730 9691 4733 9692 4959 9692 4958 9692 4992 9693 4959 9693 4733 9693 4734 9694 4960 9694 4992 9694 4992 9695 4960 9695 4959 9695 4736 9696 4960 9696 4734 9696 4736 9697 4961 9697 4960 9697 4738 9698 4961 9698 4736 9698 4739 9699 4961 9699 4738 9699 4739 9700 4962 9700 4961 9700 4742 9701 4962 9701 4739 9701 4743 9702 4962 9702 4742 9702 4743 9703 4963 9703 4962 9703 4745 9704 4963 9704 4743 9704 4746 9705 4963 9705 4745 9705 4746 9706 4964 9706 4963 9706 4748 9707 4964 9707 4746 9707 4993 9708 4964 9708 4748 9708 4993 9709 4965 9709 4964 9709 4750 9710 4965 9710 4993 9710 4750 9711 4966 9711 4965 9711 4752 9712 4966 9712 4750 9712 4754 9713 4966 9713 4752 9713 4754 9714 4279 9714 4966 9714 4756 9715 4279 9715 4754 9715 4756 9716 4282 9716 4279 9716 4757 9717 4282 9717 4756 9717 4759 9718 4282 9718 4757 9718 4759 9719 4285 9719 4282 9719 4994 9720 4285 9720 4759 9720 4994 9721 4287 9721 4285 9721 4763 9722 4287 9722 4994 9722 4763 9723 4289 9723 4287 9723 4971 9724 4970 9724 4290 9724 4291 9725 4971 9725 4290 9725 4299 9726 4972 9726 4297 9726 4973 9727 4972 9727 4299 9727 4301 9728 4973 9728 4299 9728 4974 9729 4312 9729 4314 9729 4316 9730 4974 9730 4314 9730 4353 9731 4975 9731 4351 9731 4354 9732 4975 9732 4353 9732 4405 9733 4401 9733 4403 9733 4976 9734 4412 9734 4413 9734 4416 9735 4976 9735 4413 9735 4457 9736 4977 9736 4455 9736 4460 9737 4457 9737 4458 9737 4978 9738 4465 9738 4467 9738 4469 9739 4978 9739 4467 9739 4516 9740 4979 9740 4514 9740 4547 9741 4980 9741 4546 9741 4549 9742 4980 9742 4547 9742 4567 9743 4564 9743 4566 9743 4577 9744 4981 9744 4575 9744 4982 9745 4981 9745 4577 9745 4579 9746 4982 9746 4577 9746 4581 9747 4982 9747 4579 9747 4983 9748 4583 9748 4585 9748 4586 9749 4983 9749 4585 9749 4604 9750 4984 9750 4602 9750 4607 9751 4984 9751 4604 9751 4609 9752 4985 9752 4607 9752 4611 9753 4985 9753 4609 9753 4630 9754 4627 9754 4628 9754 4986 9755 4635 9755 4637 9755 4638 9756 4986 9756 4637 9756 4987 9757 4638 9757 4641 9757 4642 9758 4987 9758 4641 9758 4988 9759 4642 9759 4644 9759 4646 9760 4988 9760 4644 9760 4647 9761 4988 9761 4646 9761 4660 9762 4656 9762 4658 9762 4670 9763 4989 9763 4668 9763 4990 9764 4675 9764 4677 9764 4679 9765 4990 9765 4677 9765 4680 9766 4990 9766 4679 9766 4682 9767 4991 9767 4680 9767 4684 9768 4991 9768 4682 9768 4734 9769 4992 9769 4733 9769 4750 9770 4993 9770 4748 9770 4761 9771 4994 9771 4759 9771 4763 9772 4994 9772 4761 9772 4289 9773 4763 9773 4765 9773 4766 9774 4289 9774 4765 9774 5001 9775 4289 9775 4766 9775 4996 9776 5001 9776 4766 9776 4995 9777 5045 9777 4997 9777 4998 9778 4996 9778 4995 9778 4766 9779 4769 9779 4996 9779 4998 9780 4995 9780 4997 9780 5001 9781 4996 9781 4998 9781 5001 9782 4997 9782 4999 9782 5001 9783 4998 9783 4997 9783 4999 9784 4997 9784 5000 9784 5002 9785 5001 9785 4999 9785 5003 9786 5002 9786 4999 9786 4289 9787 5001 9787 5002 9787 5003 9788 4999 9788 5000 9788 4289 9789 5002 9789 5003 9789 5004 9790 5003 9790 5000 9790 4287 9791 4289 9791 5003 9791 5004 9792 5000 9792 5005 9792 4287 9793 5003 9793 5004 9793 5007 9794 4287 9794 5004 9794 5006 9795 5004 9795 5005 9795 5007 9796 5004 9796 5006 9796 4288 9797 4287 9797 5007 9797 5006 9798 5005 9798 5008 9798 4286 9799 4288 9799 5007 9799 4286 9800 5007 9800 5006 9800 5009 9801 4286 9801 5006 9801 5010 9802 5006 9802 5008 9802 5010 9803 5009 9803 5006 9803 5010 9804 5008 9804 5011 9804 5012 9805 5009 9805 5010 9805 4283 9806 5009 9806 5012 9806 5012 9807 5010 9807 5011 9807 5014 9808 5012 9808 5011 9808 4283 9809 5012 9809 5014 9809 5013 9810 5014 9810 5011 9810 5015 9811 5014 9811 5013 9811 5014 9812 5016 9812 4283 9812 5016 9813 5014 9813 5015 9813 5018 9814 5016 9814 5015 9814 5019 9815 5015 9815 5013 9815 5019 9816 5013 9816 5017 9816 5020 9817 5015 9817 5019 9817 5018 9818 5015 9818 5020 9818 5020 9819 5022 9819 5018 9819 5021 9820 5020 9820 5019 9820 5022 9821 5020 9821 5021 9821 5021 9822 5019 9822 5017 9822 5024 9823 5021 9823 5017 9823 5023 9824 5024 9824 5017 9824 5026 9825 5022 9825 5021 9825 5025 9826 5021 9826 5024 9826 5026 9827 5021 9827 5025 9827 5025 9828 5024 9828 5023 9828 5028 9829 5026 9829 5025 9829 5029 9830 5025 9830 5023 9830 5028 9831 5025 9831 5029 9831 5027 9832 5029 9832 5023 9832 4275 9833 5028 9833 5029 9833 4275 9834 5029 9834 5030 9834 5030 9835 5029 9835 5027 9835 5031 9836 5030 9836 5027 9836 5032 9837 4275 9837 5030 9837 5033 9838 5030 9838 5031 9838 5032 9839 5030 9839 5033 9839 5033 9840 5031 9840 5035 9840 5033 9841 4278 9841 5032 9841 5034 9842 5035 9842 5031 9842 4278 9843 5033 9843 5036 9843 5036 9844 5033 9844 5035 9844 5037 9845 5035 9845 5034 9845 5036 9846 5035 9846 5037 9846 5039 9847 5036 9847 5037 9847 4280 9848 4278 9848 5036 9848 5037 9849 5034 9849 5038 9849 5039 9850 4280 9850 5036 9850 5041 9851 5039 9851 5037 9851 5040 9852 5037 9852 5038 9852 4280 9853 5039 9853 5041 9853 5041 9854 5037 9854 5040 9854 5041 9855 4281 9855 4280 9855 5040 9856 5038 9856 5043 9856 5042 9857 5041 9857 5040 9857 5043 9858 5042 9858 5040 9858 5042 9859 4281 9859 5041 9859 5042 9860 4284 9860 4281 9860 5044 9861 5042 9861 5043 9861 5043 9862 5038 9862 5045 9862 5044 9863 5043 9863 5045 9863 4284 9864 5042 9864 5044 9864 5046 9865 4284 9865 5044 9865 4769 9866 4284 9866 5046 9866 4995 9867 5044 9867 5045 9867 5046 9868 4995 9868 4996 9868 5046 9869 5044 9869 4995 9869 4769 9870 5046 9870 4996 9870 5000 9871 5038 9871 5034 9871 5000 9872 5045 9872 5038 9872 5000 9873 4997 9873 5045 9873 5005 9874 5000 9874 5034 9874 5011 9875 5017 9875 5013 9875 5011 9876 5031 9876 5027 9876 5011 9877 5027 9877 5023 9877 5011 9878 5008 9878 5005 9878 5011 9879 5023 9879 5017 9879 5011 9880 5005 9880 5034 9880 5011 9881 5034 9881 5031 9881 5049 9882 5047 9882 5048 9882 5051 9883 5049 9883 5048 9883 5051 9884 5048 9884 5050 9884 5052 9885 5051 9885 5050 9885 5053 9886 5049 9886 5051 9886 5053 9887 5051 9887 5052 9887 5054 9888 5053 9888 5052 9888 5055 9889 5054 9889 5052 9889 5056 9890 5053 9890 5054 9890 5056 9891 5054 9891 5055 9891 5061 9892 5053 9892 5056 9892 5056 9893 5055 9893 5057 9893 5059 9894 5061 9894 5056 9894 5059 9895 5056 9895 5057 9895 5059 9896 5057 9896 5058 9896 5060 9897 5059 9897 5058 9897 5060 9898 5058 9898 5062 9898 5061 9899 5059 9899 5060 9899 5063 9900 5060 9900 5062 9900 5064 9901 5061 9901 5060 9901 5064 9902 5060 9902 5063 9902 5064 9903 5063 9903 5065 9903 5066 9904 5064 9904 5065 9904 5066 9905 5065 9905 5067 9905 5068 9906 5064 9906 5066 9906 5068 9907 5066 9907 5067 9907 5069 9908 5068 9908 5067 9908 5069 9909 5067 9909 5070 9909 5071 9910 5068 9910 5069 9910 5072 9911 5069 9911 5070 9911 5072 9912 5071 9912 5069 9912 5073 9913 5068 9913 5071 9913 5073 9914 5071 9914 5072 9914 5073 9915 5072 9915 5074 9915 5076 9916 5073 9916 5074 9916 5076 9917 5074 9917 5075 9917 5076 9918 5075 9918 5077 9918 5079 9919 5076 9919 5077 9919 5079 9920 5077 9920 5078 9920 5080 9921 5079 9921 5078 9921 5081 9922 5079 9922 5080 9922 5083 9923 5076 9923 5079 9923 5082 9924 5081 9924 5080 9924 5083 9925 5079 9925 5081 9925 5084 9926 5081 9926 5082 9926 5084 9927 5082 9927 5085 9927 5083 9928 5081 9928 5084 9928 5087 9929 5084 9929 5085 9929 5086 9930 5083 9930 5084 9930 5086 9931 5084 9931 5087 9931 5088 9932 5083 9932 5086 9932 5089 9933 5086 9933 5087 9933 5088 9934 5086 9934 5089 9934 5091 9935 5088 9935 5089 9935 5091 9936 5089 9936 5090 9936 5092 9937 5088 9937 5091 9937 5091 9938 5090 9938 5093 9938 5094 9939 5092 9939 5091 9939 5094 9940 5091 9940 5093 9940 5095 9941 5094 9941 5093 9941 5097 9942 5092 9942 5094 9942 5097 9943 5094 9943 5095 9943 5097 9944 5095 9944 5096 9944 5099 9945 5097 9945 5096 9945 5099 9946 5096 9946 5098 9946 5100 9947 5099 9947 5098 9947 5102 9948 5099 9948 5100 9948 5103 9949 5100 9949 5101 9949 5103 9950 5102 9950 5100 9950 5103 9951 5101 9951 5104 9951 5105 9952 5099 9952 5102 9952 5105 9953 5102 9953 5103 9953 5106 9954 5103 9954 5104 9954 5107 9955 5103 9955 5106 9955 5105 9956 5103 9956 5107 9956 5108 9957 5107 9957 5106 9957 5109 9958 5107 9958 5108 9958 5110 9959 5107 9959 5109 9959 5110 9960 5105 9960 5107 9960 5110 9961 5109 9961 5111 9961 5112 9962 5105 9962 5110 9962 5113 9963 5110 9963 5111 9963 5113 9964 5112 9964 5110 9964 5114 9965 5113 9965 5111 9965 5115 9966 5112 9966 5113 9966 5047 9967 5113 9967 5114 9967 5115 9968 5113 9968 5047 9968 5115 9969 5047 9969 5049 9969 5048 9970 5047 9970 5116 9970 5048 9971 5116 9971 5182 9971 5050 9972 5048 9972 5182 9972 5050 9973 5182 9973 5117 9973 5052 9974 5050 9974 5117 9974 5052 9975 5117 9975 5179 9975 5052 9976 5179 9976 5118 9976 5055 9977 5052 9977 5118 9977 5055 9978 5118 9978 5119 9978 5057 9979 5055 9979 5119 9979 5058 9980 5119 9980 5120 9980 5058 9981 5057 9981 5119 9981 5062 9982 5058 9982 5120 9982 5062 9983 5120 9983 5121 9983 5063 9984 5062 9984 5121 9984 5063 9985 5121 9985 5122 9985 5065 9986 5063 9986 5122 9986 5065 9987 5122 9987 5170 9987 5067 9988 5065 9988 5170 9988 5067 9989 5170 9989 5123 9989 5070 9990 5067 9990 5123 9990 5070 9991 5123 9991 5124 9991 5072 9992 5070 9992 5124 9992 5072 9993 5124 9993 5125 9993 5074 9994 5072 9994 5125 9994 5074 9995 5125 9995 5167 9995 5075 9996 5074 9996 5167 9996 5075 9997 5167 9997 5165 9997 5077 9998 5165 9998 5126 9998 5077 9999 5075 9999 5165 9999 5078 10000 5077 10000 5126 10000 5078 10001 5126 10001 5161 10001 5080 10002 5078 10002 5161 10002 5080 10003 5161 10003 5159 10003 5082 10004 5080 10004 5159 10004 5082 10005 5159 10005 5157 10005 5085 10006 5082 10006 5157 10006 5087 10007 5157 10007 5127 10007 5087 10008 5085 10008 5157 10008 5089 10009 5087 10009 5127 10009 5089 10010 5127 10010 5153 10010 5090 10011 5089 10011 5153 10011 5090 10012 5153 10012 5152 10012 5093 10013 5090 10013 5152 10013 5093 10014 5152 10014 5148 10014 5095 10015 5093 10015 5148 10015 5096 10016 5095 10016 5148 10016 5096 10017 5148 10017 5128 10017 5098 10018 5096 10018 5128 10018 5098 10019 5128 10019 5129 10019 5100 10020 5098 10020 5129 10020 5100 10021 5129 10021 5144 10021 5101 10022 5100 10022 5144 10022 5101 10023 5144 10023 5143 10023 5101 10024 5143 10024 5130 10024 5104 10025 5101 10025 5130 10025 5106 10026 5130 10026 5140 10026 5106 10027 5104 10027 5130 10027 5108 10028 5140 10028 5138 10028 5108 10029 5106 10029 5140 10029 5109 10030 5108 10030 5138 10030 5109 10031 5138 10031 5136 10031 5111 10032 5136 10032 5134 10032 5111 10033 5109 10033 5136 10033 5111 10034 5134 10034 5131 10034 5114 10035 5111 10035 5131 10035 5047 10036 5114 10036 5131 10036 5047 10037 5131 10037 5116 10037 4773 10038 5088 10038 5092 10038 4773 10039 5083 10039 5088 10039 4774 10040 4773 10040 5092 10040 4300 10041 5083 10041 4773 10041 4774 10042 5092 10042 5097 10042 4968 10043 4774 10043 5097 10043 4968 10044 5097 10044 5099 10044 4300 10045 5076 10045 5083 10045 4295 10046 5076 10046 4300 10046 4968 10047 5099 10047 5105 10047 4295 10048 5073 10048 5076 10048 4298 10049 5073 10049 4295 10049 4969 10050 4968 10050 5105 10050 5112 10051 4969 10051 5105 10051 5068 10052 5073 10052 4298 10052 5068 10053 4298 10053 4296 10053 5115 10054 4969 10054 5112 10054 5064 10055 5068 10055 4296 10055 5115 10056 4967 10056 4969 10056 5064 10057 4296 10057 4293 10057 5049 10058 4967 10058 5115 10058 5053 10059 4967 10059 5049 10059 5053 10060 4970 10060 4967 10060 5061 10061 5064 10061 4293 10061 5061 10062 4293 10062 4290 10062 5053 10063 4290 10063 4970 10063 5061 10064 4290 10064 5053 10064 5132 10065 5116 10065 5131 10065 5137 10066 5132 10066 5133 10066 5137 10067 5183 10067 5132 10067 5133 10068 5132 10068 5131 10068 5134 10069 5133 10069 5131 10069 5135 10070 5133 10070 5134 10070 5137 10071 5133 10071 5135 10071 5135 10072 5134 10072 5136 10072 5137 10073 5135 10073 5139 10073 5138 10074 5135 10074 5136 10074 5139 10075 5135 10075 5138 10075 5139 10076 5138 10076 5140 10076 5141 10077 5140 10077 5130 10077 5141 10078 5139 10078 5140 10078 5142 10079 5139 10079 5141 10079 5143 10080 5141 10080 5130 10080 5142 10081 5141 10081 5143 10081 5145 10082 5142 10082 5143 10082 5145 10083 5143 10083 5144 10083 5146 10084 5142 10084 5145 10084 5145 10085 5144 10085 5129 10085 5147 10086 5145 10086 5129 10086 5147 10087 5129 10087 5128 10087 5146 10088 5145 10088 5147 10088 5148 10089 5147 10089 5128 10089 5150 10090 5146 10090 5147 10090 5149 10091 5147 10091 5148 10091 5150 10092 5147 10092 5149 10092 5152 10093 5149 10093 5148 10093 5151 10094 5150 10094 5149 10094 5152 10095 5151 10095 5149 10095 5154 10096 5151 10096 5152 10096 5153 10097 5154 10097 5152 10097 5154 10098 5153 10098 5127 10098 5155 10099 5151 10099 5154 10099 5156 10100 5154 10100 5127 10100 5155 10101 5154 10101 5156 10101 5157 10102 5156 10102 5127 10102 5158 10103 5155 10103 5156 10103 5159 10104 5156 10104 5157 10104 5160 10105 5156 10105 5159 10105 5158 10106 5156 10106 5160 10106 5160 10107 5159 10107 5161 10107 5158 10108 5160 10108 5162 10108 5162 10109 5160 10109 5161 10109 5126 10110 5162 10110 5161 10110 5163 10111 5158 10111 5162 10111 5164 10112 5162 10112 5126 10112 5163 10113 5162 10113 5164 10113 5165 10114 5164 10114 5126 10114 5166 10115 5164 10115 5165 10115 5163 10116 5164 10116 5166 10116 5166 10117 5165 10117 5167 10117 5168 10118 5163 10118 5166 10118 5166 10119 5167 10119 5125 10119 5168 10120 5166 10120 5125 10120 5124 10121 5168 10121 5125 10121 5169 10122 5168 10122 5124 10122 5169 10123 5124 10123 5123 10123 5171 10124 5169 10124 5123 10124 5171 10125 5123 10125 5170 10125 5172 10126 5170 10126 5122 10126 5172 10127 5171 10127 5170 10127 5173 10128 5169 10128 5171 10128 5173 10129 5171 10129 5172 10129 5172 10130 5122 10130 5121 10130 5174 10131 5169 10131 5173 10131 5174 10132 5173 10132 5172 10132 5174 10133 5172 10133 5121 10133 5175 10134 5174 10134 5121 10134 5175 10135 5121 10135 5120 10135 5176 10136 5174 10136 5175 10136 5177 10137 5176 10137 5175 10137 5119 10138 5175 10138 5120 10138 5177 10139 5175 10139 5119 10139 5178 10140 5177 10140 5119 10140 5118 10141 5178 10141 5119 10141 5178 10142 5176 10142 5177 10142 5179 10143 5178 10143 5118 10143 5180 10144 5176 10144 5178 10144 5180 10145 5178 10145 5179 10145 5181 10146 5179 10146 5117 10146 5181 10147 5180 10147 5179 10147 5181 10148 5117 10148 5182 10148 5183 10149 5180 10149 5181 10149 5183 10150 5181 10150 5182 10150 5132 10151 5182 10151 5116 10151 5132 10152 5183 10152 5182 10152 4263 10153 4268 10153 4270 10153 4263 10154 4265 10154 4268 10154 4261 10155 4263 10155 4271 10155 4271 10156 4263 10156 4270 10156 4258 10157 4261 10157 4272 10157 4272 10158 4261 10158 4271 10158

+
+ + + +

6041 10159 5184 10159 6037 10159 6041 10160 5185 10160 5184 10160 5186 10161 5185 10161 6041 10161 6037 10162 5184 10162 5187 10162 5186 10163 5188 10163 5185 10163 5184 10164 5189 10164 5187 10164 6002 10165 5188 10165 5186 10165 5187 10166 5189 10166 5190 10166 6002 10167 5191 10167 5188 10167 5194 10168 5191 10168 6002 10168 5189 10169 5192 10169 5190 10169 5194 10170 5193 10170 5191 10170 5194 10171 5195 10171 5193 10171 5193 10172 5195 10172 5197 10172 5203 10173 5201 10173 5200 10173 5203 10174 5204 10174 5201 10174 5206 10175 5204 10175 5203 10175 5206 10176 5205 10176 5204 10176 5206 10177 5207 10177 5205 10177 5202 10178 5207 10178 5206 10178 5202 10179 5208 10179 5207 10179 5202 10180 5209 10180 5208 10180 5210 10181 5209 10181 5202 10181 5210 10182 5211 10182 5209 10182 5212 10183 5211 10183 5210 10183 5213 10184 5211 10184 5212 10184 5213 10185 5214 10185 5211 10185 5215 10186 5214 10186 5213 10186 5215 10187 5216 10187 5214 10187 5215 10188 5217 10188 5216 10188 5218 10189 5217 10189 5215 10189 5218 10190 5219 10190 5217 10190 5220 10191 5219 10191 5218 10191 5220 10192 5221 10192 5219 10192 5222 10193 5221 10193 5220 10193 5222 10194 5223 10194 5221 10194 5224 10195 5223 10195 5222 10195 5224 10196 5225 10196 5223 10196 5224 10197 5226 10197 5225 10197 5227 10198 5226 10198 5224 10198 5227 10199 5228 10199 5226 10199 5227 10200 5229 10200 5228 10200 5230 10201 5229 10201 5227 10201 5230 10202 5231 10202 5229 10202 5232 10203 5231 10203 5230 10203 5232 10204 5233 10204 5231 10204 5234 10205 5233 10205 5232 10205 5234 10206 5235 10206 5233 10206 5236 10207 5235 10207 5234 10207 5236 10208 5237 10208 5235 10208 5238 10209 5237 10209 5236 10209 5238 10210 5239 10210 5237 10210 5238 10211 5240 10211 5239 10211 5241 10212 5240 10212 5238 10212 5241 10213 5242 10213 5240 10213 5243 10214 5242 10214 5241 10214 5243 10215 5244 10215 5242 10215 5245 10216 5244 10216 5243 10216 5245 10217 5246 10217 5244 10217 5247 10218 5246 10218 5245 10218 5247 10219 5248 10219 5246 10219 5249 10220 5248 10220 5247 10220 5249 10221 5250 10221 5248 10221 5251 10222 5250 10222 5249 10222 5252 10223 5253 10223 5251 10223 5251 10224 5253 10224 5250 10224 5252 10225 5254 10225 5253 10225 5252 10226 5255 10226 5254 10226 5256 10227 5255 10227 5252 10227 5256 10228 5257 10228 5255 10228 5258 10229 5257 10229 5256 10229 5258 10230 5259 10230 5257 10230 5260 10231 5259 10231 5258 10231 5260 10232 5261 10232 5259 10232 5262 10233 5261 10233 5260 10233 5262 10234 5263 10234 5261 10234 5262 10235 5264 10235 5263 10235 5265 10236 5264 10236 5262 10236 5265 10237 5266 10237 5264 10237 5265 10238 5267 10238 5266 10238 5268 10239 5267 10239 5265 10239 5268 10240 5269 10240 5267 10240 5268 10241 5270 10241 5269 10241 5271 10242 5270 10242 5268 10242 5271 10243 5272 10243 5270 10243 5271 10244 5273 10244 5272 10244 5274 10245 5273 10245 5271 10245 5274 10246 5275 10246 5273 10246 5276 10247 5275 10247 5274 10247 5276 10248 5277 10248 5275 10248 5278 10249 5277 10249 5276 10249 5278 10250 5279 10250 5277 10250 5278 10251 5280 10251 5279 10251 5281 10252 5280 10252 5278 10252 5281 10253 5282 10253 5280 10253 5283 10254 5282 10254 5281 10254 5283 10255 5284 10255 5282 10255 5283 10256 5285 10256 5284 10256 5286 10257 5285 10257 5283 10257 5286 10258 5287 10258 5285 10258 5288 10259 5287 10259 5286 10259 5288 10260 5289 10260 5287 10260 5290 10261 5289 10261 5288 10261 5290 10262 5291 10262 5289 10262 5290 10263 5292 10263 5291 10263 5293 10264 5292 10264 5290 10264 5293 10265 5294 10265 5292 10265 5295 10266 5294 10266 5293 10266 5295 10267 5296 10267 5294 10267 5295 10268 5297 10268 5296 10268 5298 10269 5297 10269 5295 10269 5298 10270 5299 10270 5297 10270 5300 10271 5299 10271 5298 10271 5300 10272 5301 10272 5299 10272 5302 10273 5301 10273 5300 10273 5302 10274 5303 10274 5301 10274 5304 10275 5303 10275 5302 10275 5304 10276 5305 10276 5303 10276 5306 10277 5305 10277 5304 10277 5306 10278 5307 10278 5305 10278 5308 10279 5307 10279 5306 10279 5308 10280 5309 10280 5307 10280 5310 10281 5309 10281 5308 10281 5310 10282 5311 10282 5309 10282 5312 10283 5311 10283 5310 10283 5312 10284 5313 10284 5311 10284 5312 10285 5314 10285 5313 10285 5315 10286 5314 10286 5312 10286 5316 10287 5314 10287 5315 10287 5316 10288 5317 10288 5314 10288 5316 10289 5318 10289 5317 10289 5316 10290 5319 10290 5318 10290 5320 10291 5319 10291 5316 10291 5320 10292 5321 10292 5319 10292 5322 10293 5321 10293 5320 10293 5323 10294 5321 10294 5322 10294 5323 10295 5324 10295 5321 10295 5323 10296 5325 10296 5324 10296 5326 10297 5325 10297 5323 10297 5326 10298 5327 10298 5325 10298 5328 10299 5327 10299 5326 10299 5328 10300 5329 10300 5327 10300 5328 10301 5330 10301 5329 10301 5331 10302 5330 10302 5328 10302 5331 10303 5332 10303 5330 10303 5331 10304 5333 10304 5332 10304 5334 10305 5333 10305 5331 10305 5334 10306 5335 10306 5333 10306 5336 10307 5335 10307 5334 10307 5336 10308 5337 10308 5335 10308 5336 10309 5338 10309 5337 10309 5339 10310 5338 10310 5336 10310 5339 10311 5340 10311 5338 10311 5341 10312 5340 10312 5339 10312 5341 10313 5342 10313 5340 10313 5343 10314 5342 10314 5341 10314 5343 10315 5344 10315 5342 10315 5343 10316 5345 10316 5344 10316 5346 10317 5345 10317 5343 10317 5346 10318 5347 10318 5345 10318 5348 10319 5347 10319 5346 10319 5348 10320 5349 10320 5347 10320 5350 10321 5349 10321 5348 10321 5350 10322 5351 10322 5349 10322 5350 10323 5352 10323 5351 10323 5353 10324 5352 10324 5350 10324 5353 10325 5354 10325 5352 10325 5353 10326 5355 10326 5354 10326 5356 10327 5355 10327 5353 10327 5356 10328 5357 10328 5355 10328 5358 10329 5357 10329 5356 10329 5358 10330 5359 10330 5357 10330 5360 10331 5359 10331 5358 10331 5360 10332 5361 10332 5359 10332 5360 10333 5362 10333 5361 10333 5363 10334 5362 10334 5360 10334 5363 10335 5364 10335 5362 10335 5365 10336 5364 10336 5363 10336 5365 10337 5366 10337 5364 10337 5365 10338 5367 10338 5366 10338 5368 10339 5367 10339 5365 10339 5368 10340 5369 10340 5367 10340 5370 10341 5369 10341 5368 10341 5370 10342 5371 10342 5369 10342 5372 10343 5371 10343 5370 10343 5372 10344 5373 10344 5371 10344 5374 10345 5373 10345 5372 10345 5374 10346 5375 10346 5373 10346 5376 10347 5375 10347 5374 10347 5376 10348 5377 10348 5375 10348 5378 10349 5377 10349 5376 10349 5378 10350 5379 10350 5377 10350 5380 10351 5379 10351 5378 10351 5380 10352 5381 10352 5379 10352 5380 10353 5382 10353 5381 10353 5383 10354 5382 10354 5380 10354 5383 10355 5384 10355 5382 10355 5385 10356 5384 10356 5383 10356 5385 10357 5386 10357 5384 10357 5387 10358 5386 10358 5385 10358 5387 10359 5388 10359 5386 10359 5389 10360 5388 10360 5387 10360 5389 10361 5390 10361 5388 10361 5391 10362 5390 10362 5389 10362 5391 10363 5392 10363 5390 10363 5393 10364 5392 10364 5391 10364 5393 10365 5394 10365 5392 10365 5395 10366 5394 10366 5393 10366 5395 10367 5396 10367 5394 10367 5395 10368 5397 10368 5396 10368 5398 10369 5397 10369 5395 10369 5398 10370 5399 10370 5397 10370 5400 10371 5401 10371 5398 10371 5398 10372 5401 10372 5399 10372 5400 10373 5402 10373 5401 10373 5403 10374 5402 10374 5400 10374 5403 10375 5404 10375 5402 10375 5405 10376 5404 10376 5403 10376 5405 10377 5406 10377 5404 10377 5405 10378 5407 10378 5406 10378 5408 10379 5407 10379 5405 10379 5409 10380 5407 10380 5408 10380 5409 10381 5410 10381 5407 10381 5411 10382 5410 10382 5409 10382 5411 10383 5412 10383 5410 10383 5411 10384 5413 10384 5412 10384 5414 10385 5413 10385 5411 10385 5414 10386 5415 10386 5413 10386 5416 10387 5415 10387 5414 10387 5416 10388 5417 10388 5415 10388 5418 10389 5417 10389 5416 10389 5418 10390 5419 10390 5417 10390 5420 10391 5419 10391 5418 10391 5420 10392 5421 10392 5419 10392 5420 10393 5422 10393 5421 10393 5423 10394 5422 10394 5420 10394 5423 10395 5424 10395 5422 10395 5425 10396 5424 10396 5423 10396 5425 10397 5426 10397 5424 10397 5425 10398 5427 10398 5426 10398 5428 10399 5427 10399 5425 10399 5428 10400 5429 10400 5427 10400 5430 10401 5429 10401 5428 10401 5430 10402 5431 10402 5429 10402 5430 10403 5432 10403 5431 10403 5433 10404 5432 10404 5430 10404 5433 10405 5434 10405 5432 10405 5435 10406 5434 10406 5433 10406 5435 10407 5436 10407 5434 10407 5435 10408 5437 10408 5436 10408 5438 10409 5437 10409 5435 10409 5438 10410 5439 10410 5437 10410 5438 10411 5440 10411 5439 10411 5441 10412 5440 10412 5438 10412 5441 10413 5442 10413 5440 10413 5441 10414 5443 10414 5442 10414 5444 10415 5443 10415 5441 10415 5445 10416 5446 10416 5444 10416 5444 10417 5446 10417 5443 10417 5445 10418 5447 10418 5446 10418 5448 10419 5447 10419 5445 10419 5448 10420 5449 10420 5447 10420 5450 10421 5451 10421 5448 10421 5448 10422 5451 10422 5449 10422 5450 10423 5452 10423 5451 10423 5453 10424 5452 10424 5450 10424 5454 10425 5455 10425 5453 10425 5453 10426 5455 10426 5452 10426 5454 10427 5456 10427 5455 10427 5457 10428 5456 10428 5454 10428 5457 10429 5458 10429 5456 10429 5459 10430 5458 10430 5457 10430 5459 10431 5460 10431 5458 10431 5459 10432 5461 10432 5460 10432 5462 10433 5461 10433 5459 10433 5462 10434 5463 10434 5461 10434 5464 10435 5463 10435 5462 10435 5464 10436 5465 10436 5463 10436 5464 10437 5466 10437 5465 10437 5467 10438 5466 10438 5464 10438 5467 10439 5468 10439 5466 10439 5469 10440 5468 10440 5467 10440 5469 10441 5470 10441 5468 10441 5471 10442 5470 10442 5469 10442 5471 10443 5472 10443 5470 10443 5473 10444 5472 10444 5471 10444 5473 10445 5474 10445 5472 10445 5475 10446 5474 10446 5473 10446 5475 10447 5476 10447 5474 10447 5475 10448 5477 10448 5476 10448 5478 10449 5477 10449 5475 10449 5478 10450 5479 10450 5477 10450 5480 10451 5479 10451 5478 10451 5480 10452 5481 10452 5479 10452 5482 10453 5481 10453 5480 10453 5482 10454 5483 10454 5481 10454 5482 10455 5484 10455 5483 10455 5485 10456 5484 10456 5482 10456 5485 10457 5486 10457 5484 10457 5487 10458 5486 10458 5485 10458 5487 10459 5488 10459 5486 10459 5487 10460 5489 10460 5488 10460 5490 10461 5489 10461 5487 10461 5490 10462 5491 10462 5489 10462 5490 10463 5492 10463 5491 10463 5493 10464 5492 10464 5490 10464 5493 10465 5494 10465 5492 10465 5493 10466 5495 10466 5494 10466 5496 10467 5495 10467 5493 10467 5496 10468 5497 10468 5495 10468 5498 10469 5497 10469 5496 10469 5498 10470 5499 10470 5497 10470 5500 10471 5499 10471 5498 10471 5500 10472 5501 10472 5499 10472 5502 10473 5501 10473 5500 10473 5502 10474 5503 10474 5501 10474 5504 10475 5503 10475 5502 10475 5504 10476 5505 10476 5503 10476 5506 10477 5505 10477 5504 10477 5506 10478 5507 10478 5505 10478 5508 10479 5507 10479 5506 10479 5508 10480 5509 10480 5507 10480 5510 10481 5509 10481 5508 10481 5510 10482 5511 10482 5509 10482 5510 10483 5512 10483 5511 10483 5513 10484 5512 10484 5510 10484 5513 10485 5514 10485 5512 10485 5515 10486 5514 10486 5513 10486 5515 10487 5516 10487 5514 10487 5515 10488 5517 10488 5516 10488 5518 10489 5517 10489 5515 10489 5518 10490 5519 10490 5517 10490 5520 10491 5521 10491 5518 10491 5518 10492 5521 10492 5519 10492 5520 10493 5522 10493 5521 10493 5523 10494 5522 10494 5520 10494 5523 10495 5524 10495 5522 10495 5525 10496 5524 10496 5523 10496 5525 10497 5526 10497 5524 10497 5525 10498 5527 10498 5526 10498 5528 10499 5527 10499 5525 10499 5528 10500 5529 10500 5527 10500 5530 10501 5529 10501 5528 10501 5530 10502 5531 10502 5529 10502 5532 10503 5531 10503 5530 10503 5532 10504 5533 10504 5531 10504 5534 10505 5535 10505 5532 10505 5532 10506 5535 10506 5533 10506 5534 10507 5536 10507 5535 10507 5537 10508 5536 10508 5534 10508 5537 10509 5538 10509 5536 10509 5539 10510 5540 10510 5537 10510 5537 10511 5540 10511 5538 10511 5539 10512 5541 10512 5540 10512 5542 10513 5541 10513 5539 10513 5542 10514 5543 10514 5541 10514 5542 10515 5544 10515 5543 10515 5542 10516 5545 10516 5544 10516 5546 10517 5545 10517 5542 10517 5546 10518 5547 10518 5545 10518 5548 10519 5547 10519 5546 10519 5548 10520 5549 10520 5547 10520 5550 10521 5549 10521 5548 10521 5550 10522 5551 10522 5549 10522 5550 10523 5552 10523 5551 10523 5553 10524 5552 10524 5550 10524 5553 10525 5554 10525 5552 10525 5553 10526 5555 10526 5554 10526 5556 10527 5555 10527 5553 10527 5556 10528 5557 10528 5555 10528 5556 10529 5558 10529 5557 10529 5559 10530 5558 10530 5556 10530 5559 10531 5560 10531 5558 10531 5561 10532 5560 10532 5559 10532 5561 10533 5562 10533 5560 10533 5563 10534 5562 10534 5561 10534 5563 10535 5564 10535 5562 10535 5565 10536 5564 10536 5563 10536 5565 10537 5566 10537 5564 10537 5567 10538 5566 10538 5565 10538 5567 10539 5568 10539 5566 10539 5567 10540 5569 10540 5568 10540 5567 10541 5570 10541 5569 10541 5571 10542 5570 10542 5567 10542 5571 10543 5572 10543 5570 10543 5573 10544 5572 10544 5571 10544 5573 10545 5574 10545 5572 10545 5575 10546 5576 10546 5573 10546 5573 10547 5576 10547 5574 10547 5577 10548 5576 10548 5575 10548 5577 10549 5578 10549 5576 10549 5577 10550 5579 10550 5578 10550 5580 10551 5579 10551 5577 10551 5580 10552 5581 10552 5579 10552 5582 10553 5581 10553 5580 10553 5582 10554 5583 10554 5581 10554 5582 10555 5584 10555 5583 10555 5585 10556 5584 10556 5582 10556 5585 10557 5586 10557 5584 10557 5587 10558 5586 10558 5585 10558 5587 10559 5588 10559 5586 10559 5589 10560 5588 10560 5587 10560 5589 10561 5590 10561 5588 10561 5591 10562 5590 10562 5589 10562 5592 10563 5593 10563 5591 10563 5591 10564 5593 10564 5590 10564 5592 10565 5594 10565 5593 10565 5595 10566 5594 10566 5592 10566 5595 10567 5596 10567 5594 10567 5597 10568 5596 10568 5595 10568 5597 10569 5598 10569 5596 10569 5599 10570 5598 10570 5597 10570 5599 10571 5600 10571 5598 10571 5601 10572 5600 10572 5599 10572 5601 10573 5602 10573 5600 10573 5601 10574 5603 10574 5602 10574 5604 10575 5603 10575 5601 10575 5605 10576 5606 10576 5604 10576 5604 10577 5606 10577 5603 10577 5605 10578 5607 10578 5606 10578 5608 10579 5607 10579 5605 10579 5608 10580 5609 10580 5607 10580 5608 10581 5610 10581 5609 10581 5611 10582 5610 10582 5608 10582 5611 10583 5612 10583 5610 10583 5611 10584 5613 10584 5612 10584 5614 10585 5613 10585 5611 10585 5614 10586 5615 10586 5613 10586 5616 10587 5615 10587 5614 10587 5616 10588 5617 10588 5615 10588 5618 10589 5617 10589 5616 10589 5618 10590 5619 10590 5617 10590 5618 10591 5620 10591 5619 10591 5621 10592 5620 10592 5618 10592 5621 10593 5622 10593 5620 10593 5623 10594 5622 10594 5621 10594 5623 10595 5624 10595 5622 10595 5625 10596 5624 10596 5623 10596 5625 10597 5626 10597 5624 10597 5627 10598 5626 10598 5625 10598 5627 10599 5628 10599 5626 10599 5627 10600 5629 10600 5628 10600 5630 10601 5629 10601 5627 10601 5630 10602 5631 10602 5629 10602 5632 10603 5631 10603 5630 10603 5632 10604 5633 10604 5631 10604 5634 10605 5633 10605 5632 10605 5635 10606 5633 10606 5634 10606 5635 10607 5636 10607 5633 10607 5635 10608 5637 10608 5636 10608 5638 10609 5637 10609 5635 10609 5638 10610 5639 10610 5637 10610 5640 10611 5639 10611 5638 10611 5640 10612 5641 10612 5639 10612 5642 10613 5641 10613 5640 10613 5642 10614 5643 10614 5641 10614 5644 10615 5643 10615 5642 10615 5644 10616 5645 10616 5643 10616 5646 10617 5645 10617 5644 10617 5646 10618 5647 10618 5645 10618 5646 10619 5648 10619 5647 10619 5649 10620 5648 10620 5646 10620 5649 10621 5650 10621 5648 10621 5649 10622 5651 10622 5650 10622 5652 10623 5651 10623 5649 10623 5652 10624 5653 10624 5651 10624 5654 10625 5653 10625 5652 10625 5654 10626 5655 10626 5653 10626 5656 10627 5655 10627 5654 10627 5656 10628 5657 10628 5655 10628 5658 10629 5659 10629 5656 10629 5656 10630 5659 10630 5657 10630 5658 10631 5660 10631 5659 10631 5661 10632 5660 10632 5658 10632 5661 10633 5662 10633 5660 10633 5661 10634 5663 10634 5662 10634 5664 10635 5663 10635 5661 10635 5664 10636 5665 10636 5663 10636 5666 10637 5665 10637 5664 10637 5666 10638 5667 10638 5665 10638 5668 10639 5667 10639 5666 10639 5668 10640 5669 10640 5667 10640 5670 10641 5669 10641 5668 10641 5670 10642 5671 10642 5669 10642 5672 10643 5671 10643 5670 10643 5672 10644 5673 10644 5671 10644 5672 10645 5674 10645 5673 10645 5675 10646 5674 10646 5672 10646 5675 10647 5676 10647 5674 10647 5677 10648 5676 10648 5675 10648 5677 10649 5678 10649 5676 10649 5677 10650 5679 10650 5678 10650 5680 10651 5679 10651 5677 10651 5680 10652 5681 10652 5679 10652 5682 10653 5681 10653 5680 10653 5682 10654 5683 10654 5681 10654 5684 10655 5683 10655 5682 10655 5684 10656 5685 10656 5683 10656 5684 10657 5686 10657 5685 10657 5687 10658 5686 10658 5684 10658 5687 10659 5688 10659 5686 10659 5687 10660 5689 10660 5688 10660 5690 10661 5689 10661 5687 10661 5690 10662 5691 10662 5689 10662 5690 10663 5692 10663 5691 10663 5693 10664 5692 10664 5690 10664 5693 10665 5694 10665 5692 10665 5695 10666 5694 10666 5693 10666 5695 10667 5696 10667 5694 10667 5697 10668 5696 10668 5695 10668 5697 10669 5698 10669 5696 10669 5699 10670 5698 10670 5697 10670 5699 10671 5700 10671 5698 10671 5701 10672 5700 10672 5699 10672 5701 10673 5702 10673 5700 10673 5701 10674 5703 10674 5702 10674 5704 10675 5703 10675 5701 10675 5704 10676 5705 10676 5703 10676 5706 10677 5705 10677 5704 10677 5706 10678 5707 10678 5705 10678 5708 10679 5707 10679 5706 10679 5708 10680 5709 10680 5707 10680 5710 10681 5709 10681 5708 10681 5710 10682 5711 10682 5709 10682 5712 10683 5713 10683 5710 10683 5710 10684 5713 10684 5711 10684 5714 10685 5713 10685 5712 10685 5714 10686 5715 10686 5713 10686 5714 10687 5716 10687 5715 10687 5717 10688 5716 10688 5714 10688 5717 10689 5718 10689 5716 10689 5717 10690 5719 10690 5718 10690 5720 10691 5719 10691 5717 10691 5720 10692 5721 10692 5719 10692 5722 10693 5721 10693 5720 10693 5722 10694 5723 10694 5721 10694 5722 10695 5724 10695 5723 10695 5725 10696 5724 10696 5722 10696 5725 10697 5726 10697 5724 10697 5727 10698 5726 10698 5725 10698 5727 10699 5728 10699 5726 10699 5729 10700 5728 10700 5727 10700 5729 10701 5730 10701 5728 10701 5729 10702 5731 10702 5730 10702 5732 10703 5731 10703 5729 10703 5732 10704 5733 10704 5731 10704 5732 10705 5734 10705 5733 10705 5735 10706 5734 10706 5732 10706 5735 10707 5736 10707 5734 10707 5735 10708 5737 10708 5736 10708 5738 10709 5737 10709 5735 10709 5738 10710 5739 10710 5737 10710 5738 10711 5740 10711 5739 10711 5741 10712 5740 10712 5738 10712 5741 10713 5742 10713 5740 10713 5743 10714 5742 10714 5741 10714 5743 10715 5744 10715 5742 10715 5743 10716 5745 10716 5744 10716 5746 10717 5745 10717 5743 10717 5746 10718 5747 10718 5745 10718 5748 10719 5747 10719 5746 10719 5748 10720 5749 10720 5747 10720 5750 10721 5749 10721 5748 10721 5750 10722 5751 10722 5749 10722 5752 10723 5751 10723 5750 10723 5752 10724 5753 10724 5751 10724 5752 10725 5754 10725 5753 10725 5755 10726 5754 10726 5752 10726 5755 10727 5756 10727 5754 10727 5757 10728 5756 10728 5755 10728 5757 10729 5758 10729 5756 10729 5757 10730 5759 10730 5758 10730 5760 10731 5759 10731 5757 10731 5760 10732 5761 10732 5759 10732 5762 10733 5761 10733 5760 10733 5762 10734 5763 10734 5761 10734 5762 10735 5764 10735 5763 10735 5765 10736 5764 10736 5762 10736 5765 10737 5766 10737 5764 10737 5767 10738 5766 10738 5765 10738 5767 10739 5768 10739 5766 10739 5769 10740 5768 10740 5767 10740 5769 10741 5770 10741 5768 10741 5771 10742 5770 10742 5769 10742 5771 10743 5772 10743 5770 10743 5773 10744 5772 10744 5771 10744 5773 10745 5774 10745 5772 10745 5775 10746 5774 10746 5773 10746 5775 10747 5776 10747 5774 10747 5777 10748 5776 10748 5775 10748 5777 10749 5778 10749 5776 10749 5779 10750 5778 10750 5777 10750 5779 10751 5780 10751 5778 10751 5781 10752 5782 10752 5779 10752 5779 10753 5782 10753 5780 10753 5781 10754 5783 10754 5782 10754 5784 10755 5783 10755 5781 10755 5784 10756 5785 10756 5783 10756 5786 10757 5787 10757 5784 10757 5784 10758 5787 10758 5785 10758 5786 10759 5788 10759 5787 10759 5786 10760 5789 10760 5788 10760 5790 10761 5789 10761 5786 10761 5791 10762 5792 10762 5790 10762 5790 10763 5792 10763 5789 10763 5793 10764 5792 10764 5791 10764 5793 10765 5794 10765 5792 10765 5793 10766 5199 10766 5794 10766 5795 10767 5199 10767 5793 10767 5795 10768 6013 10768 5199 10768 5796 10769 6013 10769 5795 10769 5796 10770 5197 10770 6013 10770 5796 10771 5193 10771 5197 10771 5797 10772 5212 10772 5210 10772 5213 10773 5212 10773 5797 10773 5798 10774 5213 10774 5797 10774 5215 10775 5213 10775 5798 10775 5218 10776 5215 10776 5798 10776 5222 10777 5220 10777 5799 10777 5800 10778 5222 10778 5799 10778 5224 10779 5222 10779 5800 10779 5801 10780 5224 10780 5800 10780 5802 10781 5224 10781 5801 10781 5227 10782 5224 10782 5802 10782 5803 10783 5227 10783 5802 10783 5230 10784 5227 10784 5803 10784 5804 10785 5236 10785 5234 10785 5805 10786 5236 10786 5804 10786 5238 10787 5236 10787 5805 10787 5806 10788 5238 10788 5805 10788 5241 10789 5238 10789 5806 10789 5243 10790 5241 10790 5806 10790 5807 10791 5243 10791 5806 10791 5245 10792 5243 10792 5807 10792 5808 10793 5245 10793 5807 10793 5247 10794 5245 10794 5808 10794 5249 10795 5247 10795 5808 10795 5252 10796 5251 10796 5809 10796 5810 10797 5252 10797 5809 10797 5256 10798 5252 10798 5810 10798 5262 10799 5260 10799 5811 10799 5812 10800 5262 10800 5811 10800 5265 10801 5262 10801 5812 10801 5813 10802 5265 10802 5812 10802 5814 10803 5265 10803 5813 10803 5268 10804 5265 10804 5814 10804 5271 10805 5268 10805 5814 10805 5815 10806 5271 10806 5814 10806 5274 10807 5271 10807 5815 10807 5276 10808 5274 10808 5816 10808 5278 10809 5276 10809 5816 10809 5281 10810 5278 10810 5817 10810 5818 10811 5281 10811 5817 10811 5283 10812 5281 10812 5818 10812 5819 10813 5283 10813 5818 10813 5286 10814 5283 10814 5819 10814 5820 10815 5288 10815 5286 10815 5290 10816 5288 10816 5820 10816 5821 10817 5290 10817 5820 10817 5293 10818 5290 10818 5821 10818 5822 10819 5293 10819 5821 10819 5295 10820 5293 10820 5822 10820 5298 10821 5295 10821 5822 10821 5823 10822 5300 10822 5298 10822 5302 10823 5300 10823 5823 10823 5824 10824 5302 10824 5823 10824 5304 10825 5302 10825 5824 10825 5304 10826 5824 10826 5825 10826 5306 10827 5304 10827 5825 10827 5826 10828 5306 10828 5825 10828 5308 10829 5306 10829 5826 10829 5827 10830 5308 10830 5826 10830 5310 10831 5308 10831 5827 10831 5828 10832 5310 10832 5827 10832 5312 10833 5310 10833 5828 10833 5315 10834 5312 10834 5828 10834 5316 10835 5315 10835 5829 10835 5830 10836 5316 10836 5829 10836 5320 10837 5316 10837 5830 10837 5831 10838 5320 10838 5830 10838 5322 10839 5320 10839 5831 10839 5832 10840 5323 10840 5322 10840 5326 10841 5323 10841 5832 10841 5833 10842 5328 10842 5326 10842 5331 10843 5328 10843 5833 10843 5834 10844 5331 10844 5833 10844 5835 10845 5331 10845 5834 10845 5334 10846 5331 10846 5835 10846 5336 10847 5334 10847 5835 10847 5836 10848 5336 10848 5835 10848 5339 10849 5336 10849 5836 10849 5837 10850 5339 10850 5836 10850 5341 10851 5339 10851 5837 10851 5838 10852 5341 10852 5837 10852 5343 10853 5341 10853 5838 10853 5839 10854 5343 10854 5838 10854 5346 10855 5343 10855 5839 10855 5840 10856 5346 10856 5839 10856 5348 10857 5346 10857 5840 10857 5841 10858 5348 10858 5840 10858 5350 10859 5348 10859 5841 10859 5842 10860 5350 10860 5841 10860 5353 10861 5350 10861 5842 10861 5843 10862 5353 10862 5842 10862 5356 10863 5353 10863 5843 10863 5358 10864 5356 10864 5843 10864 5844 10865 5360 10865 5358 10865 5363 10866 5360 10866 5844 10866 5845 10867 5363 10867 5844 10867 5365 10868 5363 10868 5845 10868 5846 10869 5365 10869 5845 10869 5368 10870 5365 10870 5846 10870 5370 10871 5368 10871 5847 10871 5372 10872 5370 10872 5847 10872 5848 10873 5376 10873 5374 10873 5378 10874 5376 10874 5848 10874 5849 10875 5378 10875 5848 10875 5380 10876 5378 10876 5849 10876 5850 10877 5380 10877 5849 10877 5383 10878 5380 10878 5850 10878 5851 10879 5383 10879 5850 10879 5385 10880 5383 10880 5851 10880 5852 10881 5387 10881 5385 10881 5389 10882 5387 10882 5852 10882 5853 10883 5389 10883 5852 10883 5391 10884 5389 10884 5853 10884 5854 10885 5391 10885 5853 10885 5393 10886 5391 10886 5854 10886 5393 10887 5854 10887 5855 10887 5395 10888 5393 10888 5855 10888 5856 10889 5395 10889 5855 10889 5398 10890 5395 10890 5856 10890 5400 10891 5398 10891 5856 10891 5857 10892 5400 10892 5856 10892 5403 10893 5400 10893 5857 10893 5858 10894 5405 10894 5403 10894 5859 10895 5405 10895 5858 10895 5408 10896 5405 10896 5859 10896 5409 10897 5408 10897 5859 10897 5860 10898 5409 10898 5859 10898 5411 10899 5409 10899 5860 10899 5861 10900 5411 10900 5860 10900 5862 10901 5411 10901 5861 10901 5414 10902 5411 10902 5862 10902 5416 10903 5414 10903 5862 10903 5863 10904 5416 10904 5862 10904 5418 10905 5416 10905 5863 10905 5864 10906 5420 10906 5418 10906 5865 10907 5420 10907 5864 10907 5423 10908 5420 10908 5865 10908 5425 10909 5423 10909 5865 10909 5866 10910 5428 10910 5425 10910 5867 10911 5428 10911 5866 10911 5430 10912 5428 10912 5867 10912 5433 10913 5430 10913 5867 10913 5868 10914 5433 10914 5867 10914 5435 10915 5433 10915 5868 10915 5869 10916 5435 10916 5868 10916 5438 10917 5435 10917 5869 10917 5870 10918 5438 10918 5869 10918 5441 10919 5438 10919 5870 10919 5871 10920 5441 10920 5870 10920 5444 10921 5441 10921 5871 10921 5872 10922 5444 10922 5871 10922 5445 10923 5444 10923 5872 10923 5873 10924 5445 10924 5872 10924 5448 10925 5445 10925 5873 10925 5450 10926 5448 10926 5873 10926 5453 10927 5450 10927 5874 10927 5454 10928 5453 10928 5874 10928 5875 10929 5454 10929 5874 10929 5457 10930 5454 10930 5875 10930 5462 10931 5459 10931 5876 10931 5877 10932 5462 10932 5876 10932 5464 10933 5462 10933 5877 10933 5467 10934 5464 10934 5877 10934 5878 10935 5469 10935 5467 10935 5471 10936 5469 10936 5878 10936 5879 10937 5473 10937 5471 10937 5475 10938 5473 10938 5879 10938 5880 10939 5475 10939 5879 10939 5478 10940 5475 10940 5880 10940 5881 10941 5478 10941 5880 10941 5480 10942 5478 10942 5881 10942 5882 10943 5480 10943 5881 10943 5482 10944 5480 10944 5882 10944 5883 10945 5482 10945 5882 10945 5485 10946 5482 10946 5883 10946 5884 10947 5485 10947 5883 10947 5487 10948 5485 10948 5884 10948 5885 10949 5487 10949 5884 10949 5886 10950 5487 10950 5885 10950 5490 10951 5487 10951 5886 10951 5887 10952 5490 10952 5886 10952 5493 10953 5490 10953 5887 10953 5888 10954 5493 10954 5887 10954 5496 10955 5493 10955 5888 10955 5889 10956 5496 10956 5888 10956 5498 10957 5496 10957 5889 10957 5500 10958 5498 10958 5889 10958 5506 10959 5504 10959 5890 10959 5891 10960 5506 10960 5890 10960 5508 10961 5506 10961 5891 10961 5510 10962 5508 10962 5891 10962 5892 10963 5513 10963 5510 10963 5515 10964 5513 10964 5892 10964 5893 10965 5515 10965 5892 10965 5518 10966 5515 10966 5893 10966 5894 10967 5518 10967 5893 10967 5520 10968 5518 10968 5894 10968 5520 10969 5894 10969 5895 10969 5523 10970 5520 10970 5895 10970 5896 10971 5523 10971 5895 10971 5525 10972 5523 10972 5896 10972 5897 10973 5525 10973 5896 10973 5898 10974 5525 10974 5897 10974 5528 10975 5525 10975 5898 10975 5530 10976 5528 10976 5898 10976 5532 10977 5530 10977 5899 10977 5900 10978 5532 10978 5899 10978 5901 10979 5532 10979 5900 10979 5534 10980 5532 10980 5901 10980 5537 10981 5534 10981 5901 10981 5902 10982 5539 10982 5537 10982 5542 10983 5539 10983 5902 10983 5903 10984 5542 10984 5902 10984 5546 10985 5542 10985 5903 10985 5904 10986 5546 10986 5903 10986 5905 10987 5546 10987 5904 10987 5548 10988 5546 10988 5905 10988 5550 10989 5548 10989 5905 10989 5906 10990 5550 10990 5905 10990 5553 10991 5550 10991 5906 10991 5907 10992 5553 10992 5906 10992 5556 10993 5553 10993 5907 10993 5908 10994 5563 10994 5561 10994 5909 10995 5563 10995 5908 10995 5565 10996 5563 10996 5909 10996 5910 10997 5565 10997 5909 10997 5567 10998 5565 10998 5910 10998 5911 10999 5567 10999 5910 10999 5571 11000 5567 11000 5911 11000 5912 11001 5571 11001 5911 11001 5573 11002 5571 11002 5912 11002 5913 11003 5573 11003 5912 11003 5575 11004 5573 11004 5913 11004 5577 11005 5575 11005 5914 11005 5580 11006 5577 11006 5914 11006 5915 11007 5580 11007 5914 11007 5582 11008 5580 11008 5915 11008 5916 11009 5582 11009 5915 11009 5585 11010 5582 11010 5916 11010 5587 11011 5585 11011 5916 11011 5917 11012 5592 11012 5591 11012 5918 11013 5592 11013 5917 11013 5595 11014 5592 11014 5918 11014 5919 11015 5597 11015 5595 11015 5599 11016 5597 11016 5919 11016 5601 11017 5599 11017 5920 11017 5604 11018 5601 11018 5920 11018 5605 11019 5604 11019 5921 11019 5922 11020 5605 11020 5921 11020 5608 11021 5605 11021 5922 11021 5608 11022 5922 11022 5923 11022 5611 11023 5608 11023 5923 11023 5924 11024 5611 11024 5923 11024 5614 11025 5611 11025 5924 11025 5925 11026 5618 11026 5616 11026 5621 11027 5618 11027 5925 11027 5926 11028 5621 11028 5925 11028 5623 11029 5621 11029 5926 11029 5927 11030 5623 11030 5926 11030 5625 11031 5623 11031 5927 11031 5928 11032 5625 11032 5927 11032 5627 11033 5625 11033 5928 11033 5929 11034 5627 11034 5928 11034 5630 11035 5627 11035 5929 11035 5632 11036 5630 11036 5929 11036 5930 11037 5632 11037 5929 11037 5632 11038 5930 11038 5634 11038 5638 11039 5635 11039 5931 11039 5640 11040 5638 11040 5931 11040 5644 11041 5642 11041 5932 11041 5933 11042 5644 11042 5932 11042 5646 11043 5644 11043 5933 11043 5934 11044 5646 11044 5933 11044 5649 11045 5646 11045 5934 11045 5935 11046 5649 11046 5934 11046 5652 11047 5649 11047 5935 11047 5654 11048 5652 11048 5935 11048 5654 11049 5935 11049 5936 11049 5656 11050 5654 11050 5936 11050 5937 11051 5656 11051 5936 11051 5658 11052 5656 11052 5937 11052 5938 11053 5658 11053 5937 11053 5661 11054 5658 11054 5938 11054 5939 11055 5661 11055 5938 11055 5664 11056 5661 11056 5939 11056 5940 11057 5666 11057 5664 11057 5668 11058 5666 11058 5940 11058 5670 11059 5668 11059 5940 11059 5672 11060 5670 11060 5941 11060 5942 11061 5672 11061 5941 11061 5675 11062 5672 11062 5942 11062 5943 11063 5675 11063 5942 11063 5677 11064 5675 11064 5943 11064 5944 11065 5677 11065 5943 11065 5680 11066 5677 11066 5944 11066 5945 11067 5682 11067 5680 11067 5684 11068 5682 11068 5945 11068 5946 11069 5684 11069 5945 11069 5687 11070 5684 11070 5946 11070 5947 11071 5687 11071 5946 11071 5948 11072 5687 11072 5947 11072 5690 11073 5687 11073 5948 11073 5949 11074 5690 11074 5948 11074 5693 11075 5690 11075 5949 11075 5695 11076 5693 11076 5949 11076 5950 11077 5697 11077 5695 11077 5699 11078 5697 11078 5950 11078 5708 11079 5706 11079 5951 11079 5710 11080 5708 11080 5951 11080 5712 11081 5710 11081 5952 11081 5714 11082 5712 11082 5952 11082 5953 11083 5714 11083 5952 11083 5717 11084 5714 11084 5953 11084 5954 11085 5717 11085 5953 11085 5720 11086 5717 11086 5954 11086 5722 11087 5720 11087 5955 11087 5725 11088 5722 11088 5955 11088 5727 11089 5725 11089 5956 11089 5957 11090 5727 11090 5956 11090 5729 11091 5727 11091 5957 11091 5958 11092 5729 11092 5957 11092 5959 11093 5729 11093 5958 11093 5732 11094 5729 11094 5959 11094 5732 11095 5959 11095 5960 11095 5735 11096 5732 11096 5960 11096 5961 11097 5735 11097 5960 11097 5738 11098 5735 11098 5961 11098 5962 11099 5738 11099 5961 11099 5741 11100 5738 11100 5962 11100 5743 11101 5741 11101 5963 11101 5746 11102 5743 11102 5963 11102 5750 11103 5748 11103 5964 11103 5752 11104 5750 11104 5964 11104 5965 11105 5752 11105 5964 11105 5755 11106 5752 11106 5965 11106 5966 11107 5755 11107 5965 11107 5757 11108 5755 11108 5966 11108 5967 11109 5757 11109 5966 11109 5760 11110 5757 11110 5967 11110 5762 11111 5760 11111 5968 11111 5969 11112 5762 11112 5968 11112 5765 11113 5762 11113 5969 11113 5970 11114 5765 11114 5969 11114 5767 11115 5765 11115 5970 11115 5971 11116 5767 11116 5970 11116 5769 11117 5767 11117 5971 11117 5771 11118 5769 11118 5971 11118 5773 11119 5771 11119 5972 11119 5775 11120 5773 11120 5972 11120 5973 11121 5775 11121 5972 11121 5777 11122 5775 11122 5973 11122 5974 11123 5786 11123 5784 11123 5790 11124 5786 11124 5974 11124 5790 11125 5974 11125 5975 11125 5791 11126 5790 11126 5975 11126 5795 11127 5793 11127 5976 11127 5796 11128 5795 11128 5976 11128 5977 11129 5796 11129 5976 11129 5193 11130 5796 11130 5977 11130 5978 11131 5193 11131 5977 11131 5191 11132 5193 11132 5978 11132 5979 11133 5191 11133 5978 11133 5188 11134 5191 11134 5979 11134 5980 11135 5188 11135 5979 11135 5185 11136 5188 11136 5980 11136 5982 11137 5218 11137 5798 11137 5982 11138 5220 11138 5218 11138 5982 11139 5799 11139 5220 11139 5981 11140 5799 11140 5982 11140 5981 11141 5800 11141 5799 11141 5983 11142 5800 11142 5981 11142 5983 11143 5801 11143 5800 11143 5984 11144 5801 11144 5983 11144 5984 11145 5802 11145 5801 11145 5201 11146 5802 11146 5984 11146 5201 11147 5803 11147 5802 11147 5204 11148 5803 11148 5201 11148 5204 11149 5230 11149 5803 11149 5205 11150 5230 11150 5204 11150 5205 11151 5232 11151 5230 11151 5207 11152 5232 11152 5205 11152 5207 11153 5234 11153 5232 11153 5208 11154 5234 11154 5207 11154 5208 11155 5804 11155 5234 11155 5209 11156 5804 11156 5208 11156 5211 11157 5805 11157 5209 11157 5209 11158 5805 11158 5804 11158 5214 11159 5805 11159 5211 11159 5214 11160 5806 11160 5805 11160 5216 11161 5806 11161 5214 11161 5217 11162 5806 11162 5216 11162 5217 11163 5807 11163 5806 11163 5219 11164 5807 11164 5217 11164 5219 11165 5808 11165 5807 11165 5221 11166 5808 11166 5219 11166 5223 11167 5808 11167 5221 11167 5223 11168 5249 11168 5808 11168 5225 11169 5249 11169 5223 11169 5225 11170 5251 11170 5249 11170 5226 11171 5251 11171 5225 11171 5226 11172 5809 11172 5251 11172 5228 11173 5809 11173 5226 11173 5228 11174 5810 11174 5809 11174 5229 11175 5810 11175 5228 11175 5229 11176 5256 11176 5810 11176 5231 11177 5256 11177 5229 11177 5231 11178 5258 11178 5256 11178 5233 11179 5258 11179 5231 11179 5233 11180 5260 11180 5258 11180 5235 11181 5811 11181 5233 11181 5233 11182 5811 11182 5260 11182 5237 11183 5811 11183 5235 11183 5237 11184 5812 11184 5811 11184 5239 11185 5812 11185 5237 11185 5239 11186 5813 11186 5812 11186 5240 11187 5813 11187 5239 11187 5240 11188 5814 11188 5813 11188 5242 11189 5814 11189 5240 11189 5242 11190 5815 11190 5814 11190 5244 11191 5815 11191 5242 11191 5244 11192 5274 11192 5815 11192 5246 11193 5274 11193 5244 11193 5248 11194 5274 11194 5246 11194 5248 11195 5816 11195 5274 11195 5250 11196 5816 11196 5248 11196 5250 11197 5278 11197 5816 11197 5253 11198 5278 11198 5250 11198 5253 11199 5817 11199 5278 11199 5254 11200 5817 11200 5253 11200 5255 11201 5817 11201 5254 11201 5255 11202 5818 11202 5817 11202 5257 11203 5818 11203 5255 11203 5257 11204 5819 11204 5818 11204 5259 11205 5819 11205 5257 11205 5259 11206 5286 11206 5819 11206 5261 11207 5286 11207 5259 11207 5263 11208 5286 11208 5261 11208 5263 11209 5820 11209 5286 11209 5264 11210 5820 11210 5263 11210 5266 11211 5820 11211 5264 11211 5266 11212 5821 11212 5820 11212 5267 11213 5821 11213 5266 11213 5267 11214 5822 11214 5821 11214 5269 11215 5822 11215 5267 11215 5270 11216 5822 11216 5269 11216 5270 11217 5298 11217 5822 11217 5272 11218 5298 11218 5270 11218 5272 11219 5823 11219 5298 11219 5273 11220 5823 11220 5272 11220 5275 11221 5823 11221 5273 11221 5275 11222 5824 11222 5823 11222 5277 11223 5824 11223 5275 11223 5277 11224 5825 11224 5824 11224 5279 11225 5825 11225 5277 11225 5279 11226 5826 11226 5825 11226 5280 11227 5826 11227 5279 11227 5282 11228 5826 11228 5280 11228 5282 11229 5827 11229 5826 11229 5284 11230 5827 11230 5282 11230 5285 11231 5827 11231 5284 11231 5285 11232 5828 11232 5827 11232 5287 11233 5828 11233 5285 11233 5287 11234 5315 11234 5828 11234 5289 11235 5315 11235 5287 11235 5289 11236 5829 11236 5315 11236 5291 11237 5829 11237 5289 11237 5291 11238 5830 11238 5829 11238 5292 11239 5830 11239 5291 11239 5294 11240 5830 11240 5292 11240 5294 11241 5831 11241 5830 11241 5296 11242 5831 11242 5294 11242 5297 11243 5831 11243 5296 11243 5297 11244 5322 11244 5831 11244 5299 11245 5832 11245 5297 11245 5297 11246 5832 11246 5322 11246 5301 11247 5832 11247 5299 11247 5301 11248 5326 11248 5832 11248 5303 11249 5326 11249 5301 11249 5303 11250 5833 11250 5326 11250 5985 11251 5833 11251 5303 11251 5305 11252 5833 11252 5985 11252 5305 11253 5834 11253 5833 11253 5307 11254 5834 11254 5305 11254 5307 11255 5835 11255 5834 11255 5309 11256 5835 11256 5307 11256 5311 11257 5835 11257 5309 11257 5311 11258 5836 11258 5835 11258 5313 11259 5836 11259 5311 11259 5313 11260 5837 11260 5836 11260 5986 11261 5837 11261 5313 11261 5314 11262 5837 11262 5986 11262 5314 11263 5838 11263 5837 11263 5317 11264 5838 11264 5314 11264 5317 11265 5839 11265 5838 11265 5318 11266 5839 11266 5317 11266 5318 11267 5840 11267 5839 11267 5319 11268 5840 11268 5318 11268 5321 11269 5840 11269 5319 11269 5321 11270 5841 11270 5840 11270 5324 11271 5841 11271 5321 11271 5325 11272 5841 11272 5324 11272 5325 11273 5842 11273 5841 11273 5325 11274 5843 11274 5842 11274 5327 11275 5843 11275 5325 11275 5329 11276 5843 11276 5327 11276 5330 11277 5843 11277 5329 11277 5330 11278 5358 11278 5843 11278 5332 11279 5358 11279 5330 11279 5333 11280 5358 11280 5332 11280 5333 11281 5844 11281 5358 11281 5335 11282 5844 11282 5333 11282 5337 11283 5844 11283 5335 11283 5337 11284 5845 11284 5844 11284 5338 11285 5845 11285 5337 11285 5338 11286 5846 11286 5845 11286 5340 11287 5846 11287 5338 11287 5340 11288 5368 11288 5846 11288 5342 11289 5368 11289 5340 11289 5342 11290 5847 11290 5368 11290 5344 11291 5847 11291 5342 11291 5344 11292 5372 11292 5847 11292 5347 11293 5372 11293 5344 11293 5347 11294 5374 11294 5372 11294 5349 11295 5374 11295 5347 11295 5349 11296 5848 11296 5374 11296 5351 11297 5848 11297 5349 11297 5352 11298 5848 11298 5351 11298 5352 11299 5849 11299 5848 11299 5352 11300 5850 11300 5849 11300 5354 11301 5850 11301 5352 11301 5355 11302 5850 11302 5354 11302 5355 11303 5851 11303 5850 11303 5357 11304 5851 11304 5355 11304 5359 11305 5851 11305 5357 11305 5359 11306 5385 11306 5851 11306 5361 11307 5385 11307 5359 11307 5361 11308 5852 11308 5385 11308 5362 11309 5852 11309 5361 11309 5364 11310 5852 11310 5362 11310 5364 11311 5853 11311 5852 11311 5366 11312 5853 11312 5364 11312 5366 11313 5854 11313 5853 11313 5367 11314 5854 11314 5366 11314 5369 11315 5854 11315 5367 11315 5369 11316 5855 11316 5854 11316 5371 11317 5855 11317 5369 11317 5371 11318 5856 11318 5855 11318 5373 11319 5856 11319 5371 11319 5375 11320 5856 11320 5373 11320 5375 11321 5857 11321 5856 11321 5377 11322 5857 11322 5375 11322 5379 11323 5857 11323 5377 11323 5379 11324 5403 11324 5857 11324 5381 11325 5403 11325 5379 11325 5381 11326 5858 11326 5403 11326 5382 11327 5859 11327 5381 11327 5381 11328 5859 11328 5858 11328 5384 11329 5859 11329 5382 11329 5384 11330 5860 11330 5859 11330 5987 11331 5860 11331 5384 11331 5987 11332 5861 11332 5860 11332 5388 11333 5861 11333 5987 11333 5388 11334 5862 11334 5861 11334 5390 11335 5862 11335 5388 11335 5392 11336 5862 11336 5390 11336 5392 11337 5863 11337 5862 11337 5394 11338 5863 11338 5392 11338 5394 11339 5418 11339 5863 11339 5396 11340 5418 11340 5394 11340 5396 11341 5864 11341 5418 11341 5397 11342 5864 11342 5396 11342 5397 11343 5865 11343 5864 11343 5399 11344 5865 11344 5397 11344 5401 11345 5865 11345 5399 11345 5401 11346 5425 11346 5865 11346 5402 11347 5425 11347 5401 11347 5402 11348 5866 11348 5425 11348 5404 11349 5866 11349 5402 11349 5404 11350 5867 11350 5866 11350 5406 11351 5867 11351 5404 11351 5407 11352 5867 11352 5406 11352 5407 11353 5868 11353 5867 11353 5410 11354 5868 11354 5407 11354 5410 11355 5869 11355 5868 11355 5412 11356 5869 11356 5410 11356 5412 11357 5870 11357 5869 11357 5413 11358 5870 11358 5412 11358 5413 11359 5871 11359 5870 11359 5415 11360 5871 11360 5413 11360 5417 11361 5871 11361 5415 11361 5417 11362 5872 11362 5871 11362 5419 11363 5872 11363 5417 11363 5419 11364 5873 11364 5872 11364 5421 11365 5873 11365 5419 11365 5422 11366 5873 11366 5421 11366 5422 11367 5450 11367 5873 11367 5424 11368 5450 11368 5422 11368 5424 11369 5874 11369 5450 11369 5426 11370 5874 11370 5424 11370 5427 11371 5874 11371 5426 11371 5427 11372 5875 11372 5874 11372 5429 11373 5875 11373 5427 11373 5429 11374 5457 11374 5875 11374 5431 11375 5457 11375 5429 11375 5431 11376 5459 11376 5457 11376 5432 11377 5459 11377 5431 11377 5432 11378 5876 11378 5459 11378 5434 11379 5876 11379 5432 11379 5436 11380 5876 11380 5434 11380 5436 11381 5877 11381 5876 11381 5437 11382 5877 11382 5436 11382 5439 11383 5877 11383 5437 11383 5440 11384 5877 11384 5439 11384 5440 11385 5467 11385 5877 11385 5442 11386 5467 11386 5440 11386 5443 11387 5878 11387 5442 11387 5442 11388 5878 11388 5467 11388 5988 11389 5878 11389 5443 11389 5988 11390 5471 11390 5878 11390 5989 11391 5471 11391 5988 11391 5989 11392 5879 11392 5471 11392 5447 11393 5879 11393 5989 11393 5449 11394 5879 11394 5447 11394 5449 11395 5880 11395 5879 11395 5451 11396 5880 11396 5449 11396 5451 11397 5881 11397 5880 11397 5452 11398 5881 11398 5451 11398 5455 11399 5881 11399 5452 11399 5455 11400 5882 11400 5881 11400 5456 11401 5882 11401 5455 11401 5456 11402 5883 11402 5882 11402 5458 11403 5883 11403 5456 11403 5458 11404 5884 11404 5883 11404 5460 11405 5884 11405 5458 11405 5460 11406 5885 11406 5884 11406 5461 11407 5885 11407 5460 11407 5461 11408 5886 11408 5885 11408 5463 11409 5886 11409 5461 11409 5463 11410 5887 11410 5886 11410 5465 11411 5887 11411 5463 11411 5466 11412 5887 11412 5465 11412 5466 11413 5888 11413 5887 11413 5468 11414 5888 11414 5466 11414 5470 11415 5889 11415 5468 11415 5468 11416 5889 11416 5888 11416 5472 11417 5889 11417 5470 11417 5472 11418 5500 11418 5889 11418 5474 11419 5500 11419 5472 11419 5474 11420 5502 11420 5500 11420 5476 11421 5502 11421 5474 11421 5476 11422 5504 11422 5502 11422 5477 11423 5890 11423 5476 11423 5476 11424 5890 11424 5504 11424 5479 11425 5890 11425 5477 11425 5481 11426 5891 11426 5479 11426 5479 11427 5891 11427 5890 11427 5483 11428 5891 11428 5481 11428 5483 11429 5510 11429 5891 11429 5484 11430 5510 11430 5483 11430 5484 11431 5892 11431 5510 11431 5486 11432 5892 11432 5484 11432 5488 11433 5892 11433 5486 11433 5488 11434 5893 11434 5892 11434 5489 11435 5893 11435 5488 11435 5491 11436 5893 11436 5489 11436 5492 11437 5893 11437 5491 11437 5492 11438 5894 11438 5893 11438 5494 11439 5894 11439 5492 11439 5495 11440 5894 11440 5494 11440 5495 11441 5895 11441 5894 11441 5497 11442 5895 11442 5495 11442 5497 11443 5896 11443 5895 11443 5499 11444 5896 11444 5497 11444 5499 11445 5897 11445 5896 11445 5501 11446 5897 11446 5499 11446 5501 11447 5898 11447 5897 11447 5503 11448 5898 11448 5501 11448 5503 11449 5530 11449 5898 11449 5505 11450 5530 11450 5503 11450 5505 11451 5899 11451 5530 11451 5507 11452 5899 11452 5505 11452 5507 11453 5900 11453 5899 11453 5509 11454 5900 11454 5507 11454 5509 11455 5901 11455 5900 11455 5511 11456 5901 11456 5509 11456 5512 11457 5901 11457 5511 11457 5512 11458 5537 11458 5901 11458 5514 11459 5537 11459 5512 11459 5514 11460 5902 11460 5537 11460 5516 11461 5902 11461 5514 11461 5517 11462 5902 11462 5516 11462 5517 11463 5903 11463 5902 11463 5519 11464 5903 11464 5517 11464 5521 11465 5903 11465 5519 11465 5521 11466 5904 11466 5903 11466 5522 11467 5904 11467 5521 11467 5522 11468 5905 11468 5904 11468 5524 11469 5905 11469 5522 11469 5526 11470 5905 11470 5524 11470 5526 11471 5906 11471 5905 11471 5527 11472 5906 11472 5526 11472 5527 11473 5907 11473 5906 11473 5529 11474 5907 11474 5527 11474 5531 11475 5907 11475 5529 11475 5531 11476 5556 11476 5907 11476 5533 11477 5556 11477 5531 11477 5533 11478 5559 11478 5556 11478 5535 11479 5559 11479 5533 11479 5535 11480 5561 11480 5559 11480 5536 11481 5561 11481 5535 11481 5536 11482 5908 11482 5561 11482 5536 11483 5909 11483 5908 11483 5538 11484 5909 11484 5536 11484 5540 11485 5909 11485 5538 11485 5540 11486 5910 11486 5909 11486 5541 11487 5910 11487 5540 11487 5543 11488 5910 11488 5541 11488 5543 11489 5911 11489 5910 11489 5544 11490 5911 11490 5543 11490 5545 11491 5911 11491 5544 11491 5545 11492 5912 11492 5911 11492 5547 11493 5912 11493 5545 11493 5547 11494 5913 11494 5912 11494 5549 11495 5913 11495 5547 11495 5549 11496 5575 11496 5913 11496 5551 11497 5575 11497 5549 11497 5551 11498 5914 11498 5575 11498 5552 11499 5914 11499 5551 11499 5552 11500 5915 11500 5914 11500 5554 11501 5915 11501 5552 11501 5555 11502 5915 11502 5554 11502 5555 11503 5916 11503 5915 11503 5557 11504 5916 11504 5555 11504 5558 11505 5916 11505 5557 11505 5558 11506 5587 11506 5916 11506 5560 11507 5587 11507 5558 11507 5560 11508 5589 11508 5587 11508 5562 11509 5589 11509 5560 11509 5562 11510 5591 11510 5589 11510 5564 11511 5591 11511 5562 11511 5564 11512 5917 11512 5591 11512 5566 11513 5917 11513 5564 11513 5566 11514 5918 11514 5917 11514 5568 11515 5918 11515 5566 11515 5568 11516 5595 11516 5918 11516 5569 11517 5595 11517 5568 11517 5570 11518 5595 11518 5569 11518 5570 11519 5919 11519 5595 11519 5572 11520 5919 11520 5570 11520 5572 11521 5599 11521 5919 11521 5574 11522 5599 11522 5572 11522 5574 11523 5920 11523 5599 11523 5576 11524 5920 11524 5574 11524 5578 11525 5920 11525 5576 11525 5578 11526 5604 11526 5920 11526 5579 11527 5604 11527 5578 11527 5579 11528 5921 11528 5604 11528 5581 11529 5921 11529 5579 11529 5583 11530 5921 11530 5581 11530 5583 11531 5922 11531 5921 11531 5584 11532 5922 11532 5583 11532 5584 11533 5923 11533 5922 11533 5586 11534 5923 11534 5584 11534 5586 11535 5924 11535 5923 11535 5588 11536 5924 11536 5586 11536 5590 11537 5924 11537 5588 11537 5590 11538 5614 11538 5924 11538 5593 11539 5614 11539 5590 11539 5593 11540 5616 11540 5614 11540 5594 11541 5616 11541 5593 11541 5594 11542 5925 11542 5616 11542 5596 11543 5925 11543 5594 11543 5990 11544 5925 11544 5596 11544 5990 11545 5926 11545 5925 11545 5991 11546 5926 11546 5990 11546 5991 11547 5927 11547 5926 11547 5600 11548 5927 11548 5991 11548 5600 11549 5928 11549 5927 11549 5602 11550 5928 11550 5600 11550 5603 11551 5928 11551 5602 11551 5603 11552 5929 11552 5928 11552 5606 11553 5929 11553 5603 11553 5606 11554 5930 11554 5929 11554 5607 11555 5930 11555 5606 11555 5607 11556 5634 11556 5930 11556 5609 11557 5634 11557 5607 11557 5609 11558 5635 11558 5634 11558 5610 11559 5635 11559 5609 11559 5610 11560 5931 11560 5635 11560 5612 11561 5931 11561 5610 11561 5612 11562 5640 11562 5931 11562 5613 11563 5640 11563 5612 11563 5615 11564 5640 11564 5613 11564 5615 11565 5642 11565 5640 11565 5617 11566 5642 11566 5615 11566 5617 11567 5932 11567 5642 11567 5619 11568 5932 11568 5617 11568 5620 11569 5932 11569 5619 11569 5620 11570 5933 11570 5932 11570 5622 11571 5933 11571 5620 11571 5622 11572 5934 11572 5933 11572 5624 11573 5934 11573 5622 11573 5626 11574 5934 11574 5624 11574 5626 11575 5935 11575 5934 11575 5628 11576 5935 11576 5626 11576 5629 11577 5935 11577 5628 11577 5629 11578 5936 11578 5935 11578 5631 11579 5936 11579 5629 11579 5992 11580 5936 11580 5631 11580 5992 11581 5937 11581 5936 11581 5993 11582 5937 11582 5992 11582 5993 11583 5938 11583 5937 11583 5636 11584 5938 11584 5993 11584 5636 11585 5939 11585 5938 11585 5637 11586 5939 11586 5636 11586 5637 11587 5664 11587 5939 11587 5639 11588 5664 11588 5637 11588 5639 11589 5940 11589 5664 11589 5641 11590 5940 11590 5639 11590 5643 11591 5940 11591 5641 11591 5643 11592 5670 11592 5940 11592 5645 11593 5670 11593 5643 11593 5645 11594 5941 11594 5670 11594 5647 11595 5941 11595 5645 11595 5647 11596 5942 11596 5941 11596 5648 11597 5942 11597 5647 11597 5650 11598 5942 11598 5648 11598 5650 11599 5943 11599 5942 11599 5651 11600 5943 11600 5650 11600 5651 11601 5944 11601 5943 11601 5653 11602 5944 11602 5651 11602 5653 11603 5680 11603 5944 11603 5655 11604 5680 11604 5653 11604 5657 11605 5680 11605 5655 11605 5657 11606 5945 11606 5680 11606 5659 11607 5945 11607 5657 11607 5659 11608 5946 11608 5945 11608 5660 11609 5946 11609 5659 11609 5662 11610 5947 11610 5660 11610 5660 11611 5947 11611 5946 11611 5663 11612 5947 11612 5662 11612 5663 11613 5948 11613 5947 11613 5665 11614 5948 11614 5663 11614 5667 11615 5948 11615 5665 11615 5667 11616 5949 11616 5948 11616 5669 11617 5949 11617 5667 11617 5669 11618 5695 11618 5949 11618 5671 11619 5695 11619 5669 11619 5671 11620 5950 11620 5695 11620 5673 11621 5950 11621 5671 11621 5994 11622 5950 11622 5673 11622 5994 11623 5699 11623 5950 11623 5674 11624 5699 11624 5994 11624 5674 11625 5701 11625 5699 11625 5676 11626 5701 11626 5674 11626 5678 11627 5701 11627 5676 11627 5678 11628 5704 11628 5701 11628 5679 11629 5704 11629 5678 11629 5679 11630 5706 11630 5704 11630 5679 11631 5951 11631 5706 11631 5681 11632 5951 11632 5679 11632 5683 11633 5951 11633 5681 11633 5683 11634 5710 11634 5951 11634 5685 11635 5710 11635 5683 11635 5686 11636 5710 11636 5685 11636 5686 11637 5952 11637 5710 11637 5688 11638 5952 11638 5686 11638 5689 11639 5953 11639 5688 11639 5688 11640 5953 11640 5952 11640 5689 11641 5954 11641 5953 11641 5691 11642 5954 11642 5689 11642 5692 11643 5954 11643 5691 11643 5692 11644 5720 11644 5954 11644 5694 11645 5720 11645 5692 11645 5694 11646 5955 11646 5720 11646 5696 11647 5955 11647 5694 11647 5698 11648 5955 11648 5696 11648 5698 11649 5725 11649 5955 11649 5698 11650 5956 11650 5725 11650 5700 11651 5956 11651 5698 11651 5702 11652 5956 11652 5700 11652 5702 11653 5957 11653 5956 11653 5703 11654 5957 11654 5702 11654 5703 11655 5958 11655 5957 11655 5705 11656 5958 11656 5703 11656 5705 11657 5959 11657 5958 11657 5707 11658 5959 11658 5705 11658 5707 11659 5960 11659 5959 11659 5709 11660 5960 11660 5707 11660 5711 11661 5960 11661 5709 11661 5711 11662 5961 11662 5960 11662 5995 11663 5961 11663 5711 11663 5995 11664 5962 11664 5961 11664 5716 11665 5962 11665 5995 11665 5716 11666 5741 11666 5962 11666 5716 11667 5963 11667 5741 11667 5718 11668 5963 11668 5716 11668 5719 11669 5963 11669 5718 11669 5719 11670 5746 11670 5963 11670 5721 11671 5746 11671 5719 11671 5723 11672 5746 11672 5721 11672 5723 11673 5748 11673 5746 11673 5724 11674 5748 11674 5723 11674 5724 11675 5964 11675 5748 11675 5726 11676 5964 11676 5724 11676 5726 11677 5965 11677 5964 11677 5728 11678 5965 11678 5726 11678 5730 11679 5965 11679 5728 11679 5730 11680 5966 11680 5965 11680 5731 11681 5966 11681 5730 11681 5733 11682 5967 11682 5731 11682 5731 11683 5967 11683 5966 11683 5734 11684 5967 11684 5733 11684 5734 11685 5760 11685 5967 11685 5736 11686 5760 11686 5734 11686 5736 11687 5968 11687 5760 11687 5737 11688 5968 11688 5736 11688 5737 11689 5969 11689 5968 11689 5739 11690 5969 11690 5737 11690 5740 11691 5969 11691 5739 11691 5740 11692 5970 11692 5969 11692 5742 11693 5970 11693 5740 11693 5742 11694 5971 11694 5970 11694 5744 11695 5971 11695 5742 11695 5745 11696 5971 11696 5744 11696 5745 11697 5771 11697 5971 11697 5747 11698 5771 11698 5745 11698 5747 11699 5972 11699 5771 11699 5749 11700 5972 11700 5747 11700 5749 11701 5973 11701 5972 11701 5751 11702 5973 11702 5749 11702 5753 11703 5973 11703 5751 11703 5753 11704 5777 11704 5973 11704 5754 11705 5777 11705 5753 11705 5754 11706 5779 11706 5777 11706 5756 11707 5779 11707 5754 11707 5756 11708 5781 11708 5779 11708 5758 11709 5781 11709 5756 11709 5758 11710 5784 11710 5781 11710 5759 11711 5784 11711 5758 11711 5759 11712 5974 11712 5784 11712 5761 11713 5974 11713 5759 11713 5763 11714 5975 11714 5761 11714 5761 11715 5975 11715 5974 11715 5764 11716 5975 11716 5763 11716 5764 11717 5791 11717 5975 11717 5766 11718 5791 11718 5764 11718 5766 11719 5793 11719 5791 11719 5768 11720 5793 11720 5766 11720 5768 11721 5976 11721 5793 11721 5770 11722 5976 11722 5768 11722 5770 11723 5977 11723 5976 11723 5774 11724 5977 11724 5770 11724 5774 11725 5978 11725 5977 11725 5996 11726 5978 11726 5774 11726 5996 11727 5979 11727 5978 11727 5997 11728 5979 11728 5996 11728 5997 11729 5980 11729 5979 11729 5778 11730 5980 11730 5997 11730 5778 11731 5185 11731 5980 11731 5780 11732 5185 11732 5778 11732 5780 11733 5184 11733 5185 11733 5782 11734 5184 11734 5780 11734 5783 11735 5184 11735 5782 11735 5783 11736 5189 11736 5184 11736 5785 11737 5189 11737 5783 11737 5787 11738 5189 11738 5785 11738 5787 11739 5192 11739 5189 11739 5788 11740 5192 11740 5787 11740 5788 11741 5196 11741 5192 11741 5984 11742 5983 11742 5200 11742 5201 11743 5984 11743 5200 11743 5305 11744 5985 11744 5303 11744 5314 11745 5986 11745 5313 11745 5347 11746 5344 11746 5345 11746 5386 11747 5987 11747 5384 11747 5388 11748 5987 11748 5386 11748 5446 11749 5988 11749 5443 11749 5989 11750 5988 11750 5446 11750 5447 11751 5989 11751 5446 11751 5598 11752 5990 11752 5596 11752 5991 11753 5990 11753 5598 11753 5600 11754 5991 11754 5598 11754 5633 11755 5992 11755 5631 11755 5993 11756 5992 11756 5633 11756 5636 11757 5993 11757 5633 11757 5674 11758 5994 11758 5673 11758 5995 11759 5711 11759 5713 11759 5715 11760 5995 11760 5713 11760 5716 11761 5995 11761 5715 11761 5774 11762 5770 11762 5772 11762 5776 11763 5996 11763 5774 11763 5997 11764 5996 11764 5776 11764 5778 11765 5997 11765 5776 11765 5196 11766 5788 11766 5789 11766 5198 11767 5196 11767 5789 11767 5792 11768 5198 11768 5789 11768 6021 11769 5198 11769 5792 11769 5998 11770 6038 11770 5999 11770 5999 11771 6038 11771 6000 11771 6001 11772 5998 11772 5999 11772 6001 11773 6043 11773 5998 11773 6002 11774 5186 11774 6043 11774 6002 11775 6043 11775 6001 11775 6003 11776 6001 11776 5999 11776 6000 11777 6003 11777 5999 11777 6004 11778 6003 11778 6000 11778 5194 11779 6002 11779 6001 11779 6004 11780 6001 11780 6003 11780 5194 11781 6001 11781 6004 11781 6004 11782 6000 11782 6006 11782 6005 11783 6006 11783 6000 11783 5195 11784 6004 11784 6006 11784 5195 11785 5194 11785 6004 11785 6007 11786 6006 11786 6005 11786 6008 11787 5195 11787 6006 11787 6008 11788 6006 11788 6007 11788 6007 11789 6005 11789 6010 11789 6011 11790 6008 11790 6007 11790 6008 11791 5197 11791 5195 11791 6012 11792 6007 11792 6010 11792 6011 11793 6007 11793 6012 11793 5197 11794 6008 11794 6011 11794 6010 11795 6005 11795 6009 11795 6013 11796 6011 11796 6012 11796 6014 11797 6010 11797 6009 11797 6013 11798 5197 11798 6011 11798 6012 11799 6010 11799 6014 11799 6015 11800 6013 11800 6012 11800 6015 11801 6012 11801 6014 11801 6016 11802 6014 11802 6009 11802 5199 11803 6013 11803 6015 11803 6017 11804 6016 11804 6009 11804 6018 11805 6014 11805 6016 11805 6018 11806 6015 11806 6014 11806 6018 11807 5199 11807 6015 11807 5794 11808 5199 11808 6018 11808 6019 11809 6016 11809 6017 11809 6018 11810 6016 11810 6019 11810 6020 11811 6019 11811 6017 11811 5794 11812 6018 11812 6019 11812 6019 11813 5792 11813 5794 11813 6021 11814 6019 11814 6020 11814 6020 11815 6017 11815 6022 11815 6021 11816 5792 11816 6019 11816 6023 11817 6020 11817 6022 11817 6023 11818 6021 11818 6020 11818 5198 11819 6021 11819 6023 11819 6024 11820 5198 11820 6023 11820 6023 11821 6022 11821 6027 11821 6025 11822 6022 11822 6026 11822 6027 11823 6024 11823 6023 11823 6027 11824 6022 11824 6025 11824 5196 11825 5198 11825 6024 11825 6024 11826 6027 11826 6028 11826 6028 11827 6027 11827 6025 11827 5192 11828 5196 11828 6024 11828 6028 11829 5192 11829 6024 11829 6029 11830 6028 11830 6025 11830 6029 11831 6025 11831 6026 11831 6028 11832 5190 11832 5192 11832 5190 11833 6028 11833 6029 11833 6030 11834 6029 11834 6026 11834 6031 11835 6030 11835 6026 11835 6033 11836 6029 11836 6030 11836 6033 11837 5190 11837 6029 11837 6032 11838 6031 11838 6026 11838 6034 11839 6030 11839 6031 11839 6033 11840 6030 11840 6034 11840 5187 11841 5190 11841 6033 11841 6035 11842 6034 11842 6031 11842 5187 11843 6033 11843 6034 11843 6036 11844 6031 11844 6032 11844 6037 11845 6034 11845 6035 11845 6035 11846 6031 11846 6036 11846 6037 11847 5187 11847 6034 11847 6039 11848 6037 11848 6035 11848 6039 11849 6035 11849 6036 11849 6038 11850 6036 11850 6032 11850 6040 11851 6039 11851 6036 11851 6040 11852 6036 11852 6038 11852 6040 11853 6041 11853 6039 11853 6041 11854 6037 11854 6039 11854 6042 11855 6041 11855 6040 11855 5186 11856 6041 11856 6042 11856 6043 11857 6042 11857 6040 11857 5998 11858 6040 11858 6038 11858 5998 11859 6043 11859 6040 11859 5186 11860 6042 11860 6043 11860 6009 11861 6038 11861 6032 11861 6009 11862 6022 11862 6017 11862 6009 11863 6000 11863 6038 11863 6009 11864 6005 11864 6000 11864 6009 11865 6026 11865 6022 11865 6009 11866 6032 11866 6026 11866 6045 11867 6050 11867 6053 11867 6045 11868 6044 11868 6050 11868 6044 11869 6046 11869 6050 11869 6050 11870 6046 11870 6051 11870 6046 11871 6047 11871 6051 11871 6051 11872 6047 11872 6055 11872 6047 11873 6048 11873 6055 11873 6055 11874 6048 11874 6054 11874 6048 11875 6049 11875 6054 11875 6054 11876 6049 11876 6052 11876 6049 11877 6053 11877 6052 11877 6049 11878 6045 11878 6053 11878 6051 11879 6056 11879 6057 11879 6051 11880 6057 11880 6058 11880 6055 11881 6056 11881 6051 11881 6055 11882 6060 11882 6059 11882 6055 11883 6059 11883 6056 11883 6055 11884 6063 11884 6060 11884 6050 11885 6058 11885 6061 11885 6050 11886 6061 11886 6062 11886 6050 11887 6051 11887 6058 11887 6054 11888 6063 11888 6055 11888 6064 11889 6050 11889 6062 11889 6065 11890 6063 11890 6054 11890 6053 11891 6050 11891 6064 11891 6066 11892 6053 11892 6064 11892 6067 11893 6065 11893 6054 11893 6067 11894 6054 11894 6052 11894 6068 11895 6053 11895 6066 11895 6069 11896 6067 11896 6052 11896 6068 11897 6052 11897 6053 11897 6070 11898 6052 11898 6068 11898 6070 11899 6069 11899 6052 11899 6045 11900 6049 11900 6044 11900 6044 11901 6048 11901 6046 11901 6046 11902 6048 11902 6047 11902 6049 11903 6048 11903 6044 11903 6072 11904 6071 11904 6060 11904 6072 11905 6060 11905 6063 11905 6073 11906 6072 11906 6063 11906 6073 11907 6063 11907 6065 11907 6074 11908 6073 11908 6065 11908 6074 11909 6065 11909 6067 11909 6075 11910 6074 11910 6067 11910 6075 11911 6067 11911 6069 11911 6076 11912 6075 11912 6069 11912 6076 11913 6069 11913 6070 11913 6077 11914 6076 11914 6070 11914 6077 11915 6070 11915 6068 11915 6078 11916 6077 11916 6068 11916 6078 11917 6068 11917 6066 11917 6079 11918 6078 11918 6066 11918 6079 11919 6066 11919 6064 11919 6080 11920 6079 11920 6064 11920 6080 11921 6064 11921 6062 11921 6081 11922 6080 11922 6062 11922 6081 11923 6062 11923 6061 11923 6081 11924 6061 11924 6058 11924 6082 11925 6081 11925 6058 11925 6082 11926 6058 11926 6057 11926 6083 11927 6082 11927 6057 11927 6083 11928 6057 11928 6056 11928 6084 11929 6083 11929 6056 11929 6084 11930 6056 11930 6059 11930 6071 11931 6084 11931 6059 11931 6071 11932 6059 11932 6060 11932 5797 11933 6080 11933 6081 11933 5797 11934 5210 11934 6080 11934 5210 11935 6079 11935 6080 11935 5202 11936 6079 11936 5210 11936 5202 11937 6078 11937 6079 11937 5797 11938 6081 11938 6082 11938 5798 11939 5797 11939 6082 11939 5202 11940 6077 11940 6078 11940 5206 11941 6077 11941 5202 11941 5798 11942 6082 11942 6083 11942 5982 11943 5798 11943 6083 11943 5206 11944 6076 11944 6077 11944 6084 11945 5982 11945 6083 11945 6076 11946 5206 11946 5203 11946 6075 11947 6076 11947 5203 11947 6084 11948 5981 11948 5982 11948 6071 11949 5981 11949 6084 11949 6074 11950 5203 11950 5200 11950 6074 11951 6075 11951 5203 11951 6072 11952 5981 11952 6071 11952 6072 11953 5983 11953 5981 11953 6073 11954 6074 11954 5200 11954 6073 11955 5983 11955 6072 11955 6073 11956 5200 11956 5983 11956

+
+ + + +

6086 11957 6087 11957 6085 11957 6085 11958 6087 11958 6088 11958 6087 11959 6089 11959 6088 11959 6088 11960 6089 11960 6090 11960 6089 11961 6091 11961 6090 11961 6090 11962 6091 11962 6092 11962 6091 11963 6093 11963 6092 11963 6092 11964 6093 11964 6094 11964 6093 11965 6095 11965 6094 11965 6094 11966 6095 11966 6096 11966 6096 11967 6095 11967 6097 11967 6095 11968 6098 11968 6097 11968 6097 11969 6098 11969 6099 11969 6098 11970 6100 11970 6099 11970 6100 11971 6101 11971 6099 11971 6099 11972 6101 11972 6102 11972 6102 11973 6101 11973 6103 11973 6101 11974 6104 11974 6103 11974 6103 11975 6104 11975 6105 11975 6104 11976 6106 11976 6105 11976 6105 11977 6106 11977 6085 11977 6106 11978 6086 11978 6085 11978 6107 11979 6137 11979 6108 11979 6109 11980 6107 11980 6108 11980 6109 11981 6108 11981 6110 11981 6111 11982 6109 11982 6110 11982 6111 11983 6110 11983 6112 11983 6113 11984 6111 11984 6112 11984 6113 11985 6112 11985 6114 11985 6115 11986 6113 11986 6114 11986 6115 11987 6114 11987 6116 11987 6117 11988 6115 11988 6116 11988 6117 11989 6116 11989 6118 11989 6119 11990 6117 11990 6118 11990 6119 11991 6118 11991 6120 11991 6121 11992 6119 11992 6120 11992 6121 11993 6120 11993 6122 11993 6123 11994 6121 11994 6122 11994 6123 11995 6122 11995 6124 11995 6125 11996 6123 11996 6124 11996 6125 11997 6124 11997 6126 11997 6127 11998 6125 11998 6126 11998 6127 11999 6126 11999 6128 11999 6129 12000 6127 12000 6128 12000 6129 12001 6128 12001 6130 12001 6131 12002 6129 12002 6130 12002 6131 12003 6130 12003 6132 12003 6133 12004 6131 12004 6132 12004 6133 12005 6132 12005 6134 12005 6135 12006 6133 12006 6134 12006 6136 12007 6134 12007 6137 12007 6136 12008 6135 12008 6134 12008 6107 12009 6136 12009 6137 12009 6100 12010 6134 12010 6132 12010 6098 12011 6134 12011 6100 12011 6101 1433 6100 1433 6132 1433 6098 1433 6137 1433 6134 1433 6101 12012 6132 12012 6130 12012 6095 12013 6137 12013 6098 12013 6101 1433 6130 1433 6128 1433 6095 1433 6108 1433 6137 1433 6104 12014 6101 12014 6128 12014 6093 1433 6110 1433 6108 1433 6093 1433 6108 1433 6095 1433 6106 12015 6104 12015 6128 12015 6126 1433 6106 1433 6128 1433 6112 1433 6110 1433 6093 1433 6124 1433 6086 1433 6106 1433 6124 1433 6106 1433 6126 1433 6112 12016 6093 12016 6091 12016 6114 1433 6112 1433 6091 1433 6122 1433 6086 1433 6124 1433 6122 1433 6087 1433 6086 1433 6114 12017 6091 12017 6089 12017 6116 12018 6114 12018 6089 12018 6120 12019 6087 12019 6122 12019 6118 1433 6116 1433 6089 1433 6118 12020 6089 12020 6087 12020 6118 12021 6087 12021 6120 12021 6103 759 6105 759 6127 759 6105 759 6125 759 6127 759 6103 759 6127 759 6129 759 6085 12022 6125 12022 6105 12022 6085 759 6123 759 6125 759 6102 759 6103 759 6129 759 6102 12023 6129 12023 6131 12023 6085 759 6121 759 6123 759 6099 759 6102 759 6131 759 6099 12024 6131 12024 6133 12024 6088 759 6121 759 6085 759 6088 759 6119 759 6121 759 6135 759 6099 759 6133 759 6117 759 6119 759 6088 759 6135 12025 6097 12025 6099 12025 6117 12026 6088 12026 6090 12026 6136 759 6097 759 6135 759 6115 759 6117 759 6090 759 6107 759 6097 759 6136 759 6115 12027 6090 12027 6092 12027 6107 759 6096 759 6097 759 6113 759 6115 759 6092 759 6111 759 6113 759 6092 759 6109 12028 6096 12028 6107 12028 6109 759 6094 759 6096 759 6111 12029 6092 12029 6094 12029 6111 12030 6094 12030 6109 12030

+
+ + + +

6158 12031 6139 12031 6140 12031 6138 12032 6139 12032 6158 12032 6140 12033 6139 12033 6141 12033 6139 12034 6142 12034 6141 12034 6142 12035 6143 12035 6141 12035 6141 12036 6143 12036 6144 12036 6143 12037 6145 12037 6144 12037 6144 12038 6145 12038 6146 12038 6145 12039 6147 12039 6146 12039 6147 12040 6148 12040 6146 12040 6146 12041 6148 12041 6149 12041 6148 12042 6150 12042 6149 12042 6149 12043 6150 12043 6151 12043 6150 12044 6152 12044 6151 12044 6151 12045 6152 12045 6153 12045 6152 12046 6154 12046 6153 12046 6153 12047 6154 12047 6155 12047 6154 12048 6156 12048 6155 12048 6155 12049 6156 12049 6157 12049 6157 12050 6156 12050 6158 12050 6156 12051 6138 12051 6158 12051 6159 12052 6189 12052 6160 12052 6159 12053 6188 12053 6189 12053 6159 12054 6160 12054 6161 12054 6162 12055 6159 12055 6161 12055 6162 12056 6161 12056 6163 12056 6164 12057 6162 12057 6163 12057 6164 12058 6163 12058 6165 12058 6166 12059 6164 12059 6165 12059 6166 12060 6165 12060 6167 12060 6168 12061 6166 12061 6167 12061 6168 12062 6167 12062 6169 12062 6170 12063 6168 12063 6169 12063 6170 12064 6169 12064 6171 12064 6172 12065 6170 12065 6171 12065 6172 12066 6171 12066 6173 12066 6174 12067 6172 12067 6173 12067 6174 12068 6173 12068 6175 12068 6174 12069 6175 12069 6176 12069 6177 12070 6174 12070 6176 12070 6178 12071 6177 12071 6176 12071 6178 12072 6176 12072 6179 12072 6180 12073 6178 12073 6179 12073 6180 12074 6179 12074 6181 12074 6182 12075 6180 12075 6181 12075 6182 12076 6181 12076 6183 12076 6184 12077 6182 12077 6183 12077 6184 12078 6183 12078 6185 12078 6184 12079 6185 12079 6186 12079 6187 12080 6184 12080 6186 12080 6188 12081 6187 12081 6186 12081 6188 12082 6186 12082 6189 12082 6150 1433 6186 1433 6185 1433 6152 1433 6150 1433 6185 1433 6152 12083 6185 12083 6183 12083 6150 12084 6189 12084 6186 12084 6148 12085 6189 12085 6150 12085 6152 12086 6183 12086 6181 12086 6148 1433 6160 1433 6189 1433 6154 1433 6152 1433 6181 1433 6148 12087 6161 12087 6160 12087 6154 12088 6181 12088 6179 12088 6147 12089 6161 12089 6148 12089 6156 1433 6154 1433 6179 1433 6176 1433 6156 1433 6179 1433 6163 12090 6161 12090 6147 12090 6163 1433 6147 1433 6145 1433 6175 1433 6156 1433 6176 1433 6165 1433 6163 1433 6145 1433 6175 12091 6138 12091 6156 12091 6165 12092 6145 12092 6143 12092 6173 1433 6138 1433 6175 1433 6167 1433 6165 1433 6143 1433 6173 1433 6139 1433 6138 1433 6167 12093 6143 12093 6142 12093 6171 1433 6139 1433 6173 1433 6169 12094 6167 12094 6142 12094 6169 12095 6142 12095 6139 12095 6169 12096 6139 12096 6171 12096 6155 12097 6157 12097 6178 12097 6157 12098 6177 12098 6178 12098 6155 12099 6178 12099 6180 12099 6158 12100 6177 12100 6157 12100 6158 12101 6174 12101 6177 12101 6155 12102 6180 12102 6182 12102 6153 759 6155 759 6182 759 6158 759 6172 759 6174 759 6140 759 6172 759 6158 759 6153 759 6182 759 6184 759 6140 759 6170 759 6172 759 6151 759 6153 759 6184 759 6151 12103 6184 12103 6187 12103 6170 12104 6140 12104 6141 12104 6168 12105 6170 12105 6141 12105 6188 759 6151 759 6187 759 6188 759 6149 759 6151 759 6168 12106 6141 12106 6144 12106 6166 12107 6168 12107 6144 12107 6159 12108 6149 12108 6188 12108 6164 759 6166 759 6144 759 6159 759 6146 759 6149 759 6162 12109 6146 12109 6159 12109 6164 12110 6144 12110 6146 12110 6162 12111 6164 12111 6146 12111

+
+ + + +

7054 12112 6190 12112 7050 12112 7050 12113 6190 12113 6191 12113 6190 12114 6192 12114 6191 12114 6193 12115 6190 12115 7054 12115 6193 12116 6194 12116 6190 12116 6191 12117 6192 12117 6195 12117 6192 12118 6196 12118 6195 12118 6197 12119 6194 12119 6193 12119 6197 12120 6198 12120 6194 12120 6195 12121 6196 12121 6199 12121 6197 12122 6200 12122 6198 12122 6201 12123 6200 12123 6197 12123 6196 12124 6202 12124 6199 12124 6202 12125 6203 12125 6199 12125 6201 12126 6204 12126 6200 12126 6201 12127 6205 12127 6204 12127 6801 12128 6203 12128 6202 12128 6205 12129 6206 12129 6204 12129 6204 12130 6206 12130 6207 12130 6211 12131 6209 12131 6208 12131 6211 12132 6210 12132 6209 12132 6214 12133 6210 12133 6211 12133 6214 12134 6213 12134 6210 12134 6214 12135 6215 12135 6213 12135 6216 12136 6215 12136 6214 12136 6216 12137 6217 12137 6215 12137 6212 12138 6217 12138 6216 12138 6212 12139 6218 12139 6217 12139 6219 12140 6218 12140 6212 12140 6219 12141 6220 12141 6218 12141 6221 12142 6220 12142 6219 12142 6221 12143 6222 12143 6220 12143 6221 12144 6223 12144 6222 12144 6224 12145 6223 12145 6221 12145 6224 12146 6225 12146 6223 12146 6226 12147 6225 12147 6224 12147 6226 12148 6227 12148 6225 12148 6226 12149 6228 12149 6227 12149 6229 12150 6228 12150 6226 12150 6229 12151 6230 12151 6228 12151 6231 12152 6230 12152 6229 12152 6231 12153 6232 12153 6230 12153 6231 12154 6233 12154 6232 12154 6234 12155 6233 12155 6231 12155 6234 12156 6235 12156 6233 12156 6236 12157 6235 12157 6234 12157 6236 12158 6237 12158 6235 12158 6236 12159 6238 12159 6237 12159 6239 12160 6238 12160 6236 12160 6239 12161 6240 12161 6238 12161 6241 12162 6240 12162 6239 12162 6241 12163 6242 12163 6240 12163 6243 12164 6242 12164 6241 12164 6243 12165 6244 12165 6242 12165 6243 12166 6245 12166 6244 12166 6246 12167 6245 12167 6243 12167 6246 12168 6247 12168 6245 12168 6248 12169 6247 12169 6246 12169 6248 12170 6249 12170 6247 12170 6250 12171 6249 12171 6248 12171 6250 12172 6251 12172 6249 12172 6250 12173 6252 12173 6251 12173 6253 12174 6252 12174 6250 12174 6253 12175 6254 12175 6252 12175 6255 12176 6254 12176 6253 12176 6255 12177 6256 12177 6254 12177 6257 12178 6256 12178 6255 12178 6257 12179 6258 12179 6256 12179 6257 12180 6259 12180 6258 12180 6260 12181 6259 12181 6257 12181 6260 12182 6261 12182 6259 12182 6262 12183 6261 12183 6260 12183 6262 12184 6263 12184 6261 12184 6264 12185 6263 12185 6262 12185 6264 12186 6265 12186 6263 12186 6264 12187 6266 12187 6265 12187 6267 12188 6266 12188 6264 12188 6267 12189 6268 12189 6266 12189 6269 12190 6268 12190 6267 12190 6269 12191 6270 12191 6268 12191 6271 12192 6270 12192 6269 12192 6271 12193 6272 12193 6270 12193 6273 12194 6272 12194 6271 12194 6273 12195 6274 12195 6272 12195 6275 12196 6274 12196 6273 12196 6275 12197 6276 12197 6274 12197 6275 12198 6277 12198 6276 12198 6278 12199 6277 12199 6275 12199 6278 12200 6279 12200 6277 12200 6280 12201 6279 12201 6278 12201 6280 12202 6281 12202 6279 12202 6282 12203 6281 12203 6280 12203 6282 12204 6283 12204 6281 12204 6284 12205 6283 12205 6282 12205 6284 12206 6285 12206 6283 12206 6284 12207 6286 12207 6285 12207 6287 12208 6286 12208 6284 12208 6287 12209 6288 12209 6286 12209 6289 12210 6288 12210 6287 12210 6289 12211 6290 12211 6288 12211 6289 12212 6291 12212 6290 12212 6292 12213 6291 12213 6289 12213 6293 12214 6291 12214 6292 12214 6293 12215 6294 12215 6291 12215 6293 12216 6295 12216 6294 12216 6296 12217 6295 12217 6293 12217 6296 12218 6297 12218 6295 12218 6298 12219 6297 12219 6296 12219 6298 12220 6299 12220 6297 12220 6300 12221 6299 12221 6298 12221 6300 12222 6301 12222 6299 12222 6302 12223 6301 12223 6300 12223 6302 12224 6303 12224 6301 12224 6304 12225 6303 12225 6302 12225 6305 12226 6303 12226 6304 12226 6305 12227 6306 12227 6303 12227 6305 12228 6307 12228 6306 12228 6308 12229 6307 12229 6305 12229 6308 12230 6309 12230 6307 12230 6310 12231 6309 12231 6308 12231 6310 12232 6311 12232 6309 12232 6310 12233 6312 12233 6311 12233 6313 12234 6312 12234 6310 12234 6314 12235 6312 12235 6313 12235 6314 12236 6315 12236 6312 12236 6314 12237 6316 12237 6315 12237 6317 12238 6316 12238 6314 12238 6317 12239 6318 12239 6316 12239 6317 12240 6319 12240 6318 12240 6320 12241 6319 12241 6317 12241 6321 12242 6322 12242 6320 12242 6320 12243 6322 12243 6319 12243 6321 12244 6323 12244 6322 12244 6321 12245 6324 12245 6323 12245 6325 12246 6324 12246 6321 12246 6325 12247 6326 12247 6324 12247 6327 12248 6326 12248 6325 12248 6327 12249 6328 12249 6326 12249 6327 12250 6329 12250 6328 12250 6330 12251 6329 12251 6327 12251 6330 12252 6331 12252 6329 12252 6332 12253 6333 12253 6330 12253 6330 12254 6333 12254 6331 12254 6332 12255 6334 12255 6333 12255 6335 12256 6334 12256 6332 12256 6335 12257 6336 12257 6334 12257 6337 12258 6336 12258 6335 12258 6337 12259 6338 12259 6336 12259 6339 12260 6338 12260 6337 12260 6340 12261 6338 12261 6339 12261 6340 12262 6341 12262 6338 12262 6340 12263 6342 12263 6341 12263 6343 12264 6342 12264 6340 12264 6343 12265 6344 12265 6342 12265 6345 12266 6344 12266 6343 12266 6345 12267 6346 12267 6344 12267 6345 12268 6347 12268 6346 12268 6348 12269 6347 12269 6345 12269 6348 12270 6349 12270 6347 12270 6350 12271 6349 12271 6348 12271 6351 12272 6352 12272 6350 12272 6350 12273 6352 12273 6349 12273 6351 12274 6353 12274 6352 12274 6354 12275 6353 12275 6351 12275 6354 12276 6355 12276 6353 12276 6354 12277 6356 12277 6355 12277 6357 12278 6356 12278 6354 12278 6357 12279 6358 12279 6356 12279 6359 12280 6358 12280 6357 12280 6359 12281 6360 12281 6358 12281 6359 12282 6361 12282 6360 12282 6362 12283 6361 12283 6359 12283 6362 12284 6363 12284 6361 12284 6364 12285 6363 12285 6362 12285 6364 12286 6365 12286 6363 12286 6364 12287 6366 12287 6365 12287 6367 12288 6366 12288 6364 12288 6367 12289 6368 12289 6366 12289 6367 12290 6369 12290 6368 12290 6370 12291 6369 12291 6367 12291 6370 12292 6371 12292 6369 12292 6372 12293 6371 12293 6370 12293 6372 12294 6373 12294 6371 12294 6374 12295 6373 12295 6372 12295 6374 12296 6375 12296 6373 12296 6376 12297 6375 12297 6374 12297 6376 12298 6377 12298 6375 12298 6376 12299 6378 12299 6377 12299 6379 12300 6378 12300 6376 12300 6379 12301 6380 12301 6378 12301 6381 12302 6380 12302 6379 12302 6382 12303 6383 12303 6381 12303 6381 12304 6383 12304 6380 12304 6382 12305 6384 12305 6383 12305 6385 12306 6384 12306 6382 12306 6385 12307 6386 12307 6384 12307 6385 12308 6387 12308 6386 12308 6388 12309 6387 12309 6385 12309 6388 12310 6389 12310 6387 12310 6388 12311 6390 12311 6389 12311 6391 12312 6390 12312 6388 12312 6391 12313 6392 12313 6390 12313 6393 12314 6392 12314 6391 12314 6393 12315 6394 12315 6392 12315 6395 12316 6396 12316 6393 12316 6393 12317 6396 12317 6394 12317 6397 12318 6396 12318 6395 12318 6397 12319 6398 12319 6396 12319 6399 12320 6398 12320 6397 12320 6399 12321 6400 12321 6398 12321 6399 12322 6401 12322 6400 12322 6402 12323 6401 12323 6399 12323 6402 12324 6403 12324 6401 12324 6404 12325 6403 12325 6402 12325 6404 12326 6405 12326 6403 12326 6406 12327 6405 12327 6404 12327 6406 12328 6407 12328 6405 12328 6408 12329 6407 12329 6406 12329 6408 12330 6409 12330 6407 12330 6410 12331 6409 12331 6408 12331 6410 12332 6411 12332 6409 12332 6412 12333 6411 12333 6410 12333 6412 12334 6413 12334 6411 12334 6414 12335 6413 12335 6412 12335 6414 12336 6415 12336 6413 12336 6416 12337 6415 12337 6414 12337 6416 12338 6417 12338 6415 12338 6416 12339 6418 12339 6417 12339 6419 12340 6418 12340 6416 12340 6420 12341 6421 12341 6419 12341 6419 12342 6421 12342 6418 12342 6420 12343 6422 12343 6421 12343 6423 12344 6422 12344 6420 12344 6423 12345 6424 12345 6422 12345 6423 12346 6425 12346 6424 12346 6426 12347 6425 12347 6423 12347 6427 12348 6425 12348 6426 12348 6427 12349 6428 12349 6425 12349 6427 12350 6429 12350 6428 12350 6430 12351 6429 12351 6427 12351 6430 12352 6431 12352 6429 12352 6430 12353 6432 12353 6431 12353 6433 12354 6432 12354 6430 12354 6433 12355 6434 12355 6432 12355 6435 12356 6434 12356 6433 12356 6435 12357 6436 12357 6434 12357 6435 12358 6437 12358 6436 12358 6438 12359 6437 12359 6435 12359 6438 12360 6439 12360 6437 12360 6438 12361 6440 12361 6439 12361 6441 12362 6440 12362 6438 12362 6441 12363 6442 12363 6440 12363 6443 12364 6442 12364 6441 12364 6443 12365 6444 12365 6442 12365 6445 12366 6444 12366 6443 12366 6445 12367 6446 12367 6444 12367 6447 12368 6446 12368 6445 12368 6447 12369 6448 12369 6446 12369 6449 12370 6448 12370 6447 12370 6449 12371 6450 12371 6448 12371 6449 12372 6451 12372 6450 12372 6452 12373 6451 12373 6449 12373 6452 12374 6453 12374 6451 12374 6454 12375 6453 12375 6452 12375 6454 12376 6455 12376 6453 12376 6456 12377 6455 12377 6454 12377 6456 12378 6457 12378 6455 12378 6458 12379 6457 12379 6456 12379 6458 12380 6459 12380 6457 12380 6460 12381 6459 12381 6458 12381 6460 12382 6461 12382 6459 12382 6462 12383 6461 12383 6460 12383 6462 12384 6463 12384 6461 12384 6464 12385 6463 12385 6462 12385 6464 12386 6465 12386 6463 12386 6464 12387 6466 12387 6465 12387 6467 12388 6466 12388 6464 12388 6467 12389 6468 12389 6466 12389 6469 12390 6468 12390 6467 12390 6469 12391 6470 12391 6468 12391 6469 12392 6471 12392 6470 12392 6472 12393 6471 12393 6469 12393 6472 12394 6473 12394 6471 12394 6472 12395 6474 12395 6473 12395 6475 12396 6474 12396 6472 12396 6475 12397 6476 12397 6474 12397 6477 12398 6476 12398 6475 12398 6477 12399 6478 12399 6476 12399 6477 12400 6479 12400 6478 12400 6480 12401 6479 12401 6477 12401 6480 12402 6481 12402 6479 12402 6482 12403 6481 12403 6480 12403 6482 12404 6483 12404 6481 12404 6482 12405 6484 12405 6483 12405 6485 12406 6484 12406 6482 12406 6485 12407 6486 12407 6484 12407 6485 12408 6487 12408 6486 12408 6488 12409 6487 12409 6485 12409 6488 12410 6489 12410 6487 12410 6490 12411 6489 12411 6488 12411 6490 12412 6491 12412 6489 12412 6492 12413 6491 12413 6490 12413 6492 12414 6493 12414 6491 12414 6492 12415 6494 12415 6493 12415 6495 12416 6494 12416 6492 12416 6495 12417 6496 12417 6494 12417 6495 12418 6497 12418 6496 12418 6498 12419 6497 12419 6495 12419 6498 12420 6499 12420 6497 12420 6498 12421 6500 12421 6499 12421 6501 12422 6500 12422 6498 12422 6501 12423 6502 12423 6500 12423 6503 12424 6502 12424 6501 12424 6503 12425 6504 12425 6502 12425 6503 12426 6505 12426 6504 12426 6506 12427 6505 12427 6503 12427 6506 12428 6507 12428 6505 12428 6508 12429 6509 12429 6506 12429 6506 12430 6509 12430 6507 12430 6508 12431 6510 12431 6509 12431 6511 12432 6510 12432 6508 12432 6511 12433 6512 12433 6510 12433 6513 12434 6512 12434 6511 12434 6514 12435 6515 12435 6513 12435 6513 12436 6515 12436 6512 12436 6514 12437 6516 12437 6515 12437 6517 12438 6516 12438 6514 12438 6517 12439 6518 12439 6516 12439 6517 12440 6519 12440 6518 12440 6520 12441 6519 12441 6517 12441 6520 12442 6521 12442 6519 12442 6522 12443 6521 12443 6520 12443 6522 12444 6523 12444 6521 12444 6522 12445 6524 12445 6523 12445 6525 12446 6524 12446 6522 12446 6525 12447 6526 12447 6524 12447 6527 12448 6526 12448 6525 12448 6527 12449 6528 12449 6526 12449 6529 12450 6528 12450 6527 12450 6530 12451 6528 12451 6529 12451 6530 12452 6531 12452 6528 12452 6532 12453 6531 12453 6530 12453 6532 12454 6533 12454 6531 12454 6534 12455 6533 12455 6532 12455 6534 12456 6535 12456 6533 12456 6536 12457 6535 12457 6534 12457 6536 12458 6537 12458 6535 12458 6536 12459 6538 12459 6537 12459 6536 12460 6539 12460 6538 12460 6540 12461 6539 12461 6536 12461 6540 12462 6541 12462 6539 12462 6542 12463 6541 12463 6540 12463 6542 12464 6543 12464 6541 12464 6544 12465 6543 12465 6542 12465 6544 12466 6545 12466 6543 12466 6546 12467 6545 12467 6544 12467 6546 12468 6547 12468 6545 12468 6546 12469 6548 12469 6547 12469 6549 12470 6548 12470 6546 12470 6549 12471 6550 12471 6548 12471 6551 12472 6550 12472 6549 12472 6552 12473 6550 12473 6551 12473 6552 12474 6553 12474 6550 12474 6552 12475 6554 12475 6553 12475 6555 12476 6554 12476 6552 12476 6555 12477 6556 12477 6554 12477 6555 12478 6557 12478 6556 12478 6558 12479 6557 12479 6555 12479 6558 12480 6559 12480 6557 12480 6560 12481 6559 12481 6558 12481 6560 12482 6561 12482 6559 12482 6562 12483 6563 12483 6560 12483 6560 12484 6563 12484 6561 12484 6562 12485 6564 12485 6563 12485 6565 12486 6564 12486 6562 12486 6565 12487 6566 12487 6564 12487 6567 12488 6566 12488 6565 12488 6567 12489 6568 12489 6566 12489 6567 12490 6569 12490 6568 12490 6570 12491 6569 12491 6567 12491 6570 12492 6571 12492 6569 12492 6572 12493 6571 12493 6570 12493 6572 12494 6573 12494 6571 12494 6572 12495 6574 12495 6573 12495 6575 12496 6574 12496 6572 12496 6575 12497 6576 12497 6574 12497 6575 12498 6577 12498 6576 12498 6578 12499 6577 12499 6575 12499 6578 12500 6579 12500 6577 12500 6578 12501 6580 12501 6579 12501 6581 12502 6580 12502 6578 12502 6581 12503 6582 12503 6580 12503 6581 12504 6583 12504 6582 12504 6584 12505 6583 12505 6581 12505 6584 12506 6585 12506 6583 12506 6584 12507 6586 12507 6585 12507 6587 12508 6586 12508 6584 12508 6587 12509 6588 12509 6586 12509 6589 12510 6588 12510 6587 12510 6590 12511 6588 12511 6589 12511 6590 12512 6591 12512 6588 12512 6590 12513 6592 12513 6591 12513 6593 12514 6592 12514 6590 12514 6593 12515 6594 12515 6592 12515 6595 12516 6594 12516 6593 12516 6595 12517 6596 12517 6594 12517 6597 12518 6596 12518 6595 12518 6597 12519 6598 12519 6596 12519 6599 12520 6598 12520 6597 12520 6599 12521 6600 12521 6598 12521 6601 12522 6600 12522 6599 12522 6601 12523 6602 12523 6600 12523 6601 12524 6603 12524 6602 12524 6604 12525 6603 12525 6601 12525 6604 12526 6605 12526 6603 12526 6606 12527 6605 12527 6604 12527 6606 12528 6607 12528 6605 12528 6608 12529 6607 12529 6606 12529 6608 12530 6609 12530 6607 12530 6610 12531 6609 12531 6608 12531 6610 12532 6611 12532 6609 12532 6612 12533 6611 12533 6610 12533 6612 12534 6613 12534 6611 12534 6612 12535 6614 12535 6613 12535 6615 12536 6614 12536 6612 12536 6615 12537 6616 12537 6614 12537 6617 12538 6616 12538 6615 12538 6617 12539 6618 12539 6616 12539 6617 12540 6619 12540 6618 12540 6620 12541 6619 12541 6617 12541 6620 12542 6621 12542 6619 12542 6622 12543 6621 12543 6620 12543 6622 12544 6623 12544 6621 12544 6624 12545 6623 12545 6622 12545 6624 12546 6625 12546 6623 12546 6626 12547 6625 12547 6624 12547 6626 12548 6627 12548 6625 12548 6628 12549 6627 12549 6626 12549 6629 12550 6627 12550 6628 12550 6629 12551 6630 12551 6627 12551 6629 12552 6631 12552 6630 12552 6632 12553 6631 12553 6629 12553 6632 12554 6633 12554 6631 12554 6634 12555 6633 12555 6632 12555 6634 12556 6635 12556 6633 12556 6636 12557 6635 12557 6634 12557 6637 12558 6638 12558 6636 12558 6636 12559 6638 12559 6635 12559 6637 12560 6639 12560 6638 12560 6640 12561 6639 12561 6637 12561 6640 12562 6641 12562 6639 12562 6642 12563 6641 12563 6640 12563 6642 12564 6643 12564 6641 12564 6642 12565 6644 12565 6643 12565 6645 12566 6644 12566 6642 12566 6645 12567 6646 12567 6644 12567 6647 12568 6646 12568 6645 12568 6647 12569 6648 12569 6646 12569 6647 12570 6649 12570 6648 12570 6650 12571 6649 12571 6647 12571 6650 12572 6651 12572 6649 12572 6652 12573 6651 12573 6650 12573 6652 12574 6653 12574 6651 12574 6654 12575 6653 12575 6652 12575 6654 12576 6655 12576 6653 12576 6654 12577 6656 12577 6655 12577 6657 12578 6656 12578 6654 12578 6658 12579 6656 12579 6657 12579 6658 12580 6659 12580 6656 12580 6658 12581 6660 12581 6659 12581 6661 12582 6660 12582 6658 12582 6661 12583 6662 12583 6660 12583 6663 12584 6662 12584 6661 12584 6663 12585 6664 12585 6662 12585 6663 12586 6665 12586 6664 12586 6666 12587 6665 12587 6663 12587 6666 12588 6667 12588 6665 12588 6668 12589 6667 12589 6666 12589 6668 12590 6669 12590 6667 12590 6670 12591 6669 12591 6668 12591 6670 12592 6671 12592 6669 12592 6670 12593 6672 12593 6671 12593 6673 12594 6672 12594 6670 12594 6673 12595 6674 12595 6672 12595 6675 12596 6674 12596 6673 12596 6675 12597 6676 12597 6674 12597 6675 12598 6677 12598 6676 12598 6678 12599 6677 12599 6675 12599 6678 12600 6679 12600 6677 12600 6680 12601 6679 12601 6678 12601 6680 12602 6681 12602 6679 12602 6682 12603 6681 12603 6680 12603 6682 12604 6683 12604 6681 12604 6684 12605 6683 12605 6682 12605 6684 12606 6685 12606 6683 12606 6684 12607 6686 12607 6685 12607 6687 12608 6686 12608 6684 12608 6687 12609 6688 12609 6686 12609 6689 12610 6688 12610 6687 12610 6689 12611 6690 12611 6688 12611 6689 12612 6691 12612 6690 12612 6692 12613 6691 12613 6689 12613 6692 12614 6693 12614 6691 12614 6694 12615 6693 12615 6692 12615 6694 12616 6695 12616 6693 12616 6696 12617 6695 12617 6694 12617 6696 12618 6697 12618 6695 12618 6698 12619 6697 12619 6696 12619 6698 12620 6699 12620 6697 12620 6700 12621 6699 12621 6698 12621 6700 12622 6701 12622 6699 12622 6702 12623 6701 12623 6700 12623 6702 12624 6703 12624 6701 12624 6704 12625 6703 12625 6702 12625 6704 12626 6705 12626 6703 12626 6706 12627 6705 12627 6704 12627 6706 12628 6707 12628 6705 12628 6706 12629 6708 12629 6707 12629 6709 12630 6708 12630 6706 12630 6709 12631 6710 12631 6708 12631 6711 12632 6710 12632 6709 12632 6711 12633 6712 12633 6710 12633 6713 12634 6712 12634 6711 12634 6713 12635 6714 12635 6712 12635 6713 12636 6715 12636 6714 12636 6716 12637 6715 12637 6713 12637 6716 12638 6717 12638 6715 12638 6716 12639 6718 12639 6717 12639 6719 12640 6718 12640 6716 12640 6720 12641 6721 12641 6719 12641 6719 12642 6721 12642 6718 12642 6720 12643 6722 12643 6721 12643 6723 12644 6722 12644 6720 12644 6723 12645 6724 12645 6722 12645 6723 12646 6725 12646 6724 12646 6726 12647 6725 12647 6723 12647 6726 12648 6727 12648 6725 12648 6728 12649 6727 12649 6726 12649 6728 12650 6729 12650 6727 12650 6728 12651 6730 12651 6729 12651 6731 12652 6730 12652 6728 12652 6731 12653 6732 12653 6730 12653 6733 12654 6732 12654 6731 12654 6734 12655 6732 12655 6733 12655 6734 12656 6735 12656 6732 12656 6736 12657 6735 12657 6734 12657 6736 12658 6737 12658 6735 12658 6736 12659 6738 12659 6737 12659 6739 12660 6738 12660 6736 12660 6739 12661 6740 12661 6738 12661 6741 12662 6740 12662 6739 12662 6741 12663 6742 12663 6740 12663 6743 12664 6742 12664 6741 12664 6743 12665 6744 12665 6742 12665 6743 12666 6745 12666 6744 12666 6746 12667 6745 12667 6743 12667 6746 12668 6747 12668 6745 12668 6748 12669 6747 12669 6746 12669 6748 12670 6749 12670 6747 12670 6748 12671 6750 12671 6749 12671 6751 12672 6750 12672 6748 12672 6751 12673 6752 12673 6750 12673 6753 12674 6752 12674 6751 12674 6753 12675 6754 12675 6752 12675 6753 12676 6755 12676 6754 12676 6756 12677 6755 12677 6753 12677 6756 12678 6757 12678 6755 12678 6758 12679 6757 12679 6756 12679 6758 12680 6759 12680 6757 12680 6760 12681 6759 12681 6758 12681 6760 12682 6761 12682 6759 12682 6760 12683 6762 12683 6761 12683 6763 12684 6762 12684 6760 12684 6763 12685 6764 12685 6762 12685 6763 12686 6765 12686 6764 12686 6763 12687 6766 12687 6765 12687 6767 12688 6766 12688 6763 12688 6767 12689 6768 12689 6766 12689 6769 12690 6768 12690 6767 12690 6769 12691 6770 12691 6768 12691 6771 12692 6772 12692 6769 12692 6769 12693 6772 12693 6770 12693 6773 12694 6774 12694 6771 12694 6771 12695 6774 12695 6772 12695 6773 12696 6775 12696 6774 12696 6776 12697 6775 12697 6773 12697 6776 12698 6777 12698 6775 12698 6778 12699 6777 12699 6776 12699 6778 12700 6779 12700 6777 12700 6780 12701 6779 12701 6778 12701 6780 12702 6781 12702 6779 12702 6780 12703 6782 12703 6781 12703 6783 12704 6782 12704 6780 12704 6783 12705 6784 12705 6782 12705 6785 12706 6784 12706 6783 12706 6785 12707 6786 12707 6784 12707 6785 12708 6787 12708 6786 12708 6788 12709 6789 12709 6785 12709 6785 12710 6789 12710 6787 12710 6788 12711 6790 12711 6789 12711 6791 12712 6790 12712 6788 12712 6791 12713 6792 12713 6790 12713 6793 12714 6792 12714 6791 12714 6793 12715 6794 12715 6792 12715 6795 12716 6796 12716 6793 12716 6793 12717 6796 12717 6794 12717 6795 12718 6797 12718 6796 12718 6798 12719 6797 12719 6795 12719 6798 12720 6799 12720 6797 12720 6800 12721 6799 12721 6798 12721 6800 12722 6801 12722 6799 12722 6802 12723 6801 12723 6800 12723 6802 12724 6803 12724 6801 12724 6802 12725 7029 12725 6803 12725 6804 12726 7029 12726 6802 12726 6804 12727 7026 12727 7029 12727 6804 12728 6207 12728 7026 12728 6805 12729 6207 12729 6804 12729 6805 12730 6204 12730 6207 12730 6806 12731 6204 12731 6805 12731 6200 12732 6204 12732 6806 12732 6807 12733 6221 12733 6219 12733 6224 12734 6221 12734 6807 12734 6808 12735 6226 12735 6224 12735 6229 12736 6226 12736 6808 12736 6809 12737 6229 12737 6808 12737 6231 12738 6229 12738 6809 12738 6810 12739 6231 12739 6809 12739 6811 12740 6231 12740 6810 12740 6234 12741 6231 12741 6811 12741 6812 12742 6234 12742 6811 12742 6236 12743 6234 12743 6812 12743 6239 12744 6236 12744 6812 12744 6243 12745 6241 12745 6813 12745 6814 12746 6243 12746 6813 12746 6815 12747 6243 12747 6814 12747 6246 12748 6243 12748 6815 12748 6248 12749 6246 12749 6815 12749 6816 12750 6248 12750 6815 12750 6250 12751 6248 12751 6816 12751 6817 12752 6250 12752 6816 12752 6253 12753 6250 12753 6817 12753 6255 12754 6253 12754 6818 12754 6257 12755 6255 12755 6818 12755 6819 12756 6257 12756 6818 12756 6260 12757 6257 12757 6819 12757 6820 12758 6262 12758 6260 12758 6264 12759 6262 12759 6820 12759 6821 12760 6264 12760 6820 12760 6267 12761 6264 12761 6821 12761 6822 12762 6267 12762 6821 12762 6269 12763 6267 12763 6822 12763 6271 12764 6269 12764 6822 12764 6275 12765 6273 12765 6823 12765 6278 12766 6275 12766 6823 12766 6824 12767 6278 12767 6823 12767 6280 12768 6278 12768 6824 12768 6287 12769 6284 12769 6825 12769 6826 12770 6287 12770 6825 12770 6289 12771 6287 12771 6826 12771 6292 12772 6289 12772 6826 12772 6293 12773 6292 12773 6827 12773 6296 12774 6293 12774 6827 12774 6828 12775 6298 12775 6296 12775 6300 12776 6298 12776 6828 12776 6829 12777 6300 12777 6828 12777 6302 12778 6300 12778 6829 12778 6304 12779 6302 12779 6829 12779 6305 12780 6304 12780 6830 12780 6831 12781 6305 12781 6830 12781 6308 12782 6305 12782 6831 12782 6832 12783 6308 12783 6831 12783 6310 12784 6308 12784 6832 12784 6313 12785 6310 12785 6832 12785 6314 12786 6313 12786 6833 12786 6834 12787 6314 12787 6833 12787 6317 12788 6314 12788 6834 12788 6835 12789 6317 12789 6834 12789 6320 12790 6317 12790 6835 12790 6836 12791 6320 12791 6835 12791 6321 12792 6320 12792 6836 12792 6837 12793 6321 12793 6836 12793 6325 12794 6321 12794 6837 12794 6838 12795 6325 12795 6837 12795 6327 12796 6325 12796 6838 12796 6839 12797 6327 12797 6838 12797 6840 12798 6327 12798 6839 12798 6330 12799 6327 12799 6840 12799 6332 12800 6330 12800 6840 12800 6841 12801 6332 12801 6840 12801 6842 12802 6332 12802 6841 12802 6335 12803 6332 12803 6842 12803 6843 12804 6335 12804 6842 12804 6337 12805 6335 12805 6843 12805 6844 12806 6337 12806 6843 12806 6339 12807 6337 12807 6844 12807 6340 12808 6339 12808 6844 12808 6343 12809 6340 12809 6845 12809 6846 12810 6343 12810 6845 12810 6345 12811 6343 12811 6846 12811 6847 12812 6345 12812 6846 12812 6848 12813 6345 12813 6847 12813 6348 12814 6345 12814 6848 12814 6350 12815 6348 12815 6848 12815 6849 12816 6354 12816 6351 12816 6357 12817 6354 12817 6849 12817 6850 12818 6357 12818 6849 12818 6359 12819 6357 12819 6850 12819 6851 12820 6359 12820 6850 12820 6362 12821 6359 12821 6851 12821 6852 12822 6362 12822 6851 12822 6364 12823 6362 12823 6852 12823 6853 12824 6364 12824 6852 12824 6367 12825 6364 12825 6853 12825 6854 12826 6367 12826 6853 12826 6370 12827 6367 12827 6854 12827 6855 12828 6370 12828 6854 12828 6372 12829 6370 12829 6855 12829 6374 12830 6372 12830 6855 12830 6376 12831 6374 12831 6856 12831 6857 12832 6376 12832 6856 12832 6379 12833 6376 12833 6857 12833 6858 12834 6379 12834 6857 12834 6381 12835 6379 12835 6858 12835 6382 12836 6381 12836 6858 12836 6859 12837 6382 12837 6858 12837 6860 12838 6382 12838 6859 12838 6385 12839 6382 12839 6860 12839 6861 12840 6385 12840 6860 12840 6388 12841 6385 12841 6861 12841 6862 12842 6388 12842 6861 12842 6391 12843 6388 12843 6862 12843 6863 12844 6393 12844 6391 12844 6395 12845 6393 12845 6863 12845 6864 12846 6397 12846 6395 12846 6399 12847 6397 12847 6864 12847 6865 12848 6399 12848 6864 12848 6402 12849 6399 12849 6865 12849 6404 12850 6402 12850 6865 12850 6406 12851 6404 12851 6866 12851 6867 12852 6406 12852 6866 12852 6408 12853 6406 12853 6867 12853 6410 12854 6408 12854 6867 12854 6416 12855 6414 12855 6868 12855 6419 12856 6416 12856 6868 12856 6869 12857 6423 12857 6420 12857 6426 12858 6423 12858 6869 12858 6427 12859 6426 12859 6870 12859 6430 12860 6427 12860 6870 12860 6433 12861 6430 12861 6871 12861 6872 12862 6433 12862 6871 12862 6435 12863 6433 12863 6872 12863 6873 12864 6435 12864 6872 12864 6438 12865 6435 12865 6873 12865 6874 12866 6441 12866 6438 12866 6443 12867 6441 12867 6874 12867 6449 12868 6447 12868 6875 12868 6876 12869 6449 12869 6875 12869 6452 12870 6449 12870 6876 12870 6454 12871 6452 12871 6876 12871 6877 12872 6454 12872 6876 12872 6456 12873 6454 12873 6877 12873 6878 12874 6456 12874 6877 12874 6458 12875 6456 12875 6878 12875 6879 12876 6458 12876 6878 12876 6460 12877 6879 12877 6880 12877 6460 12878 6458 12878 6879 12878 6462 12879 6460 12879 6880 12879 6881 12880 6462 12880 6880 12880 6464 12881 6462 12881 6881 12881 6467 12882 6464 12882 6881 12882 6882 12883 6469 12883 6467 12883 6472 12884 6469 12884 6882 12884 6883 12885 6472 12885 6882 12885 6475 12886 6472 12886 6883 12886 6884 12887 6477 12887 6475 12887 6885 12888 6477 12888 6884 12888 6480 12889 6477 12889 6885 12889 6482 12890 6480 12890 6885 12890 6485 12891 6482 12891 6886 12891 6887 12892 6485 12892 6886 12892 6488 12893 6485 12893 6887 12893 6888 12894 6488 12894 6887 12894 6490 12895 6488 12895 6888 12895 6889 12896 6490 12896 6888 12896 6492 12897 6490 12897 6889 12897 6890 12898 6492 12898 6889 12898 6495 12899 6492 12899 6890 12899 6891 12900 6495 12900 6890 12900 6498 12901 6495 12901 6891 12901 6892 12902 6498 12902 6891 12902 6501 12903 6498 12903 6892 12903 6893 12904 6501 12904 6892 12904 6503 12905 6501 12905 6893 12905 6894 12906 6503 12906 6893 12906 6506 12907 6503 12907 6894 12907 6895 12908 6506 12908 6894 12908 6508 12909 6506 12909 6895 12909 6896 12910 6508 12910 6895 12910 6511 12911 6508 12911 6896 12911 6897 12912 6511 12912 6896 12912 6513 12913 6511 12913 6897 12913 6898 12914 6513 12914 6897 12914 6514 12915 6513 12915 6898 12915 6899 12916 6514 12916 6898 12916 6517 12917 6514 12917 6899 12917 6520 12918 6517 12918 6899 12918 6522 12919 6520 12919 6900 12919 6901 12920 6522 12920 6900 12920 6525 12921 6522 12921 6901 12921 6902 12922 6525 12922 6901 12922 6527 12923 6525 12923 6902 12923 6529 12924 6527 12924 6902 12924 6536 12925 6534 12925 6903 12925 6904 12926 6536 12926 6903 12926 6540 12927 6536 12927 6904 12927 6905 12928 6540 12928 6904 12928 6906 12929 6540 12929 6905 12929 6542 12930 6540 12930 6906 12930 6544 12931 6542 12931 6906 12931 6907 12932 6544 12932 6906 12932 6546 12933 6544 12933 6907 12933 6555 12934 6552 12934 6908 12934 6909 12935 6555 12935 6908 12935 6558 12936 6555 12936 6909 12936 6910 12937 6558 12937 6909 12937 6560 12938 6558 12938 6910 12938 6911 12939 6560 12939 6910 12939 6562 12940 6560 12940 6911 12940 6912 12941 6562 12941 6911 12941 6565 12942 6562 12942 6912 12942 6913 12943 6565 12943 6912 12943 6567 12944 6565 12944 6913 12944 6914 12945 6567 12945 6913 12945 6570 12946 6567 12946 6914 12946 6915 12947 6570 12947 6914 12947 6916 12948 6570 12948 6915 12948 6572 12949 6570 12949 6916 12949 6917 12950 6572 12950 6916 12950 6575 12951 6572 12951 6917 12951 6918 12952 6575 12952 6917 12952 6578 12953 6575 12953 6918 12953 6919 12954 6578 12954 6918 12954 6581 12955 6578 12955 6919 12955 6584 12956 6581 12956 6919 12956 6584 12957 6919 12957 6920 12957 6587 12958 6584 12958 6920 12958 6921 12959 6587 12959 6920 12959 6589 12960 6587 12960 6921 12960 6590 12961 6589 12961 6921 12961 6593 12962 6590 12962 6922 12962 6923 12963 6593 12963 6922 12963 6595 12964 6593 12964 6923 12964 6597 12965 6595 12965 6923 12965 6924 12966 6597 12966 6923 12966 6599 12967 6597 12967 6924 12967 6925 12968 6599 12968 6924 12968 6601 12969 6599 12969 6925 12969 6604 12970 6601 12970 6925 12970 6926 12971 6604 12971 6925 12971 6606 12972 6604 12972 6926 12972 6927 12973 6606 12973 6926 12973 6608 12974 6606 12974 6927 12974 6928 12975 6608 12975 6927 12975 6610 12976 6608 12976 6928 12976 6929 12977 6610 12977 6928 12977 6612 12978 6610 12978 6929 12978 6930 12979 6612 12979 6929 12979 6615 12980 6612 12980 6930 12980 6931 12981 6615 12981 6930 12981 6617 12982 6615 12982 6931 12982 6932 12983 6617 12983 6931 12983 6620 12984 6617 12984 6932 12984 6622 12985 6620 12985 6932 12985 6933 12986 6622 12986 6932 12986 6624 12987 6622 12987 6933 12987 6934 12988 6624 12988 6933 12988 6626 12989 6624 12989 6934 12989 6628 12990 6626 12990 6934 12990 6632 12991 6629 12991 6935 12991 6936 12992 6632 12992 6935 12992 6634 12993 6632 12993 6936 12993 6636 12994 6634 12994 6936 12994 6640 12995 6637 12995 6937 12995 6938 12996 6640 12996 6937 12996 6642 12997 6640 12997 6938 12997 6645 12998 6642 12998 6938 12998 6939 12999 6645 12999 6938 12999 6647 13000 6645 13000 6939 13000 6940 13001 6652 13001 6650 13001 6654 13002 6652 13002 6940 13002 6941 13003 6654 13003 6940 13003 6657 13004 6654 13004 6941 13004 6661 13005 6658 13005 6942 13005 6943 13006 6661 13006 6942 13006 6663 13007 6661 13007 6943 13007 6944 13008 6663 13008 6943 13008 6666 13009 6663 13009 6944 13009 6668 13010 6666 13010 6944 13010 6945 13011 6668 13011 6944 13011 6670 13012 6668 13012 6945 13012 6946 13013 6670 13013 6945 13013 6673 13014 6670 13014 6946 13014 6947 13015 6673 13015 6946 13015 6675 13016 6673 13016 6947 13016 6948 13017 6675 13017 6947 13017 6949 13018 6675 13018 6948 13018 6678 13019 6675 13019 6949 13019 6950 13020 6678 13020 6949 13020 6680 13021 6678 13021 6950 13021 6951 13022 6680 13022 6950 13022 6682 13023 6680 13023 6951 13023 6952 13024 6684 13024 6682 13024 6687 13025 6684 13025 6952 13025 6953 13026 6687 13026 6952 13026 6689 13027 6687 13027 6953 13027 6954 13028 6689 13028 6953 13028 6692 13029 6689 13029 6954 13029 6955 13030 6704 13030 6702 13030 6706 13031 6704 13031 6955 13031 6956 13032 6706 13032 6955 13032 6709 13033 6706 13033 6956 13033 6711 13034 6709 13034 6956 13034 6713 13035 6711 13035 6957 13035 6958 13036 6713 13036 6957 13036 6716 13037 6713 13037 6958 13037 6959 13038 6716 13038 6958 13038 6719 13039 6716 13039 6959 13039 6720 13040 6719 13040 6959 13040 6720 13041 6959 13041 6960 13041 6723 13042 6720 13042 6960 13042 6726 13043 6723 13043 6961 13043 6962 13044 6726 13044 6961 13044 6728 13045 6726 13045 6962 13045 6963 13046 6728 13046 6962 13046 6731 13047 6728 13047 6963 13047 6964 13048 6731 13048 6963 13048 6733 13049 6731 13049 6964 13049 6739 13050 6736 13050 6965 13050 6966 13051 6739 13051 6965 13051 6741 13052 6739 13052 6966 13052 6967 13053 6741 13053 6966 13053 6743 13054 6741 13054 6967 13054 6968 13055 6743 13055 6967 13055 6969 13056 6743 13056 6968 13056 6746 13057 6743 13057 6969 13057 6970 13058 6746 13058 6969 13058 6748 13059 6746 13059 6970 13059 6971 13060 6748 13060 6970 13060 6751 13061 6748 13061 6971 13061 6972 13062 6751 13062 6971 13062 6753 13063 6751 13063 6972 13063 6973 13064 6753 13064 6972 13064 6756 13065 6753 13065 6973 13065 6974 13066 6756 13066 6973 13066 6758 13067 6756 13067 6974 13067 6760 13068 6758 13068 6974 13068 6975 13069 6760 13069 6974 13069 6763 13070 6760 13070 6975 13070 6976 13071 6763 13071 6975 13071 6763 13072 6976 13072 6977 13072 6767 13073 6763 13073 6977 13073 6978 13074 6767 13074 6977 13074 6769 13075 6767 13075 6978 13075 6979 13076 6769 13076 6978 13076 6771 13077 6769 13077 6979 13077 6773 13078 6771 13078 6979 13078 6778 13079 6776 13079 6980 13079 6780 13080 6778 13080 6980 13080 6981 13081 6780 13081 6980 13081 6783 13082 6780 13082 6981 13082 6982 13083 6783 13083 6981 13083 6785 13084 6783 13084 6982 13084 6983 13085 6785 13085 6982 13085 6984 13086 6785 13086 6983 13086 6788 13087 6785 13087 6984 13087 6791 13088 6788 13088 6984 13088 6985 13089 6791 13089 6984 13089 6793 13090 6791 13090 6985 13090 6986 13091 6793 13091 6985 13091 6795 13092 6793 13092 6986 13092 6798 13093 6795 13093 6986 13093 6800 13094 6798 13094 6987 13094 6802 13095 6800 13095 6987 13095 6988 13096 6802 13096 6987 13096 6804 13097 6802 13097 6988 13097 6805 13098 6804 13098 6988 13098 6806 13099 6805 13099 6989 13099 6990 13100 6806 13100 6989 13100 6200 13101 6806 13101 6990 13101 6991 13102 6200 13102 6990 13102 6198 13103 6200 13103 6991 13103 6194 13104 6198 13104 6991 13104 6993 13105 6224 13105 6807 13105 6993 13106 6808 13106 6224 13106 6994 13107 6808 13107 6993 13107 6994 13108 6809 13108 6808 13108 6992 13109 6809 13109 6994 13109 6992 13110 6810 13110 6809 13110 6995 13111 6810 13111 6992 13111 6995 13112 6811 13112 6810 13112 6208 13113 6811 13113 6995 13113 6209 13114 6811 13114 6208 13114 6209 13115 6812 13115 6811 13115 6210 13116 6812 13116 6209 13116 6213 13117 6812 13117 6210 13117 6213 13118 6239 13118 6812 13118 6215 13119 6239 13119 6213 13119 6215 13120 6241 13120 6239 13120 6217 13121 6241 13121 6215 13121 6217 13122 6813 13122 6241 13122 6218 13123 6813 13123 6217 13123 6218 13124 6814 13124 6813 13124 6220 13125 6814 13125 6218 13125 6220 13126 6815 13126 6814 13126 6222 13127 6815 13127 6220 13127 6223 13128 6815 13128 6222 13128 6223 13129 6816 13129 6815 13129 6225 13130 6816 13130 6223 13130 6225 13131 6817 13131 6816 13131 6227 13132 6817 13132 6225 13132 6228 13133 6817 13133 6227 13133 6228 13134 6253 13134 6817 13134 6230 13135 6253 13135 6228 13135 6230 13136 6818 13136 6253 13136 6232 13137 6818 13137 6230 13137 6232 13138 6819 13138 6818 13138 6233 13139 6819 13139 6232 13139 6235 13140 6260 13140 6233 13140 6233 13141 6260 13141 6819 13141 6235 13142 6820 13142 6260 13142 6237 13143 6820 13143 6235 13143 6238 13144 6820 13144 6237 13144 6238 13145 6821 13145 6820 13145 6240 13146 6821 13146 6238 13146 6240 13147 6822 13147 6821 13147 6242 13148 6822 13148 6240 13148 6244 13149 6822 13149 6242 13149 6244 13150 6271 13150 6822 13150 6247 13151 6273 13151 6244 13151 6244 13152 6273 13152 6271 13152 6249 13153 6273 13153 6247 13153 6249 13154 6823 13154 6273 13154 6251 13155 6823 13155 6249 13155 6251 13156 6824 13156 6823 13156 6996 13157 6824 13157 6251 13157 6254 13158 6824 13158 6996 13158 6254 13159 6280 13159 6824 13159 6256 13160 6280 13160 6254 13160 6256 13161 6282 13161 6280 13161 6258 13162 6282 13162 6256 13162 6258 13163 6284 13163 6282 13163 6259 13164 6825 13164 6258 13164 6258 13165 6825 13165 6284 13165 6261 13166 6826 13166 6259 13166 6259 13167 6826 13167 6825 13167 6997 13168 6826 13168 6261 13168 6997 13169 6292 13169 6826 13169 6265 13170 6292 13170 6997 13170 6265 13171 6827 13171 6292 13171 6266 13172 6827 13172 6265 13172 6268 13173 6827 13173 6266 13173 6268 13174 6296 13174 6827 13174 6270 13175 6296 13175 6268 13175 6270 13176 6828 13176 6296 13176 6272 13177 6828 13177 6270 13177 6274 13178 6828 13178 6272 13178 6274 13179 6829 13179 6828 13179 6276 13180 6829 13180 6274 13180 6276 13181 6304 13181 6829 13181 6277 13182 6304 13182 6276 13182 6277 13183 6830 13183 6304 13183 6279 13184 6830 13184 6277 13184 6279 13185 6831 13185 6830 13185 6281 13186 6831 13186 6279 13186 6281 13187 6832 13187 6831 13187 6283 13188 6832 13188 6281 13188 6285 13189 6832 13189 6283 13189 6285 13190 6313 13190 6832 13190 6286 13191 6313 13191 6285 13191 6286 13192 6833 13192 6313 13192 6288 13193 6833 13193 6286 13193 6290 13194 6833 13194 6288 13194 6290 13195 6834 13195 6833 13195 6291 13196 6834 13196 6290 13196 6291 13197 6835 13197 6834 13197 6294 13198 6835 13198 6291 13198 6294 13199 6836 13199 6835 13199 6295 13200 6836 13200 6294 13200 6297 13201 6836 13201 6295 13201 6297 13202 6837 13202 6836 13202 6299 13203 6837 13203 6297 13203 6299 13204 6838 13204 6837 13204 6301 13205 6838 13205 6299 13205 6998 13206 6838 13206 6301 13206 6998 13207 6839 13207 6838 13207 6303 13208 6839 13208 6998 13208 6303 13209 6840 13209 6839 13209 6306 13210 6840 13210 6303 13210 6307 13211 6840 13211 6306 13211 6307 13212 6841 13212 6840 13212 6309 13213 6841 13213 6307 13213 6309 13214 6842 13214 6841 13214 6311 13215 6842 13215 6309 13215 6311 13216 6843 13216 6842 13216 6312 13217 6843 13217 6311 13217 6312 13218 6844 13218 6843 13218 6315 13219 6844 13219 6312 13219 6316 13220 6844 13220 6315 13220 6316 13221 6340 13221 6844 13221 6318 13222 6340 13222 6316 13222 6318 13223 6845 13223 6340 13223 6318 13224 6846 13224 6845 13224 6319 13225 6846 13225 6318 13225 6322 13226 6846 13226 6319 13226 6322 13227 6847 13227 6846 13227 6323 13228 6847 13228 6322 13228 6323 13229 6848 13229 6847 13229 6324 13230 6848 13230 6323 13230 6326 13231 6848 13231 6324 13231 6326 13232 6350 13232 6848 13232 6328 13233 6350 13233 6326 13233 6328 13234 6351 13234 6350 13234 6329 13235 6351 13235 6328 13235 6329 13236 6849 13236 6351 13236 6331 13237 6849 13237 6329 13237 6333 13238 6849 13238 6331 13238 6333 13239 6850 13239 6849 13239 6334 13240 6850 13240 6333 13240 6334 13241 6851 13241 6850 13241 6999 13242 6851 13242 6334 13242 6336 13243 6851 13243 6999 13243 6336 13244 6852 13244 6851 13244 6338 13245 6852 13245 6336 13245 6341 13246 6852 13246 6338 13246 6341 13247 6853 13247 6852 13247 7000 13248 6853 13248 6341 13248 7000 13249 6854 13249 6853 13249 6342 13250 6854 13250 7000 13250 6344 13251 6854 13251 6342 13251 6344 13252 6855 13252 6854 13252 6346 13253 6855 13253 6344 13253 6346 13254 6374 13254 6855 13254 6347 13255 6374 13255 6346 13255 6347 13256 6856 13256 6374 13256 6349 13257 6856 13257 6347 13257 6349 13258 6857 13258 6856 13258 6352 13259 6857 13259 6349 13259 6352 13260 6858 13260 6857 13260 6353 13261 6858 13261 6352 13261 6356 13262 6858 13262 6353 13262 6356 13263 6859 13263 6858 13263 6358 13264 6859 13264 6356 13264 6358 13265 6860 13265 6859 13265 6360 13266 6860 13266 6358 13266 6360 13267 6861 13267 6860 13267 6361 13268 6861 13268 6360 13268 6361 13269 6862 13269 6861 13269 6363 13270 6862 13270 6361 13270 6365 13271 6862 13271 6363 13271 6365 13272 6391 13272 6862 13272 6366 13273 6391 13273 6365 13273 6366 13274 6863 13274 6391 13274 6368 13275 6863 13275 6366 13275 6369 13276 6863 13276 6368 13276 6369 13277 6395 13277 6863 13277 6371 13278 6395 13278 6369 13278 6371 13279 6864 13279 6395 13279 6375 13280 6864 13280 6371 13280 6375 13281 6865 13281 6864 13281 6377 13282 6865 13282 6375 13282 6378 13283 6865 13283 6377 13283 6378 13284 6404 13284 6865 13284 6380 13285 6404 13285 6378 13285 6380 13286 6866 13286 6404 13286 6380 13287 6867 13287 6866 13287 6383 13288 6867 13288 6380 13288 6384 13289 6867 13289 6383 13289 6384 13290 6410 13290 6867 13290 6386 13291 6410 13291 6384 13291 6386 13292 6412 13292 6410 13292 6387 13293 6412 13293 6386 13293 6389 13294 6412 13294 6387 13294 6389 13295 6414 13295 6412 13295 6390 13296 6414 13296 6389 13296 6390 13297 6868 13297 6414 13297 6392 13298 6868 13298 6390 13298 6392 13299 6419 13299 6868 13299 6394 13300 6419 13300 6392 13300 6394 13301 6420 13301 6419 13301 6396 13302 6420 13302 6394 13302 6396 13303 6869 13303 6420 13303 6398 13304 6869 13304 6396 13304 6398 13305 6426 13305 6869 13305 6400 13306 6426 13306 6398 13306 6400 13307 6870 13307 6426 13307 6401 13308 6870 13308 6400 13308 6401 13309 6430 13309 6870 13309 7001 13310 6430 13310 6401 13310 7001 13311 6871 13311 6430 13311 6405 13312 6871 13312 7001 13312 6405 13313 6872 13313 6871 13313 6407 13314 6872 13314 6405 13314 6409 13315 6872 13315 6407 13315 6409 13316 6873 13316 6872 13316 6411 13317 6873 13317 6409 13317 6411 13318 6438 13318 6873 13318 6413 13319 6438 13319 6411 13319 6413 13320 6874 13320 6438 13320 7002 13321 6874 13321 6413 13321 7002 13322 6443 13322 6874 13322 6415 13323 6443 13323 7002 13323 6418 13324 6445 13324 6415 13324 6415 13325 6445 13325 6443 13325 6421 13326 6447 13326 6418 13326 6418 13327 6447 13327 6445 13327 6421 13328 6875 13328 6447 13328 6422 13329 6875 13329 6421 13329 6422 13330 6876 13330 6875 13330 6424 13331 6876 13331 6422 13331 6425 13332 6876 13332 6424 13332 6425 13333 6877 13333 6876 13333 6428 13334 6877 13334 6425 13334 6429 13335 6878 13335 6428 13335 6428 13336 6878 13336 6877 13336 6431 13337 6878 13337 6429 13337 6431 13338 6879 13338 6878 13338 6432 13339 6879 13339 6431 13339 6434 13340 6880 13340 6432 13340 6432 13341 6880 13341 6879 13341 6436 13342 6880 13342 6434 13342 6436 13343 6881 13343 6880 13343 6437 13344 6881 13344 6436 13344 6439 13345 6881 13345 6437 13345 6439 13346 6467 13346 6881 13346 6440 13347 6467 13347 6439 13347 6442 13348 6467 13348 6440 13348 6442 13349 6882 13349 6467 13349 6444 13350 6882 13350 6442 13350 6446 13351 6882 13351 6444 13351 6446 13352 6883 13352 6882 13352 7003 13353 6883 13353 6446 13353 7003 13354 6475 13354 6883 13354 6450 13355 6475 13355 7003 13355 6451 13356 6475 13356 6450 13356 6451 13357 6884 13357 6475 13357 6451 13358 6885 13358 6884 13358 6453 13359 6885 13359 6451 13359 6455 13360 6885 13360 6453 13360 6455 13361 6482 13361 6885 13361 6457 13362 6482 13362 6455 13362 6457 13363 6886 13363 6482 13363 6459 13364 6886 13364 6457 13364 6459 13365 6887 13365 6886 13365 6461 13366 6887 13366 6459 13366 6461 13367 6888 13367 6887 13367 6463 13368 6888 13368 6461 13368 6465 13369 6888 13369 6463 13369 6465 13370 6889 13370 6888 13370 6466 13371 6889 13371 6465 13371 6466 13372 6890 13372 6889 13372 6468 13373 6890 13373 6466 13373 6468 13374 6891 13374 6890 13374 6470 13375 6891 13375 6468 13375 6471 13376 6891 13376 6470 13376 6471 13377 6892 13377 6891 13377 6473 13378 6892 13378 6471 13378 6474 13379 6892 13379 6473 13379 6474 13380 6893 13380 6892 13380 6476 13381 6893 13381 6474 13381 6478 13382 6893 13382 6476 13382 6478 13383 6894 13383 6893 13383 6479 13384 6894 13384 6478 13384 6481 13385 6894 13385 6479 13385 6481 13386 6895 13386 6894 13386 6483 13387 6895 13387 6481 13387 6483 13388 6896 13388 6895 13388 6486 13389 6896 13389 6483 13389 6486 13390 6897 13390 6896 13390 6487 13391 6897 13391 6486 13391 6487 13392 6898 13392 6897 13392 6489 13393 6898 13393 6487 13393 6491 13394 6898 13394 6489 13394 6491 13395 6899 13395 6898 13395 6493 13396 6899 13396 6491 13396 6493 13397 6520 13397 6899 13397 6494 13398 6520 13398 6493 13398 6496 13399 6520 13399 6494 13399 6496 13400 6900 13400 6520 13400 6496 13401 6901 13401 6900 13401 6497 13402 6901 13402 6496 13402 7004 13403 6901 13403 6497 13403 7004 13404 6902 13404 6901 13404 6500 13405 6902 13405 7004 13405 6500 13406 6529 13406 6902 13406 6502 13407 6529 13407 6500 13407 6504 13408 6529 13408 6502 13408 6504 13409 6530 13409 6529 13409 6505 13410 6530 13410 6504 13410 6505 13411 6532 13411 6530 13411 6505 13412 6534 13412 6532 13412 6507 13413 6534 13413 6505 13413 6507 13414 6903 13414 6534 13414 6509 13415 6903 13415 6507 13415 6510 13416 6903 13416 6509 13416 6510 13417 6904 13417 6903 13417 6510 13418 6905 13418 6904 13418 6512 13419 6905 13419 6510 13419 6515 13420 6906 13420 6512 13420 6512 13421 6906 13421 6905 13421 6516 13422 6906 13422 6515 13422 6518 13423 6906 13423 6516 13423 6518 13424 6907 13424 6906 13424 6521 13425 6907 13425 6518 13425 6521 13426 6546 13426 6907 13426 6523 13427 6546 13427 6521 13427 6523 13428 6549 13428 6546 13428 6524 13429 6549 13429 6523 13429 6524 13430 6551 13430 6549 13430 6526 13431 6551 13431 6524 13431 6526 13432 6552 13432 6551 13432 6528 13433 6552 13433 6526 13433 6528 13434 6908 13434 6552 13434 6531 13435 6908 13435 6528 13435 6531 13436 6909 13436 6908 13436 6533 13437 6909 13437 6531 13437 6535 13438 6909 13438 6533 13438 6535 13439 6910 13439 6909 13439 6535 13440 6911 13440 6910 13440 6537 13441 6911 13441 6535 13441 6538 13442 6911 13442 6537 13442 6538 13443 6912 13443 6911 13443 6539 13444 6912 13444 6538 13444 6541 13445 6912 13445 6539 13445 6541 13446 6913 13446 6912 13446 6541 13447 6914 13447 6913 13447 6543 13448 6914 13448 6541 13448 6545 13449 6914 13449 6543 13449 6545 13450 6915 13450 6914 13450 6547 13451 6915 13451 6545 13451 6547 13452 6916 13452 6915 13452 6548 13453 6916 13453 6547 13453 6550 13454 6916 13454 6548 13454 6550 13455 6917 13455 6916 13455 6553 13456 6917 13456 6550 13456 6553 13457 6918 13457 6917 13457 6554 13458 6918 13458 6553 13458 6556 13459 6918 13459 6554 13459 6556 13460 6919 13460 6918 13460 6557 13461 6919 13461 6556 13461 6559 13462 6919 13462 6557 13462 6559 13463 6920 13463 6919 13463 6561 13464 6920 13464 6559 13464 6561 13465 6921 13465 6920 13465 6563 13466 6921 13466 6561 13466 7005 13467 6921 13467 6563 13467 7005 13468 6590 13468 6921 13468 6564 13469 6590 13469 7005 13469 6564 13470 6922 13470 6590 13470 6566 13471 6922 13471 6564 13471 6568 13472 6922 13472 6566 13472 6568 13473 6923 13473 6922 13473 6569 13474 6923 13474 6568 13474 6571 13475 6923 13475 6569 13475 6571 13476 6924 13476 6923 13476 6573 13477 6924 13477 6571 13477 6574 13478 6924 13478 6573 13478 6574 13479 6925 13479 6924 13479 6576 13480 6925 13480 6574 13480 6577 13481 6925 13481 6576 13481 6577 13482 6926 13482 6925 13482 6579 13483 6926 13483 6577 13483 6580 13484 6926 13484 6579 13484 6580 13485 6927 13485 6926 13485 6582 13486 6927 13486 6580 13486 6582 13487 6928 13487 6927 13487 6583 13488 6928 13488 6582 13488 6585 13489 6928 13489 6583 13489 6585 13490 6929 13490 6928 13490 6586 13491 6929 13491 6585 13491 6586 13492 6930 13492 6929 13492 6588 13493 6930 13493 6586 13493 6591 13494 6930 13494 6588 13494 6591 13495 6931 13495 6930 13495 6592 13496 6931 13496 6591 13496 6594 13497 6931 13497 6592 13497 6594 13498 6932 13498 6931 13498 6596 13499 6932 13499 6594 13499 6596 13500 6933 13500 6932 13500 6598 13501 6933 13501 6596 13501 6600 13502 6933 13502 6598 13502 6600 13503 6934 13503 6933 13503 6602 13504 6934 13504 6600 13504 6602 13505 6628 13505 6934 13505 6603 13506 6628 13506 6602 13506 7006 13507 6628 13507 6603 13507 7006 13508 6629 13508 6628 13508 7006 13509 6935 13509 6629 13509 6605 13510 6935 13510 7006 13510 6607 13511 6935 13511 6605 13511 6607 13512 6936 13512 6935 13512 6609 13513 6936 13513 6607 13513 6609 13514 6636 13514 6936 13514 6611 13515 6636 13515 6609 13515 6611 13516 6637 13516 6636 13516 6613 13517 6637 13517 6611 13517 6613 13518 6937 13518 6637 13518 6614 13519 6937 13519 6613 13519 6614 13520 6938 13520 6937 13520 6616 13521 6938 13521 6614 13521 6618 13522 6938 13522 6616 13522 6618 13523 6939 13523 6938 13523 6619 13524 6939 13524 6618 13524 6621 13525 6939 13525 6619 13525 6621 13526 6647 13526 6939 13526 6623 13527 6647 13527 6621 13527 6623 13528 6650 13528 6647 13528 6623 13529 6940 13529 6650 13529 6625 13530 6940 13530 6623 13530 6627 13531 6940 13531 6625 13531 6627 13532 6941 13532 6940 13532 6630 13533 6941 13533 6627 13533 6630 13534 6657 13534 6941 13534 6631 13535 6657 13535 6630 13535 6631 13536 6658 13536 6657 13536 6633 13537 6658 13537 6631 13537 6633 13538 6942 13538 6658 13538 6635 13539 6942 13539 6633 13539 6638 13540 6942 13540 6635 13540 6638 13541 6943 13541 6942 13541 6639 13542 6943 13542 6638 13542 6639 13543 6944 13543 6943 13543 6641 13544 6944 13544 6639 13544 6643 13545 6944 13545 6641 13545 6643 13546 6945 13546 6944 13546 6644 13547 6945 13547 6643 13547 6646 13548 6945 13548 6644 13548 6646 13549 6946 13549 6945 13549 6648 13550 6946 13550 6646 13550 6648 13551 6947 13551 6946 13551 6649 13552 6947 13552 6648 13552 6649 13553 6948 13553 6947 13553 6651 13554 6948 13554 6649 13554 6651 13555 6949 13555 6948 13555 6653 13556 6949 13556 6651 13556 6655 13557 6949 13557 6653 13557 6655 13558 6950 13558 6949 13558 6656 13559 6950 13559 6655 13559 6656 13560 6951 13560 6950 13560 7007 13561 6951 13561 6656 13561 7007 13562 6682 13562 6951 13562 6659 13563 6682 13563 7007 13563 6660 13564 6682 13564 6659 13564 6660 13565 6952 13565 6682 13565 6662 13566 6952 13566 6660 13566 6662 13567 6953 13567 6952 13567 6664 13568 6953 13568 6662 13568 6664 13569 6954 13569 6953 13569 6665 13570 6954 13570 6664 13570 6667 13571 6954 13571 6665 13571 6667 13572 6692 13572 6954 13572 6667 13573 6694 13573 6692 13573 6669 13574 6694 13574 6667 13574 6671 13575 6694 13575 6669 13575 6671 13576 6696 13576 6694 13576 6672 13577 6696 13577 6671 13577 6672 13578 6698 13578 6696 13578 6674 13579 6698 13579 6672 13579 6674 13580 6700 13580 6698 13580 6676 13581 6700 13581 6674 13581 6676 13582 6702 13582 6700 13582 6677 13583 6702 13583 6676 13583 6677 13584 6955 13584 6702 13584 7008 13585 6955 13585 6677 13585 6679 13586 6955 13586 7008 13586 6679 13587 6956 13587 6955 13587 6681 13588 6956 13588 6679 13588 6683 13589 6956 13589 6681 13589 6683 13590 6711 13590 6956 13590 6685 13591 6711 13591 6683 13591 6685 13592 6957 13592 6711 13592 6686 13593 6957 13593 6685 13593 6686 13594 6958 13594 6957 13594 6688 13595 6958 13595 6686 13595 6690 13596 6958 13596 6688 13596 6690 13597 6959 13597 6958 13597 6691 13598 6959 13598 6690 13598 6691 13599 6960 13599 6959 13599 6693 13600 6960 13600 6691 13600 6695 13601 6960 13601 6693 13601 6695 13602 6723 13602 6960 13602 6697 13603 6723 13603 6695 13603 6697 13604 6961 13604 6723 13604 6699 13605 6961 13605 6697 13605 6699 13606 6962 13606 6961 13606 6701 13607 6962 13607 6699 13607 6701 13608 6963 13608 6962 13608 6703 13609 6963 13609 6701 13609 6705 13610 6963 13610 6703 13610 6705 13611 6964 13611 6963 13611 6707 13612 6964 13612 6705 13612 6707 13613 6733 13613 6964 13613 6708 13614 6734 13614 6707 13614 6707 13615 6734 13615 6733 13615 6710 13616 6734 13616 6708 13616 6710 13617 6736 13617 6734 13617 6712 13618 6736 13618 6710 13618 6712 13619 6965 13619 6736 13619 6714 13620 6965 13620 6712 13620 6714 13621 6966 13621 6965 13621 6715 13622 6966 13622 6714 13622 6715 13623 6967 13623 6966 13623 6717 13624 6967 13624 6715 13624 6718 13625 6967 13625 6717 13625 6718 13626 6968 13626 6967 13626 6721 13627 6968 13627 6718 13627 6721 13628 6969 13628 6968 13628 6722 13629 6969 13629 6721 13629 6722 13630 6970 13630 6969 13630 6724 13631 6970 13631 6722 13631 6724 13632 6971 13632 6970 13632 6725 13633 6971 13633 6724 13633 6727 13634 6971 13634 6725 13634 6727 13635 6972 13635 6971 13635 6729 13636 6972 13636 6727 13636 6729 13637 6973 13637 6972 13637 6730 13638 6973 13638 6729 13638 6730 13639 6974 13639 6973 13639 6732 13640 6974 13640 6730 13640 7009 13641 6974 13641 6732 13641 7009 13642 6975 13642 6974 13642 6735 13643 6975 13643 7009 13643 6737 13644 6975 13644 6735 13644 6737 13645 6976 13645 6975 13645 6738 13646 6976 13646 6737 13646 6738 13647 6977 13647 6976 13647 6740 13648 6977 13648 6738 13648 6740 13649 6978 13649 6977 13649 6742 13650 6978 13650 6740 13650 6744 13651 6978 13651 6742 13651 6744 13652 6979 13652 6978 13652 6745 13653 6979 13653 6744 13653 6747 13654 6773 13654 6745 13654 6745 13655 6773 13655 6979 13655 6749 13656 6773 13656 6747 13656 6749 13657 6776 13657 6773 13657 6749 13658 6980 13658 6776 13658 6752 13659 6980 13659 6749 13659 6752 13660 6981 13660 6980 13660 6754 13661 6981 13661 6752 13661 6755 13662 6981 13662 6754 13662 6755 13663 6982 13663 6981 13663 6757 13664 6982 13664 6755 13664 6759 13665 6982 13665 6757 13665 6759 13666 6983 13666 6982 13666 6761 13667 6983 13667 6759 13667 6761 13668 6984 13668 6983 13668 6762 13669 6984 13669 6761 13669 6764 13670 6984 13670 6762 13670 6764 13671 6985 13671 6984 13671 6765 13672 6985 13672 6764 13672 6766 13673 6985 13673 6765 13673 6766 13674 6986 13674 6985 13674 6768 13675 6986 13675 6766 13675 6770 13676 6986 13676 6768 13676 6770 13677 6798 13677 6986 13677 6770 13678 6987 13678 6798 13678 6772 13679 6987 13679 6770 13679 6774 13680 6987 13680 6772 13680 6774 13681 6988 13681 6987 13681 6775 13682 6988 13682 6774 13682 6779 13683 6988 13683 6775 13683 6779 13684 6805 13684 6988 13684 6781 13685 6805 13685 6779 13685 6781 13686 6989 13686 6805 13686 6782 13687 6989 13687 6781 13687 6782 13688 6990 13688 6989 13688 6784 13689 6990 13689 6782 13689 6784 13690 6991 13690 6990 13690 6786 13691 6991 13691 6784 13691 6787 13692 6991 13692 6786 13692 6787 13693 6194 13693 6991 13693 6789 13694 6194 13694 6787 13694 6790 13695 6194 13695 6789 13695 6790 13696 6190 13696 6194 13696 6792 13697 6190 13697 6790 13697 6792 13698 6192 13698 6190 13698 6794 13699 6192 13699 6792 13699 6794 13700 6196 13700 6192 13700 6796 13701 6196 13701 6794 13701 6797 13702 6196 13702 6796 13702 6797 13703 6202 13703 6196 13703 6799 13704 6801 13704 6202 13704 6247 13705 6244 13705 6245 13705 6252 13706 6996 13706 6251 13706 6254 13707 6996 13707 6252 13707 6997 13708 6261 13708 6263 13708 6265 13709 6997 13709 6263 13709 6303 13710 6998 13710 6301 13710 6336 13711 6999 13711 6334 13711 6342 13712 7000 13712 6341 13712 6356 13713 6353 13713 6355 13713 6375 13714 6371 13714 6373 13714 7001 13715 6401 13715 6403 13715 6405 13716 7001 13716 6403 13716 6415 13717 7002 13717 6413 13717 6418 13718 6415 13718 6417 13718 7003 13719 6446 13719 6448 13719 6450 13720 7003 13720 6448 13720 6486 13721 6483 13721 6484 13721 6499 13722 7004 13722 6497 13722 6500 13723 7004 13723 6499 13723 6521 13724 6518 13724 6519 13724 6564 13725 7005 13725 6563 13725 6605 13726 7006 13726 6603 13726 6659 13727 7007 13727 6656 13727 6679 13728 7008 13728 6677 13728 6735 13729 7009 13729 6732 13729 6752 13730 6749 13730 6750 13730 6779 13731 6775 13731 6777 13731 6799 13732 6202 13732 6797 13732 6803 13733 7035 13733 6801 13733 7012 13734 7011 13734 7010 13734 7011 13735 6197 13735 6193 13735 7013 13736 7010 13736 7014 13736 7014 13737 7010 13737 7052 13737 7012 13738 7010 13738 7013 13738 7012 13739 6197 13739 7011 13739 7015 13740 7012 13740 7013 13740 6197 13741 7012 13741 7015 13741 6201 13742 6197 13742 7015 13742 7016 13743 7014 13743 7017 13743 7013 13744 7014 13744 7016 13744 7018 13745 7013 13745 7016 13745 6205 13746 7015 13746 7013 13746 6205 13747 7013 13747 7018 13747 6205 13748 6201 13748 7015 13748 7018 13749 7016 13749 7017 13749 7019 13750 7018 13750 7017 13750 7020 13751 6205 13751 7018 13751 7022 13752 7019 13752 7017 13752 7020 13753 7018 13753 7019 13753 7020 13754 6206 13754 6205 13754 6206 13755 7020 13755 7019 13755 7023 13756 7019 13756 7022 13756 6206 13757 7019 13757 7023 13757 7021 13758 7022 13758 7017 13758 7024 13759 6206 13759 7023 13759 6207 13760 6206 13760 7024 13760 7025 13761 7023 13761 7022 13761 7025 13762 7022 13762 7021 13762 7024 13763 7023 13763 7025 13763 7026 13764 6207 13764 7024 13764 7026 13765 7024 13765 7025 13765 7027 13766 7025 13766 7021 13766 7027 13767 7026 13767 7025 13767 7028 13768 7027 13768 7021 13768 7027 13769 7029 13769 7026 13769 7031 13770 7027 13770 7028 13770 7030 13771 7031 13771 7028 13771 7031 13772 7029 13772 7027 13772 7032 13773 7031 13773 7030 13773 6803 13774 7029 13774 7031 13774 7034 13775 7032 13775 7030 13775 6803 13776 7031 13776 7032 13776 7033 13777 7034 13777 7030 13777 7035 13778 6803 13778 7032 13778 7035 13779 7032 13779 7034 13779 7037 13780 7035 13780 7034 13780 6801 13781 7035 13781 7037 13781 7033 13782 7037 13782 7034 13782 7038 13783 7037 13783 7033 13783 7037 13784 6203 13784 6801 13784 6203 13785 7037 13785 7038 13785 7038 13786 7033 13786 7039 13786 7039 13787 7033 13787 7036 13787 7040 13788 7039 13788 7036 13788 6199 13789 6203 13789 7038 13789 7041 13790 7038 13790 7039 13790 7041 13791 6199 13791 7038 13791 7042 13792 7041 13792 7039 13792 7043 13793 7040 13793 7036 13793 6195 13794 6199 13794 7041 13794 7042 13795 7039 13795 7040 13795 6195 13796 7041 13796 7042 13796 7044 13797 7040 13797 7043 13797 7042 13798 7040 13798 7044 13798 7045 13799 7042 13799 7044 13799 6195 13800 7042 13800 7045 13800 7047 13801 7044 13801 7043 13801 7048 13802 7045 13802 7044 13802 6191 13803 6195 13803 7045 13803 7048 13804 7044 13804 7047 13804 6191 13805 7045 13805 7048 13805 7047 13806 7043 13806 7046 13806 7049 13807 7048 13807 7047 13807 7050 13808 7048 13808 7049 13808 6191 13809 7048 13809 7050 13809 7051 13810 7047 13810 7046 13810 7051 13811 7049 13811 7047 13811 7053 13812 7049 13812 7051 13812 7054 13813 7050 13813 7049 13813 7054 13814 7049 13814 7053 13814 7051 13815 7046 13815 7052 13815 7010 13816 7051 13816 7052 13816 6193 13817 7054 13817 7053 13817 7011 13818 7053 13818 7051 13818 7011 13819 7051 13819 7010 13819 6193 13820 7053 13820 7011 13820 7028 13821 7033 13821 7030 13821 7028 13822 7046 13822 7043 13822 7028 13823 7021 13823 7017 13823 7028 13824 7014 13824 7052 13824 7028 13825 7052 13825 7046 13825 7028 13826 7017 13826 7014 13826 7028 13827 7036 13827 7033 13827 7028 13828 7043 13828 7036 13828 7056 13829 7055 13829 7064 13829 7064 13830 7055 13830 7061 13830 7055 13831 7057 13831 7061 13831 7061 13832 7057 13832 7062 13832 7057 13833 7058 13833 7062 13833 7062 13834 7058 13834 7066 13834 7058 13835 7059 13835 7066 13835 7066 13836 7059 13836 7065 13836 7059 13837 7060 13837 7065 13837 7065 13838 7060 13838 7063 13838 7060 13839 7064 13839 7063 13839 7060 13840 7056 13840 7064 13840 7062 13841 7070 13841 7067 13841 7062 13842 7067 13842 7068 13842 7062 13843 7068 13843 7069 13843 7066 13844 7072 13844 7070 13844 7066 13845 7071 13845 7072 13845 7066 13846 7070 13846 7062 13846 7061 13847 7069 13847 7073 13847 7061 13848 7062 13848 7069 13848 7074 13849 7061 13849 7073 13849 7065 13850 7075 13850 7071 13850 7065 13851 7071 13851 7066 13851 7064 13852 7061 13852 7074 13852 7076 13853 7064 13853 7074 13853 7077 13854 7075 13854 7065 13854 7078 13855 7077 13855 7065 13855 7078 13856 7065 13856 7063 13856 7079 13857 7064 13857 7076 13857 7080 13858 7078 13858 7063 13858 7079 13859 7063 13859 7064 13859 7081 13860 7063 13860 7079 13860 7081 13861 7080 13861 7063 13861 7056 13862 7060 13862 7055 13862 7055 13863 7058 13863 7057 13863 7060 13864 7059 13864 7055 13864 7055 13865 7059 13865 7058 13865 7082 13866 7095 13866 7072 13866 7082 13867 7072 13867 7071 13867 7083 13868 7082 13868 7071 13868 7083 13869 7071 13869 7075 13869 7084 13870 7083 13870 7075 13870 7084 13871 7075 13871 7077 13871 7084 13872 7077 13872 7078 13872 7085 13873 7084 13873 7078 13873 7085 13874 7078 13874 7080 13874 7086 13875 7085 13875 7080 13875 7086 13876 7080 13876 7081 13876 7087 13877 7086 13877 7081 13877 7087 13878 7081 13878 7079 13878 7088 13879 7087 13879 7079 13879 7088 13880 7079 13880 7076 13880 7089 13881 7088 13881 7076 13881 7089 13882 7076 13882 7074 13882 7090 13883 7089 13883 7074 13883 7090 13884 7074 13884 7073 13884 7091 13885 7090 13885 7073 13885 7091 13886 7073 13886 7069 13886 7092 13887 7091 13887 7069 13887 7092 13888 7069 13888 7068 13888 7093 13889 7092 13889 7068 13889 7093 13890 7068 13890 7067 13890 7094 13891 7093 13891 7067 13891 7094 13892 7067 13892 7070 13892 7095 13893 7094 13893 7070 13893 7095 13894 7070 13894 7072 13894 6807 13895 7090 13895 7091 13895 6807 13896 6219 13896 7090 13896 6219 13897 7089 13897 7090 13897 6993 13898 6807 13898 7091 13898 6219 13899 7088 13899 7089 13899 6212 13900 7088 13900 6219 13900 6993 13901 7091 13901 7092 13901 6212 13902 7087 13902 7088 13902 6993 13903 7092 13903 7093 13903 6216 13904 7087 13904 6212 13904 6994 13905 6993 13905 7093 13905 6216 13906 7086 13906 7087 13906 6994 13907 7093 13907 7094 13907 6214 13908 7086 13908 6216 13908 7094 13909 6992 13909 6994 13909 7085 13910 7086 13910 6214 13910 7095 13911 6992 13911 7094 13911 7085 13912 6214 13912 6211 13912 7082 13913 6992 13913 7095 13913 7084 13914 7085 13914 6211 13914 7082 13915 6995 13915 6992 13915 7084 13916 6211 13916 6208 13916 7083 13917 6995 13917 7082 13917 7083 13918 7084 13918 6208 13918 7083 13919 6208 13919 6995 13919

+
+ + + +

7117 13920 7096 13920 7116 13920 7116 13921 7096 13921 7097 13921 7097 13922 7096 13922 7098 13922 7096 13923 7099 13923 7098 13923 7099 13924 7100 13924 7098 13924 7098 13925 7100 13925 7101 13925 7100 13926 7102 13926 7101 13926 7101 13927 7102 13927 7103 13927 7103 13928 7102 13928 7104 13928 7102 13929 7105 13929 7104 13929 7104 13930 7105 13930 7106 13930 7105 13931 7107 13931 7106 13931 7106 13932 7107 13932 7108 13932 7107 13933 7109 13933 7108 13933 7109 13934 7110 13934 7108 13934 7108 13935 7110 13935 7111 13935 7111 13936 7110 13936 7112 13936 7110 13937 7113 13937 7112 13937 7112 13938 7113 13938 7114 13938 7113 13939 7115 13939 7114 13939 7114 13940 7115 13940 7116 13940 7115 13941 7117 13941 7116 13941 7119 13942 7146 13942 7118 13942 7119 13943 7118 13943 7120 13943 7119 13944 7120 13944 7121 13944 7122 13945 7119 13945 7121 13945 7122 13946 7121 13946 7123 13946 7124 13947 7122 13947 7123 13947 7124 13948 7123 13948 7125 13948 7126 13949 7124 13949 7125 13949 7127 13950 7126 13950 7125 13950 7127 13951 7125 13951 7128 13951 7129 13952 7127 13952 7128 13952 7129 13953 7128 13953 7130 13953 7131 13954 7129 13954 7130 13954 7131 13955 7130 13955 7132 13955 7133 13956 7131 13956 7132 13956 7134 13957 7133 13957 7132 13957 7134 13958 7132 13958 7135 13958 7136 13959 7134 13959 7135 13959 7136 13960 7135 13960 7137 13960 7138 13961 7136 13961 7137 13961 7138 13962 7137 13962 7139 13962 7140 13963 7138 13963 7139 13963 7140 13964 7139 13964 7141 13964 7142 13965 7141 13965 7143 13965 7142 13966 7140 13966 7141 13966 7144 13967 7142 13967 7143 13967 7144 13968 7143 13968 7145 13968 7146 13969 7144 13969 7145 13969 7146 13970 7145 13970 7118 13970 7107 1433 7143 1433 7109 1433 7107 1433 7145 1433 7143 1433 7109 13971 7143 13971 7141 13971 7110 1433 7109 1433 7141 1433 7107 1433 7118 1433 7145 1433 7105 13972 7118 13972 7107 13972 7113 13973 7141 13973 7139 13973 7113 1433 7110 1433 7141 1433 7105 1433 7120 1433 7118 1433 7113 1433 7139 1433 7137 1433 7102 1433 7120 1433 7105 1433 7102 1433 7121 1433 7120 1433 7115 1433 7113 1433 7137 1433 7115 13974 7137 13974 7135 13974 7123 13975 7102 13975 7100 13975 7123 1433 7121 1433 7102 1433 7135 1433 7117 1433 7115 1433 7132 1433 7117 1433 7135 1433 7125 1433 7123 1433 7100 1433 7132 13976 7096 13976 7117 13976 7130 13977 7096 13977 7132 13977 7125 13978 7100 13978 7099 13978 7128 13979 7096 13979 7130 13979 7128 1433 7125 1433 7099 1433 7128 13980 7099 13980 7096 13980 7114 759 7134 759 7136 759 7116 13981 7134 13981 7114 13981 7112 759 7114 759 7136 759 7112 13982 7136 13982 7138 13982 7116 759 7133 759 7134 759 7112 13983 7138 13983 7140 13983 7111 759 7112 759 7140 759 7116 759 7131 759 7133 759 7097 759 7131 759 7116 759 7111 13984 7140 13984 7142 13984 7108 13985 7111 13985 7142 13985 7097 759 7129 759 7131 759 7098 13986 7129 13986 7097 13986 7144 759 7108 759 7142 759 7127 13987 7129 13987 7098 13987 7144 759 7106 759 7108 759 7146 759 7106 759 7144 759 7126 13988 7127 13988 7098 13988 7126 13989 7098 13989 7101 13989 7146 759 7104 759 7106 759 7124 13990 7126 13990 7101 13990 7119 13991 7104 13991 7146 13991 7122 759 7124 759 7101 759 7122 13992 7101 13992 7103 13992 7119 759 7103 759 7104 759 7122 13993 7103 13993 7119 13993

+
+ + + +

7998 13994 7147 13994 7995 13994 7148 13995 7147 13995 7998 13995 7148 13996 7149 13996 7147 13996 7147 13997 7150 13997 7995 13997 7995 13998 7150 13998 7991 13998 7955 13999 7149 13999 7148 13999 7150 14000 7151 14000 7991 14000 7955 14001 7152 14001 7149 14001 7153 14002 7152 14002 7955 14002 7991 14003 7151 14003 7989 14003 7151 14004 7154 14004 7989 14004 7961 14005 7152 14005 7153 14005 7961 14006 7155 14006 7152 14006 7961 14007 7967 14007 7155 14007 7155 14008 7967 14008 7157 14008 7165 14009 7163 14009 7162 14009 7165 14010 7164 14010 7163 14010 7168 14011 7164 14011 7165 14011 7168 14012 7167 14012 7164 14012 7168 14013 7169 14013 7167 14013 7168 14014 7170 14014 7169 14014 7171 14015 7170 14015 7168 14015 7171 14016 7172 14016 7170 14016 7166 14017 7172 14017 7171 14017 7173 14018 7172 14018 7166 14018 7173 14019 7174 14019 7172 14019 7175 14020 7174 14020 7173 14020 7175 14021 7176 14021 7174 14021 7177 14022 7176 14022 7175 14022 7177 14023 7178 14023 7176 14023 7179 14024 7178 14024 7177 14024 7179 14025 7180 14025 7178 14025 7179 14026 7181 14026 7180 14026 7182 14027 7181 14027 7179 14027 7182 14028 7183 14028 7181 14028 7184 14029 7183 14029 7182 14029 7184 14030 7185 14030 7183 14030 7184 14031 7186 14031 7185 14031 7187 14032 7186 14032 7184 14032 7187 14033 7188 14033 7186 14033 7189 14034 7188 14034 7187 14034 7189 14035 7190 14035 7188 14035 7191 14036 7190 14036 7189 14036 7191 14037 7192 14037 7190 14037 7193 14038 7192 14038 7191 14038 7193 14039 7194 14039 7192 14039 7195 14040 7194 14040 7193 14040 7195 14041 7196 14041 7194 14041 7197 14042 7196 14042 7195 14042 7197 14043 7198 14043 7196 14043 7199 14044 7198 14044 7197 14044 7199 14045 7200 14045 7198 14045 7199 14046 7201 14046 7200 14046 7202 14047 7201 14047 7199 14047 7202 14048 7203 14048 7201 14048 7204 14049 7203 14049 7202 14049 7204 14050 7205 14050 7203 14050 7206 14051 7205 14051 7204 14051 7206 14052 7207 14052 7205 14052 7206 14053 7208 14053 7207 14053 7209 14054 7208 14054 7206 14054 7209 14055 7210 14055 7208 14055 7211 14056 7210 14056 7209 14056 7211 14057 7212 14057 7210 14057 7213 14058 7212 14058 7211 14058 7214 14059 7212 14059 7213 14059 7214 14060 7215 14060 7212 14060 7214 14061 7216 14061 7215 14061 7217 14062 7216 14062 7214 14062 7217 14063 7218 14063 7216 14063 7219 14064 7218 14064 7217 14064 7219 14065 7220 14065 7218 14065 7219 14066 7221 14066 7220 14066 7222 14067 7221 14067 7219 14067 7222 14068 7223 14068 7221 14068 7224 14069 7223 14069 7222 14069 7224 14070 7225 14070 7223 14070 7226 14071 7225 14071 7224 14071 7226 14072 7227 14072 7225 14072 7226 14073 7228 14073 7227 14073 7229 14074 7228 14074 7226 14074 7229 14075 7230 14075 7228 14075 7231 14076 7230 14076 7229 14076 7231 14077 7232 14077 7230 14077 7231 14078 7233 14078 7232 14078 7234 14079 7233 14079 7231 14079 7234 14080 7235 14080 7233 14080 7236 14081 7235 14081 7234 14081 7236 14082 7237 14082 7235 14082 7238 14083 7237 14083 7236 14083 7238 14084 7239 14084 7237 14084 7240 14085 7239 14085 7238 14085 7240 14086 7241 14086 7239 14086 7242 14087 7241 14087 7240 14087 7242 14088 7243 14088 7241 14088 7242 14089 7244 14089 7243 14089 7245 14090 7244 14090 7242 14090 7246 14091 7244 14091 7245 14091 7246 14092 7247 14092 7244 14092 7248 14093 7247 14093 7246 14093 7248 14094 7249 14094 7247 14094 7248 14095 7250 14095 7249 14095 7251 14096 7250 14096 7248 14096 7251 14097 7252 14097 7250 14097 7251 14098 7253 14098 7252 14098 7254 14099 7253 14099 7251 14099 7254 14100 7255 14100 7253 14100 7256 14101 7255 14101 7254 14101 7256 14102 7257 14102 7255 14102 7256 14103 7258 14103 7257 14103 7259 14104 7258 14104 7256 14104 7259 14105 7260 14105 7258 14105 7261 14106 7260 14106 7259 14106 7261 14107 7262 14107 7260 14107 7263 14108 7262 14108 7261 14108 7263 14109 7264 14109 7262 14109 7265 14110 7264 14110 7263 14110 7265 14111 7266 14111 7264 14111 7267 14112 7266 14112 7265 14112 7267 14113 7268 14113 7266 14113 7267 14114 7269 14114 7268 14114 7270 14115 7269 14115 7267 14115 7270 14116 7271 14116 7269 14116 7272 14117 7271 14117 7270 14117 7272 14118 7273 14118 7271 14118 7274 14119 7273 14119 7272 14119 7274 14120 7275 14120 7273 14120 7274 14121 7276 14121 7275 14121 7277 14122 7276 14122 7274 14122 7277 14123 7278 14123 7276 14123 7279 14124 7278 14124 7277 14124 7279 14125 7280 14125 7278 14125 7279 14126 7281 14126 7280 14126 7282 14127 7281 14127 7279 14127 7283 14128 7281 14128 7282 14128 7283 14129 7284 14129 7281 14129 7283 14130 7285 14130 7284 14130 7286 14131 7285 14131 7283 14131 7287 14132 7285 14132 7286 14132 7287 14133 7288 14133 7285 14133 7289 14134 7290 14134 7287 14134 7287 14135 7290 14135 7288 14135 7291 14136 7290 14136 7289 14136 7291 14137 7292 14137 7290 14137 7293 14138 7292 14138 7291 14138 7293 14139 7294 14139 7292 14139 7295 14140 7294 14140 7293 14140 7295 14141 7296 14141 7294 14141 7295 14142 7297 14142 7296 14142 7298 14143 7297 14143 7295 14143 7298 14144 7299 14144 7297 14144 7298 14145 7300 14145 7299 14145 7301 14146 7300 14146 7298 14146 7301 14147 7302 14147 7300 14147 7303 14148 7302 14148 7301 14148 7303 14149 7304 14149 7302 14149 7305 14150 7304 14150 7303 14150 7305 14151 7306 14151 7304 14151 7307 14152 7306 14152 7305 14152 7307 14153 7308 14153 7306 14153 7309 14154 7308 14154 7307 14154 7309 14155 7310 14155 7308 14155 7311 14156 7310 14156 7309 14156 7311 14157 7312 14157 7310 14157 7313 14158 7312 14158 7311 14158 7313 14159 7314 14159 7312 14159 7313 14160 7315 14160 7314 14160 7316 14161 7315 14161 7313 14161 7316 14162 7317 14162 7315 14162 7316 14163 7318 14163 7317 14163 7319 14164 7318 14164 7316 14164 7319 14165 7320 14165 7318 14165 7321 14166 7320 14166 7319 14166 7321 14167 7322 14167 7320 14167 7323 14168 7322 14168 7321 14168 7323 14169 7324 14169 7322 14169 7323 14170 7325 14170 7324 14170 7326 14171 7325 14171 7323 14171 7326 14172 7327 14172 7325 14172 7328 14173 7327 14173 7326 14173 7328 14174 7329 14174 7327 14174 7328 14175 7330 14175 7329 14175 7331 14176 7330 14176 7328 14176 7331 14177 7332 14177 7330 14177 7331 14178 7333 14178 7332 14178 7334 14179 7333 14179 7331 14179 7334 14180 7335 14180 7333 14180 7336 14181 7335 14181 7334 14181 7336 14182 7337 14182 7335 14182 7338 14183 7337 14183 7336 14183 7338 14184 7339 14184 7337 14184 7340 14185 7339 14185 7338 14185 7340 14186 7341 14186 7339 14186 7342 14187 7341 14187 7340 14187 7342 14188 7343 14188 7341 14188 7342 14189 7344 14189 7343 14189 7345 14190 7344 14190 7342 14190 7345 14191 7346 14191 7344 14191 7347 14192 7346 14192 7345 14192 7347 14193 7348 14193 7346 14193 7349 14194 7348 14194 7347 14194 7349 14195 7350 14195 7348 14195 7351 14196 7350 14196 7349 14196 7351 14197 7352 14197 7350 14197 7351 14198 7353 14198 7352 14198 7354 14199 7353 14199 7351 14199 7354 14200 7355 14200 7353 14200 7354 14201 7356 14201 7355 14201 7357 14202 7356 14202 7354 14202 7357 14203 7358 14203 7356 14203 7359 14204 7358 14204 7357 14204 7359 14205 7360 14205 7358 14205 7361 14206 7360 14206 7359 14206 7361 14207 7362 14207 7360 14207 7363 14208 7362 14208 7361 14208 7363 14209 7364 14209 7362 14209 7365 14210 7364 14210 7363 14210 7365 14211 7366 14211 7364 14211 7365 14212 7367 14212 7366 14212 7368 14213 7367 14213 7365 14213 7368 14214 7369 14214 7367 14214 7370 14215 7369 14215 7368 14215 7370 14216 7371 14216 7369 14216 7370 14217 7372 14217 7371 14217 7373 14218 7372 14218 7370 14218 7373 14219 7374 14219 7372 14219 7373 14220 7375 14220 7374 14220 7376 14221 7375 14221 7373 14221 7377 14222 7375 14222 7376 14222 7377 14223 7378 14223 7375 14223 7379 14224 7380 14224 7377 14224 7377 14225 7380 14225 7378 14225 7381 14226 7380 14226 7379 14226 7381 14227 7382 14227 7380 14227 7381 14228 7383 14228 7382 14228 7384 14229 7383 14229 7381 14229 7384 14230 7385 14230 7383 14230 7386 14231 7387 14231 7384 14231 7384 14232 7387 14232 7385 14232 7386 14233 7388 14233 7387 14233 7389 14234 7388 14234 7386 14234 7389 14235 7390 14235 7388 14235 7391 14236 7392 14236 7389 14236 7389 14237 7392 14237 7390 14237 7391 14238 7393 14238 7392 14238 7394 14239 7393 14239 7391 14239 7394 14240 7395 14240 7393 14240 7396 14241 7395 14241 7394 14241 7396 14242 7397 14242 7395 14242 7396 14243 7398 14243 7397 14243 7399 14244 7398 14244 7396 14244 7399 14245 7400 14245 7398 14245 7401 14246 7400 14246 7399 14246 7401 14247 7402 14247 7400 14247 7403 14248 7402 14248 7401 14248 7404 14249 7405 14249 7403 14249 7403 14250 7405 14250 7402 14250 7406 14251 7405 14251 7404 14251 7406 14252 7407 14252 7405 14252 7406 14253 7408 14253 7407 14253 7409 14254 7408 14254 7406 14254 7409 14255 7410 14255 7408 14255 7409 14256 7411 14256 7410 14256 7412 14257 7411 14257 7409 14257 7412 14258 7413 14258 7411 14258 7414 14259 7413 14259 7412 14259 7414 14260 7415 14260 7413 14260 7416 14261 7415 14261 7414 14261 7416 14262 7417 14262 7415 14262 7416 14263 7418 14263 7417 14263 7419 14264 7418 14264 7416 14264 7419 14265 7420 14265 7418 14265 7421 14266 7420 14266 7419 14266 7421 14267 7422 14267 7420 14267 7423 14268 7422 14268 7421 14268 7423 14269 7424 14269 7422 14269 7425 14270 7424 14270 7423 14270 7425 14271 7426 14271 7424 14271 7427 14272 7426 14272 7425 14272 7427 14273 7428 14273 7426 14273 7427 14274 7429 14274 7428 14274 7430 14275 7429 14275 7427 14275 7430 14276 7431 14276 7429 14276 7432 14277 7431 14277 7430 14277 7432 14278 7433 14278 7431 14278 7432 14279 7434 14279 7433 14279 7432 14280 7435 14280 7434 14280 7436 14281 7435 14281 7432 14281 7437 14282 7435 14282 7436 14282 7437 14283 7438 14283 7435 14283 7439 14284 7438 14284 7437 14284 7439 14285 7440 14285 7438 14285 7439 14286 7441 14286 7440 14286 7442 14287 7441 14287 7439 14287 7442 14288 7443 14288 7441 14288 7444 14289 7443 14289 7442 14289 7444 14290 7445 14290 7443 14290 7444 14291 7446 14291 7445 14291 7447 14292 7446 14292 7444 14292 7447 14293 7448 14293 7446 14293 7447 14294 7449 14294 7448 14294 7450 14295 7449 14295 7447 14295 7450 14296 7451 14296 7449 14296 7452 14297 7451 14297 7450 14297 7452 14298 7453 14298 7451 14298 7454 14299 7453 14299 7452 14299 7454 14300 7455 14300 7453 14300 7454 14301 7456 14301 7455 14301 7457 14302 7456 14302 7454 14302 7457 14303 7458 14303 7456 14303 7459 14304 7458 14304 7457 14304 7459 14305 7460 14305 7458 14305 7459 14306 7461 14306 7460 14306 7462 14307 7461 14307 7459 14307 7462 14308 7463 14308 7461 14308 7464 14309 7463 14309 7462 14309 7464 14310 7465 14310 7463 14310 7464 14311 7466 14311 7465 14311 7467 14312 7466 14312 7464 14312 7467 14313 7468 14313 7466 14313 7469 14314 7468 14314 7467 14314 7469 14315 7470 14315 7468 14315 7471 14316 7470 14316 7469 14316 7471 14317 7472 14317 7470 14317 7473 14318 7472 14318 7471 14318 7473 14319 7474 14319 7472 14319 7475 14320 7474 14320 7473 14320 7475 14321 7476 14321 7474 14321 7475 14322 7477 14322 7476 14322 7478 14323 7477 14323 7475 14323 7479 14324 7477 14324 7478 14324 7479 14325 7480 14325 7477 14325 7479 14326 7481 14326 7480 14326 7482 14327 7481 14327 7479 14327 7482 14328 7483 14328 7481 14328 7484 14329 7483 14329 7482 14329 7484 14330 7485 14330 7483 14330 7484 14331 7486 14331 7485 14331 7487 14332 7486 14332 7484 14332 7487 14333 7488 14333 7486 14333 7489 14334 7488 14334 7487 14334 7489 14335 7490 14335 7488 14335 7489 14336 7491 14336 7490 14336 7492 14337 7491 14337 7489 14337 7492 14338 7493 14338 7491 14338 7492 14339 7494 14339 7493 14339 7495 14340 7494 14340 7492 14340 7495 14341 7496 14341 7494 14341 7497 14342 7496 14342 7495 14342 7497 14343 7498 14343 7496 14343 7499 14344 7500 14344 7497 14344 7497 14345 7500 14345 7498 14345 7499 14346 7501 14346 7500 14346 7502 14347 7501 14347 7499 14347 7502 14348 7503 14348 7501 14348 7502 14349 7504 14349 7503 14349 7505 14350 7504 14350 7502 14350 7505 14351 7506 14351 7504 14351 7507 14352 7506 14352 7505 14352 7507 14353 7508 14353 7506 14353 7507 14354 7509 14354 7508 14354 7510 14355 7509 14355 7507 14355 7510 14356 7511 14356 7509 14356 7512 14357 7511 14357 7510 14357 7512 14358 7513 14358 7511 14358 7512 14359 7514 14359 7513 14359 7515 14360 7514 14360 7512 14360 7515 14361 7516 14361 7514 14361 7517 14362 7516 14362 7515 14362 7518 14363 7516 14363 7517 14363 7518 14364 7519 14364 7516 14364 7518 14365 7520 14365 7519 14365 7521 14366 7520 14366 7518 14366 7521 14367 7522 14367 7520 14367 7523 14368 7522 14368 7521 14368 7523 14369 7524 14369 7522 14369 7525 14370 7524 14370 7523 14370 7525 14371 7526 14371 7524 14371 7527 14372 7526 14372 7525 14372 7527 14373 7528 14373 7526 14373 7529 14374 7530 14374 7527 14374 7527 14375 7530 14375 7528 14375 7529 14376 7531 14376 7530 14376 7532 14377 7531 14377 7529 14377 7532 14378 7533 14378 7531 14378 7534 14379 7533 14379 7532 14379 7534 14380 7535 14380 7533 14380 7534 14381 7536 14381 7535 14381 7537 14382 7536 14382 7534 14382 7537 14383 7538 14383 7536 14383 7539 14384 7538 14384 7537 14384 7539 14385 7540 14385 7538 14385 7539 14386 7541 14386 7540 14386 7542 14387 7541 14387 7539 14387 7542 14388 7543 14388 7541 14388 7544 14389 7543 14389 7542 14389 7544 14390 7545 14390 7543 14390 7546 14391 7545 14391 7544 14391 7546 14392 7547 14392 7545 14392 7548 14393 7547 14393 7546 14393 7548 14394 7549 14394 7547 14394 7548 14395 7550 14395 7549 14395 7551 14396 7550 14396 7548 14396 7551 14397 7552 14397 7550 14397 7551 14398 7553 14398 7552 14398 7554 14399 7553 14399 7551 14399 7555 14400 7553 14400 7554 14400 7555 14401 7556 14401 7553 14401 7555 14402 7557 14402 7556 14402 7558 14403 7557 14403 7555 14403 7558 14404 7559 14404 7557 14404 7560 14405 7559 14405 7558 14405 7560 14406 7561 14406 7559 14406 7562 14407 7561 14407 7560 14407 7562 14408 7563 14408 7561 14408 7562 14409 7564 14409 7563 14409 7565 14410 7564 14410 7562 14410 7565 14411 7566 14411 7564 14411 7567 14412 7566 14412 7565 14412 7567 14413 7568 14413 7566 14413 7567 14414 7569 14414 7568 14414 7570 14415 7569 14415 7567 14415 7571 14416 7569 14416 7570 14416 7571 14417 7572 14417 7569 14417 7571 14418 7573 14418 7572 14418 7574 14419 7573 14419 7571 14419 7574 14420 7575 14420 7573 14420 7576 14421 7575 14421 7574 14421 7576 14422 7577 14422 7575 14422 7578 14423 7577 14423 7576 14423 7578 14424 7579 14424 7577 14424 7580 14425 7579 14425 7578 14425 7580 14426 7581 14426 7579 14426 7580 14427 7582 14427 7581 14427 7583 14428 7582 14428 7580 14428 7584 14429 7585 14429 7583 14429 7583 14430 7585 14430 7582 14430 7586 14431 7585 14431 7584 14431 7586 14432 7587 14432 7585 14432 7588 14433 7587 14433 7586 14433 7588 14434 7589 14434 7587 14434 7588 14435 7590 14435 7589 14435 7591 14436 7590 14436 7588 14436 7591 14437 7592 14437 7590 14437 7593 14438 7592 14438 7591 14438 7593 14439 7594 14439 7592 14439 7595 14440 7594 14440 7593 14440 7595 14441 7596 14441 7594 14441 7597 14442 7598 14442 7595 14442 7595 14443 7598 14443 7596 14443 7597 14444 7599 14444 7598 14444 7600 14445 7599 14445 7597 14445 7600 14446 7601 14446 7599 14446 7602 14447 7601 14447 7600 14447 7602 14448 7603 14448 7601 14448 7602 14449 7604 14449 7603 14449 7605 14450 7604 14450 7602 14450 7605 14451 7606 14451 7604 14451 7607 14452 7606 14452 7605 14452 7607 14453 7608 14453 7606 14453 7609 14454 7608 14454 7607 14454 7609 14455 7610 14455 7608 14455 7609 14456 7611 14456 7610 14456 7612 14457 7611 14457 7609 14457 7612 14458 7613 14458 7611 14458 7612 14459 7614 14459 7613 14459 7615 14460 7614 14460 7612 14460 7615 14461 7616 14461 7614 14461 7617 14462 7616 14462 7615 14462 7617 14463 7618 14463 7616 14463 7619 14464 7618 14464 7617 14464 7619 14465 7620 14465 7618 14465 7621 14466 7620 14466 7619 14466 7621 14467 7622 14467 7620 14467 7623 14468 7622 14468 7621 14468 7623 14469 7624 14469 7622 14469 7623 14470 7625 14470 7624 14470 7626 14471 7625 14471 7623 14471 7626 14472 7627 14472 7625 14472 7628 14473 7627 14473 7626 14473 7628 14474 7629 14474 7627 14474 7628 14475 7630 14475 7629 14475 7628 14476 7631 14476 7630 14476 7632 14477 7631 14477 7628 14477 7632 14478 7633 14478 7631 14478 7634 14479 7633 14479 7632 14479 7634 14480 7635 14480 7633 14480 7636 14481 7635 14481 7634 14481 7636 14482 7637 14482 7635 14482 7638 14483 7637 14483 7636 14483 7638 14484 7639 14484 7637 14484 7640 14485 7639 14485 7638 14485 7640 14486 7641 14486 7639 14486 7640 14487 7642 14487 7641 14487 7643 14488 7642 14488 7640 14488 7644 14489 7642 14489 7643 14489 7644 14490 7645 14490 7642 14490 7644 14491 7646 14491 7645 14491 7647 14492 7646 14492 7644 14492 7647 14493 7648 14493 7646 14493 7647 14494 7649 14494 7648 14494 7650 14495 7649 14495 7647 14495 7650 14496 7651 14496 7649 14496 7652 14497 7651 14497 7650 14497 7652 14498 7653 14498 7651 14498 7652 14499 7654 14499 7653 14499 7655 14500 7654 14500 7652 14500 7655 14501 7656 14501 7654 14501 7655 14502 7657 14502 7656 14502 7658 14503 7657 14503 7655 14503 7658 14504 7659 14504 7657 14504 7660 14505 7659 14505 7658 14505 7660 14506 7661 14506 7659 14506 7662 14507 7661 14507 7660 14507 7662 14508 7663 14508 7661 14508 7662 14509 7664 14509 7663 14509 7665 14510 7664 14510 7662 14510 7665 14511 7666 14511 7664 14511 7667 14512 7666 14512 7665 14512 7667 14513 7668 14513 7666 14513 7669 14514 7668 14514 7667 14514 7669 14515 7670 14515 7668 14515 7671 14516 7670 14516 7669 14516 7671 14517 7672 14517 7670 14517 7673 14518 7674 14518 7671 14518 7671 14519 7674 14519 7672 14519 7675 14520 7674 14520 7673 14520 7675 14521 7676 14521 7674 14521 7677 14522 7676 14522 7675 14522 7677 14523 7678 14523 7676 14523 7677 14524 7679 14524 7678 14524 7680 14525 7679 14525 7677 14525 7680 14526 7681 14526 7679 14526 7680 14527 7682 14527 7681 14527 7683 14528 7682 14528 7680 14528 7684 14529 7682 14529 7683 14529 7684 14530 7685 14530 7682 14530 7684 14531 7686 14531 7685 14531 7687 14532 7686 14532 7684 14532 7688 14533 7686 14533 7687 14533 7688 14534 7689 14534 7686 14534 7688 14535 7690 14535 7689 14535 7691 14536 7690 14536 7688 14536 7691 14537 7692 14537 7690 14537 7693 14538 7692 14538 7691 14538 7693 14539 7694 14539 7692 14539 7695 14540 7694 14540 7693 14540 7695 14541 7696 14541 7694 14541 7697 14542 7696 14542 7695 14542 7697 14543 7698 14543 7696 14543 7699 14544 7698 14544 7697 14544 7699 14545 7700 14545 7698 14545 7699 14546 7701 14546 7700 14546 7702 14547 7701 14547 7699 14547 7702 14548 7703 14548 7701 14548 7704 14549 7703 14549 7702 14549 7704 14550 7705 14550 7703 14550 7704 14551 7706 14551 7705 14551 7704 14552 7707 14552 7706 14552 7708 14553 7707 14553 7704 14553 7709 14554 7707 14554 7708 14554 7709 14555 7710 14555 7707 14555 7709 14556 7711 14556 7710 14556 7712 14557 7711 14557 7709 14557 7712 14558 7713 14558 7711 14558 7712 14559 7714 14559 7713 14559 7715 14560 7714 14560 7712 14560 7715 14561 7716 14561 7714 14561 7717 14562 7716 14562 7715 14562 7717 14563 7718 14563 7716 14563 7719 14564 7718 14564 7717 14564 7719 14565 7720 14565 7718 14565 7721 14566 7720 14566 7719 14566 7721 14567 7722 14567 7720 14567 7723 14568 7722 14568 7721 14568 7723 14569 7724 14569 7722 14569 7725 14570 7724 14570 7723 14570 7725 14571 7726 14571 7724 14571 7727 14572 7726 14572 7725 14572 7727 14573 7728 14573 7726 14573 7729 14574 7728 14574 7727 14574 7729 14575 7730 14575 7728 14575 7729 14576 7731 14576 7730 14576 7732 14577 7731 14577 7729 14577 7732 14578 7733 14578 7731 14578 7734 14579 7733 14579 7732 14579 7734 14580 7735 14580 7733 14580 7734 14581 7736 14581 7735 14581 7737 14582 7736 14582 7734 14582 7737 14583 7738 14583 7736 14583 7739 14584 7738 14584 7737 14584 7739 14585 7740 14585 7738 14585 7741 14586 7740 14586 7739 14586 7741 14587 7742 14587 7740 14587 7743 14588 7742 14588 7741 14588 7743 14589 7744 14589 7742 14589 7743 14590 7745 14590 7744 14590 7746 14591 7745 14591 7743 14591 7746 14592 7747 14592 7745 14592 7746 14593 7748 14593 7747 14593 7749 14594 7748 14594 7746 14594 7749 14595 7750 14595 7748 14595 7751 14596 7750 14596 7749 14596 7751 14597 7752 14597 7750 14597 7751 14598 7753 14598 7752 14598 7754 14599 7753 14599 7751 14599 7754 14600 7755 14600 7753 14600 7754 14601 7756 14601 7755 14601 7757 14602 7756 14602 7754 14602 7757 14603 7758 14603 7756 14603 7759 14604 7758 14604 7757 14604 7759 14605 7760 14605 7758 14605 7761 14606 7760 14606 7759 14606 7761 14607 7762 14607 7760 14607 7763 14608 7762 14608 7761 14608 7763 14609 7764 14609 7762 14609 7763 14610 7765 14610 7764 14610 7766 14611 7765 14611 7763 14611 7766 14612 7767 14612 7765 14612 7768 14613 7767 14613 7766 14613 7768 14614 7769 14614 7767 14614 7770 14615 7769 14615 7768 14615 7770 14616 7160 14616 7769 14616 7770 14617 7159 14617 7160 14617 7771 14618 7159 14618 7770 14618 7771 14619 7157 14619 7159 14619 7772 14620 7157 14620 7771 14620 7772 14621 7155 14621 7157 14621 7177 14622 7175 14622 7773 14622 7179 14623 7177 14623 7773 14623 7774 14624 7179 14624 7773 14624 7775 14625 7179 14625 7774 14625 7182 14626 7179 14626 7775 14626 7776 14627 7182 14627 7775 14627 7184 14628 7182 14628 7776 14628 7187 14629 7184 14629 7776 14629 7191 14630 7189 14630 7777 14630 7778 14631 7191 14631 7777 14631 7193 14632 7191 14632 7778 14632 7779 14633 7195 14633 7193 14633 7197 14634 7195 14634 7779 14634 7780 14635 7197 14635 7779 14635 7199 14636 7197 14636 7780 14636 7781 14637 7199 14637 7780 14637 7202 14638 7199 14638 7781 14638 7204 14639 7202 14639 7782 14639 7206 14640 7204 14640 7782 14640 7211 14641 7209 14641 7783 14641 7213 14642 7211 14642 7783 14642 7784 14643 7213 14643 7783 14643 7214 14644 7213 14644 7784 14644 7217 14645 7214 14645 7784 14645 7219 14646 7217 14646 7785 14646 7786 14647 7219 14647 7785 14647 7222 14648 7219 14648 7786 14648 7787 14649 7222 14649 7786 14649 7224 14650 7222 14650 7787 14650 7226 14651 7224 14651 7787 14651 7788 14652 7229 14652 7226 14652 7231 14653 7229 14653 7788 14653 7248 14654 7246 14654 7789 14654 7790 14655 7248 14655 7789 14655 7251 14656 7248 14656 7790 14656 7791 14657 7251 14657 7790 14657 7254 14658 7251 14658 7791 14658 7792 14659 7256 14659 7254 14659 7259 14660 7256 14660 7792 14660 7793 14661 7261 14661 7259 14661 7263 14662 7261 14662 7793 14662 7794 14663 7263 14663 7793 14663 7265 14664 7263 14664 7794 14664 7795 14665 7265 14665 7794 14665 7267 14666 7265 14666 7795 14666 7796 14667 7267 14667 7795 14667 7270 14668 7267 14668 7796 14668 7797 14669 7272 14669 7270 14669 7274 14670 7272 14670 7797 14670 7798 14671 7274 14671 7797 14671 7277 14672 7274 14672 7798 14672 7799 14673 7277 14673 7798 14673 7279 14674 7277 14674 7799 14674 7800 14675 7279 14675 7799 14675 7282 14676 7279 14676 7800 14676 7801 14677 7282 14677 7800 14677 7283 14678 7282 14678 7801 14678 7286 14679 7283 14679 7801 14679 7287 14680 7286 14680 7802 14680 7289 14681 7287 14681 7802 14681 7803 14682 7291 14682 7289 14682 7293 14683 7291 14683 7803 14683 7804 14684 7295 14684 7293 14684 7298 14685 7295 14685 7804 14685 7303 14686 7301 14686 7805 14686 7303 14687 7805 14687 7806 14687 7305 14688 7303 14688 7806 14688 7307 14689 7305 14689 7806 14689 7807 14690 7307 14690 7806 14690 7309 14691 7307 14691 7807 14691 7311 14692 7309 14692 7807 14692 7808 14693 7311 14693 7807 14693 7313 14694 7311 14694 7808 14694 7809 14695 7313 14695 7808 14695 7316 14696 7313 14696 7809 14696 7810 14697 7316 14697 7809 14697 7319 14698 7316 14698 7810 14698 7811 14699 7319 14699 7810 14699 7321 14700 7319 14700 7811 14700 7812 14701 7321 14701 7811 14701 7323 14702 7321 14702 7812 14702 7813 14703 7323 14703 7812 14703 7326 14704 7323 14704 7813 14704 7814 14705 7328 14705 7326 14705 7331 14706 7328 14706 7814 14706 7340 14707 7338 14707 7815 14707 7342 14708 7340 14708 7815 14708 7345 14709 7342 14709 7816 14709 7347 14710 7345 14710 7816 14710 7817 14711 7347 14711 7816 14711 7349 14712 7347 14712 7817 14712 7818 14713 7349 14713 7817 14713 7351 14714 7349 14714 7818 14714 7351 14715 7818 14715 7819 14715 7354 14716 7351 14716 7819 14716 7820 14717 7359 14717 7357 14717 7361 14718 7359 14718 7820 14718 7821 14719 7361 14719 7820 14719 7363 14720 7361 14720 7821 14720 7822 14721 7363 14721 7821 14721 7365 14722 7363 14722 7822 14722 7823 14723 7365 14723 7822 14723 7368 14724 7365 14724 7823 14724 7370 14725 7368 14725 7823 14725 7824 14726 7370 14726 7823 14726 7373 14727 7370 14727 7824 14727 7825 14728 7373 14728 7824 14728 7376 14729 7373 14729 7825 14729 7826 14730 7377 14730 7376 14730 7379 14731 7377 14731 7826 14731 7381 14732 7379 14732 7827 14732 7384 14733 7381 14733 7827 14733 7828 14734 7384 14734 7827 14734 7386 14735 7384 14735 7828 14735 7829 14736 7389 14736 7386 14736 7391 14737 7389 14737 7829 14737 7830 14738 7391 14738 7829 14738 7394 14739 7391 14739 7830 14739 7396 14740 7394 14740 7830 14740 7399 14741 7396 14741 7831 14741 7399 14742 7831 14742 7832 14742 7401 14743 7399 14743 7832 14743 7833 14744 7401 14744 7832 14744 7403 14745 7401 14745 7833 14745 7404 14746 7403 14746 7833 14746 7834 14747 7409 14747 7406 14747 7835 14748 7409 14748 7834 14748 7412 14749 7409 14749 7835 14749 7414 14750 7412 14750 7835 14750 7836 14751 7414 14751 7835 14751 7837 14752 7414 14752 7836 14752 7416 14753 7414 14753 7837 14753 7419 14754 7416 14754 7837 14754 7425 14755 7423 14755 7838 14755 7427 14756 7425 14756 7838 14756 7839 14757 7427 14757 7838 14757 7840 14758 7427 14758 7839 14758 7430 14759 7427 14759 7840 14759 7432 14760 7430 14760 7840 14760 7841 14761 7432 14761 7840 14761 7436 14762 7432 14762 7841 14762 7842 14763 7437 14763 7436 14763 7439 14764 7437 14764 7842 14764 7843 14765 7439 14765 7842 14765 7442 14766 7439 14766 7843 14766 7844 14767 7444 14767 7442 14767 7845 14768 7444 14768 7844 14768 7447 14769 7444 14769 7845 14769 7846 14770 7447 14770 7845 14770 7450 14771 7447 14771 7846 14771 7452 14772 7450 14772 7846 14772 7454 14773 7452 14773 7847 14773 7848 14774 7454 14774 7847 14774 7457 14775 7454 14775 7848 14775 7849 14776 7457 14776 7848 14776 7459 14777 7457 14777 7849 14777 7850 14778 7459 14778 7849 14778 7851 14779 7459 14779 7850 14779 7462 14780 7459 14780 7851 14780 7464 14781 7462 14781 7851 14781 7852 14782 7464 14782 7851 14782 7467 14783 7464 14783 7852 14783 7853 14784 7471 14784 7469 14784 7473 14785 7471 14785 7853 14785 7854 14786 7473 14786 7853 14786 7475 14787 7473 14787 7854 14787 7855 14788 7479 14788 7478 14788 7482 14789 7479 14789 7855 14789 7856 14790 7482 14790 7855 14790 7484 14791 7482 14791 7856 14791 7857 14792 7484 14792 7856 14792 7487 14793 7484 14793 7857 14793 7858 14794 7487 14794 7857 14794 7489 14795 7487 14795 7858 14795 7859 14796 7489 14796 7858 14796 7492 14797 7489 14797 7859 14797 7860 14798 7492 14798 7859 14798 7861 14799 7492 14799 7860 14799 7495 14800 7492 14800 7861 14800 7497 14801 7495 14801 7861 14801 7862 14802 7497 14802 7861 14802 7499 14803 7497 14803 7862 14803 7863 14804 7499 14804 7862 14804 7502 14805 7499 14805 7863 14805 7864 14806 7502 14806 7863 14806 7505 14807 7502 14807 7864 14807 7507 14808 7505 14808 7864 14808 7865 14809 7507 14809 7864 14809 7510 14810 7507 14810 7865 14810 7866 14811 7510 14811 7865 14811 7512 14812 7510 14812 7866 14812 7867 14813 7512 14813 7866 14813 7515 14814 7512 14814 7867 14814 7868 14815 7515 14815 7867 14815 7517 14816 7515 14816 7868 14816 7869 14817 7517 14817 7868 14817 7518 14818 7517 14818 7869 14818 7521 14819 7518 14819 7869 14819 7870 14820 7523 14820 7521 14820 7525 14821 7523 14821 7870 14821 7871 14822 7525 14822 7870 14822 7527 14823 7525 14823 7871 14823 7872 14824 7527 14824 7871 14824 7529 14825 7527 14825 7872 14825 7532 14826 7529 14826 7872 14826 7534 14827 7532 14827 7873 14827 7537 14828 7534 14828 7873 14828 7539 14829 7537 14829 7874 14829 7542 14830 7539 14830 7874 14830 7546 14831 7544 14831 7875 14831 7876 14832 7546 14832 7875 14832 7548 14833 7546 14833 7876 14833 7548 14834 7876 14834 7877 14834 7551 14835 7548 14835 7877 14835 7878 14836 7551 14836 7877 14836 7554 14837 7551 14837 7878 14837 7879 14838 7555 14838 7554 14838 7558 14839 7555 14839 7879 14839 7560 14840 7558 14840 7879 14840 7880 14841 7562 14841 7560 14841 7565 14842 7562 14842 7880 14842 7881 14843 7567 14843 7565 14843 7570 14844 7567 14844 7881 14844 7571 14845 7570 14845 7882 14845 7883 14846 7571 14846 7882 14846 7574 14847 7571 14847 7883 14847 7576 14848 7574 14848 7883 14848 7884 14849 7576 14849 7883 14849 7578 14850 7576 14850 7884 14850 7885 14851 7580 14851 7578 14851 7583 14852 7580 14852 7885 14852 7886 14853 7583 14853 7885 14853 7584 14854 7583 14854 7886 14854 7887 14855 7586 14855 7584 14855 7588 14856 7586 14856 7887 14856 7888 14857 7588 14857 7887 14857 7591 14858 7588 14858 7888 14858 7889 14859 7591 14859 7888 14859 7593 14860 7591 14860 7889 14860 7890 14861 7593 14861 7889 14861 7595 14862 7593 14862 7890 14862 7891 14863 7597 14863 7595 14863 7600 14864 7597 14864 7891 14864 7892 14865 7600 14865 7891 14865 7602 14866 7600 14866 7892 14866 7605 14867 7602 14867 7892 14867 7607 14868 7605 14868 7893 14868 7894 14869 7607 14869 7893 14869 7609 14870 7607 14870 7894 14870 7895 14871 7609 14871 7894 14871 7612 14872 7609 14872 7895 14872 7896 14873 7612 14873 7895 14873 7897 14874 7612 14874 7896 14874 7615 14875 7612 14875 7897 14875 7898 14876 7615 14876 7897 14876 7617 14877 7615 14877 7898 14877 7899 14878 7617 14878 7898 14878 7619 14879 7617 14879 7899 14879 7621 14880 7619 14880 7899 14880 7623 14881 7621 14881 7900 14881 7901 14882 7623 14882 7900 14882 7626 14883 7623 14883 7901 14883 7902 14884 7626 14884 7901 14884 7628 14885 7626 14885 7902 14885 7628 14886 7902 14886 7903 14886 7632 14887 7628 14887 7903 14887 7904 14888 7632 14888 7903 14888 7634 14889 7632 14889 7904 14889 7905 14890 7636 14890 7634 14890 7638 14891 7636 14891 7905 14891 7906 14892 7638 14892 7905 14892 7640 14893 7638 14893 7906 14893 7650 14894 7647 14894 7907 14894 7908 14895 7650 14895 7907 14895 7652 14896 7650 14896 7908 14896 7909 14897 7652 14897 7908 14897 7655 14898 7652 14898 7909 14898 7910 14899 7655 14899 7909 14899 7658 14900 7655 14900 7910 14900 7911 14901 7658 14901 7910 14901 7660 14902 7658 14902 7911 14902 7912 14903 7660 14903 7911 14903 7662 14904 7660 14904 7912 14904 7913 14905 7662 14905 7912 14905 7665 14906 7662 14906 7913 14906 7914 14907 7665 14907 7913 14907 7667 14908 7665 14908 7914 14908 7669 14909 7667 14909 7914 14909 7915 14910 7675 14910 7673 14910 7677 14911 7675 14911 7915 14911 7916 14912 7677 14912 7915 14912 7680 14913 7677 14913 7916 14913 7688 14914 7687 14914 7917 14914 7691 14915 7688 14915 7917 14915 7918 14916 7693 14916 7691 14916 7695 14917 7693 14917 7918 14917 7919 14918 7695 14918 7918 14918 7697 14919 7695 14919 7919 14919 7920 14920 7697 14920 7919 14920 7699 14921 7697 14921 7920 14921 7921 14922 7699 14922 7920 14922 7702 14923 7699 14923 7921 14923 7922 14924 7702 14924 7921 14924 7704 14925 7702 14925 7922 14925 7923 14926 7704 14926 7922 14926 7708 14927 7704 14927 7923 14927 7709 14928 7708 14928 7923 14928 7712 14929 7709 14929 7924 14929 7925 14930 7712 14930 7924 14930 7926 14931 7712 14931 7925 14931 7715 14932 7712 14932 7926 14932 7927 14933 7715 14933 7926 14933 7717 14934 7715 14934 7927 14934 7719 14935 7717 14935 7927 14935 7928 14936 7723 14936 7721 14936 7725 14937 7723 14937 7928 14937 7929 14938 7725 14938 7928 14938 7727 14939 7725 14939 7929 14939 7930 14940 7729 14940 7727 14940 7732 14941 7729 14941 7930 14941 7739 14942 7737 14942 7931 14942 7932 14943 7739 14943 7931 14943 7741 14944 7739 14944 7932 14944 7933 14945 7741 14945 7932 14945 7743 14946 7741 14946 7933 14946 7934 14947 7743 14947 7933 14947 7746 14948 7743 14948 7934 14948 7935 14949 7746 14949 7934 14949 7749 14950 7746 14950 7935 14950 7936 14951 7751 14951 7749 14951 7754 14952 7751 14952 7936 14952 7937 14953 7754 14953 7936 14953 7757 14954 7754 14954 7937 14954 7938 14955 7757 14955 7937 14955 7759 14956 7757 14956 7938 14956 7939 14957 7761 14957 7759 14957 7763 14958 7761 14958 7939 14958 7766 14959 7763 14959 7940 14959 7768 14960 7766 14960 7940 14960 7941 14961 7771 14961 7770 14961 7772 14962 7771 14962 7941 14962 7942 14963 7155 14963 7772 14963 7152 14964 7155 14964 7942 14964 7943 14965 7152 14965 7942 14965 7149 14966 7152 14966 7943 14966 7945 14967 7775 14967 7774 14967 7945 14968 7776 14968 7775 14968 7944 14969 7776 14969 7945 14969 7944 14970 7187 14970 7776 14970 7944 14971 7189 14971 7187 14971 7161 14972 7189 14972 7944 14972 7162 14973 7189 14973 7161 14973 7162 14974 7777 14974 7189 14974 7163 14975 7777 14975 7162 14975 7163 14976 7778 14976 7777 14976 7164 14977 7778 14977 7163 14977 7167 14978 7778 14978 7164 14978 7167 14979 7193 14979 7778 14979 7169 14980 7193 14980 7167 14980 7169 14981 7779 14981 7193 14981 7170 14982 7779 14982 7169 14982 7946 14983 7779 14983 7170 14983 7946 14984 7780 14984 7779 14984 7947 14985 7780 14985 7946 14985 7947 14986 7781 14986 7780 14986 7176 14987 7781 14987 7947 14987 7176 14988 7202 14988 7781 14988 7178 14989 7202 14989 7176 14989 7178 14990 7782 14990 7202 14990 7180 14991 7782 14991 7178 14991 7180 14992 7206 14992 7782 14992 7181 14993 7206 14993 7180 14993 7181 14994 7209 14994 7206 14994 7183 14995 7209 14995 7181 14995 7185 14996 7209 14996 7183 14996 7185 14997 7783 14997 7209 14997 7186 14998 7783 14998 7185 14998 7188 14999 7783 14999 7186 14999 7188 15000 7784 15000 7783 15000 7190 15001 7784 15001 7188 15001 7190 15002 7217 15002 7784 15002 7192 15003 7217 15003 7190 15003 7192 15004 7785 15004 7217 15004 7194 15005 7785 15005 7192 15005 7194 15006 7786 15006 7785 15006 7196 15007 7786 15007 7194 15007 7196 15008 7787 15008 7786 15008 7198 15009 7787 15009 7196 15009 7200 15010 7787 15010 7198 15010 7200 15011 7226 15011 7787 15011 7201 15012 7226 15012 7200 15012 7201 15013 7788 15013 7226 15013 7203 15014 7788 15014 7201 15014 7203 15015 7231 15015 7788 15015 7205 15016 7231 15016 7203 15016 7207 15017 7231 15017 7205 15017 7207 15018 7234 15018 7231 15018 7208 15019 7234 15019 7207 15019 7208 15020 7236 15020 7234 15020 7210 15021 7236 15021 7208 15021 7210 15022 7238 15022 7236 15022 7212 15023 7238 15023 7210 15023 7212 15024 7240 15024 7238 15024 7212 15025 7242 15025 7240 15025 7215 15026 7242 15026 7212 15026 7215 15027 7245 15027 7242 15027 7216 15028 7245 15028 7215 15028 7216 15029 7246 15029 7245 15029 7218 15030 7246 15030 7216 15030 7218 15031 7789 15031 7246 15031 7220 15032 7789 15032 7218 15032 7220 15033 7790 15033 7789 15033 7221 15034 7790 15034 7220 15034 7223 15035 7790 15035 7221 15035 7223 15036 7791 15036 7790 15036 7225 15037 7791 15037 7223 15037 7227 15038 7254 15038 7225 15038 7225 15039 7254 15039 7791 15039 7228 15040 7254 15040 7227 15040 7228 15041 7792 15041 7254 15041 7230 15042 7792 15042 7228 15042 7232 15043 7792 15043 7230 15043 7232 15044 7259 15044 7792 15044 7233 15045 7259 15045 7232 15045 7233 15046 7793 15046 7259 15046 7235 15047 7793 15047 7233 15047 7235 15048 7794 15048 7793 15048 7239 15049 7794 15049 7235 15049 7239 15050 7795 15050 7794 15050 7241 15051 7795 15051 7239 15051 7241 15052 7796 15052 7795 15052 7243 15053 7796 15053 7241 15053 7244 15054 7796 15054 7243 15054 7244 15055 7270 15055 7796 15055 7948 15056 7270 15056 7244 15056 7247 15057 7797 15057 7948 15057 7948 15058 7797 15058 7270 15058 7249 15059 7797 15059 7247 15059 7249 15060 7798 15060 7797 15060 7250 15061 7798 15061 7249 15061 7250 15062 7799 15062 7798 15062 7252 15063 7799 15063 7250 15063 7253 15064 7799 15064 7252 15064 7253 15065 7800 15065 7799 15065 7255 15066 7800 15066 7253 15066 7257 15067 7800 15067 7255 15067 7257 15068 7801 15068 7800 15068 7260 15069 7801 15069 7257 15069 7260 15070 7286 15070 7801 15070 7260 15071 7802 15071 7286 15071 7262 15072 7802 15072 7260 15072 7264 15073 7802 15073 7262 15073 7264 15074 7289 15074 7802 15074 7266 15075 7289 15075 7264 15075 7266 15076 7803 15076 7289 15076 7268 15077 7803 15077 7266 15077 7268 15078 7293 15078 7803 15078 7268 15079 7804 15079 7293 15079 7269 15080 7804 15080 7268 15080 7271 15081 7804 15081 7269 15081 7271 15082 7298 15082 7804 15082 7273 15083 7298 15083 7271 15083 7275 15084 7298 15084 7273 15084 7275 15085 7301 15085 7298 15085 7276 15086 7301 15086 7275 15086 7276 15087 7805 15087 7301 15087 7278 15088 7805 15088 7276 15088 7278 15089 7806 15089 7805 15089 7280 15090 7806 15090 7278 15090 7280 15091 7807 15091 7806 15091 7281 15092 7807 15092 7280 15092 7284 15093 7807 15093 7281 15093 7284 15094 7808 15094 7807 15094 7949 15095 7808 15095 7284 15095 7285 15096 7808 15096 7949 15096 7285 15097 7809 15097 7808 15097 7288 15098 7809 15098 7285 15098 7290 15099 7809 15099 7288 15099 7290 15100 7810 15100 7809 15100 7292 15101 7810 15101 7290 15101 7292 15102 7811 15102 7810 15102 7294 15103 7811 15103 7292 15103 7296 15104 7811 15104 7294 15104 7296 15105 7812 15105 7811 15105 7297 15106 7812 15106 7296 15106 7299 15107 7812 15107 7297 15107 7299 15108 7813 15108 7812 15108 7300 15109 7813 15109 7299 15109 7300 15110 7326 15110 7813 15110 7302 15111 7326 15111 7300 15111 7302 15112 7814 15112 7326 15112 7304 15113 7814 15113 7302 15113 7304 15114 7331 15114 7814 15114 7306 15115 7331 15115 7304 15115 7306 15116 7334 15116 7331 15116 7308 15117 7334 15117 7306 15117 7308 15118 7336 15118 7334 15118 7310 15119 7336 15119 7308 15119 7310 15120 7338 15120 7336 15120 7312 15121 7338 15121 7310 15121 7312 15122 7815 15122 7338 15122 7314 15123 7815 15123 7312 15123 7314 15124 7342 15124 7815 15124 7315 15125 7342 15125 7314 15125 7315 15126 7816 15126 7342 15126 7317 15127 7816 15127 7315 15127 7317 15128 7817 15128 7816 15128 7318 15129 7817 15129 7317 15129 7320 15130 7817 15130 7318 15130 7320 15131 7818 15131 7817 15131 7322 15132 7818 15132 7320 15132 7322 15133 7819 15133 7818 15133 7324 15134 7819 15134 7322 15134 7325 15135 7819 15135 7324 15135 7325 15136 7354 15136 7819 15136 7327 15137 7354 15137 7325 15137 7329 15138 7357 15138 7327 15138 7327 15139 7357 15139 7354 15139 7329 15140 7820 15140 7357 15140 7330 15141 7820 15141 7329 15141 7332 15142 7820 15142 7330 15142 7332 15143 7821 15143 7820 15143 7333 15144 7821 15144 7332 15144 7335 15145 7821 15145 7333 15145 7335 15146 7822 15146 7821 15146 7337 15147 7822 15147 7335 15147 7337 15148 7823 15148 7822 15148 7341 15149 7823 15149 7337 15149 7343 15150 7823 15150 7341 15150 7344 15151 7824 15151 7343 15151 7343 15152 7824 15152 7823 15152 7346 15153 7824 15153 7344 15153 7346 15154 7825 15154 7824 15154 7348 15155 7825 15155 7346 15155 7348 15156 7376 15156 7825 15156 7350 15157 7376 15157 7348 15157 7350 15158 7826 15158 7376 15158 7352 15159 7826 15159 7350 15159 7352 15160 7379 15160 7826 15160 7353 15161 7379 15161 7352 15161 7353 15162 7827 15162 7379 15162 7355 15163 7827 15163 7353 15163 7356 15164 7827 15164 7355 15164 7358 15165 7827 15165 7356 15165 7358 15166 7828 15166 7827 15166 7360 15167 7828 15167 7358 15167 7360 15168 7386 15168 7828 15168 7362 15169 7386 15169 7360 15169 7362 15170 7829 15170 7386 15170 7364 15171 7829 15171 7362 15171 7366 15172 7830 15172 7364 15172 7364 15173 7830 15173 7829 15173 7367 15174 7830 15174 7366 15174 7367 15175 7396 15175 7830 15175 7369 15176 7396 15176 7367 15176 7369 15177 7831 15177 7396 15177 7371 15178 7831 15178 7369 15178 7372 15179 7831 15179 7371 15179 7372 15180 7832 15180 7831 15180 7374 15181 7832 15181 7372 15181 7374 15182 7833 15182 7832 15182 7375 15183 7833 15183 7374 15183 7375 15184 7404 15184 7833 15184 7378 15185 7404 15185 7375 15185 7378 15186 7406 15186 7404 15186 7380 15187 7406 15187 7378 15187 7380 15188 7834 15188 7406 15188 7382 15189 7834 15189 7380 15189 7382 15190 7835 15190 7834 15190 7383 15191 7835 15191 7382 15191 7385 15192 7835 15192 7383 15192 7385 15193 7836 15193 7835 15193 7387 15194 7836 15194 7385 15194 7388 15195 7836 15195 7387 15195 7388 15196 7837 15196 7836 15196 7390 15197 7837 15197 7388 15197 7390 15198 7419 15198 7837 15198 7392 15199 7419 15199 7390 15199 7392 15200 7421 15200 7419 15200 7393 15201 7421 15201 7392 15201 7395 15202 7421 15202 7393 15202 7395 15203 7423 15203 7421 15203 7397 15204 7423 15204 7395 15204 7397 15205 7838 15205 7423 15205 7398 15206 7838 15206 7397 15206 7398 15207 7839 15207 7838 15207 7400 15208 7839 15208 7398 15208 7402 15209 7840 15209 7400 15209 7400 15210 7840 15210 7839 15210 7405 15211 7840 15211 7402 15211 7405 15212 7841 15212 7840 15212 7407 15213 7841 15213 7405 15213 7407 15214 7436 15214 7841 15214 7408 15215 7436 15215 7407 15215 7410 15216 7436 15216 7408 15216 7410 15217 7842 15217 7436 15217 7411 15218 7842 15218 7410 15218 7411 15219 7843 15219 7842 15219 7413 15220 7843 15220 7411 15220 7415 15221 7843 15221 7413 15221 7415 15222 7442 15222 7843 15222 7417 15223 7442 15223 7415 15223 7417 15224 7844 15224 7442 15224 7418 15225 7844 15225 7417 15225 7418 15226 7845 15226 7844 15226 7420 15227 7845 15227 7418 15227 7420 15228 7846 15228 7845 15228 7422 15229 7846 15229 7420 15229 7424 15230 7846 15230 7422 15230 7424 15231 7452 15231 7846 15231 7426 15232 7452 15232 7424 15232 7426 15233 7847 15233 7452 15233 7428 15234 7847 15234 7426 15234 7429 15235 7847 15235 7428 15235 7429 15236 7848 15236 7847 15236 7431 15237 7848 15237 7429 15237 7433 15238 7848 15238 7431 15238 7433 15239 7849 15239 7848 15239 7434 15240 7849 15240 7433 15240 7435 15241 7849 15241 7434 15241 7435 15242 7850 15242 7849 15242 7435 15243 7851 15243 7850 15243 7438 15244 7851 15244 7435 15244 7440 15245 7851 15245 7438 15245 7440 15246 7852 15246 7851 15246 7441 15247 7852 15247 7440 15247 7441 15248 7467 15248 7852 15248 7443 15249 7467 15249 7441 15249 7445 15250 7467 15250 7443 15250 7445 15251 7469 15251 7467 15251 7446 15252 7469 15252 7445 15252 7446 15253 7853 15253 7469 15253 7448 15254 7853 15254 7446 15254 7448 15255 7854 15255 7853 15255 7449 15256 7854 15256 7448 15256 7449 15257 7475 15257 7854 15257 7451 15258 7475 15258 7449 15258 7451 15259 7478 15259 7475 15259 7451 15260 7855 15260 7478 15260 7453 15261 7855 15261 7451 15261 7455 15262 7855 15262 7453 15262 7455 15263 7856 15263 7855 15263 7456 15264 7856 15264 7455 15264 7456 15265 7857 15265 7856 15265 7458 15266 7857 15266 7456 15266 7460 15267 7857 15267 7458 15267 7460 15268 7858 15268 7857 15268 7463 15269 7858 15269 7460 15269 7465 15270 7859 15270 7463 15270 7463 15271 7859 15271 7858 15271 7466 15272 7859 15272 7465 15272 7466 15273 7860 15273 7859 15273 7468 15274 7860 15274 7466 15274 7468 15275 7861 15275 7860 15275 7470 15276 7861 15276 7468 15276 7470 15277 7862 15277 7861 15277 7472 15278 7862 15278 7470 15278 7474 15279 7862 15279 7472 15279 7474 15280 7863 15280 7862 15280 7476 15281 7863 15281 7474 15281 7477 15282 7863 15282 7476 15282 7477 15283 7864 15283 7863 15283 7480 15284 7864 15284 7477 15284 7480 15285 7865 15285 7864 15285 7481 15286 7865 15286 7480 15286 7483 15287 7865 15287 7481 15287 7483 15288 7866 15288 7865 15288 7485 15289 7866 15289 7483 15289 7486 15290 7866 15290 7485 15290 7486 15291 7867 15291 7866 15291 7486 15292 7868 15292 7867 15292 7488 15293 7868 15293 7486 15293 7490 15294 7868 15294 7488 15294 7490 15295 7869 15295 7868 15295 7491 15296 7869 15296 7490 15296 7493 15297 7869 15297 7491 15297 7493 15298 7521 15298 7869 15298 7494 15299 7521 15299 7493 15299 7494 15300 7870 15300 7521 15300 7496 15301 7870 15301 7494 15301 7496 15302 7871 15302 7870 15302 7498 15303 7871 15303 7496 15303 7500 15304 7871 15304 7498 15304 7500 15305 7872 15305 7871 15305 7501 15306 7872 15306 7500 15306 7503 15307 7872 15307 7501 15307 7504 15308 7872 15308 7503 15308 7504 15309 7532 15309 7872 15309 7506 15310 7532 15310 7504 15310 7506 15311 7873 15311 7532 15311 7508 15312 7873 15312 7506 15312 7509 15313 7873 15313 7508 15313 7509 15314 7537 15314 7873 15314 7511 15315 7537 15315 7509 15315 7511 15316 7874 15316 7537 15316 7513 15317 7874 15317 7511 15317 7514 15318 7874 15318 7513 15318 7514 15319 7542 15319 7874 15319 7516 15320 7542 15320 7514 15320 7519 15321 7542 15321 7516 15321 7519 15322 7544 15322 7542 15322 7520 15323 7544 15323 7519 15323 7520 15324 7875 15324 7544 15324 7522 15325 7875 15325 7520 15325 7522 15326 7876 15326 7875 15326 7524 15327 7876 15327 7522 15327 7524 15328 7877 15328 7876 15328 7526 15329 7877 15329 7524 15329 7528 15330 7877 15330 7526 15330 7528 15331 7878 15331 7877 15331 7950 15332 7878 15332 7528 15332 7530 15333 7878 15333 7950 15333 7530 15334 7554 15334 7878 15334 7531 15335 7554 15335 7530 15335 7531 15336 7879 15336 7554 15336 7533 15337 7879 15337 7531 15337 7533 15338 7560 15338 7879 15338 7535 15339 7560 15339 7533 15339 7951 15340 7560 15340 7535 15340 7951 15341 7880 15341 7560 15341 7538 15342 7880 15342 7951 15342 7538 15343 7565 15343 7880 15343 7540 15344 7565 15344 7538 15344 7540 15345 7881 15345 7565 15345 7541 15346 7881 15346 7540 15346 7543 15347 7881 15347 7541 15347 7543 15348 7570 15348 7881 15348 7545 15349 7570 15349 7543 15349 7545 15350 7882 15350 7570 15350 7547 15351 7882 15351 7545 15351 7547 15352 7883 15352 7882 15352 7549 15353 7883 15353 7547 15353 7550 15354 7883 15354 7549 15354 7550 15355 7884 15355 7883 15355 7552 15356 7884 15356 7550 15356 7552 15357 7578 15357 7884 15357 7952 15358 7578 15358 7552 15358 7952 15359 7885 15359 7578 15359 7553 15360 7885 15360 7952 15360 7556 15361 7885 15361 7553 15361 7556 15362 7886 15362 7885 15362 7557 15363 7886 15363 7556 15363 7559 15364 7886 15364 7557 15364 7559 15365 7584 15365 7886 15365 7559 15366 7887 15366 7584 15366 7561 15367 7887 15367 7559 15367 7561 15368 7888 15368 7887 15368 7564 15369 7888 15369 7561 15369 7566 15370 7888 15370 7564 15370 7566 15371 7889 15371 7888 15371 7568 15372 7889 15372 7566 15372 7568 15373 7890 15373 7889 15373 7569 15374 7890 15374 7568 15374 7569 15375 7595 15375 7890 15375 7572 15376 7891 15376 7569 15376 7569 15377 7891 15377 7595 15377 7573 15378 7891 15378 7572 15378 7573 15379 7892 15379 7891 15379 7575 15380 7892 15380 7573 15380 7577 15381 7892 15381 7575 15381 7577 15382 7605 15382 7892 15382 7577 15383 7893 15383 7605 15383 7579 15384 7893 15384 7577 15384 7581 15385 7894 15385 7579 15385 7579 15386 7894 15386 7893 15386 7581 15387 7895 15387 7894 15387 7582 15388 7895 15388 7581 15388 7582 15389 7896 15389 7895 15389 7585 15390 7896 15390 7582 15390 7587 15391 7896 15391 7585 15391 7587 15392 7897 15392 7896 15392 7589 15393 7897 15393 7587 15393 7589 15394 7898 15394 7897 15394 7953 15395 7898 15395 7589 15395 7953 15396 7899 15396 7898 15396 7592 15397 7899 15397 7953 15397 7594 15398 7899 15398 7592 15398 7594 15399 7621 15399 7899 15399 7596 15400 7621 15400 7594 15400 7596 15401 7900 15401 7621 15401 7598 15402 7900 15402 7596 15402 7598 15403 7901 15403 7900 15403 7599 15404 7901 15404 7598 15404 7601 15405 7901 15405 7599 15405 7601 15406 7902 15406 7901 15406 7603 15407 7902 15407 7601 15407 7603 15408 7903 15408 7902 15408 7604 15409 7903 15409 7603 15409 7606 15410 7903 15410 7604 15410 7606 15411 7904 15411 7903 15411 7610 15412 7904 15412 7606 15412 7611 15413 7904 15413 7610 15413 7611 15414 7634 15414 7904 15414 7613 15415 7634 15415 7611 15415 7613 15416 7905 15416 7634 15416 7614 15417 7905 15417 7613 15417 7614 15418 7906 15418 7905 15418 7616 15419 7906 15419 7614 15419 7616 15420 7640 15420 7906 15420 7618 15421 7640 15421 7616 15421 7618 15422 7643 15422 7640 15422 7620 15423 7643 15423 7618 15423 7620 15424 7644 15424 7643 15424 7622 15425 7644 15425 7620 15425 7622 15426 7647 15426 7644 15426 7622 15427 7907 15427 7647 15427 7624 15428 7907 15428 7622 15428 7625 15429 7907 15429 7624 15429 7625 15430 7908 15430 7907 15430 7627 15431 7908 15431 7625 15431 7627 15432 7909 15432 7908 15432 7629 15433 7909 15433 7627 15433 7630 15434 7909 15434 7629 15434 7630 15435 7910 15435 7909 15435 7631 15436 7910 15436 7630 15436 7631 15437 7911 15437 7910 15437 7633 15438 7911 15438 7631 15438 7635 15439 7911 15439 7633 15439 7635 15440 7912 15440 7911 15440 7637 15441 7912 15441 7635 15441 7637 15442 7913 15442 7912 15442 7639 15443 7913 15443 7637 15443 7639 15444 7914 15444 7913 15444 7641 15445 7914 15445 7639 15445 7642 15446 7669 15446 7641 15446 7641 15447 7669 15447 7914 15447 7645 15448 7669 15448 7642 15448 7645 15449 7671 15449 7669 15449 7646 15450 7671 15450 7645 15450 7646 15451 7673 15451 7671 15451 7648 15452 7673 15452 7646 15452 7648 15453 7915 15453 7673 15453 7649 15454 7915 15454 7648 15454 7651 15455 7915 15455 7649 15455 7651 15456 7916 15456 7915 15456 7653 15457 7916 15457 7651 15457 7653 15458 7680 15458 7916 15458 7654 15459 7680 15459 7653 15459 7656 15460 7680 15460 7654 15460 7656 15461 7683 15461 7680 15461 7657 15462 7683 15462 7656 15462 7657 15463 7684 15463 7683 15463 7657 15464 7687 15464 7684 15464 7659 15465 7687 15465 7657 15465 7659 15466 7917 15466 7687 15466 7661 15467 7917 15467 7659 15467 7663 15468 7917 15468 7661 15468 7663 15469 7691 15469 7917 15469 7664 15470 7691 15470 7663 15470 7664 15471 7918 15471 7691 15471 7666 15472 7918 15472 7664 15472 7668 15473 7918 15473 7666 15473 7668 15474 7919 15474 7918 15474 7670 15475 7919 15475 7668 15475 7670 15476 7920 15476 7919 15476 7672 15477 7920 15477 7670 15477 7674 15478 7920 15478 7672 15478 7674 15479 7921 15479 7920 15479 7676 15480 7921 15480 7674 15480 7676 15481 7922 15481 7921 15481 7678 15482 7922 15482 7676 15482 7678 15483 7923 15483 7922 15483 7679 15484 7923 15484 7678 15484 7681 15485 7923 15485 7679 15485 7681 15486 7709 15486 7923 15486 7682 15487 7709 15487 7681 15487 7682 15488 7924 15488 7709 15488 7685 15489 7924 15489 7682 15489 7686 15490 7924 15490 7685 15490 7686 15491 7925 15491 7924 15491 7689 15492 7925 15492 7686 15492 7689 15493 7926 15493 7925 15493 7690 15494 7926 15494 7689 15494 7690 15495 7927 15495 7926 15495 7692 15496 7927 15496 7690 15496 7692 15497 7719 15497 7927 15497 7694 15498 7719 15498 7692 15498 7694 15499 7721 15499 7719 15499 7696 15500 7721 15500 7694 15500 7696 15501 7928 15501 7721 15501 7698 15502 7928 15502 7696 15502 7700 15503 7928 15503 7698 15503 7700 15504 7929 15504 7928 15504 7701 15505 7929 15505 7700 15505 7701 15506 7727 15506 7929 15506 7703 15507 7727 15507 7701 15507 7703 15508 7930 15508 7727 15508 7705 15509 7930 15509 7703 15509 7705 15510 7732 15510 7930 15510 7706 15511 7732 15511 7705 15511 7706 15512 7734 15512 7732 15512 7707 15513 7734 15513 7706 15513 7710 15514 7734 15514 7707 15514 7710 15515 7737 15515 7734 15515 7711 15516 7737 15516 7710 15516 7711 15517 7931 15517 7737 15517 7711 15518 7932 15518 7931 15518 7713 15519 7932 15519 7711 15519 7714 15520 7932 15520 7713 15520 7714 15521 7933 15521 7932 15521 7716 15522 7933 15522 7714 15522 7718 15523 7933 15523 7716 15523 7718 15524 7934 15524 7933 15524 7720 15525 7934 15525 7718 15525 7720 15526 7935 15526 7934 15526 7722 15527 7935 15527 7720 15527 7722 15528 7749 15528 7935 15528 7724 15529 7749 15529 7722 15529 7724 15530 7936 15530 7749 15530 7726 15531 7936 15531 7724 15531 7726 15532 7937 15532 7936 15532 7728 15533 7937 15533 7726 15533 7730 15534 7937 15534 7728 15534 7730 15535 7938 15535 7937 15535 7731 15536 7938 15536 7730 15536 7731 15537 7759 15537 7938 15537 7733 15538 7759 15538 7731 15538 7735 15539 7759 15539 7733 15539 7735 15540 7939 15540 7759 15540 7736 15541 7939 15541 7735 15541 7736 15542 7763 15542 7939 15542 7738 15543 7763 15543 7736 15543 7738 15544 7940 15544 7763 15544 7740 15545 7940 15545 7738 15545 7742 15546 7940 15546 7740 15546 7742 15547 7768 15547 7940 15547 7744 15548 7768 15548 7742 15548 7744 15549 7770 15549 7768 15549 7745 15550 7770 15550 7744 15550 7747 15551 7941 15551 7745 15551 7745 15552 7941 15552 7770 15552 7748 15553 7941 15553 7747 15553 7748 15554 7772 15554 7941 15554 7750 15555 7772 15555 7748 15555 7750 15556 7942 15556 7772 15556 7752 15557 7942 15557 7750 15557 7753 15558 7942 15558 7752 15558 7755 15559 7943 15559 7753 15559 7753 15560 7943 15560 7942 15560 7756 15561 7943 15561 7755 15561 7756 15562 7149 15562 7943 15562 7756 15563 7147 15563 7149 15563 7758 15564 7147 15564 7756 15564 7758 15565 7150 15565 7147 15565 7760 15566 7150 15566 7758 15566 7760 15567 7151 15567 7150 15567 7762 15568 7151 15568 7760 15568 7764 15569 7151 15569 7762 15569 7764 15570 7154 15570 7151 15570 7765 15571 7154 15571 7764 15571 7765 15572 7156 15572 7154 15572 7946 15573 7170 15573 7172 15573 7174 15574 7946 15574 7172 15574 7947 15575 7946 15575 7174 15575 7176 15576 7947 15576 7174 15576 7239 15577 7235 15577 7237 15577 7247 15578 7948 15578 7244 15578 7260 15579 7257 15579 7258 15579 7285 15580 7949 15580 7284 15580 7341 15581 7337 15581 7339 15581 7463 15582 7460 15582 7461 15582 7530 15583 7950 15583 7528 15583 7951 15584 7535 15584 7536 15584 7538 15585 7951 15585 7536 15585 7553 15586 7952 15586 7552 15586 7564 15587 7561 15587 7563 15587 7953 15588 7589 15588 7590 15588 7592 15589 7953 15589 7590 15589 7610 15590 7606 15590 7608 15590 7767 15591 7156 15591 7765 15591 7158 15592 7156 15592 7767 15592 7979 15593 7158 15593 7767 15593 7769 15594 7979 15594 7767 15594 7956 15595 7954 15595 7996 15595 7955 15596 7954 15596 7956 15596 7957 15597 7956 15597 7996 15597 7958 15598 7957 15598 7996 15598 7959 15599 7956 15599 7957 15599 7153 15600 7955 15600 7956 15600 7153 15601 7956 15601 7959 15601 7958 15602 7960 15602 7957 15602 7960 15603 7959 15603 7957 15603 7961 15604 7959 15604 7960 15604 7959 15605 7961 15605 7153 15605 7962 15606 7960 15606 7958 15606 7963 15607 7960 15607 7962 15607 7963 15608 7961 15608 7960 15608 7965 15609 7962 15609 7958 15609 7965 15610 7958 15610 7964 15610 7966 15611 7963 15611 7962 15611 7967 15612 7961 15612 7963 15612 7967 15613 7963 15613 7966 15613 7966 15614 7962 15614 7965 15614 7970 15615 7965 15615 7964 15615 7968 15616 7967 15616 7966 15616 7157 15617 7967 15617 7968 15617 7969 15618 7966 15618 7965 15618 7969 15619 7968 15619 7966 15619 7970 15620 7969 15620 7965 15620 7968 15621 7159 15621 7157 15621 7159 15622 7968 15622 7969 15622 7971 15623 7970 15623 7964 15623 7972 15624 7969 15624 7970 15624 7972 15625 7970 15625 7971 15625 7973 15626 7972 15626 7971 15626 7972 15627 7159 15627 7969 15627 7972 15628 7160 15628 7159 15628 7971 15629 7964 15629 7975 15629 7974 15630 7973 15630 7971 15630 7975 15631 7974 15631 7971 15631 7976 15632 7972 15632 7973 15632 7976 15633 7973 15633 7974 15633 7976 15634 7160 15634 7972 15634 7978 15635 7976 15635 7974 15635 7977 15636 7974 15636 7975 15636 7978 15637 7974 15637 7977 15637 7769 15638 7160 15638 7976 15638 7978 15639 7769 15639 7976 15639 7769 15640 7978 15640 7979 15640 7977 15641 7975 15641 7980 15641 7979 15642 7978 15642 7977 15642 7981 15643 7979 15643 7977 15643 7981 15644 7158 15644 7979 15644 7981 15645 7977 15645 7980 15645 7982 15646 7981 15646 7980 15646 7156 15647 7158 15647 7981 15647 7984 15648 7982 15648 7980 15648 7983 15649 7981 15649 7982 15649 7156 15650 7981 15650 7983 15650 7154 15651 7156 15651 7983 15651 7985 15652 7982 15652 7984 15652 7984 15653 7980 15653 7986 15653 7987 15654 7983 15654 7982 15654 7987 15655 7982 15655 7985 15655 7987 15656 7154 15656 7983 15656 7987 15657 7989 15657 7154 15657 7988 15658 7985 15658 7984 15658 7989 15659 7987 15659 7985 15659 7986 15660 7988 15660 7984 15660 7989 15661 7985 15661 7988 15661 7991 15662 7989 15662 7988 15662 7990 15663 7991 15663 7988 15663 7990 15664 7988 15664 7986 15664 7992 15665 7990 15665 7986 15665 7995 15666 7991 15666 7990 15666 7993 15667 7992 15667 7986 15667 7995 15668 7990 15668 7992 15668 7993 15669 7986 15669 7994 15669 7997 15670 7992 15670 7993 15670 7998 15671 7992 15671 7997 15671 7998 15672 7995 15672 7992 15672 7997 15673 7993 15673 7994 15673 7999 15674 7998 15674 7997 15674 8000 15675 7997 15675 7994 15675 8000 15676 7999 15676 7997 15676 7148 15677 7998 15677 7999 15677 7996 15678 8000 15678 7994 15678 7148 15679 7999 15679 8000 15679 7954 15680 7148 15680 8000 15680 7954 15681 8000 15681 7996 15681 7955 15682 7148 15682 7954 15682 7964 15683 7980 15683 7975 15683 7964 15684 7994 15684 7986 15684 7964 15685 7996 15685 7994 15685 7964 15686 7986 15686 7980 15686 7964 15687 7958 15687 7996 15687 8002 15688 8001 15688 8010 15688 8010 15689 8001 15689 8007 15689 8001 15690 8003 15690 8007 15690 8007 15691 8003 15691 8008 15691 8003 15692 8012 15692 8008 15692 8003 15693 8004 15693 8012 15693 8004 15694 8005 15694 8012 15694 8012 15695 8005 15695 8011 15695 8005 15696 8006 15696 8011 15696 8011 15697 8006 15697 8009 15697 8006 15698 8010 15698 8009 15698 8006 15699 8002 15699 8010 15699 8008 15700 8016 15700 8013 15700 8008 15701 8013 15701 8014 15701 8008 15702 8014 15702 8015 15702 8012 15703 8017 15703 8016 15703 8012 15704 8020 15704 8017 15704 8012 15705 8016 15705 8008 15705 8007 15706 8015 15706 8018 15706 8007 15707 8008 15707 8015 15707 8019 15708 8007 15708 8018 15708 8011 15709 8020 15709 8012 15709 8021 15710 8020 15710 8011 15710 8010 15711 8007 15711 8019 15711 8022 15712 8010 15712 8019 15712 8023 15713 8021 15713 8011 15713 8023 15714 8011 15714 8009 15714 8024 15715 8023 15715 8009 15715 8025 15716 8010 15716 8022 15716 8025 15717 8009 15717 8010 15717 8024 15718 8009 15718 8025 15718 8001 15719 8005 15719 8003 15719 8003 15720 8005 15720 8004 15720 8006 15721 8005 15721 8002 15721 8002 15722 8005 15722 8001 15722 8027 15723 8026 15723 8017 15723 8027 15724 8017 15724 8020 15724 8028 15725 8027 15725 8020 15725 8028 15726 8020 15726 8021 15726 8029 15727 8028 15727 8021 15727 8029 15728 8021 15728 8023 15728 8030 15729 8029 15729 8023 15729 8030 15730 8023 15730 8024 15730 8031 15731 8030 15731 8024 15731 8031 15732 8024 15732 8025 15732 8032 15733 8031 15733 8025 15733 8032 15734 8025 15734 8022 15734 8033 15735 8032 15735 8022 15735 8034 15736 8033 15736 8022 15736 8034 15737 8022 15737 8019 15737 8035 15738 8034 15738 8019 15738 8035 15739 8019 15739 8018 15739 8036 15740 8035 15740 8018 15740 8036 15741 8018 15741 8015 15741 8037 15742 8036 15742 8015 15742 8037 15743 8015 15743 8014 15743 8038 15744 8014 15744 8013 15744 8038 15745 8037 15745 8014 15745 8039 15746 8038 15746 8013 15746 8039 15747 8013 15747 8016 15747 8026 15748 8039 15748 8016 15748 8026 15749 8016 15749 8017 15749 7175 15750 8035 15750 8036 15750 7773 15751 7175 15751 8036 15751 7175 15752 8034 15752 8035 15752 7173 15753 8034 15753 7175 15753 7773 15754 8036 15754 8037 15754 7166 15755 8034 15755 7173 15755 7166 15756 8033 15756 8034 15756 7774 15757 7773 15757 8037 15757 7166 15758 8032 15758 8033 15758 7171 15759 8032 15759 7166 15759 7774 15760 8037 15760 8038 15760 7945 15761 7774 15761 8038 15761 7171 15762 8031 15762 8032 15762 7168 15763 8031 15763 7171 15763 8039 15764 7945 15764 8038 15764 8030 15765 8031 15765 7168 15765 8030 15766 7168 15766 7165 15766 8039 15767 7944 15767 7945 15767 8026 15768 7944 15768 8039 15768 8029 15769 8030 15769 7165 15769 8027 15770 7944 15770 8026 15770 8029 15771 7165 15771 7162 15771 8028 15772 8029 15772 7162 15772 8027 15773 7161 15773 7944 15773 8028 15774 7162 15774 7161 15774 8028 15775 7161 15775 8027 15775

+
+ + + +

8040 15776 8041 15776 8884 15776 8042 15777 8041 15777 8040 15777 8041 15778 8043 15778 8884 15778 8042 15779 8044 15779 8041 15779 8884 15780 8043 15780 8879 15780 8045 15781 8044 15781 8042 15781 8043 15782 8046 15782 8879 15782 8879 15783 8046 15783 8877 15783 8849 15784 8044 15784 8045 15784 8046 15785 8047 15785 8877 15785 8849 15786 8048 15786 8044 15786 8849 15787 8049 15787 8048 15787 8049 15788 8050 15788 8048 15788 8655 15789 8873 15789 8047 15789 8049 15790 8051 15790 8050 15790 8051 15791 8857 15791 8050 15791 8058 15792 8055 15792 8054 15792 8058 15793 8057 15793 8055 15793 8058 15794 8059 15794 8057 15794 8061 15795 8059 15795 8058 15795 8061 15796 8060 15796 8059 15796 8056 15797 8060 15797 8061 15797 8056 15798 8062 15798 8060 15798 8063 15799 8062 15799 8056 15799 8063 15800 8064 15800 8062 15800 8065 15801 8064 15801 8063 15801 8065 15802 8066 15802 8064 15802 8065 15803 8067 15803 8066 15803 8068 15804 8067 15804 8065 15804 8068 15805 8069 15805 8067 15805 8070 15806 8069 15806 8068 15806 8070 15807 8071 15807 8069 15807 8072 15808 8071 15808 8070 15808 8072 15809 8073 15809 8071 15809 8074 15810 8073 15810 8072 15810 8074 15811 8075 15811 8073 15811 8076 15812 8077 15812 8074 15812 8074 15813 8077 15813 8075 15813 8076 15814 8078 15814 8077 15814 8079 15815 8078 15815 8076 15815 8079 15816 8080 15816 8078 15816 8081 15817 8080 15817 8079 15817 8082 15818 8080 15818 8081 15818 8082 15819 8083 15819 8080 15819 8084 15820 8083 15820 8082 15820 8084 15821 8085 15821 8083 15821 8086 15822 8087 15822 8084 15822 8084 15823 8087 15823 8085 15823 8086 15824 8088 15824 8087 15824 8089 15825 8088 15825 8086 15825 8089 15826 8090 15826 8088 15826 8089 15827 8091 15827 8090 15827 8092 15828 8091 15828 8089 15828 8092 15829 8093 15829 8091 15829 8094 15830 8093 15830 8092 15830 8094 15831 8095 15831 8093 15831 8096 15832 8095 15832 8094 15832 8096 15833 8097 15833 8095 15833 8096 15834 8098 15834 8097 15834 8099 15835 8098 15835 8096 15835 8099 15836 8100 15836 8098 15836 8101 15837 8100 15837 8099 15837 8101 15838 8102 15838 8100 15838 8101 15839 8103 15839 8102 15839 8104 15840 8103 15840 8101 15840 8104 15841 8105 15841 8103 15841 8106 15842 8105 15842 8104 15842 8106 15843 8107 15843 8105 15843 8106 15844 8108 15844 8107 15844 8109 15845 8108 15845 8106 15845 8109 15846 8110 15846 8108 15846 8111 15847 8110 15847 8109 15847 8111 15848 8112 15848 8110 15848 8113 15849 8114 15849 8111 15849 8111 15850 8114 15850 8112 15850 8115 15851 8114 15851 8113 15851 8115 15852 8116 15852 8114 15852 8115 15853 8117 15853 8116 15853 8118 15854 8117 15854 8115 15854 8118 15855 8119 15855 8117 15855 8120 15856 8119 15856 8118 15856 8120 15857 8121 15857 8119 15857 8120 15858 8122 15858 8121 15858 8123 15859 8122 15859 8120 15859 8123 15860 8124 15860 8122 15860 8125 15861 8124 15861 8123 15861 8125 15862 8126 15862 8124 15862 8125 15863 8127 15863 8126 15863 8128 15864 8127 15864 8125 15864 8128 15865 8129 15865 8127 15865 8130 15866 8129 15866 8128 15866 8130 15867 8131 15867 8129 15867 8130 15868 8132 15868 8131 15868 8133 15869 8132 15869 8130 15869 8133 15870 8134 15870 8132 15870 8135 15871 8134 15871 8133 15871 8135 15872 8136 15872 8134 15872 8135 15873 8137 15873 8136 15873 8138 15874 8137 15874 8135 15874 8139 15875 8137 15875 8138 15875 8139 15876 8140 15876 8137 15876 8141 15877 8142 15877 8139 15877 8139 15878 8142 15878 8140 15878 8141 15879 8143 15879 8142 15879 8144 15880 8143 15880 8141 15880 8144 15881 8145 15881 8143 15881 8144 15882 8146 15882 8145 15882 8147 15883 8146 15883 8144 15883 8147 15884 8148 15884 8146 15884 8147 15885 8149 15885 8148 15885 8150 15886 8149 15886 8147 15886 8150 15887 8151 15887 8149 15887 8152 15888 8151 15888 8150 15888 8152 15889 8153 15889 8151 15889 8152 15890 8154 15890 8153 15890 8155 15891 8154 15891 8152 15891 8155 15892 8156 15892 8154 15892 8157 15893 8156 15893 8155 15893 8157 15894 8158 15894 8156 15894 8159 15895 8158 15895 8157 15895 8159 15896 8160 15896 8158 15896 8161 15897 8160 15897 8159 15897 8161 15898 8162 15898 8160 15898 8161 15899 8163 15899 8162 15899 8164 15900 8163 15900 8161 15900 8164 15901 8165 15901 8163 15901 8166 15902 8165 15902 8164 15902 8166 15903 8167 15903 8165 15903 8168 15904 8167 15904 8166 15904 8168 15905 8169 15905 8167 15905 8170 15906 8169 15906 8168 15906 8170 15907 8171 15907 8169 15907 8172 15908 8171 15908 8170 15908 8172 15909 8173 15909 8171 15909 8174 15910 8173 15910 8172 15910 8174 15911 8175 15911 8173 15911 8174 15912 8176 15912 8175 15912 8177 15913 8176 15913 8174 15913 8177 15914 8178 15914 8176 15914 8179 15915 8178 15915 8177 15915 8179 15916 8180 15916 8178 15916 8181 15917 8180 15917 8179 15917 8181 15918 8182 15918 8180 15918 8183 15919 8182 15919 8181 15919 8183 15920 8184 15920 8182 15920 8183 15921 8185 15921 8184 15921 8186 15922 8185 15922 8183 15922 8186 15923 8187 15923 8185 15923 8188 15924 8187 15924 8186 15924 8188 15925 8189 15925 8187 15925 8190 15926 8189 15926 8188 15926 8191 15927 8189 15927 8190 15927 8191 15928 8192 15928 8189 15928 8191 15929 8193 15929 8192 15929 8194 15930 8193 15930 8191 15930 8194 15931 8195 15931 8193 15931 8196 15932 8195 15932 8194 15932 8196 15933 8197 15933 8195 15933 8198 15934 8197 15934 8196 15934 8198 15935 8199 15935 8197 15935 8198 15936 8200 15936 8199 15936 8201 15937 8202 15937 8198 15937 8198 15938 8202 15938 8200 15938 8203 15939 8204 15939 8201 15939 8201 15940 8204 15940 8202 15940 8205 15941 8204 15941 8203 15941 8205 15942 8206 15942 8204 15942 8205 15943 8207 15943 8206 15943 8208 15944 8207 15944 8205 15944 8208 15945 8209 15945 8207 15945 8210 15946 8209 15946 8208 15946 8210 15947 8211 15947 8209 15947 8212 15948 8211 15948 8210 15948 8212 15949 8213 15949 8211 15949 8212 15950 8214 15950 8213 15950 8215 15951 8214 15951 8212 15951 8215 15952 8216 15952 8214 15952 8215 15953 8217 15953 8216 15953 8218 15954 8217 15954 8215 15954 8219 15955 8217 15955 8218 15955 8219 15956 8220 15956 8217 15956 8221 15957 8220 15957 8219 15957 8221 15958 8222 15958 8220 15958 8223 15959 8222 15959 8221 15959 8223 15960 8224 15960 8222 15960 8223 15961 8225 15961 8224 15961 8226 15962 8225 15962 8223 15962 8226 15963 8227 15963 8225 15963 8228 15964 8227 15964 8226 15964 8228 15965 8229 15965 8227 15965 8230 15966 8229 15966 8228 15966 8230 15967 8231 15967 8229 15967 8230 15968 8232 15968 8231 15968 8233 15969 8232 15969 8230 15969 8234 15970 8232 15970 8233 15970 8234 15971 8235 15971 8232 15971 8236 15972 8237 15972 8234 15972 8234 15973 8237 15973 8235 15973 8238 15974 8239 15974 8236 15974 8236 15975 8239 15975 8237 15975 8238 15976 8240 15976 8239 15976 8241 15977 8240 15977 8238 15977 8241 15978 8242 15978 8240 15978 8243 15979 8242 15979 8241 15979 8243 15980 8244 15980 8242 15980 8245 15981 8244 15981 8243 15981 8245 15982 8246 15982 8244 15982 8247 15983 8246 15983 8245 15983 8247 15984 8248 15984 8246 15984 8247 15985 8249 15985 8248 15985 8250 15986 8249 15986 8247 15986 8251 15987 8249 15987 8250 15987 8251 15988 8252 15988 8249 15988 8253 15989 8252 15989 8251 15989 8253 15990 8254 15990 8252 15990 8253 15991 8255 15991 8254 15991 8256 15992 8255 15992 8253 15992 8256 15993 8257 15993 8255 15993 8256 15994 8258 15994 8257 15994 8259 15995 8258 15995 8256 15995 8259 15996 8260 15996 8258 15996 8261 15997 8260 15997 8259 15997 8261 15998 8262 15998 8260 15998 8261 15999 8263 15999 8262 15999 8264 16000 8263 16000 8261 16000 8264 16001 8265 16001 8263 16001 8264 16002 8266 16002 8265 16002 8267 16003 8266 16003 8264 16003 8267 16004 8268 16004 8266 16004 8269 16005 8268 16005 8267 16005 8269 16006 8270 16006 8268 16006 8269 16007 8271 16007 8270 16007 8272 16008 8271 16008 8269 16008 8272 16009 8273 16009 8271 16009 8272 16010 8274 16010 8273 16010 8275 16011 8274 16011 8272 16011 8276 16012 8277 16012 8275 16012 8275 16013 8277 16013 8274 16013 8276 16014 8278 16014 8277 16014 8279 16015 8278 16015 8276 16015 8279 16016 8280 16016 8278 16016 8281 16017 8282 16017 8279 16017 8279 16018 8282 16018 8280 16018 8281 16019 8283 16019 8282 16019 8284 16020 8283 16020 8281 16020 8284 16021 8285 16021 8283 16021 8284 16022 8286 16022 8285 16022 8287 16023 8286 16023 8284 16023 8287 16024 8288 16024 8286 16024 8287 16025 8289 16025 8288 16025 8290 16026 8289 16026 8287 16026 8290 16027 8291 16027 8289 16027 8292 16028 8293 16028 8290 16028 8290 16029 8293 16029 8291 16029 8292 16030 8294 16030 8293 16030 8295 16031 8294 16031 8292 16031 8295 16032 8296 16032 8294 16032 8297 16033 8296 16033 8295 16033 8297 16034 8298 16034 8296 16034 8299 16035 8298 16035 8297 16035 8299 16036 8300 16036 8298 16036 8301 16037 8300 16037 8299 16037 8301 16038 8302 16038 8300 16038 8303 16039 8302 16039 8301 16039 8303 16040 8304 16040 8302 16040 8303 16041 8305 16041 8304 16041 8306 16042 8305 16042 8303 16042 8306 16043 8307 16043 8305 16043 8308 16044 8307 16044 8306 16044 8308 16045 8309 16045 8307 16045 8310 16046 8309 16046 8308 16046 8310 16047 8311 16047 8309 16047 8310 16048 8312 16048 8311 16048 8313 16049 8312 16049 8310 16049 8314 16050 8312 16050 8313 16050 8314 16051 8315 16051 8312 16051 8314 16052 8316 16052 8315 16052 8317 16053 8316 16053 8314 16053 8317 16054 8318 16054 8316 16054 8319 16055 8318 16055 8317 16055 8319 16056 8320 16056 8318 16056 8321 16057 8320 16057 8319 16057 8321 16058 8322 16058 8320 16058 8323 16059 8322 16059 8321 16059 8323 16060 8324 16060 8322 16060 8325 16061 8324 16061 8323 16061 8325 16062 8326 16062 8324 16062 8327 16063 8326 16063 8325 16063 8327 16064 8328 16064 8326 16064 8329 16065 8328 16065 8327 16065 8329 16066 8330 16066 8328 16066 8329 16067 8331 16067 8330 16067 8332 16068 8331 16068 8329 16068 8332 16069 8333 16069 8331 16069 8334 16070 8333 16070 8332 16070 8335 16071 8333 16071 8334 16071 8335 16072 8336 16072 8333 16072 8335 16073 8337 16073 8336 16073 8338 16074 8337 16074 8335 16074 8339 16075 8340 16075 8338 16075 8338 16076 8340 16076 8337 16076 8341 16077 8340 16077 8339 16077 8341 16078 8342 16078 8340 16078 8341 16079 8343 16079 8342 16079 8344 16080 8343 16080 8341 16080 8344 16081 8345 16081 8343 16081 8346 16082 8345 16082 8344 16082 8346 16083 8347 16083 8345 16083 8346 16084 8348 16084 8347 16084 8349 16085 8348 16085 8346 16085 8349 16086 8350 16086 8348 16086 8349 16087 8351 16087 8350 16087 8352 16088 8351 16088 8349 16088 8352 16089 8353 16089 8351 16089 8354 16090 8353 16090 8352 16090 8354 16091 8355 16091 8353 16091 8356 16092 8355 16092 8354 16092 8357 16093 8355 16093 8356 16093 8357 16094 8358 16094 8355 16094 8359 16095 8358 16095 8357 16095 8359 16096 8360 16096 8358 16096 8361 16097 8360 16097 8359 16097 8361 16098 8362 16098 8360 16098 8363 16099 8362 16099 8361 16099 8363 16100 8364 16100 8362 16100 8365 16101 8364 16101 8363 16101 8365 16102 8366 16102 8364 16102 8365 16103 8367 16103 8366 16103 8368 16104 8367 16104 8365 16104 8369 16105 8367 16105 8368 16105 8369 16106 8370 16106 8367 16106 8371 16107 8370 16107 8369 16107 8371 16108 8372 16108 8370 16108 8371 16109 8373 16109 8372 16109 8374 16110 8373 16110 8371 16110 8374 16111 8375 16111 8373 16111 8374 16112 8376 16112 8375 16112 8377 16113 8376 16113 8374 16113 8377 16114 8378 16114 8376 16114 8377 16115 8379 16115 8378 16115 8380 16116 8379 16116 8377 16116 8380 16117 8381 16117 8379 16117 8382 16118 8383 16118 8380 16118 8380 16119 8383 16119 8381 16119 8382 16120 8384 16120 8383 16120 8385 16121 8384 16121 8382 16121 8385 16122 8386 16122 8384 16122 8387 16123 8386 16123 8385 16123 8387 16124 8388 16124 8386 16124 8389 16125 8388 16125 8387 16125 8389 16126 8390 16126 8388 16126 8391 16127 8390 16127 8389 16127 8391 16128 8392 16128 8390 16128 8391 16129 8393 16129 8392 16129 8394 16130 8393 16130 8391 16130 8394 16131 8395 16131 8393 16131 8394 16132 8396 16132 8395 16132 8397 16133 8396 16133 8394 16133 8397 16134 8398 16134 8396 16134 8399 16135 8398 16135 8397 16135 8399 16136 8400 16136 8398 16136 8401 16137 8400 16137 8399 16137 8401 16138 8402 16138 8400 16138 8403 16139 8402 16139 8401 16139 8403 16140 8404 16140 8402 16140 8403 16141 8405 16141 8404 16141 8406 16142 8405 16142 8403 16142 8406 16143 8407 16143 8405 16143 8408 16144 8407 16144 8406 16144 8408 16145 8409 16145 8407 16145 8410 16146 8409 16146 8408 16146 8410 16147 8411 16147 8409 16147 8410 16148 8412 16148 8411 16148 8413 16149 8412 16149 8410 16149 8413 16150 8414 16150 8412 16150 8415 16151 8414 16151 8413 16151 8415 16152 8416 16152 8414 16152 8415 16153 8417 16153 8416 16153 8418 16154 8417 16154 8415 16154 8418 16155 8419 16155 8417 16155 8420 16156 8419 16156 8418 16156 8421 16157 8419 16157 8420 16157 8421 16158 8422 16158 8419 16158 8423 16159 8422 16159 8421 16159 8423 16160 8424 16160 8422 16160 8425 16161 8424 16161 8423 16161 8425 16162 8426 16162 8424 16162 8425 16163 8427 16163 8426 16163 8428 16164 8427 16164 8425 16164 8428 16165 8429 16165 8427 16165 8430 16166 8429 16166 8428 16166 8430 16167 8431 16167 8429 16167 8432 16168 8431 16168 8430 16168 8432 16169 8433 16169 8431 16169 8434 16170 8435 16170 8432 16170 8432 16171 8435 16171 8433 16171 8434 16172 8436 16172 8435 16172 8437 16173 8436 16173 8434 16173 8437 16174 8438 16174 8436 16174 8439 16175 8438 16175 8437 16175 8439 16176 8440 16176 8438 16176 8439 16177 8441 16177 8440 16177 8442 16178 8441 16178 8439 16178 8442 16179 8443 16179 8441 16179 8444 16180 8443 16180 8442 16180 8445 16181 8443 16181 8444 16181 8445 16182 8446 16182 8443 16182 8445 16183 8447 16183 8446 16183 8448 16184 8447 16184 8445 16184 8448 16185 8449 16185 8447 16185 8450 16186 8449 16186 8448 16186 8450 16187 8451 16187 8449 16187 8452 16188 8451 16188 8450 16188 8452 16189 8453 16189 8451 16189 8452 16190 8454 16190 8453 16190 8455 16191 8454 16191 8452 16191 8455 16192 8456 16192 8454 16192 8457 16193 8456 16193 8455 16193 8457 16194 8458 16194 8456 16194 8457 16195 8459 16195 8458 16195 8460 16196 8459 16196 8457 16196 8460 16197 8461 16197 8459 16197 8462 16198 8461 16198 8460 16198 8462 16199 8463 16199 8461 16199 8462 16200 8464 16200 8463 16200 8465 16201 8466 16201 8462 16201 8462 16202 8466 16202 8464 16202 8465 16203 8467 16203 8466 16203 8465 16204 8468 16204 8467 16204 8469 16205 8468 16205 8465 16205 8469 16206 8470 16206 8468 16206 8471 16207 8470 16207 8469 16207 8471 16208 8472 16208 8470 16208 8473 16209 8472 16209 8471 16209 8473 16210 8474 16210 8472 16210 8475 16211 8474 16211 8473 16211 8476 16212 8474 16212 8475 16212 8476 16213 8477 16213 8474 16213 8476 16214 8478 16214 8477 16214 8479 16215 8478 16215 8476 16215 8479 16216 8480 16216 8478 16216 8481 16217 8480 16217 8479 16217 8482 16218 8480 16218 8481 16218 8482 16219 8483 16219 8480 16219 8482 16220 8484 16220 8483 16220 8485 16221 8484 16221 8482 16221 8485 16222 8486 16222 8484 16222 8487 16223 8486 16223 8485 16223 8487 16224 8488 16224 8486 16224 8489 16225 8488 16225 8487 16225 8489 16226 8490 16226 8488 16226 8491 16227 8492 16227 8489 16227 8489 16228 8492 16228 8490 16228 8491 16229 8493 16229 8492 16229 8494 16230 8493 16230 8491 16230 8494 16231 8495 16231 8493 16231 8496 16232 8495 16232 8494 16232 8497 16233 8498 16233 8496 16233 8496 16234 8498 16234 8495 16234 8497 16235 8499 16235 8498 16235 8500 16236 8499 16236 8497 16236 8500 16237 8501 16237 8499 16237 8502 16238 8501 16238 8500 16238 8502 16239 8503 16239 8501 16239 8504 16240 8503 16240 8502 16240 8504 16241 8505 16241 8503 16241 8506 16242 8505 16242 8504 16242 8506 16243 8507 16243 8505 16243 8508 16244 8507 16244 8506 16244 8508 16245 8509 16245 8507 16245 8510 16246 8509 16246 8508 16246 8510 16247 8511 16247 8509 16247 8512 16248 8511 16248 8510 16248 8512 16249 8513 16249 8511 16249 8512 16250 8514 16250 8513 16250 8515 16251 8514 16251 8512 16251 8515 16252 8516 16252 8514 16252 8515 16253 8517 16253 8516 16253 8518 16254 8517 16254 8515 16254 8519 16255 8517 16255 8518 16255 8519 16256 8520 16256 8517 16256 8521 16257 8522 16257 8519 16257 8519 16258 8522 16258 8520 16258 8521 16259 8523 16259 8522 16259 8524 16260 8523 16260 8521 16260 8525 16261 8523 16261 8524 16261 8525 16262 8526 16262 8523 16262 8525 16263 8527 16263 8526 16263 8528 16264 8527 16264 8525 16264 8528 16265 8529 16265 8527 16265 8528 16266 8530 16266 8529 16266 8531 16267 8530 16267 8528 16267 8531 16268 8532 16268 8530 16268 8533 16269 8532 16269 8531 16269 8533 16270 8534 16270 8532 16270 8533 16271 8535 16271 8534 16271 8536 16272 8535 16272 8533 16272 8536 16273 8537 16273 8535 16273 8538 16274 8537 16274 8536 16274 8539 16275 8540 16275 8538 16275 8538 16276 8540 16276 8537 16276 8539 16277 8541 16277 8540 16277 8542 16278 8541 16278 8539 16278 8542 16279 8543 16279 8541 16279 8542 16280 8544 16280 8543 16280 8545 16281 8544 16281 8542 16281 8545 16282 8546 16282 8544 16282 8545 16283 8547 16283 8546 16283 8548 16284 8547 16284 8545 16284 8548 16285 8549 16285 8547 16285 8550 16286 8549 16286 8548 16286 8550 16287 8551 16287 8549 16287 8552 16288 8551 16288 8550 16288 8552 16289 8553 16289 8551 16289 8552 16290 8554 16290 8553 16290 8555 16291 8554 16291 8552 16291 8556 16292 8554 16292 8555 16292 8556 16293 8557 16293 8554 16293 8558 16294 8557 16294 8556 16294 8558 16295 8559 16295 8557 16295 8558 16296 8560 16296 8559 16296 8561 16297 8560 16297 8558 16297 8561 16298 8562 16298 8560 16298 8561 16299 8563 16299 8562 16299 8564 16300 8563 16300 8561 16300 8564 16301 8565 16301 8563 16301 8566 16302 8565 16302 8564 16302 8566 16303 8567 16303 8565 16303 8568 16304 8567 16304 8566 16304 8568 16305 8569 16305 8567 16305 8568 16306 8570 16306 8569 16306 8571 16307 8570 16307 8568 16307 8571 16308 8572 16308 8570 16308 8573 16309 8572 16309 8571 16309 8573 16310 8574 16310 8572 16310 8573 16311 8575 16311 8574 16311 8576 16312 8575 16312 8573 16312 8576 16313 8577 16313 8575 16313 8576 16314 8578 16314 8577 16314 8579 16315 8578 16315 8576 16315 8579 16316 8580 16316 8578 16316 8581 16317 8580 16317 8579 16317 8581 16318 8582 16318 8580 16318 8583 16319 8582 16319 8581 16319 8583 16320 8584 16320 8582 16320 8583 16321 8585 16321 8584 16321 8586 16322 8585 16322 8583 16322 8587 16323 8585 16323 8586 16323 8587 16324 8588 16324 8585 16324 8589 16325 8590 16325 8587 16325 8587 16326 8590 16326 8588 16326 8591 16327 8590 16327 8589 16327 8591 16328 8592 16328 8590 16328 8591 16329 8593 16329 8592 16329 8594 16330 8593 16330 8591 16330 8594 16331 8595 16331 8593 16331 8596 16332 8595 16332 8594 16332 8596 16333 8597 16333 8595 16333 8596 16334 8598 16334 8597 16334 8599 16335 8598 16335 8596 16335 8599 16336 8600 16336 8598 16336 8601 16337 8600 16337 8599 16337 8601 16338 8602 16338 8600 16338 8601 16339 8603 16339 8602 16339 8604 16340 8603 16340 8601 16340 8604 16341 8605 16341 8603 16341 8606 16342 8605 16342 8604 16342 8606 16343 8607 16343 8605 16343 8608 16344 8607 16344 8606 16344 8608 16345 8609 16345 8607 16345 8608 16346 8610 16346 8609 16346 8611 16347 8610 16347 8608 16347 8611 16348 8612 16348 8610 16348 8611 16349 8613 16349 8612 16349 8614 16350 8613 16350 8611 16350 8614 16351 8615 16351 8613 16351 8614 16352 8616 16352 8615 16352 8617 16353 8616 16353 8614 16353 8617 16354 8618 16354 8616 16354 8619 16355 8618 16355 8617 16355 8619 16356 8620 16356 8618 16356 8621 16357 8622 16357 8619 16357 8619 16358 8622 16358 8620 16358 8623 16359 8622 16359 8621 16359 8623 16360 8624 16360 8622 16360 8623 16361 8625 16361 8624 16361 8626 16362 8625 16362 8623 16362 8627 16363 8625 16363 8626 16363 8627 16364 8628 16364 8625 16364 8627 16365 8629 16365 8628 16365 8630 16366 8629 16366 8627 16366 8630 16367 8631 16367 8629 16367 8632 16368 8631 16368 8630 16368 8632 16369 8633 16369 8631 16369 8632 16370 8634 16370 8633 16370 8635 16371 8634 16371 8632 16371 8635 16372 8636 16372 8634 16372 8637 16373 8636 16373 8635 16373 8637 16374 8638 16374 8636 16374 8639 16375 8638 16375 8637 16375 8639 16376 8640 16376 8638 16376 8641 16377 8640 16377 8639 16377 8641 16378 8642 16378 8640 16378 8641 16379 8643 16379 8642 16379 8644 16380 8643 16380 8641 16380 8644 16381 8645 16381 8643 16381 8644 16382 8646 16382 8645 16382 8647 16383 8646 16383 8644 16383 8647 16384 8648 16384 8646 16384 8649 16385 8648 16385 8647 16385 8649 16386 8650 16386 8648 16386 8651 16387 8650 16387 8649 16387 8651 16388 8652 16388 8650 16388 8651 16389 8653 16389 8652 16389 8654 16390 8653 16390 8651 16390 8654 16391 8655 16391 8653 16391 8656 16392 8655 16392 8654 16392 8656 16393 8657 16393 8655 16393 8656 16394 8658 16394 8657 16394 8656 16395 8052 16395 8658 16395 8659 16396 8052 16396 8656 16396 8659 16397 8857 16397 8052 16397 8659 16398 8050 16398 8857 16398 8660 16399 8050 16399 8659 16399 8661 16400 8050 16400 8660 16400 8661 16401 8048 16401 8050 16401 8662 16402 8063 16402 8056 16402 8065 16403 8063 16403 8662 16403 8663 16404 8065 16404 8662 16404 8068 16405 8065 16405 8663 16405 8664 16406 8072 16406 8070 16406 8074 16407 8072 16407 8664 16407 8665 16408 8074 16408 8664 16408 8076 16409 8074 16409 8665 16409 8081 16410 8079 16410 8076 16410 8666 16411 8086 16411 8084 16411 8089 16412 8086 16412 8666 16412 8667 16413 8089 16413 8666 16413 8092 16414 8089 16414 8667 16414 8668 16415 8096 16415 8094 16415 8099 16416 8096 16416 8668 16416 8669 16417 8099 16417 8668 16417 8101 16418 8099 16418 8669 16418 8101 16419 8669 16419 8670 16419 8104 16420 8101 16420 8670 16420 8671 16421 8104 16421 8670 16421 8106 16422 8104 16422 8671 16422 8672 16423 8106 16423 8671 16423 8109 16424 8106 16424 8672 16424 8673 16425 8109 16425 8672 16425 8111 16426 8109 16426 8673 16426 8113 16427 8111 16427 8673 16427 8674 16428 8115 16428 8113 16428 8118 16429 8115 16429 8674 16429 8123 16430 8120 16430 8675 16430 8125 16431 8123 16431 8675 16431 8128 16432 8125 16432 8676 16432 8677 16433 8128 16433 8676 16433 8130 16434 8128 16434 8677 16434 8678 16435 8130 16435 8677 16435 8133 16436 8130 16436 8678 16436 8135 16437 8133 16437 8678 16437 8679 16438 8135 16438 8678 16438 8138 16439 8135 16439 8679 16439 8680 16440 8141 16440 8139 16440 8144 16441 8141 16441 8680 16441 8681 16442 8144 16442 8680 16442 8147 16443 8144 16443 8681 16443 8682 16444 8147 16444 8681 16444 8150 16445 8147 16445 8682 16445 8683 16446 8150 16446 8682 16446 8152 16447 8150 16447 8683 16447 8684 16448 8152 16448 8683 16448 8155 16449 8152 16449 8684 16449 8157 16450 8155 16450 8685 16450 8159 16451 8157 16451 8685 16451 8161 16452 8159 16452 8686 16452 8164 16453 8161 16453 8686 16453 8687 16454 8164 16454 8686 16454 8166 16455 8164 16455 8687 16455 8688 16456 8166 16456 8687 16456 8168 16457 8166 16457 8688 16457 8689 16458 8168 16458 8688 16458 8170 16459 8168 16459 8689 16459 8172 16460 8170 16460 8689 16460 8690 16461 8172 16461 8689 16461 8174 16462 8172 16462 8690 16462 8691 16463 8174 16463 8690 16463 8177 16464 8174 16464 8691 16464 8692 16465 8177 16465 8691 16465 8179 16466 8177 16466 8692 16466 8181 16467 8179 16467 8692 16467 8183 16468 8181 16468 8693 16468 8694 16469 8183 16469 8693 16469 8186 16470 8183 16470 8694 16470 8695 16471 8186 16471 8694 16471 8188 16472 8186 16472 8695 16472 8190 16473 8188 16473 8695 16473 8696 16474 8191 16474 8190 16474 8194 16475 8191 16475 8696 16475 8196 16476 8194 16476 8696 16476 8198 16477 8196 16477 8697 16477 8698 16478 8198 16478 8697 16478 8201 16479 8198 16479 8698 16479 8203 16480 8201 16480 8698 16480 8699 16481 8205 16481 8203 16481 8208 16482 8205 16482 8699 16482 8700 16483 8212 16483 8210 16483 8215 16484 8212 16484 8700 16484 8218 16485 8215 16485 8700 16485 8219 16486 8218 16486 8701 16486 8221 16487 8219 16487 8701 16487 8702 16488 8221 16488 8701 16488 8223 16489 8221 16489 8702 16489 8703 16490 8226 16490 8223 16490 8228 16491 8226 16491 8703 16491 8704 16492 8230 16492 8228 16492 8233 16493 8230 16493 8704 16493 8705 16494 8233 16494 8704 16494 8234 16495 8233 16495 8705 16495 8706 16496 8234 16496 8705 16496 8236 16497 8234 16497 8706 16497 8707 16498 8236 16498 8706 16498 8238 16499 8236 16499 8707 16499 8241 16500 8238 16500 8707 16500 8245 16501 8243 16501 8708 16501 8709 16502 8245 16502 8708 16502 8247 16503 8245 16503 8709 16503 8250 16504 8247 16504 8709 16504 8253 16505 8251 16505 8710 16505 8253 16506 8710 16506 8711 16506 8256 16507 8253 16507 8711 16507 8712 16508 8256 16508 8711 16508 8259 16509 8256 16509 8712 16509 8713 16510 8259 16510 8712 16510 8261 16511 8259 16511 8713 16511 8714 16512 8261 16512 8713 16512 8715 16513 8261 16513 8714 16513 8264 16514 8261 16514 8715 16514 8267 16515 8264 16515 8715 16515 8269 16516 8267 16516 8716 16516 8717 16517 8269 16517 8716 16517 8272 16518 8269 16518 8717 16518 8275 16519 8272 16519 8717 16519 8276 16520 8275 16520 8718 16520 8719 16521 8276 16521 8718 16521 8279 16522 8276 16522 8719 16522 8720 16523 8279 16523 8719 16523 8281 16524 8279 16524 8720 16524 8721 16525 8281 16525 8720 16525 8284 16526 8281 16526 8721 16526 8722 16527 8284 16527 8721 16527 8287 16528 8284 16528 8722 16528 8723 16529 8287 16529 8722 16529 8724 16530 8287 16530 8723 16530 8290 16531 8287 16531 8724 16531 8292 16532 8290 16532 8724 16532 8295 16533 8292 16533 8725 16533 8297 16534 8295 16534 8725 16534 8726 16535 8297 16535 8725 16535 8299 16536 8297 16536 8726 16536 8727 16537 8299 16537 8726 16537 8301 16538 8299 16538 8727 16538 8728 16539 8301 16539 8727 16539 8303 16540 8301 16540 8728 16540 8729 16541 8303 16541 8728 16541 8306 16542 8303 16542 8729 16542 8730 16543 8306 16543 8729 16543 8308 16544 8306 16544 8730 16544 8731 16545 8317 16545 8314 16545 8319 16546 8317 16546 8731 16546 8732 16547 8319 16547 8731 16547 8321 16548 8319 16548 8732 16548 8733 16549 8321 16549 8732 16549 8323 16550 8321 16550 8733 16550 8734 16551 8325 16551 8323 16551 8327 16552 8325 16552 8734 16552 8735 16553 8327 16553 8734 16553 8329 16554 8327 16554 8735 16554 8736 16555 8329 16555 8735 16555 8332 16556 8329 16556 8736 16556 8334 16557 8332 16557 8736 16557 8737 16558 8335 16558 8334 16558 8338 16559 8335 16559 8737 16559 8341 16560 8339 16560 8738 16560 8344 16561 8341 16561 8738 16561 8346 16562 8344 16562 8739 16562 8740 16563 8346 16563 8739 16563 8349 16564 8346 16564 8740 16564 8741 16565 8349 16565 8740 16565 8742 16566 8349 16566 8741 16566 8352 16567 8349 16567 8742 16567 8354 16568 8352 16568 8742 16568 8743 16569 8363 16569 8361 16569 8365 16570 8363 16570 8743 16570 8371 16571 8369 16571 8744 16571 8745 16572 8371 16572 8744 16572 8374 16573 8371 16573 8745 16573 8746 16574 8374 16574 8745 16574 8747 16575 8374 16575 8746 16575 8377 16576 8374 16576 8747 16576 8380 16577 8377 16577 8747 16577 8380 16578 8747 16578 8748 16578 8749 16579 8380 16579 8748 16579 8382 16580 8380 16580 8749 16580 8750 16581 8382 16581 8749 16581 8385 16582 8382 16582 8750 16582 8751 16583 8385 16583 8750 16583 8387 16584 8385 16584 8751 16584 8752 16585 8387 16585 8751 16585 8389 16586 8387 16586 8752 16586 8389 16587 8752 16587 8753 16587 8391 16588 8389 16588 8753 16588 8754 16589 8391 16589 8753 16589 8394 16590 8391 16590 8754 16590 8755 16591 8394 16591 8754 16591 8397 16592 8394 16592 8755 16592 8756 16593 8397 16593 8755 16593 8399 16594 8397 16594 8756 16594 8401 16595 8399 16595 8756 16595 8403 16596 8401 16596 8757 16596 8406 16597 8403 16597 8757 16597 8408 16598 8406 16598 8758 16598 8410 16599 8408 16599 8758 16599 8759 16600 8413 16600 8410 16600 8415 16601 8413 16601 8759 16601 8760 16602 8415 16602 8759 16602 8418 16603 8415 16603 8760 16603 8761 16604 8418 16604 8760 16604 8420 16605 8418 16605 8761 16605 8423 16606 8421 16606 8762 16606 8763 16607 8423 16607 8762 16607 8425 16608 8423 16608 8763 16608 8428 16609 8425 16609 8763 16609 8764 16610 8430 16610 8428 16610 8432 16611 8430 16611 8764 16611 8765 16612 8434 16612 8432 16612 8437 16613 8434 16613 8765 16613 8766 16614 8439 16614 8437 16614 8767 16615 8439 16615 8766 16615 8442 16616 8439 16616 8767 16616 8444 16617 8442 16617 8767 16617 8448 16618 8445 16618 8768 16618 8450 16619 8448 16619 8768 16619 8452 16620 8450 16620 8769 16620 8770 16621 8452 16621 8769 16621 8455 16622 8452 16622 8770 16622 8771 16623 8457 16623 8455 16623 8772 16624 8457 16624 8771 16624 8460 16625 8457 16625 8772 16625 8773 16626 8460 16626 8772 16626 8462 16627 8460 16627 8773 16627 8774 16628 8462 16628 8773 16628 8465 16629 8462 16629 8774 16629 8775 16630 8465 16630 8774 16630 8469 16631 8465 16631 8775 16631 8776 16632 8476 16632 8475 16632 8479 16633 8476 16633 8776 16633 8482 16634 8481 16634 8777 16634 8778 16635 8482 16635 8777 16635 8485 16636 8482 16636 8778 16636 8487 16637 8485 16637 8778 16637 8779 16638 8487 16638 8778 16638 8489 16639 8487 16639 8779 16639 8780 16640 8491 16640 8489 16640 8494 16641 8491 16641 8780 16641 8496 16642 8494 16642 8781 16642 8782 16643 8497 16643 8496 16643 8500 16644 8497 16644 8782 16644 8502 16645 8500 16645 8782 16645 8504 16646 8502 16646 8783 16646 8506 16647 8504 16647 8783 16647 8784 16648 8515 16648 8512 16648 8518 16649 8515 16649 8784 16649 8519 16650 8518 16650 8785 16650 8521 16651 8519 16651 8785 16651 8524 16652 8521 16652 8786 16652 8787 16653 8524 16653 8786 16653 8525 16654 8524 16654 8787 16654 8788 16655 8525 16655 8787 16655 8528 16656 8525 16656 8788 16656 8789 16657 8528 16657 8788 16657 8531 16658 8528 16658 8789 16658 8790 16659 8533 16659 8531 16659 8536 16660 8533 16660 8790 16660 8538 16661 8536 16661 8791 16661 8539 16662 8538 16662 8791 16662 8792 16663 8539 16663 8791 16663 8793 16664 8539 16664 8792 16664 8542 16665 8539 16665 8793 16665 8545 16666 8542 16666 8793 16666 8794 16667 8545 16667 8793 16667 8795 16668 8545 16668 8794 16668 8548 16669 8545 16669 8795 16669 8550 16670 8548 16670 8795 16670 8796 16671 8550 16671 8795 16671 8552 16672 8550 16672 8796 16672 8797 16673 8552 16673 8796 16673 8555 16674 8552 16674 8797 16674 8798 16675 8558 16675 8556 16675 8799 16676 8558 16676 8798 16676 8561 16677 8558 16677 8799 16677 8800 16678 8561 16678 8799 16678 8564 16679 8561 16679 8800 16679 8801 16680 8564 16680 8800 16680 8566 16681 8564 16681 8801 16681 8802 16682 8566 16682 8801 16682 8568 16683 8566 16683 8802 16683 8803 16684 8568 16684 8802 16684 8571 16685 8568 16685 8803 16685 8804 16686 8571 16686 8803 16686 8573 16687 8571 16687 8804 16687 8805 16688 8573 16688 8804 16688 8576 16689 8573 16689 8805 16689 8806 16690 8576 16690 8805 16690 8579 16691 8576 16691 8806 16691 8583 16692 8581 16692 8807 16692 8583 16693 8807 16693 8586 16693 8587 16694 8586 16694 8808 16694 8809 16695 8589 16695 8587 16695 8591 16696 8589 16696 8809 16696 8810 16697 8591 16697 8809 16697 8594 16698 8591 16698 8810 16698 8596 16699 8594 16699 8810 16699 8811 16700 8596 16700 8810 16700 8812 16701 8596 16701 8811 16701 8599 16702 8596 16702 8812 16702 8601 16703 8599 16703 8812 16703 8813 16704 8604 16704 8601 16704 8606 16705 8604 16705 8813 16705 8814 16706 8606 16706 8813 16706 8608 16707 8606 16707 8814 16707 8815 16708 8608 16708 8814 16708 8816 16709 8608 16709 8815 16709 8611 16710 8608 16710 8816 16710 8817 16711 8611 16711 8816 16711 8614 16712 8611 16712 8817 16712 8818 16713 8614 16713 8817 16713 8617 16714 8614 16714 8818 16714 8619 16715 8617 16715 8818 16715 8819 16716 8630 16716 8627 16716 8820 16717 8630 16717 8819 16717 8632 16718 8630 16718 8820 16718 8639 16719 8637 16719 8821 16719 8641 16720 8639 16720 8821 16720 8644 16721 8641 16721 8822 16721 8823 16722 8644 16722 8822 16722 8647 16723 8644 16723 8823 16723 8824 16724 8647 16724 8823 16724 8649 16725 8647 16725 8824 16725 8651 16726 8649 16726 8824 16726 8825 16727 8651 16727 8824 16727 8654 16728 8651 16728 8825 16728 8826 16729 8654 16729 8825 16729 8656 16730 8654 16730 8826 16730 8827 16731 8656 16731 8826 16731 8828 16732 8656 16732 8827 16732 8659 16733 8656 16733 8828 16733 8829 16734 8659 16734 8828 16734 8660 16735 8659 16735 8829 16735 8661 16736 8660 16736 8829 16736 8048 16737 8661 16737 8830 16737 8831 16738 8048 16738 8830 16738 8044 16739 8048 16739 8831 16739 8832 16740 8044 16740 8831 16740 8041 16741 8044 16741 8832 16741 8833 16742 8068 16742 8663 16742 8833 16743 8070 16743 8068 16743 8835 16744 8070 16744 8833 16744 8835 16745 8664 16745 8070 16745 8835 16746 8665 16746 8664 16746 8834 16747 8665 16747 8835 16747 8834 16748 8076 16748 8665 16748 8053 16749 8076 16749 8834 16749 8054 16750 8076 16750 8053 16750 8054 16751 8081 16751 8076 16751 8055 16752 8081 16752 8054 16752 8055 16753 8082 16753 8081 16753 8057 16754 8082 16754 8055 16754 8059 16755 8082 16755 8057 16755 8059 16756 8084 16756 8082 16756 8060 16757 8084 16757 8059 16757 8060 16758 8666 16758 8084 16758 8062 16759 8666 16759 8060 16759 8062 16760 8667 16760 8666 16760 8064 16761 8667 16761 8062 16761 8064 16762 8092 16762 8667 16762 8066 16763 8092 16763 8064 16763 8066 16764 8094 16764 8092 16764 8067 16765 8094 16765 8066 16765 8067 16766 8668 16766 8094 16766 8069 16767 8668 16767 8067 16767 8836 16768 8668 16768 8069 16768 8836 16769 8669 16769 8668 16769 8073 16770 8669 16770 8836 16770 8075 16771 8669 16771 8073 16771 8075 16772 8670 16772 8669 16772 8077 16773 8670 16773 8075 16773 8078 16774 8670 16774 8077 16774 8078 16775 8671 16775 8670 16775 8078 16776 8672 16776 8671 16776 8080 16777 8672 16777 8078 16777 8083 16778 8672 16778 8080 16778 8083 16779 8673 16779 8672 16779 8085 16780 8673 16780 8083 16780 8085 16781 8113 16781 8673 16781 8087 16782 8113 16782 8085 16782 8088 16783 8113 16783 8087 16783 8088 16784 8674 16784 8113 16784 8090 16785 8674 16785 8088 16785 8090 16786 8118 16786 8674 16786 8093 16787 8118 16787 8090 16787 8093 16788 8120 16788 8118 16788 8095 16789 8120 16789 8093 16789 8095 16790 8675 16790 8120 16790 8097 16791 8675 16791 8095 16791 8097 16792 8125 16792 8675 16792 8098 16793 8125 16793 8097 16793 8100 16794 8125 16794 8098 16794 8100 16795 8676 16795 8125 16795 8102 16796 8676 16796 8100 16796 8102 16797 8677 16797 8676 16797 8103 16798 8677 16798 8102 16798 8103 16799 8678 16799 8677 16799 8105 16800 8678 16800 8103 16800 8107 16801 8678 16801 8105 16801 8108 16802 8679 16802 8107 16802 8107 16803 8679 16803 8678 16803 8110 16804 8679 16804 8108 16804 8110 16805 8138 16805 8679 16805 8112 16806 8138 16806 8110 16806 8114 16807 8138 16807 8112 16807 8114 16808 8139 16808 8138 16808 8114 16809 8680 16809 8139 16809 8116 16810 8680 16810 8114 16810 8117 16811 8680 16811 8116 16811 8117 16812 8681 16812 8680 16812 8119 16813 8681 16813 8117 16813 8121 16814 8681 16814 8119 16814 8121 16815 8682 16815 8681 16815 8122 16816 8682 16816 8121 16816 8124 16817 8682 16817 8122 16817 8124 16818 8683 16818 8682 16818 8126 16819 8683 16819 8124 16819 8126 16820 8684 16820 8683 16820 8127 16821 8684 16821 8126 16821 8127 16822 8155 16822 8684 16822 8129 16823 8155 16823 8127 16823 8129 16824 8685 16824 8155 16824 8131 16825 8685 16825 8129 16825 8132 16826 8685 16826 8131 16826 8132 16827 8159 16827 8685 16827 8134 16828 8159 16828 8132 16828 8134 16829 8686 16829 8159 16829 8136 16830 8686 16830 8134 16830 8137 16831 8686 16831 8136 16831 8137 16832 8687 16832 8686 16832 8140 16833 8687 16833 8137 16833 8142 16834 8687 16834 8140 16834 8142 16835 8688 16835 8687 16835 8143 16836 8688 16836 8142 16836 8143 16837 8689 16837 8688 16837 8145 16838 8689 16838 8143 16838 8145 16839 8690 16839 8689 16839 8146 16840 8690 16840 8145 16840 8148 16841 8690 16841 8146 16841 8149 16842 8690 16842 8148 16842 8149 16843 8691 16843 8690 16843 8151 16844 8691 16844 8149 16844 8151 16845 8692 16845 8691 16845 8153 16846 8692 16846 8151 16846 8153 16847 8181 16847 8692 16847 8154 16848 8181 16848 8153 16848 8154 16849 8693 16849 8181 16849 8156 16850 8693 16850 8154 16850 8158 16851 8693 16851 8156 16851 8158 16852 8694 16852 8693 16852 8160 16853 8694 16853 8158 16853 8160 16854 8695 16854 8694 16854 8162 16855 8695 16855 8160 16855 8163 16856 8695 16856 8162 16856 8163 16857 8190 16857 8695 16857 8165 16858 8190 16858 8163 16858 8165 16859 8696 16859 8190 16859 8167 16860 8696 16860 8165 16860 8169 16861 8696 16861 8167 16861 8169 16862 8196 16862 8696 16862 8171 16863 8196 16863 8169 16863 8171 16864 8697 16864 8196 16864 8837 16865 8697 16865 8171 16865 8837 16866 8698 16866 8697 16866 8175 16867 8698 16867 8837 16867 8176 16868 8698 16868 8175 16868 8176 16869 8203 16869 8698 16869 8178 16870 8203 16870 8176 16870 8178 16871 8699 16871 8203 16871 8180 16872 8699 16872 8178 16872 8182 16873 8699 16873 8180 16873 8182 16874 8208 16874 8699 16874 8184 16875 8208 16875 8182 16875 8184 16876 8210 16876 8208 16876 8185 16877 8210 16877 8184 16877 8185 16878 8700 16878 8210 16878 8187 16879 8700 16879 8185 16879 8838 16880 8700 16880 8187 16880 8838 16881 8218 16881 8700 16881 8192 16882 8218 16882 8838 16882 8192 16883 8701 16883 8218 16883 8193 16884 8701 16884 8192 16884 8193 16885 8702 16885 8701 16885 8195 16886 8702 16886 8193 16886 8197 16887 8702 16887 8195 16887 8197 16888 8223 16888 8702 16888 8199 16889 8223 16889 8197 16889 8199 16890 8703 16890 8223 16890 8200 16891 8703 16891 8199 16891 8200 16892 8228 16892 8703 16892 8202 16893 8228 16893 8200 16893 8202 16894 8704 16894 8228 16894 8204 16895 8704 16895 8202 16895 8206 16896 8704 16896 8204 16896 8206 16897 8705 16897 8704 16897 8207 16898 8705 16898 8206 16898 8207 16899 8706 16899 8705 16899 8209 16900 8706 16900 8207 16900 8209 16901 8707 16901 8706 16901 8211 16902 8707 16902 8209 16902 8211 16903 8241 16903 8707 16903 8213 16904 8241 16904 8211 16904 8214 16905 8241 16905 8213 16905 8214 16906 8243 16906 8241 16906 8216 16907 8243 16907 8214 16907 8216 16908 8708 16908 8243 16908 8217 16909 8708 16909 8216 16909 8217 16910 8709 16910 8708 16910 8220 16911 8709 16911 8217 16911 8222 16912 8709 16912 8220 16912 8222 16913 8250 16913 8709 16913 8224 16914 8250 16914 8222 16914 8224 16915 8251 16915 8250 16915 8225 16916 8251 16916 8224 16916 8225 16917 8710 16917 8251 16917 8227 16918 8710 16918 8225 16918 8227 16919 8711 16919 8710 16919 8229 16920 8711 16920 8227 16920 8229 16921 8712 16921 8711 16921 8231 16922 8712 16922 8229 16922 8232 16923 8712 16923 8231 16923 8232 16924 8713 16924 8712 16924 8235 16925 8713 16925 8232 16925 8235 16926 8714 16926 8713 16926 8237 16927 8714 16927 8235 16927 8237 16928 8715 16928 8714 16928 8239 16929 8715 16929 8237 16929 8240 16930 8715 16930 8239 16930 8240 16931 8267 16931 8715 16931 8242 16932 8267 16932 8240 16932 8242 16933 8716 16933 8267 16933 8244 16934 8716 16934 8242 16934 8244 16935 8717 16935 8716 16935 8246 16936 8717 16936 8244 16936 8248 16937 8717 16937 8246 16937 8248 16938 8275 16938 8717 16938 8249 16939 8275 16939 8248 16939 8249 16940 8718 16940 8275 16940 8252 16941 8718 16941 8249 16941 8252 16942 8719 16942 8718 16942 8254 16943 8719 16943 8252 16943 8255 16944 8719 16944 8254 16944 8255 16945 8720 16945 8719 16945 8257 16946 8720 16946 8255 16946 8839 16947 8720 16947 8257 16947 8839 16948 8721 16948 8720 16948 8260 16949 8721 16949 8839 16949 8260 16950 8722 16950 8721 16950 8262 16951 8722 16951 8260 16951 8262 16952 8723 16952 8722 16952 8263 16953 8723 16953 8262 16953 8263 16954 8724 16954 8723 16954 8265 16955 8724 16955 8263 16955 8265 16956 8292 16956 8724 16956 8266 16957 8292 16957 8265 16957 8266 16958 8725 16958 8292 16958 8268 16959 8725 16959 8266 16959 8270 16960 8725 16960 8268 16960 8270 16961 8726 16961 8725 16961 8271 16962 8726 16962 8270 16962 8273 16963 8726 16963 8271 16963 8273 16964 8727 16964 8726 16964 8274 16965 8727 16965 8273 16965 8274 16966 8728 16966 8727 16966 8277 16967 8728 16967 8274 16967 8278 16968 8728 16968 8277 16968 8278 16969 8729 16969 8728 16969 8280 16970 8729 16970 8278 16970 8280 16971 8730 16971 8729 16971 8282 16972 8730 16972 8280 16972 8283 16973 8730 16973 8282 16973 8283 16974 8308 16974 8730 16974 8283 16975 8310 16975 8308 16975 8285 16976 8310 16976 8283 16976 8286 16977 8313 16977 8285 16977 8285 16978 8313 16978 8310 16978 8288 16979 8314 16979 8286 16979 8286 16980 8314 16980 8313 16980 8289 16981 8314 16981 8288 16981 8289 16982 8731 16982 8314 16982 8291 16983 8731 16983 8289 16983 8293 16984 8731 16984 8291 16984 8293 16985 8732 16985 8731 16985 8294 16986 8732 16986 8293 16986 8294 16987 8733 16987 8732 16987 8296 16988 8733 16988 8294 16988 8296 16989 8323 16989 8733 16989 8298 16990 8323 16990 8296 16990 8298 16991 8734 16991 8323 16991 8300 16992 8734 16992 8298 16992 8300 16993 8735 16993 8734 16993 8302 16994 8735 16994 8300 16994 8304 16995 8735 16995 8302 16995 8305 16996 8735 16996 8304 16996 8305 16997 8736 16997 8735 16997 8840 16998 8736 16998 8305 16998 8840 16999 8334 16999 8736 16999 8309 17000 8334 17000 8840 17000 8309 17001 8737 17001 8334 17001 8311 17002 8737 17002 8309 17002 8312 17003 8338 17003 8311 17003 8311 17004 8338 17004 8737 17004 8312 17005 8339 17005 8338 17005 8315 17006 8339 17006 8312 17006 8316 17007 8339 17007 8315 17007 8316 17008 8738 17008 8339 17008 8318 17009 8738 17009 8316 17009 8318 17010 8344 17010 8738 17010 8318 17011 8739 17011 8344 17011 8320 17012 8739 17012 8318 17012 8320 17013 8740 17013 8739 17013 8322 17014 8740 17014 8320 17014 8322 17015 8741 17015 8740 17015 8324 17016 8741 17016 8322 17016 8324 17017 8742 17017 8741 17017 8326 17018 8742 17018 8324 17018 8326 17019 8354 17019 8742 17019 8328 17020 8354 17020 8326 17020 8328 17021 8356 17021 8354 17021 8330 17022 8356 17022 8328 17022 8330 17023 8357 17023 8356 17023 8331 17024 8357 17024 8330 17024 8331 17025 8359 17025 8357 17025 8333 17026 8359 17026 8331 17026 8333 17027 8361 17027 8359 17027 8336 17028 8361 17028 8333 17028 8336 17029 8743 17029 8361 17029 8337 17030 8743 17030 8336 17030 8337 17031 8365 17031 8743 17031 8340 17032 8365 17032 8337 17032 8340 17033 8368 17033 8365 17033 8342 17034 8368 17034 8340 17034 8342 17035 8369 17035 8368 17035 8345 17036 8369 17036 8342 17036 8345 17037 8744 17037 8369 17037 8347 17038 8744 17038 8345 17038 8347 17039 8745 17039 8744 17039 8348 17040 8745 17040 8347 17040 8348 17041 8746 17041 8745 17041 8350 17042 8746 17042 8348 17042 8350 17043 8747 17043 8746 17043 8351 17044 8747 17044 8350 17044 8353 17045 8747 17045 8351 17045 8353 17046 8748 17046 8747 17046 8353 17047 8749 17047 8748 17047 8355 17048 8749 17048 8353 17048 8358 17049 8749 17049 8355 17049 8358 17050 8750 17050 8749 17050 8360 17051 8750 17051 8358 17051 8360 17052 8751 17052 8750 17052 8362 17053 8751 17053 8360 17053 8362 17054 8752 17054 8751 17054 8364 17055 8752 17055 8362 17055 8364 17056 8753 17056 8752 17056 8366 17057 8753 17057 8364 17057 8367 17058 8753 17058 8366 17058 8367 17059 8754 17059 8753 17059 8370 17060 8754 17060 8367 17060 8372 17061 8755 17061 8370 17061 8370 17062 8755 17062 8754 17062 8373 17063 8755 17063 8372 17063 8373 17064 8756 17064 8755 17064 8375 17065 8756 17065 8373 17065 8375 17066 8401 17066 8756 17066 8375 17067 8757 17067 8401 17067 8376 17068 8757 17068 8375 17068 8379 17069 8757 17069 8376 17069 8379 17070 8406 17070 8757 17070 8381 17071 8406 17071 8379 17071 8381 17072 8758 17072 8406 17072 8383 17073 8758 17073 8381 17073 8383 17074 8410 17074 8758 17074 8384 17075 8410 17075 8383 17075 8384 17076 8759 17076 8410 17076 8386 17077 8759 17077 8384 17077 8386 17078 8760 17078 8759 17078 8388 17079 8760 17079 8386 17079 8390 17080 8760 17080 8388 17080 8390 17081 8761 17081 8760 17081 8392 17082 8761 17082 8390 17082 8392 17083 8420 17083 8761 17083 8393 17084 8420 17084 8392 17084 8393 17085 8421 17085 8420 17085 8395 17086 8421 17086 8393 17086 8395 17087 8762 17087 8421 17087 8396 17088 8762 17088 8395 17088 8398 17089 8762 17089 8396 17089 8398 17090 8763 17090 8762 17090 8400 17091 8763 17091 8398 17091 8402 17092 8763 17092 8400 17092 8402 17093 8428 17093 8763 17093 8404 17094 8428 17094 8402 17094 8404 17095 8764 17095 8428 17095 8405 17096 8764 17096 8404 17096 8407 17097 8764 17097 8405 17097 8407 17098 8432 17098 8764 17098 8409 17099 8432 17099 8407 17099 8409 17100 8765 17100 8432 17100 8411 17101 8765 17101 8409 17101 8411 17102 8437 17102 8765 17102 8414 17103 8437 17103 8411 17103 8414 17104 8766 17104 8437 17104 8416 17105 8766 17105 8414 17105 8416 17106 8767 17106 8766 17106 8417 17107 8767 17107 8416 17107 8417 17108 8444 17108 8767 17108 8419 17109 8444 17109 8417 17109 8419 17110 8445 17110 8444 17110 8422 17111 8445 17111 8419 17111 8422 17112 8768 17112 8445 17112 8424 17113 8768 17113 8422 17113 8424 17114 8450 17114 8768 17114 8426 17115 8450 17115 8424 17115 8426 17116 8769 17116 8450 17116 8427 17117 8769 17117 8426 17117 8427 17118 8770 17118 8769 17118 8429 17119 8770 17119 8427 17119 8429 17120 8455 17120 8770 17120 8431 17121 8455 17121 8429 17121 8431 17122 8771 17122 8455 17122 8433 17123 8771 17123 8431 17123 8435 17124 8772 17124 8433 17124 8433 17125 8772 17125 8771 17125 8436 17126 8772 17126 8435 17126 8436 17127 8773 17127 8772 17127 8841 17128 8773 17128 8436 17128 8841 17129 8774 17129 8773 17129 8438 17130 8774 17130 8841 17130 8440 17131 8774 17131 8438 17131 8440 17132 8775 17132 8774 17132 8441 17133 8775 17133 8440 17133 8441 17134 8469 17134 8775 17134 8443 17135 8469 17135 8441 17135 8443 17136 8471 17136 8469 17136 8446 17137 8471 17137 8443 17137 8446 17138 8473 17138 8471 17138 8447 17139 8473 17139 8446 17139 8447 17140 8475 17140 8473 17140 8449 17141 8475 17141 8447 17141 8449 17142 8776 17142 8475 17142 8451 17143 8776 17143 8449 17143 8451 17144 8479 17144 8776 17144 8453 17145 8479 17145 8451 17145 8453 17146 8481 17146 8479 17146 8454 17147 8481 17147 8453 17147 8454 17148 8777 17148 8481 17148 8458 17149 8777 17149 8454 17149 8458 17150 8778 17150 8777 17150 8459 17151 8778 17151 8458 17151 8461 17152 8778 17152 8459 17152 8461 17153 8779 17153 8778 17153 8463 17154 8779 17154 8461 17154 8464 17155 8779 17155 8463 17155 8464 17156 8489 17156 8779 17156 8466 17157 8489 17157 8464 17157 8466 17158 8780 17158 8489 17158 8467 17159 8780 17159 8466 17159 8467 17160 8494 17160 8780 17160 8468 17161 8494 17161 8467 17161 8468 17162 8781 17162 8494 17162 8470 17163 8781 17163 8468 17163 8472 17164 8781 17164 8470 17164 8472 17165 8496 17165 8781 17165 8474 17166 8496 17166 8472 17166 8474 17167 8782 17167 8496 17167 8477 17168 8782 17168 8474 17168 8477 17169 8502 17169 8782 17169 8478 17170 8502 17170 8477 17170 8478 17171 8783 17171 8502 17171 8842 17172 8783 17172 8478 17172 8480 17173 8783 17173 8842 17173 8480 17174 8506 17174 8783 17174 8483 17175 8506 17175 8480 17175 8483 17176 8508 17176 8506 17176 8484 17177 8508 17177 8483 17177 8484 17178 8510 17178 8508 17178 8486 17179 8510 17179 8484 17179 8486 17180 8512 17180 8510 17180 8488 17181 8512 17181 8486 17181 8488 17182 8784 17182 8512 17182 8490 17183 8784 17183 8488 17183 8490 17184 8518 17184 8784 17184 8492 17185 8785 17185 8490 17185 8490 17186 8785 17186 8518 17186 8493 17187 8785 17187 8492 17187 8493 17188 8521 17188 8785 17188 8493 17189 8786 17189 8521 17189 8495 17190 8786 17190 8493 17190 8495 17191 8787 17191 8786 17191 8498 17192 8787 17192 8495 17192 8499 17193 8787 17193 8498 17193 8499 17194 8788 17194 8787 17194 8501 17195 8788 17195 8499 17195 8501 17196 8789 17196 8788 17196 8503 17197 8789 17197 8501 17197 8503 17198 8531 17198 8789 17198 8505 17199 8531 17199 8503 17199 8505 17200 8790 17200 8531 17200 8507 17201 8790 17201 8505 17201 8507 17202 8536 17202 8790 17202 8509 17203 8536 17203 8507 17203 8509 17204 8791 17204 8536 17204 8511 17205 8791 17205 8509 17205 8511 17206 8792 17206 8791 17206 8513 17207 8792 17207 8511 17207 8516 17208 8793 17208 8513 17208 8513 17209 8793 17209 8792 17209 8517 17210 8793 17210 8516 17210 8517 17211 8794 17211 8793 17211 8520 17212 8794 17212 8517 17212 8522 17213 8794 17213 8520 17213 8522 17214 8795 17214 8794 17214 8523 17215 8795 17215 8522 17215 8523 17216 8796 17216 8795 17216 8526 17217 8796 17217 8523 17217 8526 17218 8797 17218 8796 17218 8527 17219 8797 17219 8526 17219 8529 17220 8555 17220 8527 17220 8527 17221 8555 17221 8797 17221 8530 17222 8555 17222 8529 17222 8530 17223 8556 17223 8555 17223 8534 17224 8556 17224 8530 17224 8534 17225 8798 17225 8556 17225 8534 17226 8799 17226 8798 17226 8535 17227 8799 17227 8534 17227 8537 17228 8799 17228 8535 17228 8537 17229 8800 17229 8799 17229 8540 17230 8800 17230 8537 17230 8541 17231 8800 17231 8540 17231 8541 17232 8801 17232 8800 17232 8541 17233 8802 17233 8801 17233 8543 17234 8802 17234 8541 17234 8543 17235 8803 17235 8802 17235 8544 17236 8803 17236 8543 17236 8546 17237 8803 17237 8544 17237 8546 17238 8804 17238 8803 17238 8547 17239 8804 17239 8546 17239 8549 17240 8805 17240 8547 17240 8547 17241 8805 17241 8804 17241 8551 17242 8805 17242 8549 17242 8551 17243 8806 17243 8805 17243 8553 17244 8806 17244 8551 17244 8553 17245 8579 17245 8806 17245 8554 17246 8579 17246 8553 17246 8554 17247 8581 17247 8579 17247 8557 17248 8581 17248 8554 17248 8557 17249 8807 17249 8581 17249 8559 17250 8807 17250 8557 17250 8559 17251 8586 17251 8807 17251 8559 17252 8808 17252 8586 17252 8560 17253 8808 17253 8559 17253 8562 17254 8587 17254 8560 17254 8560 17255 8587 17255 8808 17255 8563 17256 8809 17256 8562 17256 8562 17257 8809 17257 8587 17257 8565 17258 8809 17258 8563 17258 8565 17259 8810 17259 8809 17259 8567 17260 8810 17260 8565 17260 8569 17261 8810 17261 8567 17261 8569 17262 8811 17262 8810 17262 8570 17263 8811 17263 8569 17263 8572 17264 8811 17264 8570 17264 8572 17265 8812 17265 8811 17265 8574 17266 8812 17266 8572 17266 8574 17267 8601 17267 8812 17267 8575 17268 8601 17268 8574 17268 8577 17269 8601 17269 8575 17269 8577 17270 8813 17270 8601 17270 8578 17271 8813 17271 8577 17271 8843 17272 8813 17272 8578 17272 8843 17273 8814 17273 8813 17273 8580 17274 8814 17274 8843 17274 8580 17275 8815 17275 8814 17275 8582 17276 8815 17276 8580 17276 8582 17277 8816 17277 8815 17277 8584 17278 8816 17278 8582 17278 8585 17279 8816 17279 8584 17279 8585 17280 8817 17280 8816 17280 8588 17281 8817 17281 8585 17281 8590 17282 8817 17282 8588 17282 8590 17283 8818 17283 8817 17283 8592 17284 8818 17284 8590 17284 8592 17285 8619 17285 8818 17285 8593 17286 8619 17286 8592 17286 8593 17287 8621 17287 8619 17287 8595 17288 8621 17288 8593 17288 8595 17289 8623 17289 8621 17289 8597 17290 8623 17290 8595 17290 8597 17291 8626 17291 8623 17291 8598 17292 8626 17292 8597 17292 8598 17293 8627 17293 8626 17293 8600 17294 8627 17294 8598 17294 8600 17295 8819 17295 8627 17295 8602 17296 8819 17296 8600 17296 8602 17297 8820 17297 8819 17297 8603 17298 8820 17298 8602 17298 8605 17299 8820 17299 8603 17299 8607 17300 8632 17300 8605 17300 8605 17301 8632 17301 8820 17301 8607 17302 8635 17302 8632 17302 8609 17303 8635 17303 8607 17303 8609 17304 8637 17304 8635 17304 8612 17305 8637 17305 8609 17305 8612 17306 8821 17306 8637 17306 8613 17307 8821 17307 8612 17307 8613 17308 8641 17308 8821 17308 8615 17309 8822 17309 8613 17309 8613 17310 8822 17310 8641 17310 8616 17311 8822 17311 8615 17311 8616 17312 8823 17312 8822 17312 8618 17313 8823 17313 8616 17313 8620 17314 8823 17314 8618 17314 8620 17315 8824 17315 8823 17315 8622 17316 8824 17316 8620 17316 8624 17317 8824 17317 8622 17317 8625 17318 8824 17318 8624 17318 8625 17319 8825 17319 8824 17319 8628 17320 8825 17320 8625 17320 8628 17321 8826 17321 8825 17321 8628 17322 8827 17322 8826 17322 8629 17323 8827 17323 8628 17323 8631 17324 8827 17324 8629 17324 8631 17325 8828 17325 8827 17325 8633 17326 8828 17326 8631 17326 8633 17327 8829 17327 8828 17327 8634 17328 8829 17328 8633 17328 8636 17329 8829 17329 8634 17329 8636 17330 8661 17330 8829 17330 8638 17331 8661 17331 8636 17331 8638 17332 8830 17332 8661 17332 8640 17333 8830 17333 8638 17333 8640 17334 8831 17334 8830 17334 8642 17335 8831 17335 8640 17335 8643 17336 8831 17336 8642 17336 8643 17337 8832 17337 8831 17337 8645 17338 8832 17338 8643 17338 8645 17339 8041 17339 8832 17339 8646 17340 8041 17340 8645 17340 8646 17341 8043 17341 8041 17341 8648 17342 8043 17342 8646 17342 8648 17343 8046 17343 8043 17343 8650 17344 8046 17344 8648 17344 8652 17345 8046 17345 8650 17345 8652 17346 8047 17346 8046 17346 8653 17347 8047 17347 8652 17347 8653 17348 8655 17348 8047 17348 8071 17349 8836 17349 8069 17349 8073 17350 8836 17350 8071 17350 8093 17351 8090 17351 8091 17351 8173 17352 8837 17352 8171 17352 8175 17353 8837 17353 8173 17353 8189 17354 8838 17354 8187 17354 8192 17355 8838 17355 8189 17355 8258 17356 8839 17356 8257 17356 8260 17357 8839 17357 8258 17357 8307 17358 8840 17358 8305 17358 8309 17359 8840 17359 8307 17359 8345 17360 8342 17360 8343 17360 8379 17361 8376 17361 8378 17361 8414 17362 8411 17362 8412 17362 8438 17363 8841 17363 8436 17363 8458 17364 8454 17364 8456 17364 8480 17365 8842 17365 8478 17365 8516 17366 8513 17366 8514 17366 8534 17367 8530 17367 8532 17367 8580 17368 8843 17368 8578 17368 8612 17369 8609 17369 8610 17369 8658 17370 8865 17370 8657 17370 8846 17371 8889 17371 8844 17371 8847 17372 8844 17372 8845 17372 8846 17373 8844 17373 8847 17373 8845 17374 8844 17374 8848 17374 8849 17375 8045 17375 8846 17375 8849 17376 8846 17376 8847 17376 8850 17377 8847 17377 8845 17377 8850 17378 8845 17378 8848 17378 8851 17379 8847 17379 8850 17379 8851 17380 8849 17380 8847 17380 8049 17381 8849 17381 8851 17381 8852 17382 8850 17382 8848 17382 8852 17383 8851 17383 8850 17383 8853 17384 8851 17384 8852 17384 8855 17385 8852 17385 8848 17385 8051 17386 8049 17386 8851 17386 8854 17387 8852 17387 8855 17387 8854 17388 8853 17388 8852 17388 8051 17389 8851 17389 8853 17389 8856 17390 8855 17390 8848 17390 8857 17391 8853 17391 8854 17391 8853 17392 8857 17392 8051 17392 8858 17393 8854 17393 8855 17393 8857 17394 8854 17394 8858 17394 8859 17395 8855 17395 8856 17395 8859 17396 8858 17396 8855 17396 8860 17397 8859 17397 8856 17397 8861 17398 8857 17398 8858 17398 8052 17399 8857 17399 8861 17399 8861 17400 8858 17400 8859 17400 8859 17401 8862 17401 8861 17401 8862 17402 8052 17402 8861 17402 8863 17403 8859 17403 8860 17403 8863 17404 8862 17404 8859 17404 8863 17405 8860 17405 8864 17405 8658 17406 8052 17406 8862 17406 8658 17407 8862 17407 8863 17407 8865 17408 8863 17408 8864 17408 8866 17409 8864 17409 8860 17409 8865 17410 8658 17410 8863 17410 8867 17411 8865 17411 8864 17411 8867 17412 8864 17412 8866 17412 8657 17413 8865 17413 8867 17413 8868 17414 8867 17414 8866 17414 8657 17415 8867 17415 8869 17415 8868 17416 8869 17416 8867 17416 8655 17417 8657 17417 8869 17417 8870 17418 8869 17418 8868 17418 8869 17419 8873 17419 8655 17419 8873 17420 8869 17420 8870 17420 8871 17421 8868 17421 8866 17421 8870 17422 8868 17422 8871 17422 8872 17423 8871 17423 8866 17423 8873 17424 8870 17424 8871 17424 8874 17425 8873 17425 8871 17425 8876 17426 8871 17426 8872 17426 8876 17427 8874 17427 8871 17427 8047 17428 8873 17428 8874 17428 8875 17429 8876 17429 8872 17429 8877 17430 8874 17430 8876 17430 8877 17431 8047 17431 8874 17431 8878 17432 8876 17432 8875 17432 8878 17433 8877 17433 8876 17433 8879 17434 8877 17434 8878 17434 8880 17435 8878 17435 8875 17435 8883 17436 8880 17436 8875 17436 8881 17437 8879 17437 8878 17437 8882 17438 8878 17438 8880 17438 8881 17439 8878 17439 8882 17439 8884 17440 8879 17440 8881 17440 8884 17441 8881 17441 8882 17441 8886 17442 8880 17442 8883 17442 8886 17443 8883 17443 8885 17443 8886 17444 8882 17444 8880 17444 8040 17445 8884 17445 8882 17445 8040 17446 8882 17446 8886 17446 8887 17447 8886 17447 8885 17447 8888 17448 8040 17448 8886 17448 8888 17449 8886 17449 8887 17449 8042 17450 8040 17450 8888 17450 8889 17451 8888 17451 8887 17451 8844 17452 8887 17452 8885 17452 8889 17453 8042 17453 8888 17453 8889 17454 8887 17454 8844 17454 8045 17455 8042 17455 8889 17455 8045 17456 8889 17456 8846 17456 8860 17457 8883 17457 8875 17457 8860 17458 8856 17458 8848 17458 8860 17459 8885 17459 8883 17459 8860 17460 8844 17460 8885 17460 8860 17461 8875 17461 8872 17461 8860 17462 8872 17462 8866 17462 8860 17463 8848 17463 8844 17463 8891 17464 8896 17464 8899 17464 8891 17465 8890 17465 8896 17465 8890 17466 8892 17466 8896 17466 8896 17467 8892 17467 8897 17467 8892 17468 8893 17468 8897 17468 8897 17469 8893 17469 8901 17469 8893 17470 8894 17470 8901 17470 8901 17471 8894 17471 8900 17471 8894 17472 8895 17472 8900 17472 8900 17473 8895 17473 8898 17473 8895 17474 8899 17474 8898 17474 8895 17475 8891 17475 8899 17475 8897 17476 8905 17476 8902 17476 8897 17477 8902 17477 8903 17477 8897 17478 8903 17478 8904 17478 8901 17479 8907 17479 8905 17479 8901 17480 8906 17480 8907 17480 8901 17481 8905 17481 8897 17481 8910 17482 8906 17482 8901 17482 8896 17483 8897 17483 8904 17483 8896 17484 8904 17484 8908 17484 8900 17485 8909 17485 8910 17485 8900 17486 8910 17486 8901 17486 8911 17487 8896 17487 8908 17487 8899 17488 8896 17488 8911 17488 8912 17489 8909 17489 8900 17489 8913 17490 8899 17490 8911 17490 8912 17491 8900 17491 8898 17491 8914 17492 8912 17492 8898 17492 8915 17493 8899 17493 8913 17493 8915 17494 8898 17494 8899 17494 8915 17495 8914 17495 8898 17495 8891 17496 8895 17496 8890 17496 8890 17497 8893 17497 8892 17497 8895 17498 8894 17498 8890 17498 8890 17499 8894 17499 8893 17499 8916 17500 8929 17500 8907 17500 8916 17501 8907 17501 8906 17501 8916 17502 8906 17502 8910 17502 8917 17503 8916 17503 8910 17503 8917 17504 8910 17504 8909 17504 8918 17505 8917 17505 8909 17505 8918 17506 8909 17506 8912 17506 8918 17507 8912 17507 8914 17507 8919 17508 8918 17508 8914 17508 8920 17509 8919 17509 8914 17509 8920 17510 8914 17510 8915 17510 8921 17511 8920 17511 8915 17511 8922 17512 8915 17512 8913 17512 8922 17513 8921 17513 8915 17513 8923 17514 8922 17514 8913 17514 8923 17515 8913 17515 8911 17515 8924 17516 8923 17516 8911 17516 8924 17517 8911 17517 8908 17517 8925 17518 8924 17518 8908 17518 8925 17519 8908 17519 8904 17519 8926 17520 8925 17520 8904 17520 8926 17521 8904 17521 8903 17521 8927 17522 8926 17522 8903 17522 8927 17523 8903 17523 8902 17523 8928 17524 8927 17524 8902 17524 8928 17525 8902 17525 8905 17525 8929 17526 8928 17526 8905 17526 8929 17527 8905 17527 8907 17527 8662 17528 8924 17528 8925 17528 8662 17529 8923 17529 8924 17529 8663 17530 8662 17530 8925 17530 8056 17531 8923 17531 8662 17531 8663 17532 8925 17532 8926 17532 8056 17533 8922 17533 8923 17533 8833 17534 8663 17534 8926 17534 8833 17535 8926 17535 8927 17535 8056 17536 8921 17536 8922 17536 8061 17537 8921 17537 8056 17537 8835 17538 8833 17538 8927 17538 8061 17539 8920 17539 8921 17539 8835 17540 8927 17540 8928 17540 8919 17541 8920 17541 8061 17541 8919 17542 8061 17542 8058 17542 8929 17543 8835 17543 8928 17543 8929 17544 8834 17544 8835 17544 8918 17545 8919 17545 8058 17545 8918 17546 8058 17546 8054 17546 8916 17547 8834 17547 8929 17547 8918 17548 8054 17548 8053 17548 8917 17549 8834 17549 8916 17549 8917 17550 8918 17550 8053 17550 8917 17551 8053 17551 8834 17551

+
+ + + +

8952 17552 8931 17552 8932 17552 8930 17553 8931 17553 8952 17553 8931 17554 8933 17554 8932 17554 8932 17555 8933 17555 8934 17555 8933 17556 8935 17556 8934 17556 8934 17557 8935 17557 8936 17557 8936 17558 8935 17558 8937 17558 8935 17559 8938 17559 8937 17559 8937 17560 8938 17560 8939 17560 8938 17561 8940 17561 8939 17561 8940 17562 8941 17562 8939 17562 8939 17563 8941 17563 8942 17563 8942 17564 8941 17564 8943 17564 8941 17565 8944 17565 8943 17565 8943 17566 8944 17566 8945 17566 8944 17567 8946 17567 8945 17567 8945 17568 8946 17568 8947 17568 8946 17569 8948 17569 8947 17569 8947 17570 8948 17570 8949 17570 8948 17571 8950 17571 8949 17571 8949 17572 8950 17572 8951 17572 8951 17573 8950 17573 8952 17573 8950 17574 8930 17574 8952 17574 8954 17575 8982 17575 8953 17575 8954 17576 8953 17576 8955 17576 8954 17577 8955 17577 8956 17577 8957 17578 8954 17578 8956 17578 8957 17579 8956 17579 8958 17579 8959 17580 8957 17580 8958 17580 8959 17581 8958 17581 8960 17581 8961 17582 8959 17582 8960 17582 8961 17583 8960 17583 8962 17583 8963 17584 8961 17584 8962 17584 8963 17585 8962 17585 8964 17585 8965 17586 8963 17586 8964 17586 8965 17587 8964 17587 8966 17587 8967 17588 8965 17588 8966 17588 8967 17589 8966 17589 8968 17589 8969 17590 8967 17590 8968 17590 8970 17591 8969 17591 8968 17591 8970 17592 8968 17592 8971 17592 8972 17593 8970 17593 8971 17593 8972 17594 8971 17594 8973 17594 8974 17595 8972 17595 8973 17595 8974 17596 8973 17596 8975 17596 8976 17597 8974 17597 8975 17597 8976 17598 8975 17598 8977 17598 8978 17599 8976 17599 8977 17599 8978 17600 8977 17600 8979 17600 8980 17601 8978 17601 8979 17601 8980 17602 8979 17602 8981 17602 8982 17603 8980 17603 8981 17603 8982 17604 8981 17604 8953 17604 8944 1433 8981 1433 8979 1433 8941 1433 8981 1433 8944 1433 8944 17605 8979 17605 8977 17605 8941 1433 8953 1433 8981 1433 8946 1433 8944 1433 8977 1433 8946 17606 8977 17606 8975 17606 8940 1433 8953 1433 8941 1433 8940 1433 8955 1433 8953 1433 8948 1433 8946 1433 8975 1433 8940 17607 8956 17607 8955 17607 8938 17608 8956 17608 8940 17608 8948 17609 8975 17609 8973 17609 8948 17610 8973 17610 8971 17610 8958 1433 8956 1433 8938 1433 8958 17611 8938 17611 8935 17611 8971 1433 8950 1433 8948 1433 8960 17612 8958 17612 8935 17612 8968 1433 8950 1433 8971 1433 8968 1433 8930 1433 8950 1433 8962 1433 8960 1433 8935 1433 8962 17613 8935 17613 8933 17613 8966 17614 8930 17614 8968 17614 8966 1433 8931 1433 8930 1433 8964 17615 8931 17615 8966 17615 8964 1433 8962 1433 8933 1433 8964 17616 8933 17616 8931 17616 8949 759 8970 759 8972 759 8951 759 8970 759 8949 759 8947 759 8949 759 8972 759 8947 759 8972 759 8974 759 8951 759 8969 759 8970 759 8947 759 8974 759 8976 759 8952 17617 8969 17617 8951 17617 8945 759 8947 759 8976 759 8952 759 8967 759 8969 759 8945 759 8976 759 8978 759 8943 759 8945 759 8978 759 8952 759 8965 759 8967 759 8932 17618 8965 17618 8952 17618 8980 759 8943 759 8978 759 8963 759 8965 759 8932 759 8963 17619 8932 17619 8934 17619 8980 759 8942 759 8943 759 8982 759 8942 759 8980 759 8961 759 8963 759 8934 759 8982 759 8939 759 8942 759 8961 17620 8934 17620 8936 17620 8954 17621 8939 17621 8982 17621 8959 759 8961 759 8936 759 8957 17622 8939 17622 8954 17622 8957 759 8937 759 8939 759 8957 759 8959 759 8936 759 8957 17623 8936 17623 8937 17623

+
+ + + +

8984 17624 9008 17624 8983 17624 8984 17625 8983 17625 8985 17625 8984 17626 8985 17626 8986 17626 8987 17627 8984 17627 8986 17627 8988 17628 8987 17628 8986 17628 8988 17629 8986 17629 8989 17629 8990 17630 8988 17630 8989 17630 8990 17631 8989 17631 8991 17631 8990 17632 8991 17632 8992 17632 8993 17633 8990 17633 8992 17633 8994 17634 8993 17634 8992 17634 8994 17635 8992 17635 8995 17635 8996 17636 8994 17636 8995 17636 8996 17637 8995 17637 8997 17637 8998 17638 8996 17638 8997 17638 8998 17639 8997 17639 8999 17639 9000 17640 8998 17640 8999 17640 9000 17641 8999 17641 9001 17641 9002 17642 9000 17642 9001 17642 9002 17643 9001 17643 9003 17643 9004 17644 9002 17644 9003 17644 9004 17645 9003 17645 9005 17645 9006 17646 9004 17646 9005 17646 9006 17647 9005 17647 9007 17647 9008 17648 9006 17648 9007 17648 9008 17649 9007 17649 8983 17649 9001 759 8999 759 8997 759 9001 759 8997 759 8995 759 8983 759 8986 759 8985 759 8983 759 8989 759 8986 759 9005 17650 9003 17650 9001 17650 9007 17651 8989 17651 8983 17651 9007 759 9005 759 9001 759 9007 759 8995 759 8992 759 9007 17652 9001 17652 8995 17652 9007 759 8992 759 8991 759 9007 17653 8991 17653 8989 17653 9009 759 9010 759 9011 759 9012 17654 9009 17654 9011 17654 9013 759 9010 759 9009 759 9012 759 9011 759 9014 759 9015 759 9012 759 9014 759 9015 17655 9014 17655 9016 17655 9013 759 9017 759 9010 759 9018 759 9017 759 9013 759 9019 759 9015 759 9016 759 9020 17656 9021 17656 9022 17656 9023 759 9020 759 9022 759 9019 759 9016 759 9029 759 9020 759 9024 759 9021 759 9025 759 9023 759 9022 759 9018 759 9026 759 9017 759 9027 17657 9024 17657 9020 17657 9028 759 9026 759 9018 759 9027 759 9029 759 9024 759 9025 759 9022 759 9030 759 9031 759 9025 759 9030 759 9032 17658 9019 17658 9029 17658 9032 759 9029 759 9027 759 9033 759 9030 759 9034 759 9033 759 9031 759 9030 759 9035 17659 9026 17659 9028 17659 9035 17660 9028 17660 9037 17660 9036 759 9033 759 9034 759 9036 17661 9038 17661 9033 17661 9039 759 9035 759 9037 759 9039 17662 9037 17662 9040 17662 9041 759 9039 759 9040 759 8993 17663 8994 17663 9032 17663 8994 17664 9019 17664 9032 17664 8994 17665 9042 17665 9019 17665 8993 17666 9032 17666 9043 17666 8996 759 9042 759 8994 759 8990 759 8993 759 9043 759 8996 17667 9044 17667 9042 17667 9045 759 9038 759 9036 759 8990 17668 9043 17668 9046 17668 8998 759 9044 759 8996 759 8988 759 8990 759 9046 759 8988 17669 9046 17669 9047 17669 8998 759 9048 759 9044 759 8987 759 8988 759 9047 759 9000 759 9048 759 8998 759 8987 17670 9047 17670 9049 17670 9045 759 9049 759 9038 759 9050 759 9048 759 9000 759 9051 759 9048 759 9050 759 9051 759 9040 759 9048 759 9050 17671 9000 17671 9002 17671 9052 17672 9050 17672 9002 17672 9053 759 9040 759 9051 759 9053 759 9041 759 9040 759 9053 17673 9054 17673 9041 17673 9053 17674 9055 17674 9054 17674 9056 759 9052 759 9002 759 9056 17675 9002 17675 9004 17675 9057 17676 9055 17676 9053 17676 9058 759 9055 759 9057 759 9059 759 8987 759 9049 759 9059 17677 8984 17677 8987 17677 9060 759 8984 759 9059 759 9061 17678 9059 17678 9049 17678 9061 17679 9049 17679 9045 17679 9061 17680 9045 17680 9062 17680 9063 759 8984 759 9060 759 9064 17681 9004 17681 9006 17681 9064 759 9056 759 9004 759 9061 17682 9062 17682 9065 17682 9063 17683 9008 17683 8984 17683 9066 17684 9061 17684 9065 17684 9066 17685 9065 17685 9067 17685 9058 17686 9057 17686 9072 17686 9068 759 9008 759 9063 759 9068 17687 9006 17687 9008 17687 9068 17688 9064 17688 9006 17688 9067 17689 9069 17689 9066 17689 9070 759 9064 759 9068 759 9070 17690 9090 17690 9064 17690 9071 759 9058 759 9072 759 9073 759 9069 759 9067 759 9071 17691 9072 17691 9074 17691 9073 17692 9075 17692 9069 17692 9071 17693 9074 17693 9077 17693 9076 17694 9075 17694 9073 17694 9078 17695 9071 17695 9077 17695 9076 17696 9079 17696 9075 17696 9078 17697 9077 17697 9080 17697 9076 759 9082 759 9079 759 9081 759 9082 759 9076 759 9083 759 9078 759 9080 759 9081 759 9084 759 9082 759 9083 759 9080 759 9085 759 9086 17698 9084 17698 9081 17698 9087 17699 9083 17699 9085 17699 9086 17700 9088 17700 9084 17700 9089 17701 9088 17701 9086 17701 9087 759 9085 759 9090 759 9091 17702 9087 17702 9090 17702 9089 17703 9070 17703 9088 17703 9091 759 9070 759 9089 759 9091 759 9090 759 9070 759 9037 17704 9028 17704 9092 17704 9092 17705 9028 17705 9093 17705 9093 17706 9018 17706 9094 17706 9028 17707 9018 17707 9093 17707 9094 17708 9018 17708 9095 17708 9018 17709 9013 17709 9095 17709 9095 17710 9013 17710 9096 17710 9013 17711 9009 17711 9096 17711 9096 17712 9009 17712 9097 17712 9009 17713 9012 17713 9097 17713 9012 17714 9015 17714 9097 17714 9097 17715 9015 17715 9098 17715 9098 17716 9015 17716 9099 17716 9015 17717 9019 17717 9099 17717 9099 17718 9019 17718 9100 17718 9019 17719 9042 17719 9100 17719 9100 17720 9042 17720 9101 17720 9042 17721 9044 17721 9101 17721 9101 17722 9044 17722 9102 17722 9044 17723 9048 17723 9102 17723 9102 17724 9048 17724 9103 17724 9048 17725 9040 17725 9103 17725 9103 17726 9040 17726 9104 17726 9040 17727 9037 17727 9104 17727 9104 17728 9037 17728 9092 17728 9116 17729 9046 17729 9105 17729 9046 17730 9043 17730 9105 17730 9105 17731 9043 17731 9106 17731 9043 17732 9032 17732 9106 17732 9106 17733 9032 17733 9107 17733 9032 17734 9027 17734 9107 17734 9107 17735 9027 17735 9108 17735 9027 17736 9020 17736 9108 17736 9108 17737 9020 17737 9109 17737 9020 17738 9023 17738 9109 17738 9109 17739 9023 17739 9110 17739 9023 17740 9025 17740 9110 17740 9110 17741 9025 17741 9111 17741 9025 17742 9031 17742 9111 17742 9111 17743 9033 17743 9112 17743 9031 17744 9033 17744 9111 17744 9112 17745 9033 17745 9113 17745 9033 17746 9038 17746 9113 17746 9113 17747 9038 17747 9114 17747 9038 17748 9049 17748 9114 17748 9114 17749 9049 17749 9115 17749 9049 17750 9047 17750 9115 17750 9115 17751 9047 17751 9116 17751 9047 17752 9046 17752 9116 17752 9127 17753 9077 17753 9117 17753 9077 17754 9074 17754 9117 17754 9074 17755 9072 17755 9117 17755 9117 17756 9072 17756 9118 17756 9072 17757 9057 17757 9118 17757 9118 17758 9057 17758 9119 17758 9057 17759 9053 17759 9119 17759 9119 17760 9053 17760 9120 17760 9053 17761 9051 17761 9120 17761 9051 17762 9050 17762 9120 17762 9120 17763 9050 17763 9121 17763 9050 17764 9052 17764 9121 17764 9121 17765 9052 17765 9122 17765 9052 17766 9056 17766 9122 17766 9122 17767 9056 17767 9123 17767 9056 17768 9064 17768 9123 17768 9123 17769 9064 17769 9124 17769 9064 17770 9090 17770 9124 17770 9124 17771 9090 17771 9125 17771 9090 17772 9085 17772 9125 17772 9125 17773 9085 17773 9126 17773 9085 17774 9080 17774 9126 17774 9126 17775 9080 17775 9127 17775 9080 17776 9077 17776 9127 17776 9140 17777 9088 17777 9128 17777 9088 17778 9070 17778 9128 17778 9128 17779 9070 17779 9129 17779 9070 17780 9068 17780 9129 17780 9129 17781 9068 17781 9130 17781 9130 17782 9068 17782 9131 17782 9068 17783 9063 17783 9131 17783 9131 17784 9063 17784 9132 17784 9063 17785 9060 17785 9132 17785 9060 17786 9059 17786 9132 17786 9132 17787 9059 17787 9133 17787 9059 17788 9061 17788 9133 17788 9133 17789 9061 17789 9134 17789 9061 17790 9066 17790 9134 17790 9134 17791 9066 17791 9135 17791 9066 17792 9069 17792 9135 17792 9135 17793 9069 17793 9136 17793 9069 17794 9075 17794 9136 17794 9136 17795 9075 17795 9137 17795 9137 17796 9075 17796 9138 17796 9075 17797 9079 17797 9138 17797 9138 17798 9079 17798 9139 17798 9079 17799 9082 17799 9139 17799 9139 17800 9082 17800 9140 17800 9082 17801 9084 17801 9140 17801 9084 17802 9088 17802 9140 17802 9071 17803 9141 17803 9142 17803 9058 17804 9142 17804 9143 17804 9058 17805 9071 17805 9142 17805 9055 17806 9143 17806 9144 17806 9055 17807 9058 17807 9143 17807 9055 17808 9144 17808 9145 17808 9054 17809 9055 17809 9145 17809 9041 17810 9054 17810 9145 17810 9041 17811 9145 17811 9146 17811 9039 17812 9146 17812 9147 17812 9039 17813 9041 17813 9146 17813 9035 17814 9039 17814 9147 17814 9035 17815 9147 17815 9148 17815 9026 17816 9148 17816 9149 17816 9026 17817 9035 17817 9148 17817 9017 17818 9026 17818 9149 17818 9017 17819 9149 17819 9150 17819 9010 17820 9017 17820 9150 17820 9010 17821 9150 17821 9151 17821 9010 17822 9151 17822 9152 17822 9011 17823 9010 17823 9152 17823 9014 17824 9011 17824 9152 17824 9014 17825 9152 17825 9153 17825 9016 17826 9014 17826 9153 17826 9016 17827 9153 17827 9154 17827 9016 17828 9154 17828 9155 17828 9029 17829 9016 17829 9155 17829 9029 17830 9155 17830 9156 17830 9024 17831 9029 17831 9156 17831 9021 17832 9156 17832 9157 17832 9021 17833 9024 17833 9156 17833 9022 17834 9157 17834 9158 17834 9022 17835 9021 17835 9157 17835 9022 17836 9158 17836 9159 17836 9030 17837 9022 17837 9159 17837 9030 17838 9159 17838 9160 17838 9034 17839 9030 17839 9160 17839 9034 17840 9160 17840 9161 17840 9036 17841 9034 17841 9161 17841 9036 17842 9161 17842 9162 17842 9045 17843 9162 17843 9163 17843 9045 17844 9036 17844 9162 17844 9062 17845 9045 17845 9163 17845 9062 17846 9163 17846 9164 17846 9065 17847 9164 17847 9165 17847 9065 17848 9062 17848 9164 17848 9067 17849 9065 17849 9165 17849 9067 17850 9165 17850 9166 17850 9073 17851 9067 17851 9166 17851 9073 17852 9166 17852 9167 17852 9073 17853 9167 17853 9168 17853 9076 17854 9073 17854 9168 17854 9076 17855 9168 17855 9169 17855 9081 17856 9076 17856 9169 17856 9081 17857 9169 17857 9170 17857 9086 17858 9081 17858 9170 17858 9089 17859 9170 17859 9171 17859 9089 17860 9086 17860 9170 17860 9089 17861 9171 17861 9172 17861 9091 17862 9089 17862 9172 17862 9091 17863 9172 17863 9173 17863 9091 17864 9173 17864 9174 17864 9087 17865 9091 17865 9174 17865 9087 17866 9174 17866 9175 17866 9083 17867 9087 17867 9175 17867 9083 17868 9175 17868 9176 17868 9078 17869 9083 17869 9176 17869 9078 17870 9176 17870 9141 17870 9071 17871 9078 17871 9141 17871 9104 17872 9092 17872 9103 17872 9102 759 9100 759 9101 759 9094 759 9095 759 9093 759 9093 17873 9095 17873 9092 17873 9092 17874 9095 17874 9103 17874 9099 759 9096 759 9098 759 9103 759 9096 759 9102 759 9098 17875 9096 17875 9097 17875 9102 759 9096 759 9100 759 9100 759 9096 759 9099 759 9095 759 9096 759 9103 759 9106 17876 9107 17876 9105 17876 9105 759 9107 759 9116 759 9114 17877 9111 17877 9113 17877 9113 759 9111 759 9112 759 9116 759 9111 759 9115 759 9115 17878 9111 17878 9114 17878 9111 759 9109 759 9110 759 9116 17879 9109 17879 9111 17879 9107 17880 9109 17880 9116 17880 9108 17881 9109 17881 9107 17881 9117 17882 9118 17882 9127 17882 9124 17883 9122 17883 9123 17883 9122 759 9120 759 9121 759 9127 17884 9120 17884 9126 17884 9126 17885 9120 17885 9125 17885 9119 759 9120 759 9118 759 9125 17886 9120 17886 9124 17886 9118 17887 9120 17887 9127 17887 9124 17888 9120 17888 9122 17888 9140 759 9129 759 9139 759 9128 759 9129 759 9140 759 9137 17889 9135 17889 9136 17889 9137 759 9134 759 9135 759 9131 759 9132 759 9130 759 9134 759 9132 759 9133 759 9139 17890 9132 17890 9138 17890 9130 759 9132 759 9129 759 9138 759 9132 759 9137 759 9137 759 9132 759 9134 759 9129 17891 9132 17891 9139 17891 9194 17892 9195 17892 9177 17892 9195 17893 9178 17893 9177 17893 9177 17894 9178 17894 9179 17894 9178 17895 9180 17895 9179 17895 9179 17896 9180 17896 9181 17896 9180 17897 9182 17897 9181 17897 9181 17898 9182 17898 9183 17898 9182 17899 9184 17899 9183 17899 9183 17900 9184 17900 9185 17900 9184 17901 9186 17901 9185 17901 9185 17902 9186 17902 9187 17902 9186 17903 9188 17903 9187 17903 9187 17904 9188 17904 9189 17904 9188 17905 9190 17905 9189 17905 9189 17906 9190 17906 9191 17906 9191 17907 9192 17907 9193 17907 9190 17908 9192 17908 9191 17908 9193 17909 9192 17909 9194 17909 9192 17910 9195 17910 9194 17910 9192 1433 9190 1433 9195 1433 9195 17911 9188 17911 9178 17911 9180 17912 9188 17912 9182 17912 9178 17913 9188 17913 9180 17913 9182 17914 9188 17914 9184 17914 9190 1433 9188 1433 9195 1433 9184 17915 9188 17915 9186 17915 9214 17916 9197 17916 9196 17916 9196 17917 9197 17917 9198 17917 9197 17918 9199 17918 9198 17918 9198 17919 9200 17919 9201 17919 9199 17920 9200 17920 9198 17920 9200 17921 9202 17921 9201 17921 9201 17922 9202 17922 9203 17922 9203 17923 9204 17923 9205 17923 9202 17924 9204 17924 9203 17924 9204 17925 9206 17925 9205 17925 9205 17926 9206 17926 9207 17926 9206 17927 9208 17927 9207 17927 9207 17928 9208 17928 9209 17928 9208 17929 9210 17929 9209 17929 9209 17930 9210 17930 9211 17930 9210 17931 9212 17931 9211 17931 9211 17932 9212 17932 9213 17932 9212 17933 9214 17933 9213 17933 9213 17934 9214 17934 9196 17934 9200 17935 9204 17935 9202 17935 9214 1433 9210 1433 9197 1433 9212 1433 9210 1433 9214 1433 9208 1433 9206 1433 9210 1433 9197 1433 9206 1433 9199 1433 9200 17936 9206 17936 9204 17936 9199 1433 9206 1433 9200 1433 9210 17937 9206 17937 9197 17937 9233 17938 9215 17938 9234 17938 9215 17939 9216 17939 9234 17939 9234 17940 9216 17940 9217 17940 9216 17941 9218 17941 9217 17941 9217 17942 9218 17942 9219 17942 9218 17943 9220 17943 9219 17943 9219 17944 9220 17944 9221 17944 9220 17945 9222 17945 9221 17945 9221 17946 9222 17946 9223 17946 9222 17947 9224 17947 9223 17947 9224 17948 9225 17948 9223 17948 9223 17949 9225 17949 9226 17949 9225 17950 9227 17950 9226 17950 9226 17951 9227 17951 9228 17951 9227 17952 9229 17952 9228 17952 9228 17953 9229 17953 9230 17953 9229 17954 9231 17954 9230 17954 9230 17955 9231 17955 9232 17955 9231 17956 9233 17956 9232 17956 9232 17957 9233 17957 9234 17957 9233 17958 9229 17958 9215 17958 9231 17959 9229 17959 9233 17959 9216 1433 9225 1433 9218 1433 9222 17960 9225 17960 9224 17960 9218 1433 9225 1433 9220 1433 9227 1433 9225 1433 9229 1433 9215 1433 9225 1433 9216 1433 9229 1433 9225 1433 9215 1433 9220 1433 9225 1433 9222 1433 9254 17961 9235 17961 9236 17961 9253 17962 9235 17962 9254 17962 9235 17963 9237 17963 9236 17963 9236 17964 9237 17964 9238 17964 9237 17965 9239 17965 9238 17965 9238 17966 9239 17966 9240 17966 9239 17967 9241 17967 9240 17967 9240 17968 9241 17968 9242 17968 9241 17969 9243 17969 9242 17969 9242 17970 9243 17970 9244 17970 9243 17971 9245 17971 9244 17971 9244 17972 9245 17972 9246 17972 9245 17973 9247 17973 9246 17973 9246 17974 9247 17974 9248 17974 9248 17975 9247 17975 9249 17975 9247 17976 9250 17976 9249 17976 9250 17977 9251 17977 9249 17977 9249 17978 9251 17978 9252 17978 9251 17979 9253 17979 9252 17979 9252 17980 9253 17980 9254 17980 9237 1433 9247 1433 9239 1433 9243 17981 9247 17981 9245 17981 9235 1433 9247 1433 9237 1433 9253 1433 9247 1433 9235 1433 9250 17982 9247 17982 9251 17982 9241 1433 9247 1433 9243 1433 9251 1433 9247 1433 9253 1433 9239 17983 9247 17983 9241 17983 9142 17984 9141 17984 9255 17984 9142 17985 9255 17985 9256 17985 9143 17986 9142 17986 9256 17986 9144 17987 9143 17987 9256 17987 9145 17988 9144 17988 9256 17988 9145 17989 9256 17989 9257 17989 9146 17990 9145 17990 9257 17990 9147 17991 9146 17991 9257 17991 9147 17992 9257 17992 9258 17992 9148 17993 9147 17993 9258 17993 9149 17994 9148 17994 9258 17994 9150 17995 9149 17995 9258 17995 9150 17996 9258 17996 9259 17996 9151 17997 9150 17997 9259 17997 9152 17998 9259 17998 9260 17998 9152 17999 9151 17999 9259 17999 9153 18000 9152 18000 9260 18000 9154 18001 9153 18001 9260 18001 9154 18002 9260 18002 9261 18002 9155 18003 9154 18003 9261 18003 9156 18004 9155 18004 9261 18004 9156 18005 9261 18005 9262 18005 9157 18006 9156 18006 9262 18006 9157 18007 9262 18007 9263 18007 9158 18008 9157 18008 9263 18008 9159 18009 9158 18009 9263 18009 9159 18010 9263 18010 9264 18010 9160 18011 9159 18011 9264 18011 9161 18012 9160 18012 9264 18012 9162 18013 9264 18013 9265 18013 9162 18014 9161 18014 9264 18014 9163 18015 9162 18015 9265 18015 9164 18016 9265 18016 9266 18016 9164 18017 9163 18017 9265 18017 9165 18018 9266 18018 9267 18018 9165 18019 9164 18019 9266 18019 9166 18020 9165 18020 9267 18020 9167 18021 9166 18021 9267 18021 9168 18022 9267 18022 9268 18022 9168 18023 9167 18023 9267 18023 9169 18024 9168 18024 9268 18024 9169 18025 9268 18025 9269 18025 9170 18026 9169 18026 9269 18026 9171 18027 9170 18027 9269 18027 9172 18028 9171 18028 9269 18028 9172 18029 9269 18029 9270 18029 9173 18030 9172 18030 9270 18030 9174 18031 9173 18031 9270 18031 9174 18032 9270 18032 9271 18032 9175 18033 9174 18033 9271 18033 9176 18034 9271 18034 9255 18034 9176 18035 9175 18035 9271 18035 9141 18036 9176 18036 9255 18036 9201 18037 9203 18037 9270 18037 9201 18038 9270 18038 9269 18038 9205 18039 9270 18039 9203 18039 9205 18040 9271 18040 9270 18040 9198 18041 9201 18041 9269 18041 9207 18042 9271 18042 9205 18042 9198 18043 9269 18043 9268 18043 9207 18044 9255 18044 9271 18044 9196 18045 9198 18045 9268 18045 9242 18046 9256 18046 9255 18046 9221 18047 9268 18047 9267 18047 9242 18048 9255 18048 9207 18048 9221 18049 9196 18049 9268 18049 9242 18050 9207 18050 9209 18050 9244 18051 9256 18051 9242 18051 9223 1433 9196 1433 9221 1433 9240 1433 9242 1433 9209 1433 9219 18052 9221 18052 9267 18052 9219 18053 9267 18053 9266 18053 9240 18054 9209 18054 9211 18054 9246 18055 9256 18055 9244 18055 9223 18056 9213 18056 9196 18056 9219 18057 9266 18057 9265 18057 9238 1433 9240 1433 9211 1433 9217 18058 9219 18058 9265 18058 9226 18059 9213 18059 9223 18059 9248 18060 9257 18060 9256 18060 9248 18061 9256 18061 9246 18061 9226 1433 9238 1433 9211 1433 9226 18062 9211 18062 9213 18062 9265 18063 9234 18063 9217 18063 9257 18064 9248 18064 9249 18064 9264 18065 9234 18065 9265 18065 9258 18066 9257 18066 9249 18066 9264 18067 9232 18067 9234 18067 9181 1433 9238 1433 9226 1433 9183 18068 9236 18068 9238 18068 9183 18069 9238 18069 9181 18069 9181 18070 9226 18070 9228 18070 9179 1433 9181 1433 9228 1433 9183 18071 9254 18071 9236 18071 9185 1433 9254 1433 9183 1433 9258 18072 9249 18072 9252 18072 9179 18073 9228 18073 9230 18073 9187 18074 9252 18074 9254 18074 9187 1433 9254 1433 9185 1433 9264 18075 9230 18075 9232 18075 9259 18076 9258 18076 9252 18076 9263 18077 9230 18077 9264 18077 9263 18078 9179 18078 9230 18078 9259 18079 9252 18079 9187 18079 9263 18080 9177 18080 9179 18080 9260 18081 9259 18081 9187 18081 9260 18082 9187 18082 9189 18082 9262 18083 9177 18083 9263 18083 9262 18084 9194 18084 9177 18084 9260 18085 9189 18085 9191 18085 9262 18086 9193 18086 9194 18086 9261 18087 9260 18087 9191 18087 9261 18088 9193 18088 9262 18088 9261 18089 9191 18089 9193 18089

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 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 + + + + + + + +
\ No newline at end of file diff --git a/models/gimbal_small_3d/meshes/yaw_arm.dae b/models/gimbal_small_3d/meshes/yaw_arm.dae new file mode 100644 index 0000000..823d278 --- /dev/null +++ b/models/gimbal_small_3d/meshes/yaw_arm.dae @@ -0,0 +1,552 @@ + + + + + Blender User + Blender 2.93.6 commit date:2021-11-16, commit time:14:54, hash:c842a90e2fa1 + + 2023-05-11T22:43:57 + 2023-05-11T22:43:57 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1000 + 29.99998 + 75 + 0.15 + 0 + 1 + 2 + 0.04999995 + 30.002 + 1 + 3 + 2880 + 3 + 1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 1.45 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.006289362 0.06200057 0.01424396 0.006733477 0.06999999 0.01435142 0.008868515 0.06200057 0.01469856 0.009445369 0.06999999 0.01474118 0.01230686 0.06200051 0.01466679 0.01287937 0.06999999 0.01459449 0.01567161 0.06200051 0.0139544 0.01621639 0.06999999 0.01377087 0.01882863 0.06200051 0.01258957 0.01932436 0.06999999 0.01230293 0.02165263 0.06200051 0.01062649 0.02208012 0.06999999 0.01024883 0.02403187 0.06200051 0.008142828 0.02437478 0.06999999 0.007689774 0.02587193 0.06200051 0.005237162 0.02611738 0.06999999 0.004727125 0.02709996 0.06200051 0.002024531 0.02723896 0.06999999 0.001478016 0.02766728 0.06200051 -0.001367568 0.02769517 0.06999999 -0.001928687 0.02755135 0.06200051 -0.004804968 0.02746796 0.06999999 -0.005358219 0.02675682 0.06200051 -0.008151352 0.02656626 0.06999999 -0.008675038 0.02531522 0.06200051 -0.01127386 0.02502584 0.06999999 -0.01174765 0.0232836 0.06200051 -0.01404899 0.02290755 0.06999999 -0.0144546 0.02074247 0.06200057 -0.01636672 0.02029538 0.06999999 -0.01668852 0.01779264 0.06200057 -0.01813519 0.01729255 0.06999999 -0.01836121 0.01455098 0.06200057 -0.01928418 0.01401811 0.06999999 -0.01940625 0.01114588 0.06200057 -0.01976835 0.01060152 0.06999999 -0.01978236 0.007712364 0.06200057 -0.01956838 0.007178068 0.06999999 -0.01947474 0.004386484 0.06200057 -0.01869225 0.003883361 0.06999999 -0.01849544 0.001300156 0.06200057 -0.01717472 8.47788e-4 0.06999999 -0.01688331 -0.001424372 0.06200057 -0.01507586 -0.001808643 0.06999999 -0.01470202 -0.003679335 0.06200057 -0.01247876 -0.003980755 0.06999999 -0.01203805 -0.005375087 0.06200057 -0.009486556 -0.005582392 0.06999999 -0.008996784 -0.006444513 0.06200057 -0.006217718 -0.006550312 0.06999999 -0.00569868 -0.006845235 0.06200057 -0.002801835 -0.006846189 0.06999999 -0.002274215 -0.006561338 0.06200063 6.25688e-4 -0.006458222 0.06999999 0.001141011 -0.005604147 0.06200063 0.003929078 -0.00540179 0.06999999 0.004411876 -0.004011571 0.06200063 0.006977438 -0.003718793 0.06999999 0.007408916 -0.001846671 0.06200063 0.009649991 -0.001475691 0.06999999 0.01001346 8.04663e-4 0.06200063 0.0118407 0.001238465 0.06999999 0.01212233 0.003837347 0.06200063 0.01346272 0.004249811 0.06999999 0.01362496 0.006238698 0.06999999 -0.02313554 -0.003047227 0.06999993 -0.01729112 -0.005192399 0.06999999 -0.01504141 -6.84504e-4 0.06999981 -0.01932263 -0.007342934 0.06999999 -0.01174867 0.001472771 0.06999766 -0.02165555 0.002625823 0.07000052 -0.02256083 -0.008820176 0.06999999 -0.008049488 0.003973364 0.07000029 -0.02309095 0.007176458 0.06999742 -0.02226406 -0.009536325 0.06999999 -0.004131197 0.01059633 0.07000005 -0.02252095 -0.009462952 0.06999999 -1.4874e-4 0.01249504 0.06999969 -0.02240097 0.01590812 0.07000023 -0.0230447 0.0132398 0.06999999 -0.02313649 -0.008603036 0.06999999 0.003740489 0.01744115 0.07000011 -0.02227681 0.01899665 0.06999486 -0.02107518 -0.006990611 0.06999999 0.00738275 0.02039933 0.06999981 -0.01993018 0.02250123 0.06999999 -0.01845854 -0.004689276 0.06999999 0.01063394 0.02441644 0.06999999 -0.01683115 -0.001790285 0.06999999 0.01336544 0.02708005 0.06999999 -0.01368188 0.00159192 0.06999999 0.01546937 0.02915656 0.06999999 -0.009612202 0.005323648 0.06999999 0.01686245 0.03019231 0.06999999 -0.005765736 0.009257197 0.06999999 0.01748955 0.03044641 0.06999999 -0.001790404 0.01323717 0.06999999 0.01732593 0.02990877 0.06999999 0.002156615 0.01710599 0.06999999 0.01637804 0.02860081 0.06999999 0.005919158 0.02071076 0.06999999 0.01468336 0.02657425 0.06999999 0.009348332 0.02390903 0.06999999 0.01230883 0.01255977 0.06099992 0.01061934 0.01691854 0.06099992 0.009143769 0.02092605 0.06099992 0.005718588 0.02329319 0.06099987 0.001008212 0.02365016 0.06099987 -0.00425136 0.02194118 0.06099992 -0.009238421 0.01843321 0.06099992 -0.01317352 0.01367449 0.06099992 -0.01544183 0.008408606 0.06099992 -0.01568895 0.00345844 0.06099992 -0.01387625 -2.25807e-4 0.06099992 -0.01049941 -0.002440035 0.06099987 -0.006002902 -0.002789378 0.06099987 -7.43163e-4 -0.0010733 0.06099992 0.004241049 0.002440154 0.06099992 0.008170902 0.007608771 0.06099987 0.01055532 0.007118284 0.06099998 0.001287579 0.007205069 0.05899995 0.001611471 0.007195711 0.06099998 0.001931369 0.007068037 0.05899995 0.002245128 0.006833374 0.06099998 0.002498567 0.006517171 0.05899995 0.002673625 0.006277501 0.06099998 0.002719521 0.005943775 0.05899995 0.002685785 0.005601763 0.06099998 0.002543747 0.005448579 0.05899995 0.002396702 0.005236387 0.06099998 0.002017498 0.00519967 0.05899995 0.001871049 0.005213797 0.06099998 0.001444399 0.005238234 0.05899995 0.001398921 0.00554496 0.05899995 9.23732e-4 0.005508244 0.06099998 9.71902e-4 0.005991458 0.06099998 7.11684e-4 0.006278574 0.05899995 6.8152e-4 0.006682753 0.06099998 8.07397e-4 0.006965041 0.05899995 0.001036226 0.006955325 0.06099998 -0.007463753 0.007124364 0.05900001 -0.007183909 0.007220327 0.06099998 -0.006766378 0.007189691 0.05899995 -0.006516098 0.006925106 0.06099998 -0.006053805 0.006705343 0.05899995 -0.00588572 0.00618875 0.06099998 -0.005751073 0.005916118 0.05899995 -0.005790412 0.00545752 0.06099998 -0.006066083 0.005295634 0.05899995 -0.006287455 0.005204975 0.06099998 -0.006608963 0.005202531 0.05899995 -0.0069772 0.005258142 0.06099998 -0.007184624 0.005441188 0.05900013 -0.007443904 0.005702435 0.06099998 -0.007660686 0.005897462 0.05899238 -0.007749557 0.006312847 0.06099998 -0.007790744 0.0066545 0.05899518 -0.007701456 -0.004557192 0.05900114 -0.01295244 9.5879e-4 0.05899906 -0.007854282 -0.006788432 0.05900156 -0.008487224 0.01417261 0.05899995 0.00258249 0.01372569 0.05899995 0.002078831 0.01465302 0.05899995 0.002715766 0.01374894 0.05899995 0.001281857 0.01514053 0.05899995 0.002610802 0.01548087 0.05899995 0.002318382 0.01567399 0.05899995 0.001912832 0.01395344 0.05899995 -0.006071448 0.01420331 0.05899995 8.18679e-4 0.0144304 0.05899995 -0.005799055 0.01369422 0.05899995 -0.006564974 0.01486563 0.05899995 6.94713e-4 0.0148797 0.05899995 -0.005790293 0.01371628 0.05899995 -0.007071912 0.01531267 0.05899995 -0.005984842 0.01397854 0.05899971 -0.007501542 0.01538759 0.05899995 9.91794e-4 0.02713161 0.0590111 0.005065202 0.01804614 0.05899971 -0.007746398 0.01563841 0.05899995 -0.007125854 0.01563537 0.05899995 0.00136578 0.01565462 0.05899995 -0.006476938 0.02310377 0.05900031 -0.01106232 0.01569831 0.06099998 -0.006682097 0.01536601 0.06099998 -0.006011605 0.01461106 0.06099998 -0.005753457 0.0140177 0.06099998 -0.006016731 0.01371747 0.06099998 -0.006466448 0.0137245 0.06099998 -0.007138907 0.01410621 0.06099998 -0.007604479 0.01446485 0.05899226 -0.007768988 0.01471853 0.06099998 -0.007805526 0.01517546 0.05899584 -0.007679998 0.01548004 0.06099998 -0.007428884 0.01539129 0.05614292 -0.0135563 0.015064 0.0572884 -0.01236641 0.01568788 0.05790221 -0.01147735 0.01559048 0.05835765 -0.0105803 0.01459813 0.05869871 -0.009599208 0.01602542 0.05895096 -0.008374392 0.01563036 0.06099998 0.00135827 0.01566863 0.06099998 0.001980841 0.01530343 0.06099998 0.002506673 0.01489406 0.06099998 0.002690851 0.01443701 0.06099998 0.002690076 0.01390397 0.06099998 0.00236696 0.01367336 0.06099998 0.00178796 0.01379936 0.06099998 0.00120306 0.01430583 0.06099998 7.59977e-4 0.01484489 0.06099998 7.15194e-4 0.01530587 0.06099998 9.06124e-4 -2.54222e-4 0.05136638 -0.02345925 -2.81222e-4 0.05248945 -0.02201753 -3.60892e-4 0.05290198 -0.02224195 -6.06265e-4 0.05469071 -0.02122974 -5.28047e-4 0.05437713 -0.02021998 -8.23628e-4 0.05526399 -0.01996588 -0.001030862 0.05613923 -0.0199927 -0.001143991 0.05615603 -0.01911133 -0.001676201 0.05732935 -0.01854872 -0.001525223 0.05712413 -0.01709997 -0.001956939 0.05755639 -0.01722741 -0.002072036 0.05803304 -0.01809722 -7.78598e-4 0.05539429 -0.01918143 -6.65417e-4 0.05469328 -0.02064985 -9.9197e-4 0.05601525 -0.01851886 -0.001284837 0.05704498 -0.01955473 -0.001556456 0.05700534 -0.01810473 -0.001828968 0.05814653 -0.018669 -0.001196622 0.05659818 -0.0176872 -0.001540839 0.05701643 -0.01762664 0.01977366 0.05171138 -0.0242061 0.01991063 0.05280506 -0.02236795 0.02004539 0.05364096 -0.02256619 0.0202049 0.05429613 -0.02116233 0.0212168 0.05728173 -0.01997905 0.02038407 0.05517077 -0.02159506 0.02057325 0.0554108 -0.02075916 0.02073907 0.05626082 -0.02082711 0.02048659 0.05525255 -0.02013945 0.0213133 0.0569877 -0.01936858 0.02080357 0.05613845 -0.01902651 0.02094238 0.05626124 -0.01934593 0.02210146 0.05893635 -0.01889228 0.02199625 0.05826085 -0.01883792 0.02162271 0.05803453 -0.01942551 0.02140808 0.05712765 -0.01790511 0.02093434 0.05633163 -0.02012878 0.02198177 0.05785918 -0.01838493 0.02146041 0.05709958 -0.01857841 0.02191543 0.05765968 -0.01797991 0.02250325 0.05891579 -0.01834827 0.02249854 0.05847793 -0.01798641 0.02185833 0.05764859 -0.01721543 0.02660697 0.06059038 -0.01423513 0.0259853 0.06078213 -0.01507836 0.0268293 0.06005614 -0.01356875 0.02775645 0.06064581 -0.01246786 0.02686071 0.05968737 -0.01304721 0.02544558 0.05951583 -0.01474219 0.0266329 0.05938625 -0.01280653 0.02508342 0.05918991 -0.01445716 0.02649939 0.05910193 -0.0120145 0.02496504 0.05901169 -0.01361286 0.02798479 0.06001937 -0.01156514 0.0286532 0.06059759 -0.01069885 0.02773267 0.05957674 -0.01132571 0.02746468 0.05921363 -0.01075798 0.02888101 0.05985587 -0.00931096 0.02940309 0.06081664 -0.008831918 0.02910822 0.06028366 -0.009311199 0.02849042 0.05938303 -0.009046256 0.02717125 0.05900228 -0.009750485 0.0295583 0.06028228 -0.007929801 0.02994203 0.06071412 -0.006863415 0.02843582 0.05910694 -0.007560014 0.02974516 0.05989181 -0.006338536 0.02924191 0.0594747 -0.006881296 0.03024548 0.06061917 -0.005083739 0.03007417 0.06008923 -0.004912018 0.02940034 0.05932885 -0.004900157 0.03042155 0.06078875 -0.003012537 0.02992898 0.0596708 -0.003421545 0.0288527 0.05906671 -0.004629552 0.03027969 0.06028407 -0.003489732 0.03023332 0.0601058 -0.001994311 0.02932351 0.05919492 -0.002915859 0.03036415 0.06070935 -9.89706e-4 0.0296095 0.05939763 -0.001081764 0.02876222 0.05901366 -0.003556609 0.03009045 0.06011688 -1.33823e-4 0.03010517 0.0606172 9.82085e-4 0.02978444 0.05965888 -1.25134e-4 0.02888989 0.05911612 6.0221e-4 0.02840965 0.05900418 3.92518e-4 0.0296095 0.05979579 0.001609146 0.02967047 0.06062012 0.002887964 0.02934664 0.06011247 0.003385424 0.02902185 0.0593602 0.002138257 0.02906399 0.06069386 0.004731416 0.02892577 0.05963951 0.003603577 0.02832889 0.05912017 0.002942502 0.02853208 0.06018757 0.005602955 0.02829009 0.05933225 0.004322111 0.02846205 0.06068694 0.006106793 0.02830946 0.0597431 0.005452692 0.0277571 0.06084936 0.007484257 0.02724391 0.05915123 0.00590521 0.02769851 0.06037455 0.007413148 0.0275219 0.05942189 0.006331145 0.02733522 0.05990487 0.007603883 0.0267226 0.06057733 0.009053349 0.02665776 0.05944746 0.007912635 0.02578639 0.06074154 0.01028877 0.02451562 0.05900895 0.009200453 0.02591341 0.05989289 0.009640455 0.02584505 0.05913019 0.008157312 0.02535706 0.06020075 0.01056867 0.02526473 0.05941748 0.00975871 0.02486211 0.06071323 0.01132833 0.02341341 0.06071281 0.01269614 0.02451312 0.05969208 0.01101702 0.02381533 0.05914431 0.01068347 0.02412796 0.06013613 0.01182168 0.02348965 0.05940675 0.01160639 0.02178633 0.06082499 0.01395702 0.02265959 0.05980539 0.01283985 0.02248579 0.06029748 0.01330858 0.02177309 0.05942082 0.01304835 0.02052307 0.06074953 0.01474756 0.02142024 0.05911862 0.01266723 0.02132093 0.06028366 0.01412379 0.01911157 0.06057143 0.01548606 0.01897865 0.05900663 0.01368951 0.02075994 0.05975514 0.01412147 0.02002847 0.06022328 0.01487582 0.01946157 0.05931985 0.01434803 0.01747697 0.06067389 0.0161997 0.01890057 0.05975741 0.0151512 0.01726835 0.06026571 0.01615697 0.01549661 0.0606516 0.01682734 0.01721525 0.05979734 0.01589 0.01720249 0.05913162 0.01497775 0.01679897 0.05939751 0.01562839 0.01539242 0.06002843 0.01662135 0.01497691 0.05948942 0.01629382 0.01355642 0.0607807 0.01724576 0.01466786 0.05916363 0.01582479 0.01355612 0.06024223 0.01711118 0.01337826 0.05900496 0.01554453 0.01345306 0.0597974 0.01686728 0.01205873 0.06064593 0.01740717 0.01190209 0.05950814 0.01679807 0.01133751 0.06008708 0.01727432 0.01238477 0.0593248 0.01650428 0.01050549 0.06071901 0.01748687 0.01139557 0.05913156 0.01621943 0.009699881 0.06005597 0.01725715 0.009085655 0.06064593 0.01742857 0.00962013 0.05947005 0.01679652 0.007607877 0.06078875 0.01729243 0.007625102 0.06020563 0.01714789 0.007239639 0.05977654 0.01683366 0.007943749 0.05928355 0.01639848 0.008574903 0.05900895 0.01571798 0.006161272 0.0606541 0.01701366 0.005756437 0.05997669 0.01666522 0.004643797 0.06071615 0.01663172 0.004768729 0.06016623 0.01650297 0.006011068 0.0593906 0.01618891 0.006250023 0.05908858 0.01564103 0.00445801 0.0595045 0.01590335 0.003294348 0.06059771 0.01615053 0.003064751 0.05975574 0.0156489 0.002684414 0.05901551 0.01415264 0.001990318 0.06076902 0.01562362 0.003083825 0.05919474 0.01491749 0.002002656 0.06022715 0.01548123 0.001458227 0.05970764 0.01486086 1.51271e-4 0.06062519 0.01463228 3.82292e-4 0.06002193 0.01450461 6.13529e-4 0.05928844 0.01383394 -0.00146085 0.06083559 0.01357769 -5.77396e-4 0.05957192 0.01350873 -0.001378357 0.06035041 0.01351952 -4.56877e-4 0.05909985 0.01264685 -0.001642346 0.05981189 0.01297122 -0.002620279 0.06063872 0.01262319 -0.003736495 0.06083559 0.01161485 -0.002798259 0.06002974 0.01217186 -0.001566886 0.05927407 0.01226884 -0.002666592 0.05953222 0.01178503 -0.003709554 0.06034791 0.011505 -0.004717648 0.06060594 0.01051717 -0.004248321 0.05991768 0.01062631 -0.002775132 0.05913722 0.01081848 -0.003917813 0.05948376 0.01043504 -0.005994558 0.06079828 0.008924782 -0.005281388 0.06032294 0.009695112 -0.001861393 0.05900412 0.01097017 -0.005365967 0.05983895 0.009163618 -0.004841029 0.059219 0.008716583 -0.006098449 0.06032449 0.008571267 -0.005524039 0.05953937 0.008513629 -0.004468381 0.05901855 0.008285582 -0.006618499 0.05996519 0.007418036 -0.007198154 0.06068271 0.0069229 -0.007493495 0.0601266 0.005951464 -0.006935954 0.0595268 0.006102919 -0.00604546 0.05907464 0.006095111 -0.007885813 0.06064593 0.005481064 -0.006594121 0.05924439 0.005886375 -0.008428394 0.06059759 0.004100263 -0.008101522 0.05984085 0.004035711 -0.009010672 0.06062233 0.002126872 -0.007629156 0.05934488 0.003846943 -0.007382988 0.05909502 0.002999484 -0.008654057 0.06004601 0.002657711 -0.008277297 0.05953598 0.002532005 -0.00722599 0.05900329 0.00215435 -0.009021878 0.06008595 0.001144707 -0.008248686 0.0592873 0.001338779 -0.009365081 0.06070518 3.07595e-4 -0.008771777 0.05960094 6.4061e-4 -0.009239077 0.06009554 -2.50807e-4 -0.00951147 0.06064593 -0.001233935 -0.008267521 0.05914157 -6.13653e-4 -0.009350538 0.0600965 -0.001682102 -0.009562313 0.0606938 -0.002687811 -0.009105563 0.05971539 -0.001781821 -0.008779704 0.05940276 -0.001859128 -0.009338974 0.06006646 -0.003193259 -0.00944072 0.06061387 -0.00463587 -0.008909404 0.05955243 -0.004135191 -0.007852911 0.05900752 -0.002752423 -0.009186744 0.05999904 -0.004752516 -0.00846666 0.05921792 -0.00368613 -0.007947862 0.05906009 -0.004931032 -0.009138524 0.06071573 -0.006614983 -0.008980333 0.06021219 -0.006661474 -0.008295357 0.05928695 -0.006075084 -0.008775293 0.05979114 -0.006458759 -0.008615076 0.06060296 -0.0085572 -0.008317351 0.05953586 -0.007410287 -0.008239269 0.05994558 -0.008870899 -0.007122814 0.05905526 -0.008441507 -0.007325768 0.05921596 -0.009131014 -0.007921874 0.06079822 -0.01046013 -0.007803559 0.05961573 -0.009307444 -0.00781089 0.0602737 -0.01041448 -0.007082998 0.06070941 -0.0121541 -0.007126331 0.05975413 -0.01117396 -0.006932616 0.06023174 -0.01214474 -0.006487071 0.05936312 -0.0115503 -0.006077468 0.0607649 -0.01378959 -0.005815029 0.06029552 -0.01398867 -0.005928575 0.05998915 -0.01353293 -0.006213068 0.05982345 -0.01291948 -0.005754292 0.05905896 -0.01151639 -0.004801511 0.0591281 -0.01348203 0.02295172 0.05983173 -0.01810497 0.02447825 0.0603246 -0.01671284 0.023072 0.05934363 -0.01784145 0.02319294 0.05897444 -0.01736491 0.02389991 0.0589112 -0.01576918 0.02280914 0.05849146 -0.01728385 0.02472132 0.0599004 -0.01620173 0.0232371 0.05860602 -0.01576888 0.02232187 0.05807238 -0.01655054 0.02262449 0.05826836 -0.01700043 0.02515971 0.05979233 -0.01552915 0.02439355 0.0593174 -0.0159648 0.02429342 0.05895453 -0.01452493 -0.002740979 0.05958247 -0.01758533 -0.002979278 0.05938065 -0.01726704 -0.003132224 0.05852466 -0.01543539 -0.002494215 0.05810856 -0.01604127 -0.002910792 0.05842846 -0.01521885 -0.004415154 0.05931025 -0.01495605 -0.005083441 0.05939787 -0.01389616 -0.003933787 0.05933511 -0.01585936 -0.003682136 0.06006652 -0.01666468 -0.002959728 0.0587778 -0.01683413 -0.003709912 0.05890744 -0.01542812 -0.002906203 0.05848294 -0.01634997 -0.004944086 0.06049269 -0.01527541 -0.003865003 0.05887079 -0.01461911 -0.003742575 0.05882734 -0.01411885 -0.002279818 0.05885505 -0.01808679 -0.001988172 0.0577085 -0.01636648 -0.00254929 0.05857378 -0.01745176 -0.002342045 0.05803501 -0.0170902 4.47055e-4 0.05405843 -0.01813256 -0.002444684 0.05889844 -0.01168495 -0.001582503 0.05860751 -0.01254659 -8.59795e-4 0.05813968 -0.0134676 0.00254786 0.05894291 -0.008476853 -2.22118e-4 0.05718028 -0.01506865 4.36912e-4 0.05758458 -0.01360315 0.001236557 0.05869096 -0.01033377 0.001129209 0.05675017 -0.01437848 0.001625597 0.0583173 -0.01129955 0.001336216 0.05519217 -0.01589053 3.9111e-4 0.05601549 -0.01608973 0.003677904 0.0587114 -0.009549975 0.002096593 0.05781388 -0.01215153 0.002030432 0.05555647 -0.01495563 0.003764152 0.05836248 -0.01055896 0.002451062 0.05707585 -0.01311588 0.002801299 0.05592054 -0.01416885 0.003887474 0.05791342 -0.01145434 0.004034399 0.05717903 -0.01251721 0.003566563 0.05610728 -0.01371991 0.004341363 0.0561676 -0.01351714 5.92533e-4 0.05479604 -0.01719629 -1.39848e-5 0.05354505 -0.01969546 -2.62432e-4 0.06265735 -0.02277904 -4.59951e-4 0.06076824 -0.02181792 -0.001099586 0.06088727 -0.01993799 -0.002123534 0.06803864 -0.01810967 0.02187794 0.06729048 -0.01893353 0.01928877 0.05884814 -0.01005375 0.01774573 0.05860286 -0.01046365 0.01783925 0.05774945 -0.01246684 0.01961356 0.05866408 -0.01119124 0.01663994 0.05698686 -0.01304769 0.01598125 0.0566678 -0.01320326 0.02305155 0.05892652 -0.01273363 0.0218597 0.05860114 -0.01346969 0.01661276 0.05545222 -0.01448798 0.01704263 0.05630648 -0.01396298 0.02075225 0.05800229 -0.01436662 0.01774466 0.05660164 -0.01407289 0.01774042 0.05501353 -0.01559799 0.01803338 0.05596786 -0.01501011 0.01997917 0.05728375 -0.01512825 0.01917779 0.05513757 -0.01727616 0.02014285 0.05582559 -0.01807099 0.01968538 0.05465805 -0.01880091 0.01877713 0.05387467 -0.01774716 0.01899856 0.0582537 -0.0121079 0.01907956 0.05769717 -0.01343798 0.01835 0.05706512 -0.01389473 0.02013242 0.05661022 -0.01659077 0.01866811 0.05535662 -0.01633137 0.01973503 0.05132323 -0.02289003 0.01966691 0.05322539 -0.02058446 0.01940244 0.05341666 -0.01947253 0.01972913 0.03190773 -0.03712773 0.01976901 0.05943334 -0.02421832 0.01973319 0.02154147 -0.0412451 0.01973837 0.02314329 -0.04098945 0.01973897 0.02560901 -0.04019284 0.01918458 0.02841401 -0.03770279 0.01878988 0.02646756 -0.03834259 0.01714807 0.02317523 -0.03904187 0.01597589 0.02211046 -0.03926962 0.01503598 0.02166718 -0.0394293 0.02012574 0.05914729 -0.0223428 0.0205729 0.06171047 -0.02111464 0.01734399 0.06905996 -0.02294802 0.01621055 0.06930381 -0.02340877 0.01513701 0.06923007 -0.02370619 0.021209 0.06267517 -0.01991826 0.02104127 0.06732833 -0.0196979 0.01978242 0.06196075 -0.02328091 0.02059531 0.06529062 -0.02048248 0.02005797 0.06748855 -0.02070188 0.01975196 0.06543755 -0.02191823 0.01942753 0.06479859 -0.02308583 0.0188874 0.06739133 -0.02239227 0.01858729 0.06881034 -0.02195459 0.01816582 0.06836795 -0.02269303 0.0155099 0.02506417 -0.05682641 0.01567584 0.01861357 -0.06165409 0.01607894 0.02482223 -0.05686008 0.01670598 0.01822161 -0.06155651 0.01716285 0.02671265 -0.05488604 0.01726496 0.02480733 -0.05624854 0.01741945 0.01806145 -0.06120383 0.01762336 0.02521836 -0.05564701 0.01766717 0.0256952 -0.05524921 0.01817482 0.01784217 -0.0606715 0.01885634 0.01764917 -0.05985271 0.01926225 0.01739174 -0.05917018 0.01963353 0.01732832 -0.05795723 0.01975107 0.01783806 -0.05644631 9.85374e-4 0.06895846 -0.02181261 3.97857e-4 0.06925821 -0.02079504 -0.001109659 0.06809216 -0.01917511 -3.89271e-4 0.06721723 -0.02042406 3.04635e-4 0.06717902 -0.02188193 -0.001994669 0.06496262 -0.01836264 -7.58573e-5 0.06618165 -0.02150648 -9.99154e-4 0.06438285 -0.0199356 -4.11493e-4 0.06426459 -0.02143877 -2.54483e-4 0.01791065 -0.05632293 -2.36084e-4 0.02304124 -0.04102385 -2.35923e-4 0.02506279 -0.0403952 -2.23267e-4 0.02704954 -0.03946578 -2.30183e-4 0.03206926 -0.03703552 -1.67687e-4 0.0174027 -0.05773019 1.02451e-4 0.01782304 -0.05841404 3.21325e-4 0.01752859 -0.05927324 9.03963e-4 0.01793968 -0.06003105 0.001757502 0.0181421 -0.06088477 0.002273797 0.02618342 -0.05523854 0.002295672 0.0252183 -0.05597776 0.0021829 0.02564597 -0.05557245 0.002598643 0.01831912 -0.06136983 0.002584397 0.02494478 -0.05636835 0.00261414 0.026717 -0.05505794 0.003115653 0.0271005 -0.05502957 0.00334376 0.01847362 -0.06161534 0.003168463 0.02480226 -0.05677855 0.003710031 0.02725589 -0.05511891 0.003788292 0.0248664 -0.05693525 0.004174232 0.02721279 -0.05524051 0.004706144 0.01944363 -0.06112718 0.004255354 0.02500957 -0.05690962 0.004557847 0.02708905 -0.05537295 0.006300866 0.02207225 -0.05914551 0.006758153 0.02196776 -0.05872279 0.007636368 0.02166724 -0.05828046 0.008275926 0.02381592 -0.05631887 0.008453667 0.06888329 -0.02241325 0.01002717 0.06847202 -0.02250874 0.01036465 0.02370238 -0.05616778 0.01149797 0.06903958 -0.02248066 0.01174944 0.02395015 -0.05649751 0.01219284 0.02170109 -0.05848389 0.01282286 0.02200531 -0.05877733 0.01322275 0.02235192 -0.0589357 3.91593e-4 0.02802896 -0.03780668 8.40155e-4 0.02605688 -0.03842127 0.001958489 0.02377963 -0.03887778 0.003217339 0.0222941 -0.03924286 0.004288911 0.02180409 -0.03934335 0.01174998 0.02089345 -0.06001639 0.01297402 0.02165657 -0.05945813 0.01490831 0.01914352 -0.06135243 0.0117501 0.02153462 -0.05834954 0.01226025 0.02126282 -0.05925965 0.01175016 0.02101397 -0.05922812 0.008249104 0.02076154 -0.06012028 0.00824964 0.02128148 -0.0583446 0.006878316 0.02160531 -0.05905306 0.007747948 0.0209552 -0.05950826 0.008249878 0.020796 -0.05941313 0.00745505 0.02125555 -0.05899149 0.006961643 0.02126944 -0.059749 0.004911601 0.02687442 -0.05553793 0.005205512 0.02567666 -0.05643802 0.004779517 0.02526485 -0.05674874 0.005324304 0.02604335 -0.05615901 0.005228579 0.0265302 -0.0557968 0.00824964 0.01729422 -0.05199998 0.008241832 0.01610702 -0.05199998 0.00824958 0.01611751 -0.05599999 0.008249163 0.01869422 -0.06281292 0.008249998 0.01357001 -0.05599999 0.008248984 0.01919215 -0.0619052 0.008249938 0.01968932 -0.06109368 0.008253812 0.01729381 -0.04763799 0.01174902 0.01720571 -0.04752075 0.01017516 0.01734775 -0.04770976 0.01205235 0.004916429 -0.06017291 0.01240551 0.004526913 -0.05599999 0.01139664 0.00540471 -0.05599999 0.01112365 0.005521357 -0.06017291 0.01003497 0.005834877 -0.06017291 0.01015299 0.005810022 -0.05599999 0.009018242 0.005790054 -0.05599999 0.008816003 0.005741417 -0.06017291 0.007899105 0.005374193 -0.05599999 0.007925391 0.005381166 -0.06017291 0.007162213 0.004800498 -0.06017291 0.006785571 0.004393339 -0.05599999 0.006459891 0.003801941 -0.06017291 0.006207406 0.002996861 -0.05599999 0.00614953 0.002530097 -0.06017291 0.006217598 0.001540899 -0.05599999 0.006255984 0.001486957 -0.06017291 0.006620526 5.70758e-4 -0.06017291 0.006942987 8.17687e-5 -0.05599999 0.007233917 -2.01307e-4 -0.06017291 0.008266091 -9.16732e-4 -0.05599999 0.008085787 -8.12611e-4 -0.06017291 0.009343445 -0.001176178 -0.06017291 0.009639084 -0.00118035 -0.05599999 0.01055908 -0.001063764 -0.06017291 0.01059103 -0.001051008 -0.05599999 0.01147383 -6.76642e-4 -0.05599999 0.01174825 -5.13462e-4 -0.06017291 0.01228016 -8.72251e-6 -0.05599999 0.01267939 5.26057e-4 -0.06017291 0.01289343 9.44977e-4 -0.05599999 0.01306885 0.001496493 -0.06017291 0.01316225 0.002047419 -0.05599999 0.01317119 0.002424597 -0.06017291 0.01304012 0.00334984 -0.05599999 0.01291304 0.003708302 -0.06017291 0.01450413 -0.006632804 -0.06118053 0.0148192 -0.005398154 -0.06118053 0.01420533 -0.005287647 -0.06118053 0.01550811 -0.006550669 -0.06118053 0.01368498 -0.006430029 -0.06118053 0.01540917 -0.005240201 -0.06118053 0.01282179 -0.005870699 -0.06118053 0.01370811 -0.004976868 -0.06118053 0.01636672 -0.006121098 -0.06118053 0.01603001 -0.004736542 -0.06118053 0.01695805 -0.005549013 -0.06118053 0.01212894 -0.00479412 -0.06118053 0.01327425 -0.004263281 -0.06118053 0.01741319 -0.004651367 -0.06118053 0.01199936 -0.003771483 -0.06118053 0.01626819 -0.003832101 -0.06118053 0.01333034 -0.003355324 -0.06118053 0.01750236 -0.003558158 -0.06118053 0.01218879 -0.002831518 -0.06118053 0.01611036 -0.003228604 -0.06118053 0.01708692 -0.002372682 -0.06118053 0.01296389 -0.001757204 -0.06118053 0.01386201 -0.002647638 -0.06118053 0.01623153 -0.001549005 -0.06118053 0.01402252 -0.001219213 -0.06118053 0.01471376 -0.002365112 -0.06118053 0.01516366 -0.001138508 -0.06118053 0.01562434 -0.002625882 -0.06118053 0.01214212 -0.00481528 -0.06400001 0.01199525 -0.003798127 -0.06400001 0.01224559 -0.002680778 -0.06400001 0.01297605 -0.001771748 -0.06400001 0.01395273 -0.001224219 -0.06400001 0.01518428 -0.001150131 -0.06400001 0.01637458 -0.001623213 -0.06400001 0.01724034 -0.002657651 -0.06400001 0.01753556 -0.003996431 -0.06400001 0.01719301 -0.005183339 -0.06400001 0.01663464 -0.005905568 -0.06400001 0.01583194 -0.006431877 -0.06400001 0.0149843 -0.006631374 -0.06400001 0.01396024 -0.006546616 -0.06400001 0.01281946 -0.005873143 -0.06400001 0.01526063 -0.002449035 -0.05599999 0.01433879 -0.002417206 -0.05599999 0.01365202 -0.002848327 -0.05599999 0.01325631 -0.003583788 -0.05599999 0.01340842 -0.004619419 -0.05599999 0.01423203 -0.005324244 -0.05599999 0.01505488 -0.005362868 -0.05599999 0.01569259 -0.005077898 -0.05599999 0.0161606 -0.00444734 -0.05599999 0.01626002 -0.003781378 -0.05599999 0.01601451 -0.003022074 -0.05599999 0.001809537 -0.006608128 -0.06118053 0.002424001 -0.00539267 -0.06118053 0.001760721 -0.005276679 -0.06118053 0.003088355 -0.006546437 -0.06118053 7.82001e-4 -0.006163537 -0.06118053 0.003034174 -0.005214989 -0.06118053 0.001235187 -0.004919171 -0.06118053 0.004043102 -0.006051778 -0.06118053 1.34547e-4 -0.005551099 -0.06118053 0.0036031 -0.004727542 -0.06118053 0.00465548 -0.005374729 -0.06118053 8.49401e-4 -0.004221141 -0.06118053 -3.68308e-4 -0.004523992 -0.06118053 0.005031943 -0.004491806 -0.06118053 0.003852546 -0.00386554 -0.06118053 -3.79658e-4 -0.003357708 -0.06118053 9.55996e-4 -0.003204822 -0.06118053 0.005055308 -0.003348708 -0.06118053 -9.85858e-5 -0.002583265 -0.06118053 0.003644406 -0.003121078 -0.06118053 0.004627406 -0.002338051 -0.06118053 4.32493e-4 -0.001868903 -0.06118053 0.001586556 -0.002565324 -0.06118053 0.003798425 -0.001519322 -0.06118053 0.001196265 -0.001368045 -0.06118053 0.001986682 -0.0011397 -0.06118053 0.002156257 -0.002383172 -0.06118053 0.002974748 -0.002485573 -0.06118053 0.002809047 -0.001163601 -0.06118053 1.26544e-4 -0.005531251 -0.06400001 -2.68864e-4 -0.004808485 -0.06400001 -4.29418e-4 -0.003862202 -0.06400001 -1.74103e-4 -0.002676546 -0.06400001 7.64813e-4 -0.001585364 -0.06400001 0.001939475 -0.001140534 -0.06400001 0.002897977 -0.001178443 -0.06400001 0.003792762 -0.001527845 -0.06400001 0.004746854 -0.002482473 -0.06400001 0.005111813 -0.003922879 -0.06400001 0.004883766 -0.004928171 -0.06400001 0.004426479 -0.005691885 -0.06400001 0.003676116 -0.006291687 -0.06400001 0.002884984 -0.006585538 -0.06400001 0.001765429 -0.006599307 -0.06400001 7.06414e-4 -0.006113469 -0.06400001 0.00273323 -0.002407193 -0.05599999 0.001959621 -0.002418339 -0.05599999 0.001357734 -0.002719879 -0.05599999 8.86652e-4 -0.003409147 -0.05599999 8.80292e-4 -0.004343867 -0.05599999 0.001309275 -0.004987657 -0.05599999 0.001877725 -0.005325019 -0.05599999 0.002775132 -0.005345284 -0.05599999 0.003494679 -0.004851162 -0.05599999 0.003821849 -0.004178643 -0.05599999 0.00379002 -0.003480732 -0.05599999 0.003469526 -0.002875089 -0.05599999 0.004525065 0.005576729 -0.06118053 0.004126548 0.006866812 -0.06118053 0.003382921 0.005811989 -0.06118053 0.004983603 0.006938815 -0.06118053 0.005696654 0.005890429 -0.06118053 0.003435373 0.007241427 -0.06118053 0.002573072 0.006327152 -0.06118053 0.005533456 0.007305681 -0.06118053 0.006563901 0.006561458 -0.06118053 0.001973152 0.00713557 -0.06118053 0.00301367 0.00785917 -0.06118053 0.005899846 0.007900416 -0.06118053 0.001693785 0.008124947 -0.06118053 0.007036507 0.007399201 -0.06118053 0.007210969 0.008202135 -0.06118053 0.002968072 0.008655488 -0.06118053 0.001774311 0.009014129 -0.06118053 0.005945861 0.008547127 -0.06118053 0.007063448 0.009288728 -0.06118053 0.002090454 0.009796142 -0.06118053 0.003211796 0.009214878 -0.06118053 0.002884626 0.01064932 -0.06118053 0.006489694 0.01022434 -0.06118053 0.00373286 0.009699344 -0.06118053 0.00574547 0.009150803 -0.06118053 0.005216658 0.009662449 -0.06118053 0.005827248 0.0107479 -0.06118053 0.003880202 0.01105779 -0.06118053 0.004907369 0.01109272 -0.06118053 0.004537403 0.009870648 -0.06118053 0.002250194 0.006685137 -0.06400001 0.001760363 0.007691383 -0.06400001 0.00171554 0.008718192 -0.06400001 0.001943349 0.009508669 -0.06400001 0.002529025 0.01035535 -0.06400001 0.00356549 0.01098316 -0.06400001 0.004564106 0.01111531 -0.06400001 0.005371868 0.01095974 -0.06400001 0.006266593 0.01045393 -0.06400001 0.007028043 0.009397268 -0.06400001 0.007213056 0.008245646 -0.06400001 0.006985247 0.007243156 -0.06400001 0.006305992 0.006296336 -0.06400001 0.005356252 0.005746364 -0.06400001 0.004201531 0.005590975 -0.06400001 0.003030836 0.005982518 -0.06400001 0.005161345 0.009690344 -0.05599999 0.004587948 0.00986129 -0.05599999 0.003774642 0.009729921 -0.05599999 0.003132343 0.00910288 -0.05599999 0.002945303 0.008456408 -0.05599999 0.003070414 0.007718443 -0.05599999 0.003571212 0.007129251 -0.05599999 0.004302263 0.006841719 -0.05599999 0.005250751 0.007054448 -0.05599999 0.005864918 0.007792115 -0.05599999 0.005952656 0.008498132 -0.05599999 0.005730271 0.009186029 -0.05599999 0.01616805 0.005666017 -0.06118053 0.01696252 0.006826102 -0.06118053 0.01740217 0.005637049 -0.06118053 0.01609373 0.007053077 -0.06118053 0.0183559 0.006022453 -0.06118053 0.01513451 0.006204068 -0.06118053 0.01786106 0.007196962 -0.06118053 0.01455622 0.006853461 -0.06118053 0.0155031 0.00767821 -0.06118053 0.01897257 0.006568789 -0.06118053 0.01415914 0.007778406 -0.06118053 0.01829749 0.007849752 -0.06118053 0.01947063 0.007387936 -0.06118053 0.01536506 0.008464276 -0.06118053 0.01415777 0.008875846 -0.06118053 0.01962822 0.008336782 -0.06118053 0.01835495 0.008746564 -0.06118053 0.01551765 0.009016335 -0.06118053 0.0194832 0.009284555 -0.06118053 0.01464825 0.01003265 -0.06118053 0.01598918 0.009598493 -0.06118053 0.01895236 0.01016652 -0.06118053 0.01787 0.009488165 -0.06118053 0.01556694 0.01078557 -0.06118053 0.0182687 0.01073789 -0.06118053 0.01652306 0.01110249 -0.06118053 0.01665657 0.009843468 -0.06118053 0.01725524 0.009819447 -0.06118053 0.01748132 0.01104295 -0.06118053 0.01457816 0.006811559 -0.06400001 0.01416909 0.007755339 -0.06400001 0.01414155 0.008783042 -0.06400001 0.01448363 0.009753108 -0.06400001 0.01514625 0.01051074 -0.06400001 0.01611632 0.01102316 -0.06400001 0.01727992 0.01108956 -0.06400001 0.01818853 0.01078021 -0.06400001 0.01894313 0.01018691 -0.06400001 0.01948678 0.0092597 -0.06400001 0.01962828 0.007964968 -0.06400001 0.01915818 0.006799221 -0.06400001 0.01847022 0.006099343 -0.06400001 0.01753687 0.005666851 -0.06400001 0.01637196 0.005626261 -0.06400001 0.01529741 0.006076931 -0.06400001 0.01767754 0.009627342 -0.05599999 0.01704591 0.009862005 -0.05599999 0.01634186 0.009767293 -0.05599999 0.01570218 0.009331881 -0.05599999 0.01537483 0.008576929 -0.05599999 0.01549118 0.007686376 -0.05599999 0.01610666 0.007048845 -0.05599999 0.01671135 0.006852328 -0.05599999 0.01748973 0.006958365 -0.05599999 0.01821392 0.007624983 -0.05599999 0.01838034 0.008405387 -0.05599999 0.01818233 0.009127199 -0.05599999 0.01175057 0.01865476 -0.06276351 0.01174998 0.01357001 -0.05599999 0.01175063 0.01885646 -0.06243914 0.01174998 0.01598924 -0.05599999 0.01175028 0.01916664 -0.06180715 0.01175081 0.01974666 -0.06099206 0.01175051 0.01721721 -0.05199998 0.01175206 0.01600271 -0.05199998 0.02053236 0.01539766 -0.06132894 0.01731449 0.01432704 -0.06399774 0.01880824 0.01379954 -0.06393474 0.01656645 0.01518505 -0.06395226 0.01863408 0.01441127 -0.06382781 0.01869463 0.01495939 -0.06359845 0.02007365 0.01458567 -0.06319558 0.01826047 0.01581454 -0.06326925 0.01614922 0.01605737 -0.06377834 0.01916033 0.01577204 -0.06276381 0.01711708 0.01584637 -0.06365072 0.01996082 0.01566863 -0.06199783 0.01863783 0.01650512 -0.06219011 0.01447784 0.0159828 -0.06398004 0.01727861 0.016891 -0.06280386 0.01941126 0.01622933 -0.06147366 0.01619178 0.01675307 -0.06340193 0.01435673 0.01679861 -0.06376308 0.01542401 0.01738679 -0.06315678 0.01429885 0.01736277 -0.0634694 0.01581841 0.01760393 -0.06273251 0.01219105 0.01709562 -0.06385642 0.01441591 0.01811635 -0.06272053 0.010773 0.01655966 -0.06399345 0.01259601 0.01771861 -0.06352263 0.0134204 0.01806181 -0.06309717 0.01305657 0.01852315 -0.06262785 0.01018214 0.01723235 -0.06387627 0.01158273 0.01834946 -0.06314593 0.01006358 0.01794552 -0.06355696 0.007486939 0.01643395 -0.06399416 0.007475376 0.01687031 -0.06393605 0.009578824 0.01871883 -0.0628696 0.008774757 0.01781213 -0.0636298 0.007698714 0.01823353 -0.06325036 0.006617188 0.01756429 -0.06359982 0.003401756 0.01518392 -0.06399828 0.006017327 0.01699668 -0.06380748 0.006660938 0.01856261 -0.06271016 0.005914747 0.01793795 -0.06322354 0.004053711 0.01604425 -0.06390273 0.004510343 0.01716983 -0.06349641 0.003622889 0.0165202 -0.06366544 0.005127012 0.01828593 -0.0625714 0.004165112 0.0176748 -0.06297993 0.00242567 0.015325 -0.06388676 0.002635419 0.0167185 -0.06326663 0.001352727 0.01531481 -0.06367278 0.002914607 0.01739525 -0.06269603 1.21908e-4 0.01345378 -0.06394445 0.001421868 0.0158329 -0.06341558 4.52732e-4 0.014333 -0.06379956 0.001060307 0.01619052 -0.06295478 0.001716434 0.01689815 -0.06256574 -0.001355707 0.01173907 -0.06397664 2.51784e-4 0.01530861 -0.06324678 5.7243e-4 0.01657003 -0.06190377 3.78289e-4 0.01610279 -0.06255453 -9.18515e-4 0.01397454 -0.06348067 -9.88204e-4 0.01318621 -0.06376469 -9.37883e-4 0.01476556 -0.06291842 -0.001544773 0.01382035 -0.06323307 -8.78648e-4 0.01557028 -0.06183958 -0.002722859 0.009424686 -0.06399524 -4.3869e-4 0.01602703 -0.06125152 -0.001461863 0.01482021 -0.06234353 -0.00200212 0.01257324 -0.06360822 -0.002783656 0.01083964 -0.06382697 -0.002143144 0.01364034 -0.06290823 -0.001636683 0.01506644 -0.06123512 -0.002702355 0.01355081 -0.06238442 -0.002611994 0.01399612 -0.06178754 -0.003003299 0.01207953 -0.0632897 -0.003160893 0.01268714 -0.0627287 -0.004339694 0.005618035 -0.06399148 -0.003764688 0.008370459 -0.06392604 -0.002581059 0.01414495 -0.06130802 -0.003805696 0.0123741 -0.06216019 -0.003813624 0.0106911 -0.06339454 -0.003977358 0.01160717 -0.0627222 -0.003973901 0.009401142 -0.0636959 -0.00352776 0.01307541 -0.06137734 -0.00461924 0.00947535 -0.06329333 -0.005070388 0.009710788 -0.06275248 -0.00457251 0.007738173 -0.06375968 -0.004438996 0.01183879 -0.06142538 -0.004799902 0.01072305 -0.06233423 -0.004982471 0.0109393 -0.06156682 -0.004737257 0.008285284 -0.06357055 -0.005381166 0.007632553 -0.06330823 -0.005732178 0.007777988 -0.06293612 -0.005041062 0.005681216 -0.06381601 -0.005708515 0.009339511 -0.06192266 -0.005533277 0.00603789 -0.0635364 -0.005745828 0.009560883 -0.06123161 -0.005906522 0.008184194 -0.06248635 -0.005821108 0.006419539 -0.06325119 -0.004680454 0.001402616 -0.06399214 -0.006246984 0.008321702 -0.06142723 -0.006312012 0.007383227 -0.06227135 -0.005266129 0.003543496 -0.06385099 -0.006471753 0.005857586 -0.06268024 -0.006344377 0.004886209 -0.06306505 -0.00583899 0.003321051 -0.06360584 -0.006620287 0.007223546 -0.06143826 -0.006841659 0.005918741 -0.06190931 -0.006242632 0.003718435 -0.0632928 -0.00692594 0.005004346 -0.06213736 -0.007016539 0.005714058 -0.06124645 -0.006844401 0.004220485 -0.06251263 -0.005200564 9.70603e-4 -0.06387281 -0.006642639 0.003361165 -0.06290966 -0.006390452 0.002433955 -0.0632165 -0.007129728 0.004218816 -0.06188672 -0.005632281 5.07684e-4 -0.06367236 -0.007013976 0.002357602 -0.06241035 -0.0072636 0.004041492 -0.06124925 -0.006307065 0.001120328 -0.06325048 -0.007236182 0.002764642 -0.06185621 -0.00681442 0.001731514 -0.06270867 -0.00735104 0.002584397 -0.06119477 -0.006611526 9.15651e-5 -0.06279295 -0.003275454 -0.003690063 -0.06399625 -0.007287859 0.00173664 -0.06159627 -0.00592482 -0.001046001 -0.06330579 -0.004628717 -0.001529276 -0.0639069 -0.007023334 6.86246e-4 -0.06222778 -0.005176901 -0.002049207 -0.06363648 -0.006237685 -0.001126289 -0.06299233 -0.007266879 7.38881e-4 -0.06134593 -0.00673294 -7.1408e-4 -0.06239753 -0.006917417 -8.6574e-4 -0.06189835 -0.004039347 -0.003950893 -0.06382077 -0.007050335 -8.20745e-4 -0.06127446 -0.005459904 -0.003293633 -0.06314092 -0.006370306 -0.002294659 -0.0623731 -0.005776345 -0.003418087 -0.06273877 -0.00650531 -0.002702474 -0.06173264 -0.004524588 -0.004736959 -0.0633831 -0.006651937 -0.002475082 -0.06122881 -0.003164529 -0.004995286 -0.06390702 -0.001287221 -0.007051289 -0.0639823 -0.005855917 -0.004236221 -0.06200796 -0.003515839 -0.005988538 -0.0635634 -0.005016386 -0.005156934 -0.06271916 -0.002771496 -0.006811499 -0.06365925 -0.006096839 -0.004058241 -0.06123208 -0.001836121 -0.007239758 -0.06385326 -0.004081249 -0.006383538 -0.06297963 -0.005198121 -0.005545973 -0.06207662 -0.00540328 -0.005542993 -0.06130421 -8.30565e-4 -0.008104145 -0.0639072 -0.003087341 -0.007648766 -0.06307691 -0.004200339 -0.006893396 -0.06242626 -0.004935979 -0.006204605 -0.06181424 0.00374341 -0.01076108 -0.06399971 -0.002208888 -0.008332669 -0.06328433 -0.004513382 -0.007053732 -0.06122773 -0.003952324 -0.007650673 -0.06188178 -0.001294314 -0.008934855 -0.0634818 -0.003219068 -0.0081712 -0.06247574 -0.00346148 -0.008448183 -0.06143313 -0.002083718 -0.00918889 -0.06274938 -0.002760112 -0.009027481 -0.06200659 1.90034e-4 -0.009942352 -0.06360834 9.78726e-4 -0.009584426 -0.06391596 -6.73729e-4 -0.0101279 -0.06306487 -0.001588106 -0.00999099 -0.06235402 -0.002332329 -0.009677588 -0.06149065 0.001549541 -0.01085716 -0.06362092 0.002885699 -0.0106666 -0.06393778 -2.02677e-4 -0.01088774 -0.06268066 -0.001055419 -0.01064538 -0.06200969 -0.001710295 -0.01029223 -0.06130349 8.81261e-4 -0.01111066 -0.06319022 -7.31856e-4 -0.01109367 -0.06137543 0.001165628 -0.01179796 -0.06268924 2.65938e-4 -0.01168167 -0.06190359 0.003690361 -0.01181161 -0.06369084 0.002623379 -0.01200777 -0.06326788 2.45149e-4 -0.01181364 -0.06121069 0.005607068 -0.01200509 -0.06387788 0.00163263 -0.01245933 -0.06199407 0.002378106 -0.0125457 -0.06255882 0.00338447 -0.01269924 -0.06293749 0.001643955 -0.01263946 -0.06132012 0.004634618 -0.01275652 -0.06332415 0.003134131 -0.01309311 -0.06222039 0.006375133 -0.01297575 -0.06351232 0.003187954 -0.01335895 -0.06141167 0.004780888 -0.01345467 -0.06262612 0.005692005 -0.01344597 -0.06295907 0.007855534 -0.01217991 -0.06394302 0.004687845 -0.01374745 -0.06198471 0.01259809 -0.01173996 -0.06399154 0.004275023 -0.01376628 -0.06132483 0.008096992 -0.01287353 -0.06371098 0.006325244 -0.01396602 -0.06242501 0.007727682 -0.01379543 -0.06300079 0.005523622 -0.01413768 -0.06129044 0.008034706 -0.01341158 -0.06337863 0.01151937 -0.01216298 -0.06394457 0.006872415 -0.01431864 -0.06185543 0.009872019 -0.01289874 -0.06374651 0.008018136 -0.01416558 -0.06251728 0.006735026 -0.01438689 -0.06132602 0.0100063 -0.01356071 -0.06332719 0.009640932 -0.01414245 -0.0626983 0.008847594 -0.01447099 -0.06200015 0.008109092 -0.01457512 -0.06129467 0.01157051 -0.01290458 -0.06367963 0.01182538 -0.0136938 -0.06307715 0.01751196 -0.009547591 -0.06399846 0.00974822 -0.01464343 -0.06132173 0.01050084 -0.01447337 -0.06198465 0.01128053 -0.01416021 -0.06253671 0.0129761 -0.01302766 -0.06347054 0.01416403 -0.01203608 -0.06381356 0.01095324 -0.0145899 -0.0613079 0.01229488 -0.01432001 -0.06189107 0.01301288 -0.01392108 -0.06248617 0.01378488 -0.01347243 -0.06287938 0.01225858 -0.01444745 -0.06124114 0.01632982 -0.01069831 -0.06393891 0.01469105 -0.01259374 -0.06344532 0.01370728 -0.01411074 -0.06164836 0.01527887 -0.01293605 -0.06295251 0.01484268 -0.01358962 -0.062213 0.01671516 -0.01115828 -0.06374216 0.01689964 -0.01186549 -0.06330364 0.01473551 -0.01386463 -0.06132495 0.01608508 -0.01316225 -0.06215178 0.01692712 -0.01248991 -0.06263363 0.0183202 -0.01015573 -0.06375592 0.0163564 -0.0132659 -0.06129521 0.01927655 -0.008415222 -0.06398975 0.01916772 -0.01040744 -0.06333267 0.01824641 -0.01178532 -0.06262677 0.0177344 -0.01244163 -0.0619536 0.0174269 -0.01275348 -0.06133186 0.01955759 -0.01061904 -0.06291323 0.01919895 -0.01160258 -0.06180346 0.01858115 -0.01211291 -0.06124341 0.019979 -0.009128928 -0.06364583 0.0196706 -0.01098155 -0.06237965 0.02102363 -0.007332086 -0.0638675 0.02083319 -0.00971651 -0.06276094 0.02048683 -0.01053255 -0.06201267 0.02046197 -0.01077038 -0.06132215 0.02141672 -0.00816977 -0.06344091 0.0219087 -0.008651196 -0.06272697 0.02219521 -0.004730045 -0.06398016 0.02199536 -0.009111762 -0.06200826 0.02248877 -0.006322085 -0.06362259 0.02243709 -0.007552385 -0.06308835 0.02190572 -0.009418725 -0.06136059 0.02302461 -0.007682204 -0.06231576 0.02273893 -0.004941046 -0.06384515 0.02356147 -9.49443e-4 -0.06399673 0.02319455 -0.006345391 -0.06315845 0.02298355 -0.008178353 -0.06138974 0.02360844 -0.006437182 -0.06268715 0.02394849 -0.00401473 -0.06353014 0.02409213 -0.005086541 -0.06302392 0.0237717 -0.002701938 -0.06384688 0.02371126 -0.007164657 -0.06145483 0.02424657 -0.00599122 -0.06208425 0.02443063 -0.006030082 -0.06136292 0.0247516 -0.004848361 -0.06227678 0.02480489 -0.003652274 -0.06295067 0.02447342 2.71461e-4 -0.06386309 0.02477633 -0.001376628 -0.06356674 0.02517002 -0.004559934 -0.06139177 0.02529627 -0.003630578 -0.06223762 0.02524513 -0.002182722 -0.06302589 0.02579003 -0.00293982 -0.06143319 0.02588087 -0.001678466 -0.06230652 0.02556449 -6.14511e-4 -0.06307053 0.02546167 8.57057e-4 -0.06335675 0.02477878 0.002092421 -0.06378972 0.0261206 -0.001792907 -0.06139105 0.02604478 1.84951e-4 -0.0626387 0.02404707 0.002834796 -0.06399041 0.02638781 -4.76738e-4 -0.06152766 0.02538907 0.002661108 -0.06346732 0.0263639 0.001110136 -0.06222796 0.0260325 0.002500295 -0.06284898 0.02419978 0.004737377 -0.0639193 0.02660238 0.001215994 -0.06136715 0.02508652 0.00440967 -0.06357192 0.02630728 0.003132164 -0.06240028 0.02575033 0.004297256 -0.06303697 0.02661722 0.002925336 -0.06150603 0.02460712 0.005890548 -0.06368333 0.0258578 0.00531888 -0.06272149 0.02628409 0.004981935 -0.06201994 0.02525258 0.006527721 -0.06312096 0.02344626 0.007561504 -0.06391155 0.02649325 0.004562795 -0.06139659 0.0224623 0.008840262 -0.06399011 0.02382004 0.007950544 -0.06374937 0.02449095 0.007943749 -0.06337505 0.02573657 0.006961584 -0.06227695 0.02618139 0.006269395 -0.06137037 0.02246236 0.01014482 -0.06385016 0.02460986 0.008845508 -0.06293803 0.02530997 0.00813961 -0.06233781 0.02574092 0.007779717 -0.06144493 0.02366775 0.009634137 -0.06341338 0.02045494 0.01159375 -0.06399762 0.02486819 0.009310781 -0.06227695 0.02376508 0.01053971 -0.06292617 0.02510464 0.009406268 -0.0613901 0.02248537 0.01139765 -0.06348979 0.02078384 0.01230025 -0.06386816 0.02407264 0.01077771 -0.06232643 0.02428686 0.01095587 -0.06149291 0.02258664 0.01225614 -0.06296032 0.0229426 0.0124011 -0.06243169 0.02080249 0.01320886 -0.06357759 0.02126169 0.01345193 -0.06319344 0.02339547 0.01232469 -0.0614553 0.02272915 0.01289826 -0.06210696 0.02157002 0.0138598 -0.06258028 0.02261525 0.01332789 -0.06133067 0.02175229 0.01426327 -0.0614857 0.02084213 0.01481622 -0.06223434 0.01362431 0.01890599 -0.0618093 0.01343303 0.01563954 -0.05599999 0.01384311 0.015509 -0.05199998 0.01560097 0.01481306 -0.05599999 0.01607728 0.01458549 -0.05199998 0.01766961 0.01360619 -0.05599999 0.01892149 0.01263809 -0.05199998 0.01997727 0.0115543 -0.05599999 0.02114307 0.01002639 -0.05199998 0.02175688 0.009016394 -0.05599999 0.02271085 0.006956458 -0.05199998 0.02305197 0.005841791 -0.05599999 0.02345424 0.003252327 -0.05199998 0.02348113 0.002081632 -0.05599999 0.0232976 1.68433e-4 -0.05199998 0.02306139 -9.89497e-4 -0.05599999 0.02270644 -0.002152383 -0.05199998 0.02223205 -0.003351688 -0.05599999 0.02140033 -0.004980444 -0.05199998 0.02086681 -0.005739033 -0.05599999 0.01921713 -0.007624328 -0.05199998 0.01909381 -0.007727503 -0.05599999 0.01685261 -0.00946635 -0.05599999 0.01646864 -0.00970453 -0.05199998 0.0140385 -0.01075202 -0.05599999 0.01295155 -0.01108396 -0.05199998 0.01112008 -0.0114054 -0.05599999 0.009537398 -0.01148325 -0.05199998 0.008266568 -0.0113942 -0.05599999 0.007186353 -0.01123225 -0.05199998 0.005235671 -0.01077139 -0.05599999 0.004816651 -0.01061189 -0.05199998 0.001650989 -0.008955836 -0.05599999 0.002067625 -0.009205341 -0.05199998 -4.981e-4 -0.007066607 -0.05199998 -9.39683e-4 -0.006537079 -0.05599999 -0.002662837 -0.00396645 -0.05199998 -0.002306997 -0.004556834 -0.05599999 -0.003301978 -0.002473235 -0.05599999 -0.003765761 -9.71833e-4 -0.05199998 -0.004062116 5.19641e-4 -0.05599999 -0.004127919 0.001395583 -0.05199998 -0.004112541 0.003618776 -0.05599999 -0.004073262 0.004059076 -0.05199998 -0.003499925 0.006645381 -0.05599999 -0.003345429 0.007065951 -0.05199998 -0.002201735 0.009460031 -0.05599999 -0.001741468 0.0102266 -0.05199998 -7.73455e-4 0.01141053 -0.05599999 3.05764e-4 0.01251995 -0.05199998 9.41571e-4 0.0130822 -0.05599999 0.002216219 0.01400148 -0.05199998 0.002950489 0.01442724 -0.05599999 0.004993975 0.01537662 -0.05199998 0.005133509 0.01541215 -0.05599999 0.01059067 0.01734155 -0.03999996 0.008061468 0.01727735 -0.03999996 0.0057379 0.01685446 -0.05199998 0.00549072 0.01678514 -0.03999996 0.002950429 0.015796 -0.05199998 0.002748548 0.01569312 -0.03999996 3.46873e-4 0.0141505 -0.05199998 3.64468e-4 0.01415419 -0.03999996 -0.001699268 0.01219213 -0.03999996 -0.001865386 0.01199781 -0.05199998 -0.003404974 0.009782612 -0.03999996 -0.003543794 0.009534001 -0.05199998 -0.004606723 0.007085561 -0.03999996 -0.004702568 0.006787657 -0.05199998 -0.005257666 0.004205226 -0.03999996 -0.00529623 0.00386691 -0.05199998 -0.005344152 0.001611411 -0.03999996 -0.005337417 0.00163114 -0.05199998 -0.005080223 -6.03019e-4 -0.05199998 -0.005000233 -9.76618e-4 -0.03999996 -0.004202067 -0.003465414 -0.05199998 -0.004052698 -0.003808975 -0.03999996 -0.002773761 -0.006096839 -0.05199998 -0.002563536 -0.006397902 -0.03999996 -8.5206e-4 -0.008392751 -0.05199998 -5.91659e-4 -0.008641123 -0.03999996 0.001486837 -0.01026201 -0.05199998 0.00178498 -0.01044994 -0.03999996 0.004150032 -0.01163029 -0.05199998 0.004472374 -0.01175278 -0.03999996 0.00703144 -0.0124433 -0.05199998 0.007364571 -0.01249831 -0.03999996 0.01001715 -0.01266878 -0.05199998 0.010347 -0.01265698 -0.03999996 0.01298815 -0.01229768 -0.05199998 0.01330184 -0.01222252 -0.03999996 0.01582646 -0.01134479 -0.05199998 0.01611232 -0.01121217 -0.03999996 0.01841962 -0.009847939 -0.05199998 0.01866745 -0.009665787 -0.03999996 0.02066445 -0.007866501 -0.05199998 0.02086609 -0.007644593 -0.03999996 0.02247178 -0.005479276 -0.05199998 0.02262145 -0.005228459 -0.03999996 0.02376973 -0.002781033 -0.05199998 0.0238642 -0.002512812 -0.03999996 0.0245068 1.21061e-4 -0.05199998 0.02454525 3.94943e-4 -0.03999996 0.02465373 0.00311172 -0.05199998 0.02463763 0.00337994 -0.03999996 0.02420461 0.006072103 -0.05199998 0.02413773 0.006324172 -0.03999996 0.02317726 0.008884727 -0.05199998 0.02306538 0.009111225 -0.03999996 0.02161258 0.01143765 -0.05199998 0.02146291 0.01163119 -0.03999996 0.01957255 0.01362967 -0.05199998 0.01939386 0.01378422 -0.03999996 0.0171383 0.01537352 -0.05199998 0.01693981 0.01548552 -0.03999996 0.01440644 0.01659995 -0.05199998 0.01383781 0.0167917 -0.03999996 0.01559549 0.02004802 -0.0399878 0.01558178 0.02107375 -0.03973799 -1.00188e-4 0.03050529 -0.0373907 9.9811e-4 0.02130752 -0.04000735 2.91543e-4 0.02541643 -0.03923302 4.21089e-4 0.02455973 -0.03945189 0.001742362 0.02288067 -0.0394864 5.80952e-4 0.02310496 -0.03981834 0.003088474 0.02165788 -0.03961801 0.00223273 0.02157193 -0.03979629 0.003411889 0.02004915 -0.03998559 0.004189908 0.02100753 -0.0397576 -0.001299202 0.01536041 -0.05954635 -0.00143826 0.01526612 -0.0563538 0.02074956 0.01528584 -0.05683106 0.02051389 0.01545447 -0.05934429 -4.82212e-4 0.01680433 -0.05646282 -4.00775e-4 0.01615345 -0.06021904 3.72853e-5 0.01676273 -0.05983299 -4.84227e-4 0.01644819 -0.05835127 -0.001117944 0.0156272 -0.05741435 8.18911e-4 0.0173583 -0.06061744 6.40776e-4 0.01689434 -0.06114846 0.001902699 0.01751035 -0.06170481 0.003145873 0.01794081 -0.06206583 0.004216849 0.01862382 -0.06174015 0.005658268 0.01903694 -0.06163924 0.006987154 0.0196501 -0.06106752 0.01851207 0.01701879 -0.06123006 0.01746577 0.01741427 -0.06185668 0.01579594 0.01806312 -0.06215345 0.01915323 0.01683783 -0.06037735 0.01973247 0.01612371 -0.06063258 0.01983952 0.01715147 -0.05653053 0.02016299 0.01622438 -0.05673444 0.01982897 0.01672309 -0.05799847 0.02001792 0.01614397 -0.05874747 0.019589 0.03049933 -0.03738325 0.01708906 0.02129614 -0.0398606 0.01794356 0.02298915 -0.03950357 0.01843404 0.02103316 -0.04000276 0.01813459 0.02469205 -0.03877151 0.01872164 0.0225178 -0.03987586 0.01864355 0.02156841 -0.04000103 0.01921683 0.02461117 -0.03954058 0.01933854 0.02615231 -0.03905403 0.01958256 0.02751612 -0.03882533 -0.00380212 -0.005839228 -0.04000699 -6.14494e-4 -0.009653806 -0.04001343 -0.005284488 -0.002513349 -0.04000675 -0.006031692 4.49993e-4 -0.0400148 0.006895899 -0.0130831 -0.04000306 0.01075083 -0.0132699 -0.04000204 -0.004400968 0.009334683 -0.04000353 -2.45185e-5 0.01490789 -0.04001057 0.02491247 -0.001572966 -0.04001051 0.02530229 0.003075182 -0.04000145 0.024351 0.007875263 -0.040003 0.02185446 0.0122649 -0.04000735 0.01973599 0.01444941 -0.04000777 0.01886701 0.01585787 -0.040008 0.01848578 0.01790976 -0.04001021 1.02495e-4 0.02614521 -0.03913509 -1.5689e-4 0.02476084 -0.04015153 8.79283e-6 0.02311813 -0.04033172 -2.26078e-5 0.02199399 -0.04061096 5.80836e-4 0.02196353 -0.04005348 -2.21591e-4 0.02091622 -0.04116463 7.64134e-4 0.02096867 -0.04007804 -8.74637e-5 0.0275644 -0.038814 -1.03018e-4 0.0256555 -0.0396828 6.6372e-5 0.02431881 -0.03989046 -2.01616e-4 0.02185177 -0.04104316 2.97555e-4 0.02267956 -0.04011797 1.95321e-4 0.02157562 -0.04038423 5.84611e-5 0.02096247 -0.04057705 4.77112e-4 0.02117532 -0.04020196 -1.65084e-4 0.02358537 -0.04057544 -2.88686e-4 0.01510131 -0.04009765 -9.82214e-4 0.01511991 -0.04044282 -6.55085e-4 0.01533591 -0.04032212 -0.001260519 0.01512217 -0.04069668 -0.001450002 0.01522487 -0.04121595 5.08293e-4 0.01661777 -0.04007172 -2.11279e-4 0.01602452 -0.04030609 -7.75827e-4 0.01587599 -0.04083055 -9.8278e-4 0.01582145 -0.04125887 1.31316e-4 0.01687401 -0.04030716 -3.23048e-4 0.01667577 -0.04071408 -4.8875e-4 0.01667308 -0.04106092 4.81268e-4 0.01788842 -0.04019176 -6.29475e-4 0.01647907 -0.04135596 9.91604e-4 0.01729613 -0.04000788 -7.39129e-5 0.01725763 -0.04060626 -2.55584e-4 0.01747173 -0.04102355 2.03081e-5 0.01793521 -0.04061192 -3.41021e-4 0.01733964 -0.04127836 -2.3413e-4 0.01802957 -0.04117459 0.02168256 0.01318114 -0.0401507 0.02204132 0.01341766 -0.04047483 0.02194768 0.01381534 -0.04075777 0.02209144 0.01391774 -0.04121327 0.0226168 0.01231652 -0.04025852 0.02302652 0.01109778 -0.04007136 0.02300292 0.01263284 -0.04083007 0.02344131 0.01174604 -0.04056519 0.0232039 0.01259899 -0.04125308 0.02360403 0.01093077 -0.04027163 0.02386856 0.01162505 -0.04116195 0.02432215 0.008950233 -0.04009991 0.02450662 0.01017093 -0.04069709 0.02464121 0.009372889 -0.04041332 0.0245344 0.01054382 -0.04123437 0.02509015 0.009418427 -0.04119831 0.02506864 0.007271945 -0.04014962 0.02530688 0.008191883 -0.0405941 0.02554953 0.008148014 -0.04098862 0.0255981 0.008244156 -0.04138624 0.02575111 0.006454348 -0.0404728 0.02561199 0.004155337 -0.04008591 0.02563512 0.005156219 -0.04017657 0.02601146 0.006584346 -0.04093819 0.02609038 0.006668984 -0.04131484 0.02609062 0.004856407 -0.04049646 0.0263257 0.00495553 -0.04087799 0.02643024 0.005048274 -0.04128515 0.02618044 0.00326538 -0.04041767 0.02556866 0.001618981 -0.04005414 0.02644199 0.003335177 -0.0407738 0.0265783 0.00373578 -0.041229 0.02609235 0.001158356 -0.04034268 0.02662938 0.002418637 -0.04114973 0.02636438 0.001506924 -0.04063045 0.02560836 -2.84104e-4 -0.04014849 0.02656978 8.30754e-4 -0.04120987 0.02622675 -3.79919e-4 -0.04071635 0.02578258 -0.001277029 -0.04039329 0.02631884 -8.67273e-4 -0.04112929 0.02498871 -0.002689301 -0.04012978 0.02594965 -0.002095758 -0.0409159 0.02531528 -0.003235757 -0.04049229 0.025936 -0.00252825 -0.04135489 0.02559357 -0.003304898 -0.04097473 0.02352941 -0.005156576 -0.04001075 0.024158 -0.004844009 -0.04015791 0.02449333 -0.004981458 -0.04041182 0.02518421 -0.00456947 -0.04130244 0.02510583 -0.004435956 -0.04088824 0.02448624 -0.005626976 -0.04079705 0.02301669 -0.007029116 -0.04023301 0.02322369 -0.007138907 -0.04041743 0.02192366 -0.007823407 -0.04005175 0.02422595 -0.006391942 -0.0412929 0.02344965 -0.007314443 -0.04079633 0.02334296 -0.007711708 -0.04124867 0.02152568 -0.008932411 -0.04027163 0.02004688 -0.00962007 -0.0400213 0.02182012 -0.00903064 -0.04052114 0.02222412 -0.009058892 -0.0411427 0.02130234 -0.009858846 -0.04088264 0.02009731 -0.0103352 -0.0403099 0.018651 -0.01095426 -0.0400955 0.02102744 -0.01027685 -0.04129475 0.02036255 -0.01060372 -0.04074227 0.0186578 -0.01158791 -0.04044878 0.02010339 -0.0110324 -0.04119831 0.01901048 -0.01171529 -0.0409184 0.01639807 -0.01190423 -0.04000669 0.01907759 -0.01179599 -0.04133504 0.01736867 -0.01200968 -0.04021346 0.01714426 -0.01273733 -0.04079276 0.01768976 -0.01262021 -0.04125207 0.01679378 -0.01271098 -0.04053878 0.01552116 -0.01281517 -0.04019671 0.01519125 -0.01332098 -0.04048353 0.01617264 -0.01334464 -0.04128962 0.0135346 -0.01309734 -0.0400511 0.01527011 -0.01358795 -0.0409314 0.01314604 -0.01355302 -0.04020577 0.01317161 -0.01389932 -0.04048621 0.01452332 -0.01393616 -0.04133504 0.01341992 -0.01410651 -0.04087245 0.009660482 -0.01364475 -0.040066 0.01282912 -0.01434224 -0.04124885 0.01142746 -0.01386839 -0.04022532 0.0116536 -0.01430517 -0.04069238 0.01162517 -0.01452028 -0.04123449 0.01036947 -0.01448756 -0.04083251 0.009895384 -0.01420265 -0.04040408 0.01041632 -0.01462554 -0.04125463 0.008506417 -0.014445 -0.04078644 0.00762403 -0.01398587 -0.04032927 0.009138584 -0.01462352 -0.04119831 0.006303668 -0.01334512 -0.040084 0.007801234 -0.01454168 -0.04125177 0.006627857 -0.01425802 -0.04085803 0.00620532 -0.01391369 -0.04049301 0.004806935 -0.01320517 -0.04020494 0.006284952 -0.0143035 -0.04122734 0.003193974 -0.01202136 -0.04000955 0.004271924 -0.01344114 -0.04054498 0.004610478 -0.01381826 -0.04102408 0.004128456 -0.01373541 -0.04129004 0.002766788 -0.0125913 -0.04032319 0.002960622 -0.01318782 -0.04097414 0.002571165 -0.01200211 -0.040075 0.002352118 -0.01268404 -0.04060369 0.001051127 -0.01140946 -0.04017287 0.002195477 -0.01292896 -0.04134649 0.001559674 -0.01244705 -0.04084473 9.45967e-4 -0.01178765 -0.04047107 7.81289e-4 -0.01214492 -0.04125458 -2.2929e-4 -0.01054781 -0.040187 1.4028e-4 -0.01156884 -0.04084074 -3.3467e-4 -0.01094132 -0.04049205 -6.02155e-4 -0.01120519 -0.04128313 -0.001774489 -0.009247004 -0.04020148 -0.001468479 -0.01033335 -0.04083287 -0.001949608 -0.009459495 -0.04040527 -0.001871228 -0.01013523 -0.04121857 -0.002421975 -0.008068978 -0.04005497 -0.003217816 -0.008569538 -0.04085618 -0.003247261 -0.007982373 -0.04038602 -0.003135859 -0.008847057 -0.04128301 -0.003774166 -0.006723284 -0.04016482 -0.004429638 -0.006335735 -0.04040294 -0.003888189 -0.007906973 -0.04122906 -0.004437506 -0.006854414 -0.04078125 -0.004635632 -0.006849825 -0.04124331 -0.004764497 -0.005004465 -0.04015272 -0.005235314 -0.005266726 -0.04061633 -0.005400061 -0.005376279 -0.04097622 -0.005651354 -0.004020035 -0.04043447 -0.005652189 -0.002882838 -0.04013645 -0.005457699 -0.00544697 -0.04135739 -0.006047308 -0.003823101 -0.04085534 -0.006155729 -0.003902614 -0.04130613 -0.006418406 -0.001630842 -0.04040855 -0.006436407 -0.002220332 -0.04061347 -0.006687521 -0.002281904 -0.04116195 -0.006364107 -1.19561e-4 -0.04016411 -0.006920456 -5.76943e-4 -0.04078519 -0.006756365 1.38391e-4 -0.04042005 -0.006980121 -0.001084983 -0.04119831 -0.007201075 1.96457e-4 -0.04121267 -0.006675004 0.001861274 -0.04023307 -0.007082223 0.001107513 -0.04069262 -0.006321966 0.003396093 -0.0400744 -0.00572431 0.005818426 -0.04000496 -0.007309794 0.001415431 -0.04123449 -0.007192909 0.002553701 -0.04079008 -0.006638765 0.00385189 -0.04025328 -0.00603801 0.005255401 -0.04005944 -0.007017135 0.003466427 -0.04058879 -0.007344782 0.002713322 -0.04132127 -0.007246017 0.003951132 -0.04113179 -0.006766438 0.005472719 -0.04058116 -0.006427586 0.005666375 -0.04029285 -0.007100582 0.005153536 -0.04117703 -0.006138503 0.007143676 -0.04036784 -0.005459547 0.007983088 -0.04012131 -0.006749629 0.006756901 -0.04115486 -0.006359696 0.007551193 -0.04076844 -0.005424082 0.008982121 -0.04033052 -0.006060421 0.008855044 -0.04127645 -0.005794286 0.009124577 -0.04084563 -0.004296779 0.01054304 -0.04014796 -0.004573643 0.01082527 -0.04041653 -0.003194212 0.01146942 -0.04000753 -0.005028367 0.01063233 -0.04081702 -0.005125224 0.01075416 -0.04131442 -0.00362873 0.01215565 -0.04035836 -0.002474427 0.01277846 -0.04007112 -0.003858268 0.01236838 -0.0407443 -0.004255294 0.01211726 -0.04125458 -0.002368211 0.01346623 -0.04026091 -0.003464639 0.01314324 -0.04122906 -0.00240463 0.01396483 -0.04063761 -0.00266242 0.01404339 -0.0411542 0.01905286 0.01768678 -0.04021233 0.01887953 0.01645106 -0.04004937 0.01941227 0.01774555 -0.04053568 0.01919823 0.01679295 -0.0402109 0.01965892 0.01777124 -0.04093271 0.01962053 0.01662445 -0.04051715 0.01966977 0.01688504 -0.04067701 0.01976197 0.01765745 -0.04137194 0.01943278 0.01593631 -0.04016953 0.01986926 0.01669871 -0.04097527 0.01982331 0.0159623 -0.04044812 0.02024692 0.01495486 -0.0403009 0.01998066 0.01665109 -0.04129183 0.02007812 0.01464629 -0.04011058 0.02032393 0.01565414 -0.04086601 0.02026504 0.01537746 -0.0405395 0.02036142 0.01582193 -0.04119783 0.0207622 0.01486396 -0.04062181 0.02087122 0.01504421 -0.04101645 0.02077478 0.0152443 -0.04134279 0.01880574 0.0210253 -0.04010391 0.01916456 0.02098566 -0.0403015 0.0195651 0.02087098 -0.04076081 0.01972335 0.02719467 -0.03940892 0.01956468 0.02441185 -0.04006069 0.01905304 0.02355408 -0.03976756 0.019665 0.02270269 -0.04078632 0.01970428 0.02434426 -0.04046809 0.01945537 0.02374899 -0.04009705 0.01935732 0.02239173 -0.04032272 0.01907122 0.02248942 -0.04005974 0.01908385 0.02167969 -0.0401948 0.01945608 0.02158033 -0.04055583 0.01959627 0.02219682 -0.04071134 0.01962792 0.02555012 -0.03977894 0.005594313 0.02640664 -0.05464577 0.005396842 0.02650338 -0.05531007 0.005732834 0.0260607 -0.05553835 0.006079316 0.02610558 -0.05480253 0.005702495 0.02546489 -0.0559498 0.006509482 0.02597182 -0.05434525 0.00604391 0.02561515 -0.05554854 0.00656706 0.02570712 -0.05488812 0.005489587 0.02516508 -0.05616027 0.00485903 0.02460467 -0.05631643 0.006533563 0.02548062 -0.05518013 0.005351662 0.02466028 -0.05610936 0.004508852 0.02442973 -0.05629563 0.007043659 0.02573651 -0.0542739 0.006318271 0.02510815 -0.05553525 0.005928575 0.02471655 -0.05580091 0.00781548 0.02556973 -0.05384838 0.007169663 0.02540343 -0.05471765 0.006977677 0.02503442 -0.05511432 0.007774889 0.02539408 -0.05428028 0.00327593 0.02451753 -0.05623245 0.006842613 0.02426213 -0.05527341 0.005407392 0.02361291 -0.05526322 0.004459798 0.0238099 -0.0554288 0.005907595 0.02383673 -0.05540549 0.006178319 0.02407848 -0.05547308 0.007720649 0.02504563 -0.05469167 0.003534138 0.02416491 -0.05537223 0.002725124 0.02485138 -0.05534386 0.003911912 0.02402859 -0.0555579 0.007490575 0.02468979 -0.05496495 0.007068216 0.0244525 -0.05519568 0.002949535 0.02459537 -0.05551743 0.002684533 0.02510625 -0.05501371 0.008631467 0.02530008 -0.05397284 0.009199023 0.02541661 -0.053321 0.002618491 0.02556651 -0.05484318 0.008526742 0.02495628 -0.05441564 0.003665506 0.02410644 -0.05468338 0.004971086 0.023404 -0.05463898 0.007000863 0.0229839 -0.05439805 0.007341861 0.0236085 -0.05491268 0.008021175 0.0240463 -0.05486333 0.004473328 0.02360451 -0.05442464 0.003438711 0.02445185 -0.05438882 0.008266389 0.02454411 -0.05473256 0.002636849 0.02607125 -0.05480188 0.009412825 0.02531707 -0.05366557 0.007706522 0.02392846 -0.05493414 0.009185791 0.02513587 -0.0540452 0.007727503 0.02311366 -0.05451589 0.003156363 0.02519863 -0.05424988 0.006357967 0.02300357 -0.05433279 0.009166598 0.0248062 -0.05437541 0.003041625 0.02626705 -0.0544936 0.004314482 0.0239275 -0.05378764 0.004449963 0.0237143 -0.05400067 0.008803725 0.02432173 -0.05466359 0.003357887 0.02660536 -0.05449765 0.003410458 0.02556204 -0.05399006 0.0104711 0.02540051 -0.05331104 0.01027518 0.02524071 -0.05376881 0.006035387 0.02297335 -0.0538634 0.008924186 0.02381324 -0.05467939 0.004028499 0.02444863 -0.05364131 0.005343675 0.02324247 -0.05382478 0.01011359 0.02502375 -0.05410486 0.008763551 0.02333182 -0.05456185 0.004021346 0.02661854 -0.05428761 0.007319808 0.02269017 -0.05380541 0.004038691 0.02505522 -0.05346488 0.009566426 0.02433419 -0.0545665 0.00412178 0.02568817 -0.05355221 0.009998619 0.02462852 -0.05441617 0.005267381 0.02339071 -0.05347341 0.01100766 0.0253998 -0.05353915 0.008630156 0.02262407 -0.05389273 0.004701018 0.02432477 -0.05311566 0.006178855 0.02299475 -0.05328917 0.004934132 0.02388846 -0.05317556 0.01056236 0.0247702 -0.0543642 0.004736721 0.0264886 -0.05409753 0.01003527 0.02374565 -0.05459475 0.004717886 0.02468281 -0.05302333 0.01096278 0.02518844 -0.05401211 0.005532264 0.0235356 -0.05298966 0.01043206 0.02424848 -0.05458438 0.007836639 0.02256011 -0.05344253 0.004699826 0.02576965 -0.05334645 0.00971198 0.02342534 -0.0545383 0.00738579 0.02264314 -0.05323261 0.01106387 0.02492392 -0.05433005 0.01173442 0.02548283 -0.05373346 0.0102424 0.02283221 -0.05416578 0.005279839 0.0249477 -0.05274027 0.005620658 0.02401518 -0.05262154 0.00664407 0.02315235 -0.05261856 0.011792 0.02528923 -0.05417889 0.005322277 0.02569192 -0.05310791 0.01238542 0.02566158 -0.05363452 0.007067024 0.02282577 -0.05287998 0.005199193 0.02651035 -0.05430555 0.005557179 0.02511531 -0.05268436 0.006292343 0.02357399 -0.0524674 0.01032525 0.02310663 -0.0543816 0.01120895 0.02265107 -0.05394238 0.006031095 0.02432143 -0.05236208 0.0117644 0.02496778 -0.05451172 0.01260501 0.02564829 -0.05406093 0.01095843 0.02336966 -0.05454504 0.01136291 0.02428978 -0.05469959 0.005910754 0.02576017 -0.05310094 0.006415784 0.02390974 -0.05226475 0.008663654 0.02245342 -0.05304729 0.01131457 0.02376842 -0.05470657 0.008294522 0.02263951 -0.05256307 0.01167398 0.02452498 -0.05471664 0.007157146 0.02342295 -0.0521599 0.01329523 0.02592211 -0.05385315 0.007932543 0.02294653 -0.05224829 0.006905674 0.02562886 -0.0529595 0.01267451 0.02549874 -0.0544607 0.009603321 0.02243369 -0.05349892 0.01242357 0.02512729 -0.05470263 0.009931325 0.0223912 -0.05320626 0.01339477 0.02592104 -0.05437141 0.006608605 0.0246635 -0.05220723 0.009224891 0.02250248 -0.0526033 0.006885707 0.02572774 -0.0531733 0.01255398 0.02476209 -0.05496335 0.007211446 0.02405178 -0.0519675 0.01216793 0.02390736 -0.05489492 0.006194591 0.02608036 -0.05383318 0.01225143 0.02325475 -0.054627 0.01030403 0.02241843 -0.05280303 0.008441746 0.02326804 -0.05188369 0.0131269 0.02538156 -0.05497306 0.006996095 0.02523994 -0.05244523 0.00757873 0.02434468 -0.051898 0.007880926 0.02381616 -0.05181825 0.01261246 0.02441412 -0.05505663 0.01351821 0.0258243 -0.05480819 0.01222211 0.02360677 -0.05482095 0.009250581 0.02288299 -0.05202388 0.01263916 0.02300763 -0.05443191 0.007378578 0.02478009 -0.05207997 0.009862303 0.02264446 -0.05226427 0.01119101 0.02244055 -0.05323505 0.01437902 0.02639877 -0.05458402 0.01200544 0.02255469 -0.05357605 0.01415747 0.02619218 -0.05512863 0.01278823 0.02279961 -0.0540871 0.0137149 0.02567297 -0.05524587 0.008648455 0.02375924 -0.05169117 0.01329714 0.02505326 -0.05528348 0.01306384 0.02420556 -0.05522876 0.01304376 0.02381044 -0.05510467 0.01072913 0.02263802 -0.0523166 0.007196128 0.02575713 -0.05345475 0.009539783 0.02347499 -0.05166012 0.008460044 0.02483898 -0.05198246 0.008803248 0.02434146 -0.05171442 0.01148617 0.02252334 -0.05278575 0.01049107 0.02303045 -0.05188125 0.01348555 0.02467548 -0.05546146 0.01481044 0.02657967 -0.05575406 0.01154643 0.02273052 -0.05235415 0.01398992 0.02509582 -0.05576401 0.01405924 0.02543449 -0.05574512 0.01244896 0.02261859 -0.05310773 0.009734332 0.02405077 -0.05160731 0.01044726 0.02340131 -0.05169302 0.01366364 0.02382028 -0.05528104 0.01509535 0.02687728 -0.05552059 0.008394062 0.02551448 -0.05326271 0.01378339 0.02435415 -0.05556982 0.01422816 0.02588236 -0.05567419 0.008698344 0.02539801 -0.05275076 0.0117228 0.02304613 -0.05206739 0.009787499 0.02507281 -0.05216312 0.009856343 0.02452117 -0.05173438 0.01368069 0.0228973 -0.05388724 0.01060998 0.02398288 -0.05160975 0.01146072 0.02330225 -0.05184948 0.01386994 0.02355587 -0.05512607 0.01467943 0.02626252 -0.05599731 0.01276803 0.02286887 -0.05266606 0.01469117 0.02593946 -0.05623722 0.01461827 0.02497792 -0.0561937 0.01062786 0.02476108 -0.05187618 0.01438283 0.02320939 -0.05455255 0.01483148 0.02563339 -0.05646491 0.01148712 0.02384543 -0.05170083 0.01454514 0.0245288 -0.05599814 0.01359891 0.02290189 -0.05332446 0.01303988 0.02318978 -0.05241262 0.01238393 0.02354973 -0.05194979 0.01520889 0.02434432 -0.05613058 0.01531314 0.02413439 -0.05593317 0.01038694 0.02527451 -0.05252099 0.01157552 0.02441966 -0.05177718 0.01399028 0.02322506 -0.05298477 0.009887874 0.02537101 -0.05283784 0.0123558 0.02407521 -0.05185848 0.01477897 0.02362293 -0.05526071 0.0149964 0.02336007 -0.05409359 0.01515477 0.02529853 -0.05670148 0.0134198 0.02385979 -0.05220216 0.01517027 0.02474367 -0.05642658 0.0147919 0.02337425 -0.0535773 0.01539117 0.02374428 -0.05534172 0.01405906 0.0236603 -0.05260342 0.01150661 0.02530306 -0.05250233 0.01551306 0.02363121 -0.05491214 0.01231002 0.02477419 -0.05202633 0.01110726 0.02542424 -0.05289804 0.01311677 0.02439427 -0.05207103 0.01483148 0.02355563 -0.05330348 0.01283395 0.02528196 -0.05246752 0.01502031 0.02398473 -0.05306977 0.01601481 0.02386993 -0.05484235 0.01337265 0.02509099 -0.05238646 0.01563227 0.02394485 -0.05370551 0.01462393 0.02434235 -0.05266982 0.01660948 0.02471971 -0.05671149 0.01609897 0.02399224 -0.05438238 0.01389873 0.02456212 -0.05235254 0.01167994 0.02551859 -0.05311834 0.01647067 0.0243591 -0.05606544 0.01415073 0.02511531 -0.05259621 0.01676946 0.0244134 -0.05581694 0.0139029 0.02583706 -0.05322164 0.01601278 0.02444058 -0.05368602 0.01556885 0.02447682 -0.05327069 0.01314073 0.02573156 -0.05315238 0.01541554 0.02482736 -0.053101 0.01499539 0.02502137 -0.05288988 0.01693284 0.02449518 -0.05547672 0.01666408 0.02459925 -0.05438619 0.01706528 0.02464097 -0.05525785 0.01295661 0.02578026 -0.05343729 0.01623666 0.0250225 -0.0537011 0.01730835 0.02502524 -0.05509871 0.01560831 0.02563518 -0.05339509 0.01679104 0.02506709 -0.05425095 0.01506006 0.0257461 -0.0532574 0.01641446 0.02563089 -0.05386412 0.01466751 0.02590155 -0.05331224 0.01727271 0.02524 -0.05483543 0.01687443 0.02552461 -0.05425393 0.0141623 0.02615588 -0.05378854 0.01763367 0.02590763 -0.05511629 0.01725369 0.02596211 -0.05466943 0.01640427 0.02643179 -0.05425715 0.01653671 0.02712106 -0.05494666 0.01597011 0.02649343 -0.05415457 0.01673424 0.02633893 -0.05437874 0.01507747 0.02654558 -0.05423486 0.01737886 0.02644991 -0.05492174 0.01608049 0.02719116 -0.05507463 0.01517742 0.02676802 -0.05469769 0.01559984 0.02713966 -0.05525052 0.01116293 0.002368152 -0.05617815 0.01113182 0.002651095 -0.05618685 0.01132553 0.002544224 -0.05659621 0.01121115 0.0028162 -0.05649721 0.01104378 0.002924919 -0.05610752 0.01164382 0.002596557 -0.05686891 0.01082646 0.003294527 -0.05610519 0.01089346 0.00328958 -0.05633383 0.01103156 0.003371477 -0.05661296 0.01192098 0.002854585 -0.05698865 0.01139813 0.003115594 -0.05680984 0.01059556 0.003530859 -0.05618178 0.01146399 0.003526389 -0.05693501 0.01113837 0.003639876 -0.05684238 0.01061636 0.003671109 -0.05650615 0.01080858 0.003715336 -0.05669617 0.01033467 0.003701031 -0.05618947 0.01140618 0.003973722 -0.0569911 0.01028418 0.00388813 -0.05654668 0.009953081 0.003830254 -0.05614137 0.01063394 0.004194915 -0.0569157 0.01023972 0.00410676 -0.05675888 0.01066046 0.004490256 -0.05699056 0.009582877 0.003866255 -0.05620276 0.009997606 0.003914773 -0.05645298 0.01009017 0.004474699 -0.0569424 0.009564101 0.004030883 -0.05657994 0.01217257 0.00480318 -0.05700588 0.009213507 0.003799736 -0.0561906 0.009761273 0.00426042 -0.05681359 0.009164512 0.003924489 -0.05651038 0.008902668 0.003673136 -0.05622291 0.009423077 0.00439006 -0.05689233 0.009265661 0.004110693 -0.05671876 0.00928533 0.004683673 -0.05699127 0.00862652 0.00345999 -0.05613982 0.008896231 0.004108786 -0.05681258 0.008641123 0.003734529 -0.05662208 0.008436203 0.003349781 -0.05637067 0.008328735 0.003101229 -0.05620443 0.008232474 0.003933429 -0.05692231 0.008344113 0.003478407 -0.05663228 0.008343815 0.003682851 -0.05677098 0.007974445 0.004098236 -0.05699449 0.008169114 0.002681553 -0.05620616 0.008125782 0.003034889 -0.05655908 0.007962763 0.003047823 -0.05673778 0.00813651 0.002335548 -0.05617684 0.007673978 0.003072559 -0.05691295 0.008027315 0.002597749 -0.05651348 0.007837891 0.002484679 -0.05673164 0.008081793 0.002143502 -0.05639094 0.008178889 0.002011954 -0.05614602 0.007323265 0.002885937 -0.05699485 0.008319258 0.001621484 -0.05618125 0.007506489 0.002288043 -0.05693596 0.007879853 0.001887559 -0.05674391 0.008098423 0.001778006 -0.05653494 0.00852102 0.001348674 -0.05614912 0.007610142 0.001557886 -0.05695223 0.008283197 0.001437306 -0.05652749 0.007367074 0.001319468 -0.05699771 0.008117198 0.001226544 -0.05679553 0.008778512 0.001112282 -0.05617654 0.00852108 0.001177787 -0.0564903 0.009026467 9.77943e-4 -0.05610877 0.008793711 9.48492e-4 -0.0565232 0.007905006 0.001063525 -0.05694884 0.009078264 8.7193e-4 -0.0564109 0.009348154 8.70056e-4 -0.05614155 0.008520781 6.00551e-4 -0.05690342 0.008640527 7.68979e-4 -0.05677562 0.008602797 1.98461e-4 -0.05699336 0.009359776 7.57734e-4 -0.05647534 0.009736835 8.4212e-4 -0.05614 0.009321451 4.31361e-4 -0.05683279 0.00942105 6.13531e-4 -0.0566653 0.009911179 7.62524e-4 -0.05643743 0.01010102 9.08205e-4 -0.05614644 0.009515106 3.12063e-5 -0.05698895 0.009895086 6.60855e-4 -0.05660474 0.009859621 4.37445e-4 -0.05681985 0.01044571 0.001062452 -0.05617547 0.010046 2.0238e-4 -0.05694574 0.01044386 9.1419e-4 -0.05651688 0.01071333 0.001277327 -0.05612254 0.01036453 5.68867e-4 -0.05681365 0.01069825 0.001144349 -0.05643081 0.01077347 8.99837e-4 -0.05674648 0.01100122 0.001658022 -0.05619257 0.01098334 0.001493752 -0.05640119 0.01074671 3.03701e-4 -0.05698651 0.01098585 0.001268804 -0.05662196 0.0110892 7.38656e-4 -0.05694293 0.01119148 0.001195132 -0.05681973 0.01113247 0.002040803 -0.05619221 0.01119995 0.001615583 -0.05662566 0.0112819 0.002034723 -0.05654317 0.01145845 0.001369953 -0.05690205 0.0117771 0.001233756 -0.05699551 0.01146912 0.002178072 -0.05673736 0.01177543 0.001960515 -0.05694484 0.01113146 0.002649486 -0.05149996 0.01082116 0.003316581 -0.05149996 0.0101453 0.00378549 -0.05149996 0.009210944 0.00381577 -0.05149996 0.008472979 0.003304302 -0.05149996 0.008170068 0.002661585 -0.05149996 0.008175492 0.002025783 -0.05149996 0.00847876 0.001383364 -0.05149996 0.009019196 9.80927e-4 -0.05149996 0.009789824 8.26254e-4 -0.05149996 0.01055192 0.001139283 -0.05149996 0.01107573 0.001790404 -0.05149996 0.01109802 0.005559206 -0.05699998 0.01286727 0.003771245 -0.05699998 0.01315933 0.002585232 -0.05699998 0.009678363 0.005878686 -0.05699998 0.01301437 0.001312196 -0.05699998 0.008391976 0.005629539 -0.05699998 0.01226121 -3.38272e-5 -0.05699998 0.007340192 0.00500971 -0.05699998 0.006578266 0.004053652 -0.05699998 0.01101684 -8.92641e-4 -0.05699998 0.006191074 0.00298804 -0.05699998 0.009973168 -0.001143634 -0.05699998 0.006172716 0.001853287 -0.05699998 0.008838713 -0.00107795 -0.05699998 0.006542921 6.89999e-4 -0.05699998 0.007496654 -4.45706e-4 -0.05699998 0.02022945 0.003167629 -0.05599999 0.02225756 0.004686892 -0.05599993 0.01973259 0.003559768 -0.05599999 0.02245795 0.002669453 -0.05599999 0.02049338 0.002484381 -0.05599999 0.01910513 0.003704488 -0.05599999 0.02166569 0.006786048 -0.05599993 0.02009725 0.009861111 -0.05600005 0.02035391 0.00172019 -0.05599999 0.02224057 -1.42594e-4 -0.05599999 0.01843863 0.003493309 -0.05599999 0.01076048 0.01114839 -0.05599999 0.01368761 0.01454508 -0.05600005 0.01028937 0.01516306 -0.05599999 0.01003801 0.01164513 -0.05599999 0.01100432 0.0102145 -0.05599999 0.01710277 0.01281321 -0.05600005 0.01985168 0.001201629 -0.05599999 0.009439527 0.01167547 -0.05599999 0.007141351 0.01492899 -0.05599993 0.008908808 0.01147735 -0.05599999 0.01929485 0.001011252 -0.05599999 0.02148073 -0.002587437 -0.05599999 0.008478462 0.01101386 -0.05599999 0.003739178 0.0137555 -0.05600005 0.008288323 0.01023668 -0.05599999 0.01197773 0.005643308 -0.05599999 0.01306337 0.00447297 -0.05599999 0.01067095 0.009463608 -0.05599999 0.01796072 0.002997636 -0.05599999 0.01061046 0.006247699 -0.05599999 0.01361691 0.003049433 -0.05599999 0.01975959 -0.005594372 -0.05600005 0.01857048 0.001121044 -0.05599999 0.01002764 0.009048402 -0.05599999 0.01780092 0.00225985 -0.05599999 0.009418904 0.006357669 -0.05599999 0.01358819 0.001553833 -0.05599999 0.009328186 0.009042441 -0.05599999 0.01801812 0.001618921 -0.05599999 0.00796175 0.006012558 -0.05599999 0.008685111 0.009393334 -0.05599999 8.37329e-4 0.01171237 -0.05600005 0.01304918 1.92833e-4 -0.05599999 0.006704688 0.005082845 -0.05599999 0.01739937 -0.007880628 -0.05599999 -0.001325845 0.008958756 -0.05599993 0.01041603 -0.004526376 -0.05599999 0.01067453 -0.001543343 -0.05599999 0.01202213 -8.95176e-4 -0.05599999 0.01091253 -0.005166232 -0.05599999 0.009706258 -0.004304587 -0.05599999 0.00935024 -0.001649916 -0.05599999 0.01098752 -0.005760788 -0.05599999 0.01438707 -0.009578764 -0.05599999 0.009127259 -0.004409909 -0.05599999 0.007992267 -0.001323819 -0.05599999 0.001211225 0.003210663 -0.05599999 0.005830109 0.003667891 -0.05599999 5.04879e-4 0.003651618 -0.05599999 0.008545815 -0.004856169 -0.05599999 0.001508474 0.002327203 -0.05599999 -0.002641975 0.006082296 -0.05599999 0.005643784 0.002149999 -0.05599999 -2.9449e-4 0.00363779 -0.05599999 0.005854666 0.001042068 -0.05599999 0.001248598 0.001560091 -0.05599999 0.01102173 -0.01043421 -0.05600005 0.006581485 -2.67121e-4 -0.05599999 0.01075828 -0.006446778 -0.05599999 -0.001011431 0.003059685 -0.05599999 -0.003171443 0.00293821 -0.05599999 0.01008999 -0.006925344 -0.05599999 -0.001197993 0.002293646 -0.05599999 0.009460031 -0.006983041 -0.05599999 0.0077371 -0.01034092 -0.05599999 -0.00103116 0.001706719 -0.05599999 0.008871316 -0.006751775 -0.05599999 -0.002862572 -4.71415e-4 -0.05599993 -6.02527e-4 0.001226663 -0.05599999 9.35991e-5 9.99106e-4 -0.05599999 0.004282116 -0.009314358 -0.05599999 0.008487105 -0.00632137 -0.05599999 -0.001766145 -0.003502726 -0.05600005 7.33897e-4 0.001137495 -0.05599999 0.008292913 -0.005683839 -0.05599999 0.001403629 -0.007477581 -0.05600005 -3.668e-4 -0.005638122 -0.05599999 0.009708881 -0.0114609 -0.05500191 0.01173746 -0.01130223 -0.05500417 0.01445508 -0.01062232 -0.05499464 0.01687657 -0.009419381 -0.05500417 0.01876521 -0.008034288 -0.05499607 0.02088582 -0.005727946 -0.05498796 0.02236241 -0.00307548 -0.05499917 0.02330744 1.4808e-4 -0.05499517 0.02345198 0.003001987 -0.05499607 0.0230664 0.005668818 -0.05499219 0.02233052 0.007809102 -0.05499774 0.02136385 0.009684681 -0.0549997 0.01951354 0.01204943 -0.05499273 0.01742845 0.01375889 -0.05500686 0.01502531 0.01510161 -0.05498796 0.01235777 0.01589286 -0.05500417 0.009843826 0.01616936 -0.0549997 0.007591903 0.01600426 -0.05500429 0.005578398 0.01554977 -0.05500161 0.003846406 0.01487362 -0.05500024 0.002230942 0.01401072 -0.05499219 -7.10885e-5 0.01217979 -0.05499589 -0.00174576 0.0101639 -0.05499607 -0.002833664 0.008245348 -0.05499774 -0.003600299 0.006279468 -0.0549997 -0.004150569 0.003305494 -0.05499464 -0.004070043 7.83276e-4 -0.05500143 -0.003532111 -0.001816034 -0.05499589 -0.002637684 -0.003949522 -0.05499821 -0.001565635 -0.005713522 -0.05500167 1.08287e-4 -0.007648408 -0.0549997 0.002122581 -0.009236991 -0.05499607 0.004688143 -0.01055371 -0.05499589 0.007398486 -0.01128607 -0.0549997 0.009994506 -0.01147043 -0.05149996 0.007153809 -0.01124364 -0.05149996 0.004278123 -0.01039338 -0.05149996 0.001294195 -0.008681118 -0.05149996 -9.34834e-4 -0.006531715 -0.05149996 -0.002491116 -0.004261732 -0.05149996 -0.003797233 -9.63621e-4 -0.05149996 -0.004167497 0.002349972 -0.05149996 -0.003841578 0.005429327 -0.05149996 -0.002759575 0.008434474 -0.05149996 -0.001513063 0.01048189 -0.05149996 2.10408e-6 0.01224148 -0.05149996 0.002434015 0.0141583 -0.05149996 0.005007326 0.01535725 -0.05149996 0.007588744 0.01602488 -0.05149996 0.01033842 0.01614654 -0.05149996 0.01306241 0.01575171 -0.05149996 0.01626837 0.0145033 -0.05149996 0.01905637 0.01248759 -0.05149996 0.02081316 0.01048183 -0.05149996 0.02205955 0.008434474 -0.05149996 0.02311354 0.005529165 -0.05149996 0.02345937 0.002694308 -0.05149996 0.02325522 -1.54209e-4 -0.05149996 0.02234745 -0.003108322 -0.05149996 0.02087861 -0.005722761 -0.05149996 0.01904565 -0.0077762 -0.05149996 0.01648181 -0.009697139 -0.05149996 0.01306241 -0.01105171 -0.05149996 0.01233345 0.005342781 -0.05579996 0.01182425 0.005121588 -0.05579996 0.01333075 0.004010796 -0.05579996 0.01273012 0.004059374 -0.05579996 0.01096516 0.006162464 -0.05579996 0.01068621 0.005709409 -0.05579996 0.01308673 0.003044724 -0.05579996 0.01366472 0.002450048 -0.05579996 0.009414732 0.005864799 -0.05579996 0.009180724 0.006355524 -0.05579996 0.01315522 0.002059459 -0.05579996 0.0135492 0.001430988 -0.05579996 0.01278829 7.41073e-4 -0.05579996 0.00798732 0.005462586 -0.05579996 0.01312035 3.09303e-4 -0.05579996 0.007757425 0.00589019 -0.05579996 0.006581485 0.004967093 -0.05579996 0.0117371 -5.03968e-4 -0.05579996 0.01220655 -7.45003e-4 -0.05579996 0.006917417 0.004564523 -0.05579996 0.01129865 -0.001303732 -0.05579996 0.006347894 0.00355184 -0.05579996 0.005880713 0.003721892 -0.05579996 0.0105412 -0.001043498 -0.05579996 0.01027894 -0.001614749 -0.05579996 0.006120204 0.002145111 -0.05579996 0.005627393 0.002450287 -0.05579996 0.009326875 -0.001163959 -0.05579996 0.008751988 -0.001584231 -0.05579996 0.005861937 0.001004934 -0.05579996 0.006569802 6.40618e-4 -0.05579996 0.007992208 -7.52097e-4 -0.05579996 0.007475197 -0.001017212 -0.05579996 0.006569206 -2.35079e-4 -0.05579996 0.007220208 -1.76568e-4 -0.05579996 0.0191608 0.003696501 -0.05149996 0.01986789 0.003503501 -0.05149996 0.02039778 0.002875983 -0.05149996 0.02048248 0.002115011 -0.05149996 0.02022093 0.001538753 -0.05149996 0.01976591 0.001148521 -0.05149996 0.01920628 0.001008987 -0.05149996 0.0185185 0.00114274 -0.05149996 0.01796591 0.001705169 -0.05149996 0.01781243 0.002239048 -0.05149996 0.01792901 0.002963304 -0.05149996 0.01853406 0.003551363 -0.05149996 0.01012784 -0.004369854 -0.05149996 0.01085174 -0.00500822 -0.05149996 0.01097685 -0.005987823 -0.05149996 0.01051604 -0.006682097 -0.05149996 0.009874403 -0.006986498 -0.05149996 0.009179234 -0.006911575 -0.05149996 0.008653581 -0.00655961 -0.05149996 0.008339881 -0.005972266 -0.05149996 0.008382201 -0.005140364 -0.05149996 0.008822381 -0.004595637 -0.05149996 0.009295105 -0.004348278 -0.05149996 0.009992778 0.01165217 -0.05149996 0.01062178 0.01129782 -0.05149996 0.01098841 0.01056283 -0.05149996 0.01092278 0.009922266 -0.05149996 0.01061016 0.009398043 -0.05149996 0.01009905 0.009085178 -0.05149996 0.009572029 0.009005665 -0.05149996 0.00893557 0.009202063 -0.05149996 0.008503556 0.009649455 -0.05149996 0.008306562 0.01021552 -0.05149996 0.008390545 0.01081979 -0.05149996 0.008738398 0.01134854 -0.05149996 0.009360432 0.01166772 -0.05149996 8.52869e-4 0.00352168 -0.05149996 0.001404523 0.002854168 -0.05149996 0.001489222 0.002283155 -0.05149996 0.001348078 0.001723349 -0.05149996 9.25938e-4 0.001252353 -0.05149996 3.73509e-4 0.001019418 -0.05149996 -4.52949e-4 0.001123845 -0.05149996 -0.001058101 0.001742959 -0.05149996 -0.001195907 0.002552807 -0.05149996 -8.39699e-4 0.003268241 -0.05149996 -1.20473e-4 0.003687918 -0.05149996 0.002850651 -0.00271058 -0.06249183 0.001481056 -0.002832829 -0.06250381 0.002903878 -0.002583026 -0.06260067 0.001420497 -0.002751827 -0.06264317 9.94228e-4 -0.004110753 -0.06248915 8.46909e-4 -0.004126548 -0.06258624 0.001787364 -0.005192935 -0.06249213 0.001733064 -0.005318939 -0.0626018 0.003156304 -0.005068898 -0.06250381 0.003216803 -0.0051499 -0.06264317 0.003704547 -0.003784596 -0.06250405 0.003805816 -0.003772616 -0.06264108 0.00323683 -0.005179762 -0.06417292 0.003841161 -0.003769755 -0.06417274 0.001713752 -0.005360841 -0.06417292 7.95176e-4 -0.004131972 -0.06417292 0.001400053 -0.002722024 -0.06417292 0.002923071 -0.002541005 -0.06417286 0.001045763 -0.003710269 -0.05543452 8.4559e-4 -0.00385493 -0.05543369 0.001321375 -0.003027439 -0.05543422 0.001078188 -0.003152608 -0.05543404 0.001149356 -0.004464149 -0.05545645 0.001344442 -0.002835392 -0.05542564 0.001569986 -0.004992246 -0.05544215 0.001428067 -0.005127012 -0.05543398 0.001618444 -0.002648055 -0.05542492 0.002212822 -0.002480328 -0.05542993 0.002286911 -0.005268216 -0.05543535 0.00269562 -0.00251609 -0.05543059 0.003057777 -0.005094528 -0.05543404 0.003185331 -0.00514692 -0.05543404 0.003541231 -0.004648327 -0.05543404 0.003761231 -0.004266202 -0.05543971 0.002228736 -0.005442976 -0.06116729 0.002916812 -0.005292356 -0.06117069 0.00337255 -0.005001544 -0.06111067 0.003329157 -0.004915833 -0.06118416 0.003725469 -0.004444837 -0.06109219 0.003479301 -0.003407835 -0.06118452 0.003800332 -0.003863453 -0.06106722 0.003644049 -0.004202127 -0.06118434 0.003606736 -0.003209471 -0.06106519 0.003170728 -0.003006219 -0.06117451 0.003255367 -0.002795338 -0.06102043 0.002766907 -0.002760767 -0.06116676 0.002873897 -0.00257498 -0.06099742 0.002407491 -0.002468764 -0.06098848 0.002109825 -0.002677977 -0.06111156 0.001930952 -0.002520203 -0.06096655 0.001470863 -0.00299108 -0.06108039 0.001414537 -0.002768278 -0.06094706 0.001061379 -0.003163516 -0.06091761 0.001170456 -0.003400087 -0.06105774 8.81128e-4 -0.003571867 -0.06090927 0.001030147 -0.004030108 -0.06102925 8.38533e-4 -0.004150331 -0.06088829 0.001022458 -0.004682421 -0.06086546 0.001235187 -0.004620194 -0.06100195 0.001407384 -0.005130827 -0.060844 0.001614987 -0.00502187 -0.06097817 0.001832842 -0.005360424 -0.06083095 0.002073049 -0.005189836 -0.06099402 0.002409577 -0.0054304 -0.06080257 0.002657592 -0.005185067 -0.06093072 0.002953827 -0.005296885 -0.06078398 0.003258287 -0.004833221 -0.06090033 0.003404319 -0.004966259 -0.06075763 0.003673911 -0.004562079 -0.06074357 0.003573954 -0.004199206 -0.06086868 0.003790974 -0.004133999 -0.06073486 0.003543794 -0.003642857 -0.06088107 0.003763794 -0.003590762 -0.06070381 0.003261923 -0.003063797 -0.06081658 0.003507137 -0.003065407 -0.06068587 0.003026425 -0.002642989 -0.06068247 0.002657532 -0.002720654 -0.06078493 0.002322852 -0.00246638 -0.0606327 0.00216335 -0.002686321 -0.06076371 0.001818954 -0.002551078 -0.06061929 0.001561641 -0.002903461 -0.06073606 0.00138688 -0.002796351 -0.06058609 0.001083016 -0.003124177 -0.0605778 0.001110434 -0.003522276 -0.06070184 9.04855e-4 -0.003518342 -0.06058365 0.001047551 -0.004050731 -0.06067854 8.24581e-4 -0.003891468 -0.06054365 9.46551e-4 -0.004514515 -0.06052398 0.00120604 -0.004583239 -0.0606544 0.001224279 -0.004960656 -0.06050491 0.001693189 -0.005078077 -0.06062334 0.001541495 -0.005213677 -0.06048387 0.001968801 -0.005391776 -0.06047046 0.00254774 -0.00522691 -0.06058579 0.00255084 -0.005421221 -0.06044924 0.003050506 -0.005241334 -0.06042081 0.003178834 -0.004892766 -0.06055378 0.003400802 -0.004970252 -0.0604121 0.003569781 -0.004291951 -0.06052297 0.003670632 -0.004568755 -0.06039762 0.003802657 -0.004048526 -0.06037378 0.003522098 -0.003515601 -0.0604884 0.003725588 -0.00348258 -0.0603525 0.00339514 -0.002910852 -0.06032592 0.003205478 -0.003027856 -0.06046319 0.002838313 -0.002561748 -0.06030237 0.002649307 -0.002712249 -0.06043523 0.002206981 -0.002460658 -0.06027597 0.002007424 -0.002707302 -0.06040704 0.001634776 -0.002629995 -0.06026786 0.001348912 -0.003096282 -0.06037312 0.001208722 -0.002953886 -0.06023639 9.71146e-4 -0.003315865 -0.06021833 0.001072824 -0.00368154 -0.06034475 8.41607e-4 -0.003760874 -0.06020063 0.001066863 -0.004206478 -0.06032145 8.88141e-4 -0.004376709 -0.06017661 0.0013718 -0.004830002 -0.0602917 0.001224339 -0.004958808 -0.06014633 0.001609861 -0.00525552 -0.0601359 0.001951277 -0.005171597 -0.06026184 0.00209397 -0.005419969 -0.06012177 0.002445638 -0.005224108 -0.06024014 0.002589762 -0.005409538 -0.06008929 0.003009676 -0.005267202 -0.06008058 0.003156363 -0.004939913 -0.06020623 0.003395497 -0.004975378 -0.06006616 0.003689944 -0.004527032 -0.06004226 0.003521323 -0.004371941 -0.06017631 0.003800272 -0.0039801 -0.06001871 0.00359261 -0.00388205 -0.06015509 0.003742396 -0.003523528 -0.06000953 0.00339955 -0.00324279 -0.06012612 0.003565192 -0.003152012 -0.05998516 0.003298163 -0.00283885 -0.05997359 0.002927362 -0.002845048 -0.06013554 0.002813875 -0.002547442 -0.05995237 0.002400219 -0.002673208 -0.06007379 0.002259671 -0.00246644 -0.05992931 0.001790523 -0.002785384 -0.06004697 0.001632452 -0.002628445 -0.05990022 0.001137316 -0.003032684 -0.05988115 0.001308977 -0.003160595 -0.06001967 8.75699e-4 -0.003590464 -0.05985826 0.001048564 -0.003775238 -0.05999088 8.33174e-4 -0.004043817 -0.05984622 0.001106917 -0.004356741 -0.05996507 9.71359e-4 -0.00457859 -0.05981647 0.001178979 -0.004886746 -0.05982851 0.001429378 -0.00487405 -0.05993837 0.001619517 -0.005256652 -0.05980706 0.001996457 -0.005192577 -0.0599094 0.002122461 -0.005426168 -0.05976068 0.002643823 -0.005188345 -0.05988132 0.00281769 -0.005355894 -0.05974525 0.003270089 -0.004825472 -0.05984914 0.003408372 -0.004952371 -0.05973333 0.00368154 -0.004540741 -0.0596928 0.003604471 -0.004054486 -0.05981278 0.00380063 -0.0038262 -0.05968725 0.003489673 -0.003450095 -0.0597853 0.00368154 -0.003342151 -0.05964076 0.003107607 -0.002929031 -0.05975687 0.003269314 -0.002809345 -0.05962216 0.002780318 -0.002535998 -0.0595991 0.002477526 -0.002697885 -0.05976271 0.002132892 -0.002475202 -0.05957096 0.001866877 -0.002739191 -0.05970025 0.001554846 -0.002669334 -0.05955755 0.001376211 -0.003109097 -0.05970984 0.001112699 -0.003088295 -0.05952936 0.00106436 -0.003661274 -0.05964595 8.7145e-4 -0.003606021 -0.05951046 8.83439e-4 -0.004334032 -0.05950188 0.001080214 -0.004248023 -0.05961972 0.001304864 -0.004731535 -0.05959624 0.001106142 -0.004820466 -0.05946105 0.001741528 -0.00507456 -0.05960869 0.001407802 -0.005129635 -0.05944293 0.001816809 -0.005352675 -0.05942434 0.00221467 -0.005226075 -0.05954974 0.002593457 -0.005411565 -0.05941998 0.002952814 -0.005080521 -0.0595175 0.003298282 -0.005072772 -0.0593729 0.003506839 -0.004446089 -0.0594803 0.003694295 -0.004519879 -0.05934226 0.003801405 -0.00399971 -0.05931389 0.00358951 -0.003865659 -0.05945414 0.003752827 -0.003559172 -0.05930519 0.003437042 -0.00332427 -0.0594294 0.003551125 -0.003119766 -0.0592907 0.003188192 -0.002745389 -0.05926442 0.003053843 -0.002924561 -0.05944174 0.002717971 -0.00252074 -0.05924838 0.002633869 -0.002715289 -0.05938404 0.002175629 -0.002468585 -0.05922657 0.001937389 -0.00271219 -0.05935424 0.00169605 -0.002598285 -0.05920737 0.001311242 -0.002863943 -0.05919533 0.00120759 -0.003282845 -0.05931335 9.42349e-4 -0.003367364 -0.05916744 0.001041412 -0.004065394 -0.05927771 8.36696e-4 -0.003996849 -0.05914294 9.50726e-4 -0.004530072 -0.05912369 0.001339673 -0.0048002 -0.05924296 0.001243472 -0.004976928 -0.05910587 0.00161004 -0.00525254 -0.0590828 0.001934707 -0.005165934 -0.05921262 0.002141654 -0.005428373 -0.05906659 0.002401232 -0.005226433 -0.059192 0.002619624 -0.005403041 -0.05903768 0.002982079 -0.005047559 -0.05916535 0.003034532 -0.005249679 -0.05903029 0.003445744 -0.004919052 -0.05901557 0.00339508 -0.004611253 -0.0591768 0.003682732 -0.004533946 -0.05898416 0.003584563 -0.004140257 -0.05911588 0.003797411 -0.004082322 -0.05897486 0.003759264 -0.003591716 -0.05896061 0.003548383 -0.003615438 -0.05909335 0.003531694 -0.003088295 -0.05893462 0.003330588 -0.003166019 -0.05907076 0.003100633 -0.00269103 -0.05891382 0.002747237 -0.002734422 -0.05903971 0.002483665 -0.00246334 -0.05888688 0.002106308 -0.002693176 -0.05901104 0.001832485 -0.002549409 -0.05886322 0.001642405 -0.002870261 -0.0589894 0.001359701 -0.002815008 -0.05884766 0.001277029 -0.003207623 -0.0589677 0.001096069 -0.003115892 -0.05882769 9.13052e-4 -0.00347799 -0.05881255 0.001032114 -0.003870189 -0.05893635 8.35299e-4 -0.004012823 -0.05879461 9.49798e-4 -0.004538059 -0.05877351 0.001166522 -0.004501402 -0.05890768 0.001640498 -0.005054593 -0.05887663 0.001262605 -0.004994928 -0.0587517 0.00187993 -0.005371868 -0.05874609 0.002524852 -0.005227684 -0.05883753 0.002636969 -0.005403101 -0.05869549 0.003199994 -0.005160272 -0.05867236 0.003294706 -0.004799306 -0.05879771 0.003486454 -0.004854917 -0.05867826 0.003706276 -0.004487097 -0.05863785 0.003597438 -0.004068136 -0.05876296 0.003801107 -0.003970861 -0.05861628 0.00374031 -0.003514349 -0.05860406 0.003470361 -0.003381788 -0.05873262 0.003468692 -0.003014981 -0.0585823 0.003007829 -0.002869069 -0.05870234 0.002988398 -0.00261569 -0.05855959 0.002269506 -0.002658367 -0.05866932 0.00238198 -0.00246936 -0.0585345 0.00180298 -0.002554833 -0.05851054 0.001641392 -0.002885103 -0.05867731 0.001241624 -0.002917289 -0.05849277 0.001267313 -0.003229796 -0.05861634 9.08451e-4 -0.003475546 -0.0584656 0.001023232 -0.00389266 -0.05858492 8.48359e-4 -0.004120111 -0.05846011 0.001240074 -0.004639804 -0.05855149 9.79888e-4 -0.004593491 -0.05842006 0.001442313 -0.005152404 -0.05841451 0.001658201 -0.005047142 -0.05852586 0.002011299 -0.005401551 -0.05836874 0.002153575 -0.00521326 -0.05850261 0.002557516 -0.005416989 -0.05834943 0.002672612 -0.005182206 -0.05847972 0.003086745 -0.005225479 -0.05832105 0.003089904 -0.004950881 -0.05849462 0.003496289 -0.004855334 -0.05830723 0.003514766 -0.004433751 -0.05842906 0.003747344 -0.004371106 -0.05828642 0.003801107 -0.003843069 -0.05826503 0.003584504 -0.003795444 -0.05840098 0.003669798 -0.003337621 -0.0582478 0.003319382 -0.003126263 -0.05836975 0.003340363 -0.002864658 -0.05822587 0.002829372 -0.002558887 -0.05820178 0.002749502 -0.0027529 -0.05833953 0.002292335 -0.002465426 -0.05818247 0.002258002 -0.002673685 -0.05831772 0.001795709 -0.002561211 -0.05816447 0.001633942 -0.002860665 -0.05828911 0.001393139 -0.002794444 -0.05814194 0.001190423 -0.003349721 -0.0582605 0.001035153 -0.003199517 -0.0581271 0.001029849 -0.004009485 -0.05823117 8.5462e-4 -0.003702282 -0.05810499 8.72239e-4 -0.00430262 -0.05807542 0.001286149 -0.004679918 -0.05823719 0.001135528 -0.004857659 -0.05806136 0.001590549 -0.005000293 -0.05817919 0.001584827 -0.005239248 -0.05803602 0.002272903 -0.005244553 -0.05814641 0.002122163 -0.005424976 -0.05801427 0.002684891 -0.00538671 -0.05801552 0.002937912 -0.005065262 -0.05811715 0.003364264 -0.005013883 -0.05797129 0.003311812 -0.004752755 -0.05809599 0.003702461 -0.004493355 -0.05793994 0.00353527 -0.004336535 -0.05807501 0.003800868 -0.003963887 -0.05792158 0.003568708 -0.003608703 -0.05804342 0.003661334 -0.003311216 -0.05791723 0.003163397 -0.002992153 -0.05801028 0.003255486 -0.002801537 -0.0578702 0.002703309 -0.002734303 -0.05798774 0.002775251 -0.002537071 -0.05785036 0.002310156 -0.002467632 -0.05783206 0.002237915 -0.002676606 -0.05796647 0.001841664 -0.002547025 -0.05781394 0.001679301 -0.002842009 -0.05794155 0.001346826 -0.002824962 -0.05779218 0.001289129 -0.003196477 -0.05791825 0.001011192 -0.003244102 -0.0577684 0.001056671 -0.003727078 -0.05789291 8.52612e-4 -0.003703832 -0.05775433 8.67413e-4 -0.004316091 -0.05773115 0.001114547 -0.004398584 -0.05786341 0.001124918 -0.004844963 -0.05771356 0.001510798 -0.004944086 -0.05783325 0.001614987 -0.005257368 -0.05769085 0.002210736 -0.005241632 -0.05780005 0.002077579 -0.00542283 -0.057666 0.002658665 -0.005396485 -0.05764472 0.003022015 -0.005029201 -0.05776357 0.00311464 -0.005204617 -0.05761998 0.003460824 -0.004897534 -0.05761444 0.003536224 -0.004387378 -0.05772811 0.00369811 -0.004500746 -0.05759108 0.003813862 -0.003861546 -0.05756932 0.003564119 -0.003656744 -0.05769526 0.003575682 -0.003179609 -0.05756109 0.0031901 -0.002991557 -0.05766081 0.003254055 -0.002795279 -0.05751985 0.002732694 -0.002521038 -0.05749732 0.002580165 -0.002703547 -0.05763185 0.002153992 -0.002477347 -0.05747658 0.002024471 -0.002704799 -0.05760782 0.001574039 -0.002658247 -0.05744606 0.001550316 -0.00293219 -0.05758452 0.001298904 -0.002882301 -0.05746161 0.001173675 -0.003374576 -0.05755913 0.001029431 -0.003209292 -0.05742406 8.57688e-4 -0.003672838 -0.05740225 0.001036524 -0.004097044 -0.0575264 8.55815e-4 -0.004205405 -0.05738747 0.001006662 -0.004643321 -0.05736798 0.001350164 -0.004793167 -0.05749291 0.00129342 -0.005026459 -0.0573461 0.001797854 -0.005114614 -0.05746883 0.001738488 -0.005318462 -0.05732887 0.002370715 -0.005232274 -0.05744349 0.002271473 -0.005432784 -0.05730962 0.002903878 -0.005326688 -0.05728459 0.003033399 -0.005019903 -0.05741292 0.00341922 -0.004944384 -0.05726063 0.003498494 -0.004457592 -0.05738091 0.00371617 -0.004459977 -0.05723881 0.003804743 -0.003929615 -0.05721634 0.003593027 -0.003906726 -0.05735534 0.003705263 -0.00341928 -0.05719918 0.003432273 -0.003308176 -0.05732923 0.003445625 -0.002974331 -0.05718088 0.003045439 -0.002917766 -0.05734133 0.003032565 -0.00264436 -0.05715924 0.002511203 -0.002685666 -0.05727905 0.002432644 -0.002461493 -0.05713605 0.001902699 -0.002512335 -0.05711865 0.001928865 -0.00273174 -0.05725342 0.001343429 -0.002831518 -0.05709254 0.001478075 -0.002994716 -0.05723017 0.001001656 -0.003257274 -0.05707305 0.001158952 -0.003406345 -0.05720728 8.50125e-4 -0.003754079 -0.0570743 0.001039028 -0.004023373 -0.05717939 9.4702e-4 -0.004539966 -0.05702871 0.001228213 -0.004622101 -0.0571525 0.001324236 -0.005054771 -0.05699741 0.001721858 -0.00509119 -0.05712282 0.001771032 -0.005327165 -0.05698162 0.002362072 -0.005228757 -0.05709379 0.002354681 -0.005445718 -0.05695974 0.003001272 -0.005043208 -0.05706435 0.003095567 -0.005215942 -0.05692678 0.003569722 -0.004772782 -0.05690115 0.003485441 -0.004488587 -0.05703169 0.003731369 -0.004382014 -0.05690807 0.003591418 -0.003917872 -0.05700653 0.003805994 -0.003964722 -0.05687069 0.003432154 -0.003292977 -0.05697846 0.003723621 -0.003460228 -0.05684638 0.003365278 -0.002887308 -0.05681908 0.002866268 -0.002793848 -0.05694526 0.002858698 -0.002559661 -0.0568093 0.002324521 -0.002673089 -0.05692088 0.002209126 -0.002467691 -0.05677914 0.001805961 -0.002782821 -0.05689704 0.001668334 -0.002618432 -0.05675739 0.001267075 -0.003197908 -0.05686712 0.001316249 -0.002860963 -0.0567398 0.001026749 -0.003211736 -0.05672776 0.001042783 -0.003885984 -0.05683594 8.50695e-4 -0.003726482 -0.05670362 8.5932e-4 -0.004232645 -0.05668044 0.001124799 -0.004407703 -0.05681276 0.001054763 -0.004731178 -0.05666273 0.001467406 -0.004909038 -0.05678611 0.0014261 -0.005135059 -0.05664396 0.001942992 -0.005392789 -0.056625 0.001965224 -0.005177795 -0.05676126 0.002483069 -0.005218029 -0.05673784 0.00250405 -0.005423307 -0.05659985 0.00300455 -0.005029082 -0.05671375 0.003056347 -0.005243062 -0.05657643 0.003500461 -0.004853427 -0.05655705 0.003450095 -0.004565417 -0.0566861 0.003747165 -0.004348278 -0.05653542 0.003596484 -0.003917038 -0.05665671 0.003799438 -0.003842949 -0.05651128 0.003719389 -0.00346297 -0.05650728 0.003472208 -0.003401279 -0.05663317 0.003484845 -0.003034055 -0.05648291 0.003150582 -0.00298506 -0.05661016 0.003113746 -0.002697288 -0.05646139 0.002720057 -0.002735733 -0.05658847 0.002664625 -0.002506852 -0.05644643 0.00198692 -0.002701818 -0.05655533 0.002174675 -0.002477169 -0.05642873 0.001698195 -0.002599239 -0.05640947 0.001266062 -0.003198981 -0.05651849 0.00130999 -0.002863347 -0.05638247 0.001021146 -0.003229618 -0.05637317 8.62645e-4 -0.003670513 -0.05636405 0.001028299 -0.00407356 -0.05647802 8.43174e-4 -0.004141926 -0.05633652 0.001016974 -0.004662275 -0.05631715 0.001440346 -0.00490415 -0.05643725 0.001319766 -0.005047559 -0.05629408 0.001747012 -0.005325078 -0.05627721 0.002110719 -0.005211472 -0.05640369 0.002258777 -0.005432784 -0.05625987 0.002662181 -0.005181968 -0.05638056 0.002866446 -0.00534439 -0.05623453 0.00316751 -0.005159974 -0.05624496 0.003084599 -0.004969537 -0.05635941 0.003500998 -0.004849433 -0.05620616 0.003417074 -0.004599452 -0.05633777 0.003808379 -0.004102945 -0.05617743 0.003613948 -0.003930926 -0.05630773 0.003721177 -0.003464162 -0.05615139 0.003270208 -0.003068447 -0.05626517 0.003454208 -0.002988338 -0.05613183 0.003036499 -0.002647578 -0.05611097 0.002669692 -0.002740085 -0.05626797 0.002396285 -0.002463102 -0.0560925 0.002020061 -0.002692222 -0.05620771 0.001790583 -0.002555668 -0.05606269 0.001359105 -0.003100693 -0.05617356 0.00132519 -0.002843856 -0.05604153 0.001021385 -0.00322473 -0.05602133 0.001044571 -0.003754615 -0.05614185 8.47529e-4 -0.003729879 -0.05600082 8.77609e-4 -0.0042997 -0.05598205 0.001123547 -0.004393398 -0.0561133 0.001131057 -0.004854023 -0.05595195 0.001419126 -0.004868447 -0.05608779 0.001390993 -0.005100071 -0.05596691 0.00195682 -0.005173921 -0.05606162 0.001750528 -0.005325436 -0.05592954 0.002177357 -0.005427658 -0.05590701 0.002428174 -0.005222976 -0.05604082 0.002693533 -0.005390167 -0.05589407 0.003054976 -0.005010306 -0.05601233 0.0031901 -0.005149722 -0.055875 0.003678083 -0.004578948 -0.05584609 0.003492772 -0.004460573 -0.05598098 0.003803253 -0.003947854 -0.05581986 0.003580391 -0.003886699 -0.05599087 0.003725886 -0.003482878 -0.0558111 0.003454029 -0.003335118 -0.05592924 0.003532469 -0.003094434 -0.05578118 0.003160595 -0.002730488 -0.05576592 0.003006994 -0.002879917 -0.05590224 0.002368807 -0.002655148 -0.05587285 0.002664506 -0.002505719 -0.05574649 0.002152681 -0.002475202 -0.05572706 0.001646578 -0.002629101 -0.05570596 0.001619458 -0.002878606 -0.05583846 0.001137316 -0.003047466 -0.05570334 0.001140236 -0.0034222 -0.05580705 8.54063e-4 -0.003708481 -0.0556541 0.00105232 -0.004122734 -0.05577492 8.5369e-4 -0.004182219 -0.05564451 0.001204371 -0.004571199 -0.0557546 9.82022e-4 -0.004598498 -0.05561584 0.001286506 -0.005015313 -0.0556001 0.001548051 -0.004969477 -0.05573165 0.001772999 -0.005335628 -0.0555787 0.002192497 -0.00523734 -0.05570125 0.002326071 -0.005437135 -0.05555456 0.002854168 -0.005331993 -0.05554056 0.002852141 -0.005107998 -0.05567145 0.003200113 -0.005141437 -0.05551832 0.003279149 -0.00480014 -0.05564856 0.00351119 -0.004838705 -0.05550718 0.003601253 -0.004109382 -0.05561405 0.00375092 -0.004339754 -0.05548012 0.003788828 -0.003765404 -0.05545186 0.003500103 -0.003471851 -0.05558639 0.003570258 -0.003160536 -0.05545914 0.003177344 -0.003001213 -0.05556452 0.002616941 -0.002702176 -0.05553311 0.001920223 -0.002731382 -0.05550205 0.001407563 -0.003053963 -0.05547606 0.0021528 -0.002679228 -0.06118494 0.001642525 -0.002859652 -0.06117379 0.001173555 -0.003368556 -0.06113398 0.001048922 -0.00387758 -0.06111067 0.001106858 -0.004354834 -0.06108891 0.001455843 -0.004907846 -0.06105625 0.002617061 -0.005201637 -0.06100672 0.003287136 -0.004802107 -0.06097197 0.003583252 -0.004153549 -0.0609408 0.003296971 -0.003124892 -0.06089276 0.002854585 -0.002794861 -0.06086885 0.002263724 -0.002662897 -0.06084239 0.001483321 -0.002964496 -0.0608052 0.001099407 -0.003567039 -0.06077396 0.001064896 -0.004243791 -0.0607441 0.001337766 -0.00476247 -0.06071859 0.001789033 -0.005121052 -0.06069356 0.002328813 -0.005224764 -0.06066906 0.002868711 -0.005107343 -0.06064474 0.00331372 -0.004753172 -0.06061959 0.003608524 -0.004070043 -0.06058675 0.003465175 -0.003392159 -0.0605567 0.00316739 -0.00300014 -0.06053549 0.002693712 -0.002722859 -0.06051081 0.002085924 -0.002696871 -0.06048446 0.001533687 -0.00293225 -0.06045764 0.00106734 -0.003616333 -0.06042116 0.00110042 -0.004334807 -0.06039041 0.001411497 -0.004856169 -0.06036323 0.001958429 -0.005181252 -0.06033521 0.002696394 -0.005183458 -0.06030279 0.003207027 -0.004862844 -0.0602765 0.003528892 -0.004380941 -0.06025093 0.003584265 -0.003777682 -0.06022477 0.003365159 -0.00321114 -0.06019765 0.002517402 -0.002691149 -0.06015372 0.001917302 -0.002728879 -0.060126 0.001249372 -0.00322014 -0.06008994 0.001041948 -0.003908157 -0.06005918 0.001205384 -0.004608511 -0.06002718 0.001671195 -0.005047142 -0.0599997 0.002292156 -0.005242705 -0.05996984 0.002879202 -0.005092203 -0.05994415 0.003355264 -0.00471872 -0.05991804 0.003576159 -0.004151523 -0.05989086 0.003533244 -0.003516733 -0.05986273 0.003039419 -0.002882421 -0.05982708 0.00187081 -0.002750277 -0.05977451 0.001132428 -0.003486633 -0.05972778 0.001042306 -0.004175424 -0.05969715 0.001374781 -0.004809617 -0.05966591 0.002295315 -0.005231022 -0.05962032 0.002833068 -0.005116462 -0.05959683 0.003322899 -0.00475943 -0.05956953 0.003592073 -0.004086673 -0.05953794 0.003477811 -0.003385663 -0.05950629 0.002557277 -0.002692759 -0.05945473 0.002008259 -0.002715289 -0.05943125 0.001464664 -0.002984881 -0.05940395 0.001087009 -0.003600716 -0.0593729 0.001059114 -0.004168927 -0.05934679 0.001250505 -0.004643976 -0.05932515 0.001686692 -0.005075514 -0.05929851 0.002298176 -0.005223929 -0.05927062 0.00295329 -0.005080878 -0.05924087 0.003602147 -0.004032969 -0.05918473 0.003394722 -0.003230035 -0.05914872 0.002832889 -0.002781569 -0.05911791 0.002235293 -0.002672016 -0.05909079 0.00152868 -0.002927005 -0.05905783 0.001111507 -0.003525972 -0.05902522 0.001047253 -0.004018008 -0.05900406 0.001220107 -0.004627168 -0.05897682 0.001664876 -0.005043566 -0.05894958 0.002297103 -0.005243718 -0.05892032 0.002887547 -0.005088269 -0.05889409 0.003374934 -0.00469464 -0.05886536 0.003608882 -0.003861844 -0.05882734 0.003345966 -0.003187954 -0.05879658 0.002955734 -0.002848565 -0.05877387 0.002313792 -0.002654671 -0.05874496 0.0012362 -0.003255844 -0.0586881 0.001052081 -0.003821671 -0.05866289 0.001089453 -0.004302322 -0.05864173 0.001319169 -0.004743158 -0.05861967 0.001770377 -0.005108833 -0.0585941 0.002471745 -0.005230963 -0.05856239 0.003443479 -0.004566073 -0.05850964 0.003601849 -0.003892838 -0.05847984 0.003337919 -0.003155231 -0.05844426 0.002641379 -0.002703428 -0.05840837 0.002015113 -0.002713799 -0.05838131 0.001466393 -0.002983033 -0.05835402 0.001110613 -0.003541171 -0.0583257 0.001048743 -0.004173696 -0.05829709 0.001790463 -0.005126178 -0.05824273 0.002409458 -0.005221307 -0.05821573 0.002994358 -0.005049407 -0.05818921 0.003439605 -0.004559516 -0.05815988 0.003608107 -0.003944694 -0.05813151 0.00339365 -0.003255248 -0.05810046 0.002864003 -0.002782046 -0.05806779 0.002073049 -0.002687036 -0.0580343 0.001547455 -0.002937674 -0.05800831 0.001169621 -0.003377318 -0.05798268 0.001044988 -0.003913581 -0.0579586 0.001168906 -0.004531323 -0.05793076 0.001632809 -0.005031108 -0.05790084 0.002320706 -0.005240976 -0.05786997 0.00290817 -0.005079507 -0.05784273 0.003409445 -0.004645287 -0.05781346 0.003602385 -0.003793358 -0.05777502 0.003240168 -0.003052055 -0.05773806 0.002641975 -0.002713263 -0.05770921 0.001920938 -0.002720117 -0.05767637 0.001194238 -0.003299534 -0.05763697 0.001054108 -0.004228889 -0.05759406 0.001411736 -0.004849672 -0.05756348 0.0018965 -0.005159199 -0.05753856 0.002561032 -0.00521481 -0.05750858 0.003317773 -0.004781901 -0.05747139 0.00359106 -0.00406295 -0.05743658 0.003490388 -0.003414988 -0.05740773 0.002635955 -0.002711057 -0.05735826 0.002118527 -0.002693593 -0.05733591 0.001520097 -0.002933621 -0.05730801 0.001118898 -0.003514826 -0.05727618 0.00104314 -0.004008114 -0.05725437 0.001186192 -0.004550516 -0.05723029 0.001739978 -0.00511074 -0.05719524 0.002595305 -0.005209505 -0.05715781 0.003149628 -0.004918754 -0.0571295 0.003557801 -0.0043298 -0.05709826 0.003548979 -0.003608822 -0.05706727 0.003275334 -0.003100872 -0.05704146 0.002879142 -0.002806067 -0.05701977 0.00219959 -0.002660989 -0.05698966 0.001518189 -0.002954125 -0.05695629 0.001112937 -0.003499329 -0.05692744 0.001053452 -0.004107892 -0.0569002 0.001286745 -0.004725337 -0.05687105 0.001987636 -0.00520122 -0.0568338 0.002701103 -0.005170822 -0.05680191 0.003145933 -0.004918754 -0.05678027 0.003529727 -0.004403889 -0.05675244 0.003575563 -0.003746032 -0.05672323 0.003321468 -0.003130197 -0.05669438 0.002504289 -0.002665877 -0.05665165 0.001740276 -0.00281012 -0.05661839 0.001217365 -0.003278732 -0.05658793 0.001047372 -0.003882408 -0.05656021 0.00116539 -0.004542529 -0.05653125 0.001649081 -0.005034148 -0.05650049 0.00224483 -0.005240261 -0.05647182 0.002963662 -0.005057036 -0.05644059 0.003433287 -0.004591286 -0.05641078 0.003592193 -0.004001677 -0.05638438 0.003505289 -0.003460586 -0.05636048 0.003103971 -0.002941071 -0.05633091 0.00218302 -0.002676665 -0.05628901 0.001503229 -0.002950966 -0.05625629 0.001142323 -0.003463983 -0.05622905 0.001034021 -0.004099607 -0.05620115 0.00135374 -0.004793882 -0.05616652 0.001947522 -0.005184829 -0.05613607 0.002727568 -0.005171 -0.05610138 0.003235578 -0.004837572 -0.05607479 0.003538012 -0.004343748 -0.05604982 0.00343728 -0.003335893 -0.0560038 0.002946257 -0.002817571 -0.05597311 0.002236902 -0.002677023 -0.05594104 0.001655697 -0.002849161 -0.05591404 0.001231789 -0.003285884 -0.05588805 0.001039445 -0.003822267 -0.05586177 0.001132309 -0.004414141 -0.05583643 0.001509428 -0.004962503 -0.05580753 0.002384066 -0.005245447 -0.05576658 0.003088831 -0.00497204 -0.05573403 0.003454506 -0.004537522 -0.0557084 0.003605782 -0.003887057 -0.05567812 0.003389298 -0.00325191 -0.05564999 0.003034353 -0.002895653 -0.05562776 0.002497017 -0.002681314 -0.05560219 0.001751363 -0.00278896 -0.05556905 0.001223862 -0.003288149 -0.05553668 0.001048922 -0.003818929 -0.05551278 0.00124967 -0.003124713 -0.06118404 0.001226067 -0.004969835 -0.06117868 8.92794e-4 -0.003893733 -0.06118381 0.001820445 -0.005344927 -0.06117749 0.002838671 -0.005331814 -0.0611155 0.003702104 -0.003405153 -0.06102734 0.002974689 -0.002605676 -0.0606355 0.001437246 -0.005147039 -0.05977159 0.003241181 -0.005117356 -0.0596984 0.003794252 -0.0040645 -0.0596528 8.4753e-4 -0.004120469 -0.059466 0.002308309 -0.00542593 -0.05938619 0.002871096 -0.005326151 -0.05936425 0.001662135 -0.005277276 -0.05871158 0.002201676 -0.005424439 -0.05868953 8.33033e-4 -0.003884077 -0.05842566 0.001360297 -0.005095362 -0.05837428 0.00283575 -0.005344867 -0.0579648 0.003680408 -0.003338515 -0.05787485 0.003702402 -0.003403484 -0.05752658 8.32981e-4 -0.003979086 -0.05702114 0.002698481 -0.005378007 -0.056921 0.003711581 -0.004443228 -0.056167 0.003476858 -0.004867851 -0.05583572 0.00109148 -0.003094017 -0.05565685 0.00354886 -0.003186583 -0.05531406 0.003658831 -0.003637015 -0.05522781 0.003733456 -0.003583192 -0.05533885 0.003604769 -0.004075109 -0.05518978 0.003774285 -0.004045784 -0.05533885 0.003703355 -0.004202485 -0.05525869 0.003531396 -0.004413306 -0.05518889 0.003676116 -0.004477202 -0.05533373 0.003427386 -0.004764914 -0.05522364 0.002816975 -0.005135297 -0.05518519 0.003553032 -0.004767894 -0.05542778 0.003360569 -0.004965543 -0.05533438 0.003121316 -0.005155742 -0.05531418 0.003010272 -0.005124926 -0.05522358 0.002576947 -0.0052827 -0.05521833 0.002808213 -0.005319774 -0.05532503 0.002065837 -0.005229413 -0.05518853 0.002318501 -0.005399227 -0.05531114 0.0026021 -0.005408763 -0.05543005 0.001918435 -0.005332767 -0.05529838 0.001738548 -0.005183756 -0.05522495 0.001454234 -0.004943668 -0.05519717 0.001936376 -0.005385518 -0.05543327 0.001558423 -0.005182266 -0.05531495 0.001101255 -0.004390537 -0.05518704 0.001327991 -0.005009591 -0.05531781 0.001168727 -0.004743516 -0.05524599 0.001089632 -0.004773855 -0.0554254 0.001008152 -0.004560649 -0.05531537 9.28627e-4 -0.004173398 -0.05525457 9.00726e-4 -0.004381656 -0.05542999 0.001195967 -0.003295123 -0.05518913 8.56971e-4 -0.003928601 -0.0553323 9.98058e-4 -0.003740608 -0.05520439 9.84485e-4 -0.003455698 -0.05528062 9.10586e-4 -0.003500998 -0.05542361 0.001087605 -0.003176391 -0.0553295 0.001538217 -0.002913057 -0.0551905 0.001278281 -0.003013908 -0.05525189 0.001572251 -0.002754688 -0.05525875 0.002025306 -0.00268048 -0.05519038 0.001883566 -0.002571821 -0.05531316 0.002220571 -0.002554416 -0.05525118 0.002083003 -0.002490222 -0.05542296 0.002617657 -0.002640724 -0.05520832 0.002869248 -0.002757549 -0.05519294 0.002510726 -0.002508878 -0.05532968 0.002839446 -0.00259006 -0.05534046 0.003425538 -0.003280401 -0.0551868 0.003295063 -0.002960264 -0.05523848 0.003081738 -0.002718925 -0.05531847 0.003311216 -0.002849757 -0.0554313 3.27777e-4 -0.005780518 -0.06138789 5.98147e-4 -0.00596112 -0.06126528 9.14247e-4 -0.00626415 -0.06138098 9.2073e-4 -0.006070256 -0.06119209 0.001097917 -0.00629878 -0.06126999 0.001516759 -0.006525695 -0.06135797 0.001398801 -0.006307542 -0.06118935 0.001755416 -0.006515383 -0.06124716 0.001992225 -0.006625056 -0.06135368 0.002416491 -0.006490945 -0.06119167 0.00247085 -0.006646156 -0.06137329 0.00238949 -0.006581306 -0.06125026 0.002972304 -0.006568074 -0.06136184 0.003025174 -0.006486058 -0.06124979 0.003203868 -0.006299018 -0.06118655 0.003608703 -0.006327092 -0.06136548 0.003684163 -0.006197929 -0.06124329 0.00393486 -0.005874633 -0.06118696 0.004246234 -0.005847573 -0.06136935 0.004327535 -0.005667626 -0.0612573 0.004517853 -0.005264163 -0.06119674 0.004659831 -0.005296528 -0.06137853 0.004697144 -0.00508666 -0.06125456 0.004896223 -0.004762768 -0.0613752 0.004895746 -0.004527926 -0.06125551 0.005004823 -0.004185438 -0.06135153 0.004820168 -0.004167258 -0.06118601 0.004940629 -0.003977954 -0.06124675 0.004998147 -0.003674149 -0.06135225 0.004837989 -0.003489375 -0.06120097 0.004900038 -0.003176569 -0.06134057 0.004685282 -0.00299263 -0.06119185 0.004700183 -0.002692759 -0.06134814 0.004424929 -0.002258598 -0.06139087 0.004454493 -0.002406656 -0.06125116 0.004177987 -0.002193927 -0.06120139 0.004069864 -0.001963615 -0.06126677 0.004049658 -0.001878499 -0.06137746 0.003508806 -0.001531302 -0.06134152 0.003730356 -0.001864135 -0.06118583 0.003587901 -0.001662015 -0.06124186 0.002953231 -0.001329004 -0.0613622 0.003030538 -0.001469671 -0.06121003 0.002378225 -0.001248359 -0.06138026 0.002494513 -0.001316845 -0.06125819 0.002145946 -0.001418352 -0.06118994 0.00183326 -0.001303255 -0.06133502 0.001550972 -0.00143969 -0.06124562 0.001306593 -0.001448869 -0.06136453 0.001279175 -0.001605331 -0.06119954 7.85632e-4 -0.001741468 -0.06132376 7.32706e-4 -0.001943826 -0.06120187 3.72934e-4 -0.002081215 -0.06136691 2.1539e-4 -0.002277493 -0.06131899 3.38652e-4 -0.002385854 -0.06118732 -7.96371e-5 -0.002722918 -0.06135243 7.84957e-5 -0.002601444 -0.06123983 -2.56272e-4 -0.003145694 -0.06135904 -1.23011e-4 -0.003094553 -0.06121563 -3.5008e-4 -0.003603279 -0.06133311 -2.02674e-4 -0.003688335 -0.06119012 -3.75459e-4 -0.004115998 -0.0613662 -3.31388e-4 -0.004182875 -0.06128084 -2.71107e-4 -0.004704833 -0.06136125 -2.06817e-4 -0.004565 -0.06121838 -4.94498e-5 -0.005244135 -0.06135261 1.29268e-4 -0.005217969 -0.06118625 1.64844e-4 -0.005487203 -0.06125855 5.53724e-4 -0.005997538 -0.06398928 0.00157833 -0.006538391 -0.0640226 0.002421915 -0.006646811 -0.06400328 0.002880275 -0.006590068 -0.06399554 0.00393933 -0.006106376 -0.06401312 0.004402518 -0.005665779 -0.06401211 0.005002796 -0.004232585 -0.06401634 0.004989266 -0.003528535 -0.06398165 0.00467962 -0.002641975 -0.06400084 0.004348397 -0.002173185 -0.0640034 0.004007339 -0.001858174 -0.06403422 0.003655493 -0.001607716 -0.06399464 0.003223001 -0.001417458 -0.0640369 0.002850055 -0.001303255 -0.06398886 0.001994848 -0.001272916 -0.06399548 0.001573264 -0.001359224 -0.06401455 7.1933e-4 -0.001768529 -0.06396311 2.85251e-4 -0.002175271 -0.06399482 -5.74138e-5 -0.002662479 -0.06398832 -3.76142e-4 -0.004109323 -0.06400847 -2.59871e-4 -0.004758536 -0.06399482 4.37007e-5 -0.005413949 -0.06399685 1.74028e-4 -0.00548011 -0.06411826 1.67067e-4 -0.005274474 -0.06417912 -4.61456e-5 -0.004860758 -0.06418031 -1.78307e-4 -0.004851281 -0.06409001 -2.94065e-4 -0.004260897 -0.06412148 -3.50262e-4 -0.003596603 -0.06402444 -2.2374e-4 -0.003575205 -0.06416666 -2.55189e-4 -0.003158807 -0.06401896 -4.42621e-6 -0.002950012 -0.0641787 -8.9489e-5 -0.002852678 -0.06409513 2.76408e-4 -0.00243777 -0.06417733 1.60059e-4 -0.00240767 -0.06408852 6.19989e-4 -0.001923739 -0.06410825 0.001123547 -0.001736462 -0.06418138 0.001048088 -0.001575171 -0.06401509 0.00114566 -0.001579463 -0.06410759 0.001723766 -0.001463532 -0.0641725 0.001962125 -0.001351058 -0.06412369 0.00236541 -0.001261889 -0.06403332 0.002706527 -0.00134927 -0.06412041 0.003002822 -0.001511931 -0.06417965 0.003630816 -0.001667439 -0.06411355 0.003962695 -0.002002835 -0.06417548 0.00439316 -0.002270102 -0.0640769 0.004465579 -0.002569794 -0.06416761 0.004811465 -0.002943098 -0.06404536 0.004716992 -0.003097593 -0.06417578 0.004921913 -0.00352931 -0.06411427 0.004986464 -0.003946542 -0.06407248 0.004866063 -0.004125475 -0.06417196 0.00475043 -0.004730701 -0.06417405 0.004855513 -0.004849195 -0.06403541 0.004680335 -0.005248129 -0.06401205 0.004475533 -0.005420684 -0.06413435 0.004205226 -0.005635678 -0.06417971 0.004103541 -0.005927085 -0.0640769 0.003719687 -0.006078064 -0.06417638 0.003552317 -0.006340682 -0.06403464 0.003235995 -0.006479561 -0.06402778 0.003121495 -0.006406068 -0.06415748 0.002652525 -0.006577849 -0.06409698 0.002095401 -0.00646317 -0.06418085 0.002096414 -0.006556689 -0.06413388 0.001938998 -0.006620347 -0.06401228 0.001251816 -0.006333887 -0.0641393 0.001318633 -0.006261527 -0.06418025 0.001076102 -0.006346464 -0.06401306 5.28287e-4 -0.005926847 -0.06407558 6.73164e-4 -0.005884051 -0.0641753 0.01526832 -0.00270754 -0.06249225 0.01390051 -0.002833545 -0.06250339 0.01532417 -0.002582013 -0.06260067 0.01384055 -0.002750635 -0.06264203 0.01335257 -0.004115879 -0.06250405 0.01325124 -0.00412786 -0.06264108 0.01421344 -0.005174398 -0.06248861 0.01415526 -0.005312383 -0.06258624 0.01557695 -0.005068898 -0.06250494 0.01563686 -0.005148828 -0.06264394 0.01612395 -0.003782033 -0.06250339 0.01622539 -0.003771424 -0.06264114 0.01565855 -0.00517857 -0.06417328 0.01625961 -0.003767132 -0.06417232 0.01413351 -0.00535959 -0.06417292 0.01321488 -0.00413078 -0.06417292 0.01381981 -0.002720773 -0.06417292 0.01534283 -0.002539753 -0.06417286 0.01723486 -0.004397511 -0.06417781 0.01346033 -0.004021286 -0.05543404 0.01355695 -0.003445923 -0.05544388 0.01327419 -0.004128217 -0.05543404 0.0136187 -0.004554092 -0.05545276 0.01375848 -0.002845227 -0.0554338 0.01409035 -0.002701938 -0.0554344 0.01403099 -0.005023121 -0.05544018 0.01420456 -0.002565562 -0.05543386 0.01408767 -0.00528407 -0.05543428 0.01490658 -0.00248295 -0.05542773 0.01475208 -0.005264103 -0.05543506 0.01546323 -0.002658009 -0.05543547 0.01513558 -0.005372285 -0.05543404 0.01547753 -0.005093336 -0.05543404 0.01566505 -0.005105316 -0.05543422 0.01596093 -0.004647135 -0.05543404 0.01617282 -0.00428307 -0.05544441 0.01481658 -0.005422234 -0.06118196 0.01536875 -0.00527656 -0.06117171 0.01579457 -0.004998087 -0.06111055 0.01614642 -0.004440486 -0.06109172 0.01589906 -0.003406584 -0.06118452 0.015922 -0.004651963 -0.06118422 0.01621919 -0.003852248 -0.06106525 0.01605796 -0.00402975 -0.0611841 0.01606029 -0.003251314 -0.06104654 0.01559048 -0.003004968 -0.06117451 0.01567292 -0.002792477 -0.06102031 0.0151866 -0.002759575 -0.06116676 0.01525449 -0.002553582 -0.06100332 0.01452958 -0.002676784 -0.06111156 0.01483851 -0.00245893 -0.06098467 0.01431959 -0.002526402 -0.06096458 0.01389062 -0.002989888 -0.06108039 0.01382493 -0.002775132 -0.06094503 0.01353621 -0.003085613 -0.0609281 0.01357626 -0.003424704 -0.06105643 0.01334458 -0.003443717 -0.06091403 0.01346391 -0.003907561 -0.06103491 0.01325213 -0.004007399 -0.06089538 0.01353406 -0.004377603 -0.06101363 0.01339668 -0.004599988 -0.06086248 0.01395714 -0.004982292 -0.06098216 0.01372563 -0.005030512 -0.06085449 0.01420748 -0.005343616 -0.06082201 0.01466894 -0.005227565 -0.06094801 0.01473742 -0.005437493 -0.06080728 0.01533854 -0.005316853 -0.06078988 0.01542299 -0.005050897 -0.06091463 0.01583045 -0.004954516 -0.06076657 0.01584964 -0.004547953 -0.06092071 0.01608067 -0.004590153 -0.06074482 0.0160318 -0.003893673 -0.06085509 0.01621913 -0.004096746 -0.0607205 0.01615995 -0.003515183 -0.06070095 0.01568168 -0.003062605 -0.06081658 0.01581585 -0.002913475 -0.06067413 0.01552772 -0.002697825 -0.06068581 0.01507729 -0.002719402 -0.06078493 0.01518726 -0.002535164 -0.06064426 0.01467144 -0.002468466 -0.06063032 0.01458311 -0.00268507 -0.06076371 0.01406461 -0.002616286 -0.06060016 0.0139814 -0.002902209 -0.06073606 0.01381856 -0.002793669 -0.06061667 0.01350265 -0.003126263 -0.0605778 0.01353019 -0.003521025 -0.06070184 0.01329648 -0.003589808 -0.06055462 0.01346731 -0.004049479 -0.06067854 0.01326304 -0.00412327 -0.06053698 0.01361364 -0.004555106 -0.06065559 0.01342916 -0.004645884 -0.0605182 0.0138145 -0.005122065 -0.06049835 0.01408594 -0.005065321 -0.06062465 0.01435637 -0.005383372 -0.06047159 0.01496744 -0.005225718 -0.06058579 0.01495033 -0.005424439 -0.06044852 0.01547265 -0.005238771 -0.06042075 0.01559853 -0.004891574 -0.06055378 0.01582205 -0.004967629 -0.06041204 0.01606196 -0.004608511 -0.06041783 0.01589357 -0.004491865 -0.06053268 0.0160259 -0.003859698 -0.06050473 0.01620316 -0.004250645 -0.06037718 0.01618272 -0.003611505 -0.06035715 0.01578325 -0.003212869 -0.06047356 0.01596462 -0.003107309 -0.06033784 0.01544147 -0.00288701 -0.06045287 0.01563549 -0.002768754 -0.06031024 0.01527023 -0.002566576 -0.06030547 0.01478207 -0.002654314 -0.06042265 0.01473104 -0.002462267 -0.06028479 0.01430708 -0.002533078 -0.06026297 0.01407277 -0.002858996 -0.06038951 0.01392459 -0.002710223 -0.0602498 0.01352965 -0.00308603 -0.06023055 0.01367276 -0.003244221 -0.06036585 0.01330679 -0.003552675 -0.06020408 0.01349258 -0.003680229 -0.06034475 0.01325267 -0.004009723 -0.06019258 0.01348656 -0.004205226 -0.0603215 0.01337331 -0.00454843 -0.06017464 0.0137915 -0.004828751 -0.0602917 0.01369392 -0.005009293 -0.06014764 0.0139656 -0.005205631 -0.06016004 0.01432466 -0.005142152 -0.06030118 0.01466655 -0.005449533 -0.06011742 0.01483744 -0.005223572 -0.06024134 0.01533597 -0.005306661 -0.06008404 0.01531744 -0.005084097 -0.06021875 0.01582956 -0.004963815 -0.06006383 0.0157653 -0.004722416 -0.06019419 0.01612454 -0.004481792 -0.06004542 0.01598668 -0.004200458 -0.06016856 0.01621299 -0.004132807 -0.06002545 0.01597678 -0.003597557 -0.06014281 0.0161783 -0.003567934 -0.06000369 0.01593685 -0.00307548 -0.05997639 0.0155375 -0.00293678 -0.06010836 0.01562559 -0.002756536 -0.05996811 0.01523375 -0.00255084 -0.05995935 0.01487636 -0.002676427 -0.06007629 0.01474547 -0.0024634 -0.05993187 0.01434969 -0.002737402 -0.06005311 0.01420998 -0.00256437 -0.05991232 0.01377099 -0.003086149 -0.06002312 0.01383346 -0.002777218 -0.05989807 0.01354491 -0.003061771 -0.05988132 0.01333487 -0.003472924 -0.0598604 0.01346683 -0.003803491 -0.05998957 0.01325321 -0.004042387 -0.05983924 0.01357918 -0.004519462 -0.05995804 0.0133621 -0.004501044 -0.05982422 0.01360094 -0.004900634 -0.05980592 0.01420456 -0.00512892 -0.05991876 0.01404833 -0.005268454 -0.0597853 0.01470112 -0.005441486 -0.05975234 0.01491826 -0.005213797 -0.05988758 0.01512163 -0.005374491 -0.0597648 0.01556706 -0.004942774 -0.05985629 0.01551735 -0.005221605 -0.0597276 0.01586782 -0.004916727 -0.05970668 0.01596742 -0.004306972 -0.05982393 0.01613831 -0.004441082 -0.05968916 0.01622772 -0.003828942 -0.05966359 0.01599824 -0.003724515 -0.05979824 0.01603484 -0.003229796 -0.05964142 0.01579678 -0.003241956 -0.05977505 0.01566982 -0.002790093 -0.0596227 0.01543182 -0.002872288 -0.05975216 0.01519918 -0.002535879 -0.0595991 0.01477432 -0.002663135 -0.05972254 0.01445543 -0.002490162 -0.05959421 0.01414322 -0.002817988 -0.05969327 0.01382863 -0.002782166 -0.05956751 0.01376944 -0.003123521 -0.05967211 0.01350873 -0.003112912 -0.05952817 0.01347529 -0.003686487 -0.05964469 0.01331663 -0.003522872 -0.05950891 0.01325201 -0.004011631 -0.05949199 0.01350885 -0.004274785 -0.05961841 0.01337808 -0.004541218 -0.05947208 0.01374071 -0.004754722 -0.05959504 0.01366823 -0.004979968 -0.05944806 0.01434153 -0.005177676 -0.05956357 0.01409423 -0.005289971 -0.05943256 0.01464831 -0.005429804 -0.05941134 0.01503133 -0.005194127 -0.0595324 0.01525563 -0.005349874 -0.05939143 0.01563173 -0.004880487 -0.05950355 0.0158202 -0.004971742 -0.05935519 0.01616489 -0.004393696 -0.05933624 0.0159626 -0.004312634 -0.05947422 0.01621973 -0.00379014 -0.05931913 0.01600551 -0.003767669 -0.05944961 0.01599001 -0.003144681 -0.05928593 0.01568406 -0.003062307 -0.05941617 0.01569885 -0.002821385 -0.05927252 0.01533252 -0.002590894 -0.059255 0.01488262 -0.002666056 -0.05937659 0.01475477 -0.002461254 -0.05923783 0.01419961 -0.002790749 -0.05934619 0.0142098 -0.002559959 -0.05921137 0.01374518 -0.002847373 -0.05919378 0.0136274 -0.003281593 -0.05931335 0.0133472 -0.003413438 -0.05917042 0.01346313 -0.00397551 -0.0592814 0.01325643 -0.003996253 -0.05914288 0.01357948 -0.004488289 -0.05925905 0.01337063 -0.004529356 -0.05912363 0.01361131 -0.004913151 -0.05910044 0.01385664 -0.004870116 -0.05923795 0.01392614 -0.005192995 -0.05908924 0.01440995 -0.005195856 -0.05920964 0.01447403 -0.005416512 -0.0590704 0.01506495 -0.005399584 -0.05904424 0.01504659 -0.005188167 -0.0591818 0.01554709 -0.005191862 -0.05902671 0.01568424 -0.004835665 -0.05915027 0.0159797 -0.004777669 -0.05900996 0.01600426 -0.004139244 -0.05911588 0.01622205 -0.004045963 -0.05897372 0.01617842 -0.003586411 -0.05896121 0.01590079 -0.003374934 -0.05908197 0.01596808 -0.003114879 -0.05893588 0.01559245 -0.002738714 -0.05891418 0.01537305 -0.002840816 -0.05904954 0.01517647 -0.002529144 -0.05890154 0.01473003 -0.002660334 -0.0590204 0.01465868 -0.002465426 -0.05887526 0.01418417 -0.002569973 -0.05886125 0.01411211 -0.002839922 -0.0589919 0.01377588 -0.002817332 -0.05885058 0.01361656 -0.003300249 -0.05896228 0.01344108 -0.003225982 -0.05882239 0.01325708 -0.003814876 -0.05879557 0.01346296 -0.004019796 -0.05893015 0.01331472 -0.004389405 -0.05877953 0.01362121 -0.004580199 -0.05890393 0.01358461 -0.004882991 -0.05875331 0.01394951 -0.00521934 -0.0587393 0.01416176 -0.005103647 -0.05887162 0.01433098 -0.005376994 -0.05874478 0.01500362 -0.005215585 -0.05883491 0.01479506 -0.00544095 -0.05869954 0.01547825 -0.005241096 -0.05867624 0.01558798 -0.004884243 -0.05884397 0.01596015 -0.00480616 -0.05864918 0.01587611 -0.004498302 -0.05881696 0.01620119 -0.004248917 -0.0586391 0.01602399 -0.003873884 -0.05875438 0.01617503 -0.003558993 -0.05860483 0.01574951 -0.003152847 -0.05872124 0.01590961 -0.003040373 -0.05858349 0.01557099 -0.002722859 -0.05857014 0.01520609 -0.002758383 -0.05869144 0.01521104 -0.002537369 -0.05854916 0.0146895 -0.00267744 -0.05866825 0.01466381 -0.002466559 -0.05852979 0.01408189 -0.002837479 -0.05864036 0.01416885 -0.002576828 -0.0585066 0.01372051 -0.002867877 -0.05848896 0.01359343 -0.00337857 -0.05860888 0.01339936 -0.003312468 -0.05847024 0.01325017 -0.00387299 -0.05845171 0.01345402 -0.004118263 -0.05857557 0.01333492 -0.004431962 -0.05842602 0.01388955 -0.00492984 -0.05853539 0.01360422 -0.004909455 -0.0584076 0.01402592 -0.005261242 -0.05838155 0.01451462 -0.005202889 -0.05850517 0.01463514 -0.005428731 -0.05836164 0.01520258 -0.005161583 -0.05847465 0.01522302 -0.00535953 -0.05834221 0.0157423 -0.005049586 -0.05830883 0.01589214 -0.004538357 -0.05843406 0.01612043 -0.004503011 -0.05829596 0.0162239 -0.003943979 -0.05826884 0.01601046 -0.003852903 -0.05840361 0.01612073 -0.003413975 -0.05825084 0.01578712 -0.00319314 -0.05837345 0.01581943 -0.002918839 -0.05823177 0.01527851 -0.002796471 -0.05834472 0.01518499 -0.002533793 -0.05819946 0.01476144 -0.00266993 -0.05832141 0.01472342 -0.002471148 -0.05820399 0.01426684 -0.00276494 -0.0582993 0.01440513 -0.002491116 -0.05816555 0.01383125 -0.002775609 -0.05814617 0.01378452 -0.003092586 -0.05827349 0.01344919 -0.003205239 -0.05812191 0.01349067 -0.003657519 -0.05824589 0.01327341 -0.003716826 -0.05810791 0.01350718 -0.004300057 -0.0582177 0.01332712 -0.004417479 -0.05809956 0.01379048 -0.004808962 -0.05819213 0.0135619 -0.004871785 -0.05805599 0.01403284 -0.005256354 -0.05803477 0.01435881 -0.005178391 -0.05816203 0.01449829 -0.005414664 -0.05801439 0.01517641 -0.005167365 -0.0581265 0.01503318 -0.00540781 -0.05799901 0.01544219 -0.005255818 -0.05797791 0.01576858 -0.004710137 -0.05809366 0.01587837 -0.004905223 -0.05795484 0.01615649 -0.004400074 -0.05793416 0.01598441 -0.004222035 -0.05806982 0.01622003 -0.003847956 -0.05791664 0.01598459 -0.003753066 -0.05808663 0.01604533 -0.003220558 -0.05791336 0.01581692 -0.003261089 -0.05802649 0.01531881 -0.002802073 -0.05799645 0.01547819 -0.002659618 -0.05785685 0.01506072 -0.00250256 -0.05784732 0.01462876 -0.002671003 -0.05796533 0.01467204 -0.002466261 -0.05782765 0.0142017 -0.002565085 -0.0578112 0.01392644 -0.002947628 -0.05793291 0.01376807 -0.002820134 -0.05779826 0.0134136 -0.003277838 -0.05776965 0.01356285 -0.003486514 -0.05794072 0.01324689 -0.003921926 -0.05774188 0.01345521 -0.004133641 -0.05787533 0.01334643 -0.004499197 -0.05772423 0.01378262 -0.004797518 -0.05784213 0.0136528 -0.004960536 -0.05770516 0.01408624 -0.005285561 -0.05768376 0.01420575 -0.005109548 -0.05781966 0.01457881 -0.005426049 -0.05767005 0.01480889 -0.005235254 -0.05779224 0.01507759 -0.005395412 -0.05764478 0.01548415 -0.004993259 -0.05776119 0.01553434 -0.005203425 -0.05761998 0.01587939 -0.004897713 -0.0576145 0.01595586 -0.004386425 -0.05772811 0.01611751 -0.004500329 -0.05759108 0.01622515 -0.003978133 -0.05756539 0.01598745 -0.003676772 -0.0576958 0.01614934 -0.00349164 -0.0575571 0.01573354 -0.003145694 -0.05767023 0.01592308 -0.003057003 -0.05753481 0.01558697 -0.002730548 -0.05751484 0.01519614 -0.002746462 -0.05764037 0.01511913 -0.002513229 -0.05749601 0.01450186 -0.002691805 -0.05761033 0.01457476 -0.002475976 -0.05747658 0.01389592 -0.002716898 -0.05747079 0.01396828 -0.002927482 -0.05758464 0.01353919 -0.003479599 -0.05755424 0.01346939 -0.003178417 -0.05742532 0.01324915 -0.003790199 -0.05740362 0.01349925 -0.004326224 -0.05751693 0.01342004 -0.004643619 -0.05736809 0.0137822 -0.005100727 -0.05734819 0.01403534 -0.00503534 -0.05747699 0.01431477 -0.005376219 -0.05732262 0.01476061 -0.005229294 -0.05744469 0.01492524 -0.005430519 -0.05730527 0.01548177 -0.005009889 -0.05741214 0.01554167 -0.005201041 -0.05727642 0.01594585 -0.004810214 -0.05725479 0.01592588 -0.004422783 -0.057379 0.0161783 -0.004321992 -0.05723458 0.01601344 -0.00395435 -0.05735808 0.0162062 -0.003693342 -0.05720323 0.01588958 -0.00338447 -0.05733233 0.0159676 -0.003103613 -0.05719405 0.01547521 -0.002901196 -0.05730468 0.01550948 -0.002679944 -0.05716192 0.0148729 -0.002676486 -0.05727654 0.01500666 -0.002491772 -0.05714541 0.01429396 -0.00252211 -0.0571174 0.01418566 -0.002785623 -0.0572462 0.0137642 -0.002829372 -0.0570926 0.01366019 -0.003260076 -0.05721461 0.01346617 -0.003187954 -0.05708348 0.01328617 -0.003626406 -0.05705583 0.01348215 -0.00373125 -0.0571925 0.01352822 -0.004401028 -0.05716294 0.01327031 -0.004153311 -0.05703622 0.01343548 -0.004665017 -0.05701792 0.01394808 -0.00495398 -0.05713254 0.01375901 -0.00506556 -0.05699968 0.01417827 -0.005325376 -0.05697971 0.01442152 -0.005183994 -0.05710953 0.01474875 -0.005446553 -0.05695843 0.01494657 -0.005214571 -0.05708658 0.01531589 -0.005325794 -0.05692988 0.01558661 -0.00491631 -0.05705523 0.01588475 -0.004898846 -0.05690574 0.01596552 -0.004325091 -0.05702412 0.01611793 -0.004492461 -0.05689203 0.01622527 -0.003964483 -0.05687552 0.01597207 -0.003676772 -0.05703383 0.01608824 -0.003299772 -0.05684745 0.01583904 -0.003299593 -0.05697834 0.01541709 -0.002862334 -0.0569517 0.01577657 -0.002874314 -0.05682313 0.01523375 -0.00254482 -0.05680233 0.01488184 -0.002680897 -0.0569269 0.01471561 -0.002458095 -0.05677992 0.0143069 -0.002742052 -0.05690109 0.01415073 -0.002585947 -0.05675971 0.01368689 -0.003196537 -0.05686718 0.01369291 -0.002889096 -0.05673933 0.01341414 -0.003277122 -0.05671781 0.01346248 -0.003884553 -0.05683594 0.01326406 -0.003792107 -0.05670124 0.01331812 -0.004410862 -0.05668157 0.013592 -0.004539728 -0.0568068 0.01360976 -0.004922449 -0.05664867 0.01406455 -0.005016922 -0.05681365 0.01415246 -0.005316674 -0.05663263 0.01446408 -0.005198121 -0.05675774 0.01465141 -0.005430757 -0.05660289 0.01513546 -0.005175232 -0.056728 0.01506304 -0.00539875 -0.05659574 0.01552194 -0.005211114 -0.05658119 0.01565665 -0.004836201 -0.0567004 0.01590144 -0.004873991 -0.05655485 0.01598054 -0.004287898 -0.05667328 0.0161466 -0.004415214 -0.0565378 0.01622343 -0.003891646 -0.05652374 0.0159794 -0.003644585 -0.05664467 0.01615393 -0.003512084 -0.05649971 0.01596611 -0.003118157 -0.05648648 0.01570051 -0.00310254 -0.05661791 0.01556414 -0.002712428 -0.05646777 0.01516145 -0.002738535 -0.05658894 0.01488077 -0.002470672 -0.05645924 0.01454526 -0.002687156 -0.05656212 0.01429682 -0.002526342 -0.05641281 0.01392894 -0.002945303 -0.05653226 0.013736 -0.002849161 -0.05639046 0.01339626 -0.003319501 -0.05636972 0.0135346 -0.003520786 -0.05650222 0.01324325 -0.003943145 -0.05634486 0.01346379 -0.004042744 -0.05647903 0.01339 -0.00456655 -0.05632072 0.01364785 -0.004623234 -0.05645233 0.01373744 -0.005052626 -0.05629789 0.01411873 -0.00507307 -0.0564233 0.0143308 -0.005383968 -0.05627596 0.01468634 -0.005223572 -0.05639743 0.01495814 -0.005420386 -0.05625069 0.01531696 -0.005102992 -0.05636978 0.0155034 -0.005231499 -0.05622398 0.01584035 -0.004600644 -0.05633789 0.01596939 -0.004778206 -0.05620115 0.01620548 -0.004215598 -0.05617505 0.0160107 -0.004071056 -0.05631339 0.01621407 -0.003882348 -0.05618906 0.01595753 -0.003582954 -0.05629158 0.01614415 -0.003464043 -0.05615139 0.01562821 -0.003009319 -0.05626225 0.01590317 -0.00302565 -0.05612546 0.01553755 -0.002699911 -0.05612009 0.01494681 -0.002687275 -0.05622929 0.01513755 -0.002520918 -0.05609673 0.01458531 -0.002469837 -0.05607616 0.01419907 -0.002771735 -0.0561971 0.01405841 -0.002628982 -0.05605506 0.01363313 -0.002961635 -0.05603706 0.01359486 -0.003358542 -0.05615985 0.01340585 -0.003302454 -0.0560168 0.01326698 -0.003734827 -0.0560038 0.01346492 -0.003930211 -0.05613368 0.01329672 -0.004296004 -0.05598211 0.01357239 -0.004482269 -0.05610895 0.01357889 -0.004896402 -0.05595785 0.01389348 -0.004904627 -0.05608546 0.01416087 -0.005320489 -0.05593246 0.01432067 -0.00515443 -0.05606412 0.01501673 -0.005215406 -0.05603379 0.01463997 -0.005433261 -0.05590969 0.01515734 -0.00537616 -0.05589067 0.01579689 -0.004993855 -0.05588579 0.01562422 -0.004865825 -0.05600273 0.0159766 -0.004322409 -0.05597412 0.01619982 -0.004263997 -0.05583107 0.0162065 -0.003704488 -0.05581206 0.01597088 -0.003615617 -0.05594348 0.01602661 -0.003196895 -0.05579149 0.01564598 -0.003031373 -0.05591386 0.0155726 -0.002714931 -0.05577379 0.01489847 -0.002669036 -0.05587762 0.01502436 -0.002490997 -0.05573928 0.01448923 -0.002485394 -0.05572164 0.0141673 -0.002802193 -0.0558449 0.01388269 -0.002729117 -0.05570495 0.01364541 -0.003270089 -0.05581426 0.01347017 -0.003159701 -0.05567538 0.01327157 -0.00370413 -0.05565392 0.01346743 -0.003862917 -0.05578649 0.01352834 -0.004368841 -0.05576413 0.01327192 -0.004194974 -0.05563431 0.01344662 -0.004686117 -0.05561792 0.01379626 -0.004806101 -0.05574172 0.01375108 -0.005062103 -0.0555979 0.01426458 -0.005143821 -0.05571681 0.01418924 -0.005332529 -0.05557262 0.0147438 -0.005436003 -0.05555456 0.01505404 -0.005203843 -0.05568271 0.01527142 -0.005331754 -0.05554062 0.01564925 -0.005121111 -0.05552119 0.01576405 -0.004732489 -0.05564409 0.01596063 -0.00479561 -0.0555036 0.01621764 -0.00410068 -0.0554986 0.01602441 -0.003984868 -0.05560934 0.0160796 -0.003316044 -0.05545908 0.01589643 -0.003417551 -0.05558383 0.01585125 -0.00298047 -0.05544894 0.0154708 -0.002884566 -0.05555826 0.01474589 -0.002668142 -0.05552035 0.01415908 -0.002810359 -0.05549395 0.0137661 -0.003122925 -0.0554713 0.01455056 -0.002679526 -0.06118279 0.01399624 -0.002902567 -0.06117182 0.01359331 -0.003367364 -0.06113392 0.01345968 -0.004012763 -0.06110477 0.01370483 -0.004726827 -0.06106883 0.01423954 -0.005121171 -0.06104212 0.01473635 -0.005230069 -0.06101989 0.01541751 -0.005046248 -0.06098806 0.01600635 -0.004093289 -0.06093835 0.01592516 -0.003450095 -0.06090968 0.01552498 -0.002943873 -0.06088155 0.0150091 -0.002698302 -0.06085664 0.01428055 -0.002740383 -0.0608235 0.01366013 -0.003249049 -0.06078886 0.0134468 -0.00404936 -0.06075239 0.01370251 -0.004693508 -0.06072229 0.0142064 -0.005124688 -0.06069362 0.01489526 -0.005219161 -0.06066268 0.01561421 -0.004908442 -0.06062829 0.01602828 -0.004068791 -0.06058675 0.0158745 -0.003365993 -0.06055593 0.01548045 -0.002904534 -0.06052881 0.0148862 -0.002676188 -0.0605008 0.0143131 -0.002747416 -0.06047588 0.01389396 -0.002989947 -0.06045365 0.0134871 -0.003615081 -0.06042116 0.01352012 -0.004333436 -0.06039035 0.01383113 -0.004854857 -0.06036323 0.01492339 -0.005227029 -0.06031125 0.01556646 -0.004925131 -0.06028014 0.01597088 -0.004330933 -0.06024926 0.01599109 -0.003721475 -0.06022202 0.01572561 -0.003114461 -0.06019282 0.01519203 -0.002760052 -0.06016528 0.01468819 -0.002672076 -0.0601418 0.01411056 -0.002831578 -0.06011575 0.01358759 -0.003366649 -0.06008362 0.01346999 -0.00420165 -0.06004524 0.01387196 -0.004900097 -0.06001102 0.01437574 -0.005168378 -0.05998545 0.01492226 -0.005223631 -0.05996125 0.01547574 -0.004987597 -0.05993533 0.01581227 -0.00464344 -0.05991423 0.0160312 -0.003974735 -0.05988222 0.01577585 -0.003185689 -0.05984646 0.01507228 -0.002697408 -0.05980885 0.01434856 -0.002733707 -0.05977725 0.01383149 -0.003043055 -0.05975103 0.01346838 -0.003706932 -0.0597167 0.0135771 -0.004501819 -0.05968201 0.01396059 -0.004957973 -0.05965632 0.01457011 -0.00523436 -0.05962657 0.01525211 -0.005115568 -0.05959683 0.01574224 -0.004758656 -0.05956953 0.01601147 -0.004088044 -0.05953848 0.0159434 -0.00352329 -0.05951243 0.01551496 -0.002912878 -0.05947995 0.01483565 -0.002676129 -0.05944913 0.01415663 -0.002798199 -0.05941832 0.01370263 -0.003209054 -0.05939167 0.0134961 -0.003655076 -0.05937033 0.01347875 -0.004167079 -0.05934685 0.01379841 -0.004840791 -0.05931437 0.01442784 -0.005188584 -0.05928349 0.01500648 -0.005200386 -0.05925774 0.01564764 -0.00486952 -0.05922603 0.01599687 -0.004193603 -0.059192 0.01598054 -0.003670036 -0.0591697 0.01570832 -0.003098964 -0.05914241 0.01519954 -0.002762794 -0.05911523 0.01454335 -0.00267136 -0.05908596 0.01396214 -0.002940535 -0.05905842 0.01362341 -0.003323853 -0.059035 0.01345711 -0.003899574 -0.05900895 0.01357406 -0.004468798 -0.05898374 0.01385343 -0.004873692 -0.05896222 0.01429533 -0.005143225 -0.05893951 0.01495999 -0.005226731 -0.0589106 0.01601946 -0.003981292 -0.0588333 0.01589167 -0.003397703 -0.05880737 0.01543635 -0.002861142 -0.05877542 0.01467949 -0.002666652 -0.05874228 0.01418972 -0.002804696 -0.05871957 0.01375621 -0.003117084 -0.05869603 0.01350206 -0.003645956 -0.05867052 0.01348298 -0.004221439 -0.05864548 0.0137217 -0.004717111 -0.05862098 0.0142101 -0.005125761 -0.05859345 0.01491695 -0.005217909 -0.05856114 0.01556676 -0.004935383 -0.05853044 0.01595515 -0.004351615 -0.05850023 0.01600265 -0.003758847 -0.05847352 0.01576948 -0.003184318 -0.05844628 0.01514357 -0.002722859 -0.05841207 0.01426136 -0.00274533 -0.05837315 0.01370412 -0.003200292 -0.05834227 0.0134707 -0.003760516 -0.05831515 0.01350772 -0.004280984 -0.05829226 0.01375699 -0.004771351 -0.05826866 0.0143398 -0.005176723 -0.058236 0.0151664 -0.005166769 -0.05820119 0.01566833 -0.004819393 -0.05817395 0.01596719 -0.004323184 -0.05814832 0.01581424 -0.003255426 -0.05810052 0.0153104 -0.002796649 -0.05806922 0.01452112 -0.002677917 -0.05803561 0.01387226 -0.003005266 -0.05800312 0.01346474 -0.003966271 -0.05795669 0.01363652 -0.004629671 -0.05792534 0.01423227 -0.005126833 -0.05789202 0.01482093 -0.005225539 -0.05786615 0.01530146 -0.005093932 -0.05784404 0.01575422 -0.004730761 -0.05781847 0.01600503 -0.004149019 -0.05779105 0.01592844 -0.003468751 -0.05776 0.01561492 -0.003025054 -0.05773663 0.01517385 -0.002748012 -0.0577144 0.01462858 -0.002674758 -0.05768948 0.01413339 -0.002829432 -0.05766713 0.01368409 -0.003210544 -0.0576415 0.01345968 -0.003876566 -0.05760973 0.01363551 -0.004628598 -0.05757594 0.0141592 -0.00508511 -0.05754619 0.01471567 -0.005235552 -0.05752021 0.01543855 -0.005028665 -0.05748784 0.01584237 -0.004588484 -0.05746078 0.01602005 -0.004013597 -0.05743473 0.01586979 -0.003340482 -0.05740481 0.01536303 -0.002827346 -0.05737268 0.0148319 -0.002679109 -0.0573486 0.01425796 -0.002759695 -0.05732357 0.01377511 -0.003110408 -0.05729633 0.01345342 -0.00378257 -0.05726397 0.01359349 -0.004519939 -0.05723166 0.01410925 -0.005083203 -0.05719774 0.01477861 -0.005222201 -0.0571683 0.01529216 -0.005105733 -0.05714392 0.01570326 -0.004780232 -0.05712163 0.01599955 -0.004221975 -0.05709439 0.01564902 -0.003031492 -0.05703794 0.01508587 -0.002724826 -0.05701041 0.01454782 -0.002682864 -0.05698561 0.01399248 -0.002910017 -0.05695968 0.01354104 -0.003469228 -0.05692881 0.01348042 -0.004193484 -0.05689626 0.01373112 -0.004736959 -0.05686992 0.01454949 -0.005211651 -0.05682778 0.01520168 -0.005154013 -0.0567981 0.01580286 -0.004668235 -0.05676555 0.01600724 -0.004097819 -0.05673843 0.01593565 -0.003492832 -0.05671167 0.01565051 -0.00305891 -0.0566892 0.01520103 -0.00275731 -0.0566647 0.01468557 -0.002674221 -0.05664199 0.01421743 -0.002786159 -0.05662113 0.01368069 -0.003205358 -0.05659168 0.01347196 -0.003820359 -0.05656284 0.01355987 -0.004489719 -0.05653375 0.01405793 -0.005029737 -0.05650055 0.01471143 -0.005241513 -0.05647039 0.01550716 -0.004985034 -0.05643433 0.01598453 -0.004294872 -0.05639624 0.01593303 -0.003466904 -0.0563603 0.01555168 -0.002969264 -0.05633324 0.01495724 -0.00267297 -0.05630439 0.01426827 -0.002764999 -0.05627357 0.01378655 -0.003084659 -0.05624783 0.01348078 -0.003708124 -0.05621802 0.01350837 -0.004303991 -0.05619072 0.01377153 -0.004778861 -0.05616772 0.01423281 -0.005133211 -0.05614233 0.01482892 -0.005219697 -0.05611574 0.01546853 -0.00502032 -0.05608606 0.01593726 -0.004399657 -0.05605244 0.01600497 -0.003721535 -0.05602115 0.01563042 -0.003017485 -0.05598759 0.01509362 -0.002726972 -0.05596029 0.0144326 -0.002693176 -0.05593115 0.01370245 -0.003175139 -0.05589264 0.01345145 -0.003961026 -0.05585557 0.01364833 -0.004619181 -0.05582678 0.01417422 -0.005113422 -0.05579394 0.01507049 -0.005202472 -0.05575573 0.01571834 -0.004773616 -0.05572092 0.01600903 -0.004155516 -0.05569005 0.01592564 -0.003473341 -0.0556612 0.01557701 -0.002979338 -0.05563402 0.01497548 -0.002690255 -0.05560481 0.01422828 -0.002761304 -0.05557179 0.01365798 -0.003259718 -0.05553799 0.01345527 -0.003903329 -0.05550938 0.01383578 -0.00512439 -0.06117892 0.01344525 -0.003447711 -0.06118404 0.01334798 -0.004401922 -0.06118363 0.01424837 -0.005342066 -0.06117582 0.01470702 -0.005431234 -0.06113636 0.01526248 -0.005329012 -0.06111538 0.01436203 -0.005387902 -0.06009989 0.01471036 -0.002475142 -0.05955922 0.01407641 -0.002618253 -0.0595352 0.01351416 -0.003123164 -0.05915653 0.01612436 -0.004464805 -0.05896776 0.01559627 -0.002744793 -0.05819487 0.01327508 -0.00416553 -0.05806457 0.01600342 -0.003167927 -0.05786699 0.01398104 -0.00266987 -0.0574305 0.01327615 -0.004198431 -0.05736297 0.01460468 -0.002477645 -0.05710589 0.01505684 -0.00250101 -0.05642235 0.01559346 -0.005151152 -0.05585086 0.01603585 -0.004676163 -0.05582678 0.01596361 -0.003536641 -0.05518782 0.01583033 -0.003156721 -0.05521368 0.01582926 -0.002984642 -0.05533415 0.01603174 -0.003360211 -0.05527466 0.01608097 -0.003982365 -0.05520665 0.01619446 -0.003656864 -0.05543363 0.01618033 -0.003822028 -0.05530905 0.01594948 -0.004381954 -0.05518698 0.01617509 -0.004182219 -0.05533713 0.01604551 -0.004467725 -0.05525606 0.01569408 -0.004864037 -0.0551961 0.01608693 -0.004565179 -0.05542927 0.01589298 -0.004835188 -0.05532413 0.0153802 -0.005102038 -0.05519354 0.01556605 -0.005147337 -0.05532026 0.01499295 -0.005286991 -0.0552209 0.01514011 -0.005340993 -0.05531525 0.01451981 -0.00524199 -0.05519163 0.014862 -0.005400896 -0.05533993 0.01395881 -0.004958271 -0.05518412 0.01458132 -0.005352616 -0.05526584 0.0146622 -0.005422413 -0.05543404 0.01439058 -0.005356311 -0.05530822 0.01396745 -0.005075395 -0.05522167 0.01407092 -0.005245327 -0.05534255 0.0138207 -0.005079686 -0.05533468 0.01358461 -0.004820644 -0.05530798 0.01346719 -0.00428766 -0.05519217 0.01364296 -0.004733026 -0.0552144 0.01363033 -0.004922747 -0.05543398 0.01337474 -0.004436671 -0.05530971 0.01339429 -0.004557669 -0.05543386 0.01369792 -0.003198087 -0.05518448 0.01330065 -0.004026114 -0.05529636 0.01342034 -0.003712356 -0.0552085 0.01327335 -0.003741085 -0.05542665 0.01338618 -0.003520846 -0.05526989 0.01360988 -0.003171145 -0.05522578 0.01338005 -0.003349781 -0.05542922 0.01351159 -0.003159344 -0.05534172 0.01452535 -0.002690315 -0.05518466 0.01375889 -0.002886652 -0.0553115 0.01399034 -0.002813458 -0.05521988 0.01405489 -0.00266093 -0.05534052 0.01432996 -0.002621889 -0.05523955 0.0144295 -0.002523601 -0.05534338 0.0147143 -0.00250107 -0.05531734 0.01482623 -0.002600789 -0.05521672 0.01513689 -0.002569675 -0.05528676 0.0153526 -0.002805292 -0.055188 0.01545417 -0.002674877 -0.0553469 0.01561594 -0.002866148 -0.05524319 0.01268684 -0.005703866 -0.06135827 0.01264005 -0.005520939 -0.06123864 0.01304781 -0.006051301 -0.06137615 0.01294296 -0.005695164 -0.06118577 0.01310425 -0.006013274 -0.06125199 0.01335674 -0.006258606 -0.06133317 0.01347601 -0.006168842 -0.06120032 0.01380932 -0.006486833 -0.06139349 0.0137974 -0.006415724 -0.06125849 0.01427227 -0.006605923 -0.06135302 0.01431584 -0.006465077 -0.06119251 0.014835 -0.006632566 -0.06131511 0.01498347 -0.006474196 -0.06119126 0.01532226 -0.006582617 -0.06135439 0.01563972 -0.006407141 -0.06123751 0.01585668 -0.006398439 -0.06133455 0.01582491 -0.006209194 -0.06118685 0.01628899 -0.006157279 -0.06136363 0.01670849 -0.005790352 -0.06135123 0.0165714 -0.005675256 -0.06118708 0.01643162 -0.005955278 -0.06123811 0.01698166 -0.005443513 -0.06135886 0.01693499 -0.005367398 -0.06123989 0.01719039 -0.00507164 -0.06135678 0.0170657 -0.004899322 -0.061185 0.01719838 -0.004867613 -0.06124842 0.01731997 -0.00471282 -0.06134921 0.01739811 -0.004324913 -0.06131982 0.01727682 -0.004305064 -0.06120496 0.01743429 -0.003829777 -0.06135106 0.0172789 -0.003768324 -0.06119197 0.01734209 -0.003241062 -0.06136727 0.01725035 -0.003135859 -0.06125396 0.01704519 -0.002941966 -0.06118655 0.01716166 -0.002756834 -0.06137543 0.01697129 -0.002568721 -0.0612424 0.01680725 -0.002213001 -0.06136798 0.01648765 -0.002031803 -0.06121563 0.01653933 -0.001951694 -0.06133586 0.01620686 -0.001690387 -0.06135553 0.01592534 -0.001720786 -0.06118625 0.0158708 -0.001513183 -0.06132483 0.01548606 -0.001370668 -0.06132423 0.01550942 -0.001505792 -0.06120586 0.01512318 -0.001280844 -0.06135588 0.01488882 -0.001321494 -0.06125056 0.01455301 -0.001423418 -0.06118744 0.01452863 -0.001254796 -0.06137973 0.01426446 -0.001352608 -0.061257 0.01394963 -0.00136578 -0.06139189 0.01390874 -0.001453638 -0.06125068 0.01348769 -0.001559436 -0.06135773 0.01341164 -0.001804113 -0.06118744 0.01327276 -0.001769304 -0.06124097 0.01310765 -0.001809716 -0.06134241 0.01274114 -0.002127289 -0.06138461 0.01269888 -0.002252995 -0.06127071 0.01284927 -0.002266228 -0.06119 0.01234906 -0.002692699 -0.06135606 0.01240384 -0.002777636 -0.06123667 0.01215839 -0.003198146 -0.06132447 0.01229286 -0.003267407 -0.06119072 0.0120477 -0.003695547 -0.06138288 0.01211506 -0.003855407 -0.06124109 0.01206588 -0.004259347 -0.06133425 0.01212763 -0.004635095 -0.06136572 0.01225608 -0.004457116 -0.06118899 0.01222336 -0.004760563 -0.06126332 0.01234292 -0.005185544 -0.06135123 0.01245439 -0.005038082 -0.06119084 0.01291227 -0.005945444 -0.06399267 0.01390957 -0.006512701 -0.06401079 0.01527911 -0.006586372 -0.0640192 0.01563894 -0.006486535 -0.06403052 0.01722288 -0.005016505 -0.06398111 0.01739519 -0.003461122 -0.06398147 0.01722395 -0.002886593 -0.06398546 0.01691848 -0.002357125 -0.06399339 0.0165748 -0.001969993 -0.06399023 0.01623165 -0.001705229 -0.06402462 0.01578313 -0.00146991 -0.06402432 0.01532012 -0.00131148 -0.06399726 0.01372623 -0.001447081 -0.06400841 0.01291263 -0.001963078 -0.06400239 0.01234424 -0.002703666 -0.06399255 0.0120486 -0.003710865 -0.06400436 0.01206737 -0.004288017 -0.06402921 0.01215261 -0.004704058 -0.06401985 0.01233834 -0.005183756 -0.06399941 0.01258021 -0.00555855 -0.06401985 0.01264697 -0.005419254 -0.06417298 0.01238209 -0.005133152 -0.06411004 0.01227474 -0.004632234 -0.06417185 0.01214545 -0.003792166 -0.06415045 0.01225996 -0.00350058 -0.06418198 0.01215869 -0.003164768 -0.06401479 0.01222968 -0.003134369 -0.06411099 0.01239097 -0.002765893 -0.06412136 0.01270234 -0.002399027 -0.06417226 0.01261615 -0.002292096 -0.06402212 0.01316887 -0.001812577 -0.06409955 0.01315248 -0.001985967 -0.06418067 0.01326376 -0.001688838 -0.06398355 0.01377224 -0.001556813 -0.0641579 0.01406341 -0.001379072 -0.06408226 0.01437705 -0.001269996 -0.06398004 0.01454049 -0.001451075 -0.06418263 0.01465481 -0.001308262 -0.06411373 0.01483607 -0.001258254 -0.06401342 0.01526951 -0.001471877 -0.06417763 0.01556164 -0.001453638 -0.06412357 0.01624572 -0.001846492 -0.06415361 0.01640582 -0.002057969 -0.06418132 0.01672261 -0.002228975 -0.06412237 0.01703613 -0.002645492 -0.06411141 0.01693409 -0.002735376 -0.06418061 0.01727235 -0.0032081 -0.06410896 0.01722866 -0.003481686 -0.06417626 0.01737165 -0.003833472 -0.06411695 0.01743918 -0.003964543 -0.0639922 0.01737737 -0.004211664 -0.06409245 0.017385 -0.004475712 -0.06398952 0.01723456 -0.004890143 -0.06407654 0.01702201 -0.00508666 -0.06417322 0.01697897 -0.005434572 -0.06404101 0.01670354 -0.005787491 -0.06403815 0.01654505 -0.005755603 -0.06417179 0.01629531 -0.006139457 -0.06404328 0.01589155 -0.006226301 -0.06417453 0.01599091 -0.006331384 -0.06402283 0.01521104 -0.00646162 -0.06417179 0.01489382 -0.006641328 -0.06401288 0.01468217 -0.006555736 -0.06413924 0.01437473 -0.006622731 -0.06400889 0.01424205 -0.006406664 -0.06418246 0.01411867 -0.00649774 -0.06412386 0.01352977 -0.006358206 -0.06402891 0.01359039 -0.006251096 -0.06415992 0.01303899 -0.005970656 -0.06411099 0.01315456 -0.005908489 -0.06417989 0.01738095 0.009528517 -0.06249159 0.01601457 0.009407401 -0.06250393 0.01743549 0.009655952 -0.06259864 0.01595228 0.009488046 -0.06264281 0.01550948 0.008128166 -0.06249213 0.01537394 0.008111894 -0.06260079 0.01632028 0.007048845 -0.06249195 0.01626557 0.006920874 -0.06260049 0.0176599 0.007209122 -0.06249147 0.01774263 0.007098674 -0.06260079 0.01819139 0.008451223 -0.06249225 0.01832866 0.008466124 -0.06260156 0.01776957 0.007062196 -0.0641725 0.01837426 0.008471846 -0.0641731 0.01624691 0.006877303 -0.06417328 0.0153287 0.00810647 -0.0641725 0.01593011 0.009517967 -0.06417328 0.01745325 0.00969851 -0.0641725 0.01560634 0.008609473 -0.05544042 0.01559978 0.008035778 -0.0554341 0.01566475 0.009187281 -0.0554338 0.01550811 0.007666051 -0.0554341 0.01602554 0.009399533 -0.05543428 0.01590108 0.007428526 -0.0554462 0.01631236 0.009671449 -0.0554282 0.01634562 0.00712186 -0.0554369 0.01694083 0.00976783 -0.05542606 0.01686501 0.006974697 -0.055435 0.01733773 0.009687483 -0.05542749 0.01758992 0.007145404 -0.05543404 0.01818478 0.007652044 -0.05544406 0.01833021 0.008326292 -0.05543822 0.0174818 0.006962478 -0.06117165 0.01790803 0.007241725 -0.06111043 0.01825916 0.007799327 -0.06109166 0.0180118 0.008831381 -0.0611844 0.01803433 0.007586777 -0.06118422 0.01832985 0.008455991 -0.06106489 0.01817029 0.00820893 -0.0611841 0.01817214 0.00898528 -0.06103968 0.01768577 0.009250283 -0.06117451 0.01759189 0.009581267 -0.06103396 0.01725405 0.009496271 -0.06116575 0.01707041 0.009767949 -0.06098711 0.01667165 0.009563624 -0.06111264 0.01645922 0.009718656 -0.06096637 0.01599991 0.00925219 -0.06108045 0.01594376 0.009469509 -0.06094694 0.01552218 0.008965253 -0.06091374 0.01558715 0.008566081 -0.06104588 0.01536095 0.008350849 -0.06090432 0.01564639 0.007861137 -0.06101363 0.01547551 0.007722914 -0.0608707 0.01606953 0.007256448 -0.06098216 0.01577901 0.007265806 -0.06085389 0.01619178 0.006957113 -0.06083691 0.01678133 0.007011175 -0.06094801 0.01692134 0.00679779 -0.06080728 0.01745897 0.007154464 -0.06091839 0.01765739 0.00702846 -0.06079822 0.01789039 0.007553458 -0.0608921 0.01814228 0.007560491 -0.06074821 0.01810604 0.008040726 -0.06086874 0.01832103 0.008076667 -0.06072896 0.0181005 0.008544325 -0.06084674 0.01829683 0.008642077 -0.0607025 0.01786184 0.009077489 -0.06082135 0.01799476 0.009244978 -0.06067824 0.01766788 0.009525537 -0.06068706 0.01747655 0.009384691 -0.0608381 0.01737833 0.009680926 -0.0606473 0.01701855 0.009553074 -0.06077766 0.01681685 0.009771347 -0.06063145 0.01638889 0.009490966 -0.0607503 0.01622164 0.009641766 -0.06060099 0.01593053 0.009444713 -0.06061661 0.01590901 0.009146094 -0.06072396 0.01563233 0.009141802 -0.060579 0.01563525 0.008689999 -0.06070065 0.01541447 0.008677542 -0.06055468 0.0155797 0.008189201 -0.06067854 0.01537555 0.008114457 -0.06053698 0.01573812 0.007656753 -0.0606544 0.01559442 0.007484674 -0.06050932 0.01600027 0.007057189 -0.06049293 0.01617801 0.007195353 -0.06062579 0.01670849 0.006803095 -0.0604602 0.01696801 0.006998658 -0.06059086 0.01710283 0.006829261 -0.0604701 0.01743185 0.006922185 -0.06042778 0.01766908 0.007304668 -0.06055641 0.01785916 0.007202029 -0.0604155 0.01818621 0.007638037 -0.06039625 0.01801949 0.00777179 -0.06053149 0.0183264 0.008123576 -0.06037825 0.01813173 0.008468389 -0.06050121 0.01829481 0.008628189 -0.06035709 0.01807653 0.009132087 -0.06033778 0.01776134 0.009199202 -0.06046384 0.01778709 0.009437203 -0.06031566 0.01741981 0.009656727 -0.06030702 0.01715213 0.009532809 -0.06043386 0.016896 0.009776949 -0.06028658 0.01651179 0.009527683 -0.06040585 0.01616621 0.009607613 -0.06027722 0.0159524 0.009198486 -0.06037682 0.01555091 0.009023606 -0.0602461 0.0155853 0.008564352 -0.06034559 0.0153684 0.00833112 -0.0601961 0.01568037 0.007759153 -0.06030905 0.01546883 0.007733166 -0.06017369 0.01580476 0.007230281 -0.06014573 0.01604473 0.007300674 -0.06028342 0.01620346 0.006947159 -0.06013262 0.01643681 0.007096648 -0.06030118 0.01661449 0.006826758 -0.06013858 0.01694983 0.007015168 -0.06024134 0.01730829 0.006875574 -0.06011146 0.01756304 0.007218837 -0.06021261 0.01775693 0.007101356 -0.06006944 0.01796078 0.007659137 -0.0601868 0.01814806 0.007560491 -0.06004661 0.01812058 0.008154094 -0.06016343 0.01831877 0.008073449 -0.06002837 0.01829695 0.008636832 -0.06000286 0.01807123 0.008663892 -0.06014156 0.01807135 0.00913763 -0.05998462 0.0178492 0.009083449 -0.06012046 0.01767873 0.009519994 -0.05996578 0.01743412 0.009408414 -0.06013405 0.01730465 0.009698748 -0.05995285 0.01696068 0.009567141 -0.06007498 0.01684063 0.009778439 -0.05993276 0.01637846 0.009473443 -0.06004935 0.01613891 0.009601473 -0.05991029 0.0158323 0.009085893 -0.06001961 0.01561188 0.009098708 -0.05989873 0.01543754 0.00874108 -0.05986005 0.01557821 0.008406102 -0.05998826 0.01536685 0.008173286 -0.05983847 0.015639 0.007883191 -0.05996507 0.01551109 0.007651031 -0.05982375 0.0159614 0.007365942 -0.05993837 0.01578098 0.007259309 -0.05980247 0.01617431 0.00696659 -0.05978161 0.01652866 0.007047235 -0.05990934 0.01676285 0.006800413 -0.05975335 0.01726347 0.007068932 -0.05987781 0.01735043 0.006887316 -0.05973935 0.0178405 0.007169783 -0.05971676 0.0177915 0.007425546 -0.05984896 0.01821666 0.007692635 -0.05970114 0.01807975 0.007931649 -0.05982393 0.01832932 0.008203446 -0.05967193 0.01809448 0.008627653 -0.05979353 0.01829564 0.008643805 -0.05965924 0.01809757 0.009099841 -0.0596379 0.01771956 0.009228587 -0.05976188 0.01775729 0.009467482 -0.05961185 0.01728767 0.00948745 -0.05973988 0.01724749 0.009723246 -0.05959469 0.01679688 0.009562969 -0.05971813 0.01669359 0.009765863 -0.0595771 0.01629918 0.009665012 -0.05956393 0.01612693 0.009364426 -0.05968707 0.01591062 0.009441792 -0.05954891 0.01546442 0.008826732 -0.059538 0.01559442 0.008607864 -0.05964708 0.01536047 0.008229672 -0.05949318 0.01562756 0.007935345 -0.05961716 0.01548707 0.007695734 -0.05947208 0.01587283 0.007463335 -0.05959385 0.015769 0.007267475 -0.05944782 0.01627039 0.007153809 -0.05957174 0.01622867 0.006940126 -0.05943012 0.01674866 0.00701797 -0.05954998 0.01676112 0.006808936 -0.05941134 0.0173816 0.007113337 -0.05952149 0.01716774 0.006842851 -0.05939704 0.01758956 0.006995856 -0.05937927 0.01787 0.007525444 -0.05949378 0.01802766 0.007387936 -0.05935919 0.0180841 0.007951736 -0.05947303 0.01822978 0.007742762 -0.05933433 0.01834487 0.00832802 -0.05931395 0.01811099 0.008499801 -0.0594483 0.01824647 0.008766889 -0.05932354 0.01791751 0.008989393 -0.05942589 0.01809203 0.009107172 -0.05928039 0.01775705 0.009463667 -0.05927503 0.01744818 0.00943309 -0.05939793 0.0173496 0.009687662 -0.05925142 0.01677 0.009564995 -0.05936676 0.01682591 0.00977534 -0.0592246 0.01622712 0.009646892 -0.05920559 0.01631355 0.009444415 -0.05934607 0.01570045 0.00923717 -0.05919027 0.01577001 0.009004414 -0.05931586 0.0154066 0.008650243 -0.05915778 0.01557111 0.008263528 -0.05928146 0.01538425 0.008071064 -0.05913698 0.0158019 0.007526814 -0.0592482 0.01559495 0.007480323 -0.05911123 0.01604032 0.007047176 -0.05908924 0.01641315 0.00708872 -0.05921465 0.01661437 0.006817221 -0.0590679 0.01710408 0.007022023 -0.0591849 0.01723533 0.006853103 -0.05903983 0.01773846 0.007100045 -0.0590223 0.01769852 0.007336914 -0.05915504 0.01818567 0.007613301 -0.05901753 0.01798802 0.007706463 -0.05913454 0.01813083 0.008276283 -0.05910819 0.01832336 0.008495271 -0.05898463 0.01797622 0.008908629 -0.05908012 0.01815259 0.009018421 -0.05893862 0.01738595 0.009468376 -0.05904406 0.01776683 0.009454369 -0.05891841 0.01727712 0.009714007 -0.05889797 0.01666742 0.009553551 -0.05901241 0.0167616 0.009770214 -0.05888432 0.01632815 0.009681403 -0.05886262 0.01597464 0.009246289 -0.05897873 0.01594543 0.009464204 -0.05884003 0.01554167 0.009007871 -0.05881774 0.01562982 0.008649587 -0.05894881 0.01538497 0.00850892 -0.05880767 0.01558005 0.008134543 -0.05892652 0.01540875 0.007901847 -0.05877655 0.01579278 0.007594883 -0.05894052 0.01565641 0.007402122 -0.05876034 0.01606053 0.007282197 -0.05888271 0.01611864 0.006991803 -0.05873608 0.01658904 0.007036447 -0.05885708 0.01652342 0.006840348 -0.05872559 0.01703369 0.006817638 -0.05870026 0.01711249 0.007043123 -0.05883383 0.01755475 0.006980836 -0.05868095 0.0175907 0.007243096 -0.058811 0.01799464 0.007336795 -0.05865448 0.01793754 0.007625102 -0.05878835 0.01825815 0.007823944 -0.05863916 0.01814359 0.008255362 -0.05875909 0.01833719 0.008402645 -0.05861318 0.01819032 0.00893253 -0.05859363 0.01786684 0.009089767 -0.05872166 0.01788586 0.009358704 -0.05857568 0.01747268 0.009642362 -0.05856227 0.01721149 0.009520828 -0.05868649 0.01691401 0.009770572 -0.0585345 0.01653224 0.009530484 -0.05865633 0.01634854 0.009689033 -0.05851584 0.01611089 0.009313941 -0.05867344 0.01586252 0.009402155 -0.05848735 0.01570582 0.00886023 -0.05860888 0.01551175 0.008926331 -0.05847024 0.01535385 0.00827986 -0.05845063 0.01558595 0.008271098 -0.05861848 0.01565933 0.007840454 -0.05856275 0.01549506 0.007677316 -0.05842125 0.01598727 0.007333934 -0.0585367 0.01603597 0.007032454 -0.05839121 0.01651179 0.007061719 -0.0585103 0.01664441 0.00681883 -0.05836522 0.01704233 0.007023513 -0.05848705 0.01729303 0.00685817 -0.05833876 0.01760178 0.00701636 -0.05834937 0.01768922 0.007308006 -0.05845677 0.01796102 0.007303118 -0.05831032 0.01806443 0.007887125 -0.0584256 0.01821523 0.007706105 -0.05828893 0.01833939 0.008243203 -0.05827236 0.01812285 0.008385717 -0.05840361 0.0182082 0.008897364 -0.05824196 0.01798826 0.008863985 -0.05838197 0.01786887 0.009378015 -0.05822706 0.01766538 0.009278893 -0.05835902 0.01736193 0.009680926 -0.05820178 0.01701891 0.009564161 -0.05832767 0.01682502 0.009774565 -0.05818253 0.01643311 0.009494423 -0.05830186 0.0164079 0.009703159 -0.05816209 0.01603049 0.009525597 -0.05814933 0.01593774 0.009189009 -0.05827605 0.01563584 0.009144246 -0.05813062 0.0156368 0.008689105 -0.05825078 0.01539391 0.008606135 -0.05810344 0.01558572 0.008082985 -0.05822414 0.01538151 0.008162736 -0.05811202 0.01553446 0.007609546 -0.05809062 0.01580154 0.007561504 -0.05819934 0.01598697 0.007080435 -0.05806344 0.01620256 0.007185459 -0.05817466 0.01662206 0.006823778 -0.05802381 0.01695114 0.006996333 -0.05814141 0.01714116 0.006827414 -0.05799412 0.0176444 0.0072878 -0.05810785 0.01768136 0.007061898 -0.05797344 0.01798611 0.00733906 -0.05796194 0.01804989 0.00781542 -0.05807924 0.01824605 0.00775963 -0.05793708 0.01833027 0.008390426 -0.0579167 0.01809018 0.008657336 -0.05804222 0.01815235 0.009028255 -0.05789667 0.01773661 0.009204745 -0.05801284 0.01773655 0.009483814 -0.05786776 0.01726269 0.009502768 -0.05798906 0.01732707 0.009695291 -0.0578466 0.01682925 0.009774625 -0.05783402 0.01674115 0.009559094 -0.05796527 0.01639795 0.009700477 -0.05781245 0.01608026 0.00933057 -0.05793547 0.01588213 0.009420454 -0.05779242 0.01554143 0.008987128 -0.05777746 0.01558929 0.008574426 -0.05789637 0.01539057 0.008570969 -0.05775576 0.01545858 0.007739901 -0.05772423 0.01566094 0.007809638 -0.05786138 0.0157842 0.007255733 -0.05770266 0.01600766 0.007332623 -0.05783575 0.01618069 0.006964087 -0.05768769 0.01643604 0.007096946 -0.05785292 0.01671534 0.00680679 -0.05766534 0.01689189 0.007014214 -0.05779314 0.01728934 0.0068717 -0.0576412 0.01737296 0.007126212 -0.05777209 0.0176559 0.007045924 -0.05762624 0.01778101 0.007410287 -0.05775028 0.01798075 0.007318794 -0.05760943 0.01811194 0.008026838 -0.05771982 0.01825398 0.007803261 -0.05758869 0.01833349 0.008256971 -0.05756455 0.01800912 0.008868157 -0.05768251 0.01827222 0.008723914 -0.05755597 0.01801192 0.009211301 -0.05753219 0.01745712 0.00941956 -0.0576477 0.01754623 0.009608805 -0.0575031 0.0172131 0.009721338 -0.05751818 0.01693803 0.009559392 -0.0576241 0.01679092 0.009775221 -0.05748021 0.01633781 0.009469807 -0.05759793 0.01599121 0.009515464 -0.05745005 0.0158751 0.009107649 -0.0575717 0.01556473 0.009030878 -0.05742412 0.01562011 0.008639693 -0.05754828 0.01539975 0.008595228 -0.057415 0.01558434 0.008137345 -0.05752629 0.01537638 0.008071959 -0.05738055 0.01576477 0.007612586 -0.05750209 0.01558893 0.007509052 -0.05736458 0.01597088 0.0070858 -0.05734008 0.01632195 0.007106542 -0.05746877 0.01625865 0.006935536 -0.05735206 0.01666396 0.006813526 -0.05731439 0.0171867 0.007043302 -0.0574311 0.01749789 0.006939232 -0.05728387 0.01771897 0.007357597 -0.0574035 0.01799649 0.007344841 -0.05725836 0.01802933 0.007789731 -0.05738025 0.0183019 0.007918417 -0.0572319 0.01832836 0.008264482 -0.05724251 0.01812583 0.00828427 -0.05735814 0.01827162 0.008720397 -0.05720347 0.01803141 0.008771061 -0.05733609 0.0180307 0.00919342 -0.05717658 0.01761978 0.009332239 -0.05730628 0.01757109 0.009598076 -0.05715763 0.01696866 0.009772658 -0.05713766 0.01695644 0.009559154 -0.05727517 0.01640462 0.009714961 -0.05711609 0.01643395 0.009501278 -0.05725222 0.01587706 0.009409844 -0.0570926 0.0158109 0.009056985 -0.05721831 0.01548075 0.008894145 -0.0570662 0.01535803 0.008368909 -0.0570507 0.01556932 0.008333921 -0.05718499 0.01551127 0.007633864 -0.05702126 0.01570814 0.007712483 -0.05715674 0.0159021 0.007142961 -0.05699306 0.01606035 0.007284879 -0.05713254 0.01639014 0.006877183 -0.05697554 0.01675677 0.006996095 -0.05709975 0.01697319 0.00680083 -0.05695581 0.01752978 0.007201194 -0.05706411 0.01756513 0.006989777 -0.05692917 0.01797008 0.00731498 -0.05691528 0.01799404 0.007702529 -0.05703461 0.01823347 0.007730305 -0.0568906 0.01812362 0.008264899 -0.05700856 0.01833224 0.00824958 -0.05686897 0.01800197 0.008872449 -0.05698204 0.01824504 0.008811354 -0.05685091 0.01796764 0.009265184 -0.05682152 0.01762974 0.009555637 -0.05681329 0.01747852 0.009406864 -0.05694913 0.0171222 0.009755671 -0.05679351 0.01687163 0.009553015 -0.05696105 0.01659345 0.009755671 -0.05677187 0.0164209 0.009492218 -0.05690091 0.01600974 0.009523928 -0.05674874 0.01597392 0.009216666 -0.0568785 0.01562833 0.009154498 -0.05673116 0.01567 0.008783459 -0.0568546 0.01538985 0.008555293 -0.05670434 0.01557695 0.008238852 -0.05683094 0.01538175 0.008084237 -0.05670952 0.0156784 0.00778073 -0.05681025 0.01565665 0.007395803 -0.05665796 0.01604437 0.007292568 -0.05678355 0.01605892 0.007030844 -0.05666118 0.01663637 0.007024347 -0.05675458 0.01671653 0.006810188 -0.05661869 0.0174238 0.007127821 -0.05672055 0.01726531 0.006862998 -0.05658823 0.01782602 0.007161557 -0.05656516 0.01794546 0.00763005 -0.05668765 0.01816487 0.0075953 -0.05654567 0.01833719 0.008150696 -0.05652993 0.01811492 0.008125185 -0.0566653 0.01808655 0.008621573 -0.05664348 0.018251 0.008786737 -0.05650007 0.01784408 0.009085536 -0.05662024 0.01797467 0.009256064 -0.05648064 0.01744961 0.009421765 -0.05659741 0.01756781 0.009590685 -0.05645662 0.01714301 0.009750545 -0.0564444 0.01695215 0.009558558 -0.05657476 0.01644575 0.009722948 -0.05642491 0.01629686 0.009457647 -0.05654543 0.01590001 0.009438395 -0.05639439 0.01581418 0.009028494 -0.0565173 0.0155524 0.009014606 -0.05637329 0.01557624 0.008470237 -0.05649113 0.01538538 0.008539795 -0.05634677 0.01539021 0.008019506 -0.05633556 0.01564258 0.00788635 -0.05646491 0.01558238 0.00752151 -0.05631488 0.01590782 0.007424116 -0.05644148 0.0158711 0.007177829 -0.05630272 0.01650339 0.007045865 -0.05641126 0.01626539 0.006918549 -0.05627363 0.01685637 0.006805598 -0.05625772 0.01719653 0.007058501 -0.05638003 0.01729208 0.006873726 -0.05624204 0.01770836 0.007072925 -0.05622559 0.01761627 0.007270097 -0.05635946 0.01798176 0.007688999 -0.05633533 0.01810365 0.007496535 -0.05620288 0.01832526 0.008048415 -0.05617761 0.01813691 0.0083673 -0.05630499 0.018283 0.00867325 -0.05615502 0.01789331 0.009031772 -0.05627346 0.01802718 0.009200692 -0.05613106 0.01752245 0.00937283 -0.05625128 0.01769244 0.009509563 -0.05611276 0.01732486 0.009696483 -0.05610013 0.01700103 0.009560048 -0.05622678 0.01677489 0.009775221 -0.0560826 0.01650917 0.009504914 -0.05624365 0.01621991 0.009635448 -0.05606371 0.01590543 0.009167432 -0.05617535 0.01563555 0.009145975 -0.05605161 0.01559621 0.008539974 -0.05614411 0.01540988 0.00868684 -0.05600798 0.01538079 0.008078813 -0.05598682 0.0156244 0.00792098 -0.05611652 0.01555514 0.007555842 -0.05596667 0.01588588 0.007453322 -0.05609333 0.01594203 0.007105648 -0.05594462 0.01629757 0.007138252 -0.05606997 0.01651322 0.006836652 -0.05592173 0.01675933 0.00703001 -0.05608791 0.01725447 0.006862819 -0.05591356 0.01726448 0.007081806 -0.05602699 0.01786923 0.007487416 -0.05599546 0.01790791 0.007243514 -0.05588585 0.01821732 0.007690191 -0.05584156 0.01812386 0.008180201 -0.05596226 0.01833993 0.008339822 -0.05580985 0.01798754 0.008913218 -0.05592954 0.01817178 0.008982658 -0.0557934 0.01781648 0.009420692 -0.05576699 0.01758992 0.009570658 -0.05578398 0.01741498 0.00943768 -0.0558961 0.01716822 0.009742975 -0.05573946 0.01670241 0.009572625 -0.05586451 0.01663291 0.009756684 -0.05572944 0.01620841 0.009630322 -0.05570781 0.01608407 0.009307622 -0.05583465 0.01558178 0.009083807 -0.05567669 0.01576524 0.008963048 -0.05581408 0.01539248 0.008560717 -0.0556572 0.0155937 0.008493721 -0.05579155 0.01538884 0.008019089 -0.0556358 0.01562535 0.007893145 -0.05576533 0.01558589 0.007507026 -0.0556187 0.01607334 0.007262945 -0.05573207 0.01597255 0.007093071 -0.05559313 0.01639717 0.006876289 -0.05557137 0.01667004 0.007024049 -0.05570346 0.01685518 0.006802737 -0.05555462 0.01727771 0.007080376 -0.05567675 0.0173825 0.006906509 -0.05554068 0.01776081 0.007117033 -0.05552124 0.01781612 0.007444322 -0.05564779 0.0180723 0.007442116 -0.05550366 0.01812648 0.008111059 -0.05561619 0.01829147 0.007926702 -0.05548077 0.0183109 0.008529841 -0.05548322 0.01801592 0.008826017 -0.05558347 0.01808458 0.009107232 -0.05545961 0.01748943 0.009413659 -0.0555526 0.0176984 0.009493708 -0.05543738 0.01679915 0.009564757 -0.05551779 0.01629632 0.009438514 -0.05549526 0.01589608 0.009139835 -0.05547243 0.01662129 0.009548962 -0.06118285 0.01612836 0.009347558 -0.06117218 0.0157057 0.008871376 -0.06113392 0.01557207 0.008225977 -0.06110477 0.01581728 0.007511794 -0.06106877 0.01635205 0.007117509 -0.06104212 0.01704072 0.007003784 -0.06101197 0.01779818 0.00741893 -0.06097328 0.0180791 0.007945895 -0.06094712 0.01810824 0.008545339 -0.06092077 0.01786166 0.009068965 -0.0608952 0.01709598 0.009543776 -0.06085515 0.01639282 0.009498298 -0.0608235 0.01577252 0.008989691 -0.06078881 0.01558452 0.008424162 -0.06076312 0.01566797 0.007760047 -0.06073337 0.01612609 0.007241189 -0.06070363 0.01668679 0.007010281 -0.06067633 0.01739913 0.007131874 -0.06064534 0.01784473 0.00748533 -0.06061923 0.01814067 0.008169949 -0.06058675 0.01798689 0.008872747 -0.06055593 0.01761448 0.009315371 -0.06053012 0.01705694 0.009554803 -0.06050336 0.01645165 0.009501874 -0.06047719 0.01591831 0.009176135 -0.06044846 0.01558542 0.008509695 -0.06041651 0.01563245 0.007905423 -0.06039035 0.01594352 0.007383882 -0.06036323 0.01703566 0.007011651 -0.06031119 0.01767885 0.007313549 -0.06028014 0.01808327 0.007907748 -0.06024926 0.01808482 0.008634448 -0.06021672 0.01779079 0.009155631 -0.06019037 0.0167427 0.00957942 -0.060139 0.01602989 0.009272992 -0.06010568 0.0156756 0.008792638 -0.06007981 0.01557224 0.008095979 -0.0600478 0.01592481 0.007399201 -0.06001472 0.01645952 0.007073879 -0.05998659 0.01695317 0.00701642 -0.05996489 0.01749408 0.007180869 -0.05994015 0.01792448 0.007595002 -0.05991417 0.01814359 0.008263826 -0.05988222 0.01790261 0.009028792 -0.05984765 0.01744765 0.009414076 -0.0598219 0.01680088 0.009583771 -0.05979216 0.01600044 0.009258568 -0.05975478 0.01558077 0.008531987 -0.0597167 0.01568931 0.007737219 -0.05968201 0.01625955 0.007136404 -0.05964553 0.01696938 0.007017433 -0.05961471 0.01754409 0.007210969 -0.05958759 0.01803946 0.007779955 -0.05955374 0.01809865 0.008611559 -0.05951762 0.01762759 0.009325683 -0.05947995 0.01694834 0.009562611 -0.05944913 0.01634889 0.009468436 -0.05942201 0.01578408 0.009014546 -0.05938977 0.01556921 0.008316814 -0.05935794 0.01567351 0.007804453 -0.05933529 0.01603734 0.007287681 -0.05930805 0.01659595 0.007041573 -0.05928081 0.01708972 0.007034718 -0.05925905 0.01771646 0.007327556 -0.05922871 0.01810592 0.008017718 -0.05919313 0.01803874 0.008800566 -0.05915856 0.01756799 0.009348571 -0.05912786 0.01708674 0.009540259 -0.05910509 0.0163908 0.009504318 -0.05907505 0.01569485 0.008872568 -0.0590322 0.01558268 0.008104801 -0.05899888 0.01626861 0.00714457 -0.05894553 0.01685512 0.007012546 -0.05891925 0.01749944 0.00717175 -0.0588895 0.01804536 0.007802784 -0.05885332 0.01811641 0.008430063 -0.05882638 0.01789355 0.009058296 -0.05879646 0.01719903 0.009527385 -0.05875962 0.01660209 0.009539961 -0.05873346 0.01569527 0.008874118 -0.05868279 0.01574277 0.00763607 -0.05862706 0.01617729 0.007207691 -0.05860072 0.01671284 0.007010638 -0.05857521 0.01752328 0.007181882 -0.05853873 0.01799631 0.007724285 -0.05850791 0.01813012 0.008286774 -0.05848205 0.01799017 0.008877515 -0.05845528 0.01760947 0.009313583 -0.05843043 0.01714748 0.009534835 -0.05840682 0.01660639 0.009538829 -0.05838394 0.01604384 0.009295582 -0.05835729 0.01567733 0.00878328 -0.0583294 0.01556551 0.008122742 -0.05829972 0.01595717 0.007361352 -0.05826205 0.01656049 0.007042944 -0.05823212 0.01727807 0.007071733 -0.05820125 0.01786333 0.007503688 -0.0581687 0.01814132 0.008209407 -0.05813533 0.01790696 0.009031116 -0.0580976 0.01734703 0.009468495 -0.05806654 0.01663422 0.009560883 -0.05803561 0.01608139 0.009303629 -0.05800843 0.01570284 0.0088647 -0.0579828 0.01557248 0.008094191 -0.05794841 0.01594138 0.007379472 -0.05791252 0.01693236 0.007013142 -0.05786615 0.01760071 0.007235705 -0.0578342 0.018063 0.007864952 -0.05780106 0.01809382 0.008636355 -0.0577659 0.01776874 0.009173274 -0.05773913 0.01731497 0.009482026 -0.05771571 0.01665765 0.009560525 -0.05768585 0.01612269 0.009332418 -0.05766075 0.01572656 0.008919298 -0.05763524 0.01557755 0.008313357 -0.05760824 0.01571834 0.007659673 -0.0575785 0.01621997 0.007182061 -0.05754882 0.01679831 0.007000982 -0.05752152 0.01741945 0.0071491 -0.05749392 0.0178678 0.007502198 -0.05746835 0.01810169 0.00805056 -0.05744272 0.01808553 0.008662462 -0.05741608 0.0177465 0.009194135 -0.05738818 0.01717561 0.009543597 -0.0573585 0.01648426 0.009509086 -0.05732876 0.01598203 0.00923717 -0.05730235 0.01557505 0.008513808 -0.05726635 0.01567053 0.007800877 -0.05723547 0.01602542 0.007308542 -0.05720841 0.01648807 0.007067263 -0.05718553 0.01714605 0.007032454 -0.05715638 0.01776051 0.007389366 -0.05712527 0.0181117 0.008015811 -0.05709445 0.01805007 0.008740544 -0.05706191 0.01755326 0.009382128 -0.05702698 0.01619225 0.009398698 -0.05696368 0.01571023 0.008868515 -0.05693364 0.01556843 0.008280813 -0.05690646 0.01574689 0.007638156 -0.05687725 0.01610094 0.007258176 -0.05685484 0.01659464 0.00703603 -0.05683034 0.01711612 0.0070405 -0.05680763 0.01761049 0.007260084 -0.05678409 0.01803517 0.007784128 -0.05675476 0.018121 0.008374094 -0.05672848 0.01799082 0.008871614 -0.05670553 0.01757478 0.009348511 -0.05667769 0.01679986 0.009584367 -0.05664223 0.01615321 0.009354531 -0.05661273 0.01569348 0.008871853 -0.0565828 0.01558834 0.008042335 -0.05654668 0.01584613 0.00750339 -0.05651962 0.01631313 0.007123827 -0.05649358 0.01699382 0.007012188 -0.05646359 0.01765865 0.007290422 -0.05643153 0.01799458 0.007728219 -0.05640739 0.0181387 0.008348464 -0.05637985 0.01785469 0.009097158 -0.05634313 0.01717913 0.009536564 -0.05630928 0.01595205 0.009222686 -0.0562517 0.0155732 0.008454263 -0.05621403 0.01567703 0.007779955 -0.05618405 0.01612699 0.007221043 -0.05615323 0.01725411 0.007072448 -0.05610162 0.01770186 0.007340312 -0.05607873 0.018076 0.007882654 -0.05604958 0.01809364 0.008593082 -0.05601847 0.01776146 0.009198844 -0.05598878 0.01723563 0.009504795 -0.0559616 0.01657384 0.009549021 -0.05593234 0.01585263 0.009111285 -0.0558952 0.01556062 0.008308947 -0.05585688 0.01575994 0.007620751 -0.05582684 0.01628524 0.007125914 -0.055794 0.01718151 0.007035851 -0.05575579 0.01784473 0.00747931 -0.05571955 0.01813501 0.008161544 -0.05568701 0.01793658 0.008991837 -0.05565053 0.01744323 0.009415924 -0.05562168 0.0169512 0.009565412 -0.05559873 0.0163272 0.009460568 -0.05557084 0.01585888 0.00909239 -0.05554491 0.01558125 0.008516669 -0.05551701 0.01566475 0.007806181 -0.05548536 0.01566344 0.008962571 -0.06118404 0.01578849 0.007262229 -0.06118142 0.01541358 0.008093357 -0.06118363 0.01621091 0.006955981 -0.06117159 0.01682132 0.006807386 -0.06113624 0.01737684 0.006910502 -0.06111526 0.01773959 0.009468555 -0.06099635 0.01656407 0.006838023 -0.06079632 0.01770645 0.007072865 -0.06075114 0.01642316 0.009707629 -0.06024408 0.01592063 0.009433507 -0.06022268 0.01550996 0.008932173 -0.06019771 0.01697349 0.006807088 -0.06008076 0.0157907 0.009331881 -0.05986666 0.01553076 0.00896269 -0.0594992 0.01817846 0.007619261 -0.05897384 0.01832985 0.008311212 -0.05894708 0.01575422 0.007296383 -0.05838209 0.01543927 0.00783497 -0.05805563 0.01578104 0.007264137 -0.0580303 0.01625359 0.006940722 -0.0580089 0.01538062 0.008147299 -0.05771809 0.01634085 0.009677648 -0.05744099 0.01708894 0.006831884 -0.05727654 0.01543724 0.007826983 -0.05665516 0.01626545 0.006926953 -0.05660873 0.01580625 0.009336411 -0.05601656 0.01699358 0.006808757 -0.05588036 0.01771116 0.007079124 -0.05585068 0.01583421 0.009364366 -0.05566883 0.01679825 0.006801009 -0.0611841 0.01785659 0.009191155 -0.05521482 0.0180819 0.008635044 -0.05518513 0.0181626 0.00865966 -0.05521446 0.01803046 0.009107947 -0.05529779 0.01821279 0.008833169 -0.05535304 0.01827883 0.008497774 -0.05530816 0.0182777 0.008124709 -0.05529087 0.01813471 0.008001983 -0.05519747 0.01798784 0.007671833 -0.05518805 0.01821839 0.007813036 -0.05531477 0.01807481 0.00751692 -0.05531096 0.0177738 0.007274091 -0.05522215 0.0171979 0.007027924 -0.05518949 0.01788192 0.00722897 -0.05542808 0.01771879 0.007124483 -0.05533081 0.01731717 0.006920456 -0.05530273 0.01739484 0.006906688 -0.05542975 0.01669335 0.007001101 -0.05518835 0.01689934 0.006847798 -0.05529922 0.01649969 0.006911575 -0.05527406 0.01661401 0.006824612 -0.05543261 0.01581436 0.007511615 -0.05518805 0.0162326 0.007119178 -0.05520218 0.01624161 0.006941199 -0.05542594 0.01603072 0.007096052 -0.055305 0.01590102 0.007259249 -0.05524927 0.01556313 0.008113205 -0.05518549 0.01576703 0.007279932 -0.05542767 0.01556313 0.007626473 -0.05531108 0.01555013 0.007818996 -0.05523711 0.01552158 0.008312761 -0.05520248 0.01541715 0.008060872 -0.05531191 0.01537317 0.008211195 -0.05542379 0.0154497 0.008598566 -0.05528706 0.01539826 0.00856316 -0.05543369 0.0156883 0.00887829 -0.05519074 0.01550972 0.008841693 -0.05531144 0.01580911 0.009194672 -0.05523663 0.01571643 0.009205818 -0.05533814 0.01610636 0.009367465 -0.05519288 0.01598739 0.00945568 -0.05532157 0.01686167 0.009584903 -0.05518817 0.01620644 0.009548902 -0.05526697 0.01653373 0.00964117 -0.05523943 0.01672756 0.009733498 -0.05531483 0.01741057 0.009450674 -0.05518567 0.01714003 0.009663879 -0.05525809 0.01753664 0.009523093 -0.0552572 0.01758939 0.009542047 -0.05533587 0.01783871 0.009363412 -0.05534136 0.01492804 0.006392598 -0.0613808 0.01485532 0.00656861 -0.06124967 0.01514244 0.006218254 -0.06131654 0.01523095 0.006332576 -0.06119179 0.01555866 0.005920529 -0.06136506 0.01567536 0.00601083 -0.06119877 0.01586854 0.005781948 -0.06134402 0.01632565 0.00563848 -0.06139665 0.01625263 0.005719184 -0.06125819 0.01661223 0.005773067 -0.06118863 0.01669239 0.005669951 -0.06124645 0.0168116 0.005591154 -0.06136029 0.01722848 0.005630016 -0.0613268 0.01741015 0.005795598 -0.06119436 0.0176053 0.005702257 -0.06135636 0.01802951 0.00586903 -0.06133079 0.01807701 0.00606966 -0.06118971 0.01828044 0.006005525 -0.06135058 0.01842415 0.006203532 -0.06123536 0.01867598 0.006303429 -0.06135904 0.0189687 0.006697595 -0.06125801 0.01910418 0.00680685 -0.06134366 0.01886343 0.006753742 -0.06119114 0.01934361 0.00728017 -0.06133252 0.01924669 0.007471203 -0.06118786 0.01951944 0.007836222 -0.06138557 0.0194559 0.00781089 -0.06126773 0.01947379 0.008316695 -0.06123852 0.01954549 0.008476972 -0.06138712 0.01946091 0.008936405 -0.06133258 0.01935744 0.008763074 -0.06119525 0.01932841 0.009347081 -0.06135374 0.01915097 0.009571135 -0.06124693 0.0189985 0.009617626 -0.06118595 0.01913714 0.009718239 -0.06136524 0.01880097 0.01015532 -0.06135445 0.01853275 0.01029425 -0.06123107 0.01836633 0.01051634 -0.06135034 0.01787537 0.01061308 -0.0611909 0.01797622 0.01073068 -0.06132471 0.01759701 0.01088815 -0.06138998 0.01727181 0.01094228 -0.06132203 0.01714462 0.01081001 -0.06119126 0.01672637 0.01098632 -0.06137686 0.01668518 0.01092553 -0.06125664 0.01638698 0.01078712 -0.06119167 0.01622402 0.01090276 -0.06132924 0.01582771 0.01078432 -0.06134754 0.01582568 0.0106737 -0.0612238 0.01543688 0.01059019 -0.06138157 0.01537901 0.01047247 -0.06125509 0.01526159 0.01025688 -0.06118905 0.01501893 0.01026839 -0.06135839 0.01490616 0.01004314 -0.06123799 0.01470935 0.009925365 -0.06135839 0.01449918 0.009256184 -0.06118762 0.01447206 0.009542703 -0.06132417 0.01424169 0.008967638 -0.06135058 0.01432937 0.008994221 -0.06123828 0.01416283 0.008502721 -0.06136232 0.01423263 0.008358776 -0.06124013 0.01416504 0.008006572 -0.06136792 0.01435005 0.007902145 -0.06118917 0.01426243 0.00781244 -0.06125384 0.01433324 0.00730139 -0.0613628 0.01443541 0.007170557 -0.06128269 0.01457059 0.007162511 -0.06119114 0.01463311 0.006752192 -0.06137692 0.01529246 0.006087124 -0.06399554 0.01567369 0.005859553 -0.06399434 0.01610708 0.005696058 -0.06399494 0.01646894 0.005628585 -0.06403994 0.0173195 0.005626678 -0.06398445 0.0181483 0.005919277 -0.06397473 0.01891732 0.006545901 -0.06398439 0.01954573 0.008483946 -0.06397593 0.0194897 0.008792281 -0.06404399 0.01936811 0.009264409 -0.06399387 0.01877659 0.01018267 -0.06398415 0.01842159 0.01047086 -0.06403869 0.01802957 0.0107187 -0.06398808 0.01689589 0.01098805 -0.0640099 0.01639574 0.01094806 -0.06399494 0.01594465 0.01083385 -0.06398051 0.01468896 0.009911656 -0.06398856 0.01416873 0.008635818 -0.06399822 0.01417672 0.007948577 -0.06401604 0.01430785 0.007384479 -0.06401157 0.01459133 0.006811797 -0.06399494 0.01472741 0.00669825 -0.06410115 0.01471269 0.006882071 -0.06416863 0.01440769 0.007260024 -0.06409889 0.0143429 0.007817327 -0.06417524 0.01422601 0.008324265 -0.06412488 0.01439297 0.008898019 -0.06417775 0.01429384 0.008880734 -0.0641219 0.01435554 0.009319186 -0.06400704 0.01449054 0.009471416 -0.0641095 0.0146988 0.009642601 -0.06417793 0.01488763 0.01005214 -0.06411546 0.01506322 0.01030349 -0.06401836 0.01496458 0.009951293 -0.06418204 0.01547122 0.01060074 -0.06403428 0.01561051 0.01055377 -0.06415796 0.01647657 0.01078581 -0.06418329 0.01620179 0.01085573 -0.06410491 0.01705867 0.01091194 -0.06411838 0.01737898 0.01079535 -0.06416493 0.0175054 0.01090812 -0.06399494 0.01775479 0.01078253 -0.06409543 0.01812922 0.01049786 -0.06417399 0.01880735 0.01003736 -0.06412619 0.01895672 0.009713947 -0.06417798 0.01911556 0.009744763 -0.06403481 0.01936894 0.009056389 -0.06412088 0.01937967 0.008545815 -0.06417709 0.01953297 0.008178532 -0.06404733 0.01946848 0.007676005 -0.06404465 0.01933914 0.007814407 -0.06417787 0.01924961 0.007286965 -0.06414449 0.01927655 0.007100939 -0.0639981 0.01908689 0.006890058 -0.06411021 0.01879084 0.006686925 -0.06418097 0.01884931 0.006562769 -0.06410789 0.01849263 0.006334722 -0.06417548 0.01849919 0.006159722 -0.06402224 0.01809036 0.005969285 -0.06411862 0.01772379 0.005749344 -0.06404465 0.01749759 0.005838751 -0.06418102 0.01720446 0.005703747 -0.0641368 0.01689159 0.005598366 -0.06402283 0.01670253 0.005719482 -0.06415712 0.0161271 0.005852937 -0.06417524 0.01581484 0.005863308 -0.06411415 0.01521325 0.006240606 -0.06412696 0.0153138 0.006308555 -0.06418257 0.014961 0.006361424 -0.06400185 0.00496298 0.0095281 -0.06249183 0.003592967 0.009406507 -0.06250435 0.005015492 0.009656012 -0.06260067 0.003532946 0.009486556 -0.06264227 0.003044009 0.008120119 -0.06250452 0.002943694 0.008109748 -0.06264203 0.003901481 0.007049798 -0.06249094 0.003845691 0.006920456 -0.06259959 0.005239725 0.00720638 -0.06249225 0.005322992 0.007097125 -0.06260067 0.005817651 0.008452892 -0.06250393 0.005918622 0.008466482 -0.06264287 0.005349218 0.007058978 -0.06417292 0.005954504 0.008470654 -0.0641731 0.003826141 0.006877899 -0.06417292 0.002907514 0.008106768 -0.06417292 0.003511846 0.009514749 -0.0641725 0.005032479 0.009699046 -0.06417292 0.003152251 0.008123457 -0.05543452 0.003252565 0.008798778 -0.05544459 0.003132283 0.009001553 -0.05543404 0.003068387 0.00771743 -0.05543261 0.003783345 0.009535789 -0.0554344 0.003480076 0.007435858 -0.05544638 0.003524422 0.009453594 -0.05543416 0.003280162 0.007365167 -0.05543404 0.004099905 0.009734809 -0.05542671 0.003872692 0.007142603 -0.05543756 0.004514992 0.009764313 -0.05542016 0.004444181 0.006973326 -0.05543506 0.005038082 0.009637415 -0.05543041 0.004763841 0.006852567 -0.05543404 0.005170166 0.007144153 -0.05543404 0.005206286 0.007026791 -0.05543404 0.005800187 0.007730066 -0.05544197 0.005909919 0.008359432 -0.05543774 0.004480302 0.006801068 -0.06117224 0.005043447 0.006935238 -0.06113725 0.0055027 0.007257401 -0.06111109 0.005199015 0.007099807 -0.06118416 0.005837082 0.007793009 -0.06109333 0.00559169 0.008830904 -0.06118452 0.005614638 0.007585585 -0.06118422 0.005916714 0.00842303 -0.06106483 0.005750596 0.008207738 -0.0611841 0.005792856 0.008912801 -0.06104409 0.005283117 0.009232521 -0.06117451 0.005392253 0.009419977 -0.06102162 0.004879236 0.009477913 -0.06116676 0.004740893 0.009742379 -0.06101614 0.004222214 0.009560763 -0.06111156 0.003976345 0.009703814 -0.06096827 0.003583252 0.009247601 -0.06108039 0.003481388 0.009429633 -0.06094807 0.003172814 0.009073734 -0.06091755 0.003282785 0.008838653 -0.06105774 0.002993047 0.008665561 -0.06090927 0.003142476 0.008208632 -0.06102925 0.002949237 0.008120775 -0.0608896 0.003103196 0.007613837 -0.06086897 0.003347516 0.007618546 -0.06100195 0.003417789 0.007207512 -0.06085455 0.003772795 0.007181942 -0.06097573 0.003898799 0.006894469 -0.06082206 0.004437983 0.006799876 -0.06080955 0.004391312 0.007011055 -0.0609467 0.005039215 0.007153213 -0.06091839 0.005067288 0.006942331 -0.06078392 0.005517601 0.007273375 -0.06075757 0.005470633 0.007552206 -0.0608921 0.005786836 0.007677793 -0.06074351 0.005686342 0.008039534 -0.06086868 0.005903482 0.008105397 -0.0607348 0.005680739 0.008543074 -0.06084674 0.005880355 0.008623361 -0.06070792 0.005442082 0.009076237 -0.06082135 0.005652844 0.009129643 -0.06068843 0.005387008 0.009424209 -0.06066787 0.004986047 0.00943911 -0.06079518 0.004951834 0.009679138 -0.06065517 0.004392623 0.009569108 -0.06076896 0.004468262 0.009772479 -0.06063389 0.003760576 0.009615421 -0.06062841 0.00367403 0.009335279 -0.06073606 0.003194689 0.009113609 -0.0605778 0.003222823 0.008716464 -0.06070184 0.002975702 0.008612215 -0.06055819 0.00315994 0.008188009 -0.06067854 0.002955794 0.008082211 -0.06053572 0.003134369 0.00755918 -0.06051713 0.003306269 0.007682383 -0.06065559 0.003525197 0.007095336 -0.06049269 0.003778576 0.007172167 -0.06062465 0.004020452 0.006852328 -0.06047654 0.004660069 0.00701183 -0.06058579 0.004645645 0.006819844 -0.06045693 0.00510329 0.006957113 -0.06042599 0.005291163 0.007345914 -0.06055378 0.005579054 0.007349491 -0.06040853 0.00568211 0.007946729 -0.06052297 0.005815982 0.007757186 -0.06039106 0.005914807 0.008214116 -0.06037127 0.005634486 0.008723139 -0.0604884 0.005837678 0.008757054 -0.0603525 0.005506813 0.009328663 -0.06032586 0.005317866 0.009210884 -0.06046324 0.004761695 0.009526491 -0.06043517 0.004947006 0.009678602 -0.06030166 0.004413962 0.009774446 -0.06028604 0.004256069 0.009549677 -0.06041288 0.00392127 0.009681165 -0.06025505 0.003763139 0.009382724 -0.06038963 0.003531336 0.009471416 -0.06024634 0.00313127 0.009023904 -0.0602355 0.003232419 0.008782386 -0.060355 0.002953886 0.008476912 -0.06020057 0.003179192 0.008032262 -0.0603215 0.003000795 0.007860958 -0.06017655 0.003484129 0.007408738 -0.0602917 0.00330156 0.00732398 -0.06015133 0.003672838 0.007014393 -0.06013834 0.004063665 0.007067084 -0.06026184 0.004191935 0.006819903 -0.06011909 0.004557967 0.007014632 -0.06024014 0.004620432 0.006819188 -0.06009733 0.00502789 0.00693053 -0.06008404 0.005035877 0.007168889 -0.06021749 0.00549972 0.007253527 -0.06006169 0.005439281 0.007494866 -0.06019538 0.005798757 0.007705271 -0.06004148 0.005666613 0.007979512 -0.06017112 0.005913317 0.008235573 -0.06002128 0.005683124 0.008586168 -0.06014525 0.005854725 0.008715569 -0.06000953 0.005630135 0.009161114 -0.05997645 0.00525552 0.009284377 -0.06010997 0.00531882 0.009480476 -0.05996811 0.004798591 0.009735643 -0.05994707 0.004397034 0.009583652 -0.06006908 0.004235804 0.00976336 -0.05992424 0.003768205 0.0096156 -0.05990952 0.003716409 0.009328663 -0.06007397 0.003296434 0.009257435 -0.05988734 0.003308892 0.008909583 -0.06001079 0.003020167 0.008739173 -0.05985903 0.003145933 0.008175015 -0.05997842 0.002945125 0.008200764 -0.05984276 0.003084003 0.007659316 -0.05981642 0.00337547 0.007572412 -0.05994963 0.003358423 0.007258355 -0.05980241 0.003727674 0.007241129 -0.05996412 0.003859639 0.006904721 -0.05977928 0.00422126 0.007023215 -0.05990427 0.004268765 0.006819963 -0.05978524 0.004697978 0.006824433 -0.05974477 0.004782795 0.007063746 -0.05987995 0.005184769 0.007011592 -0.05972254 0.005229771 0.007287025 -0.05985772 0.005543589 0.007300615 -0.05971163 0.005639255 0.007843554 -0.0598281 0.005829572 0.007795453 -0.05968922 0.005919456 0.008413553 -0.05966651 0.005690872 0.008513033 -0.05979824 0.005727708 0.009007215 -0.05964142 0.005489349 0.008995592 -0.05977505 0.005352497 0.009456574 -0.05961745 0.005034863 0.009429514 -0.05974721 0.004826426 0.00972253 -0.05959653 0.004318177 0.009562373 -0.05971574 0.004284918 0.009762108 -0.05958032 0.00362575 0.009544968 -0.05957293 0.003664433 0.009324789 -0.05968463 0.003184139 0.009094476 -0.05952697 0.003174662 0.008606612 -0.05964714 0.00293976 0.008374989 -0.05950379 0.003221988 0.007876873 -0.05961465 0.00304532 0.007760584 -0.05947446 0.003341376 0.007275581 -0.05945265 0.003492593 0.007422447 -0.05959141 0.004061579 0.00704813 -0.05956256 0.003786504 0.006947696 -0.05943262 0.004449725 0.006797313 -0.05941385 0.004937589 0.007097959 -0.05952262 0.005167663 0.007001519 -0.05939996 0.005506038 0.007592678 -0.05949014 0.00555247 0.007310748 -0.05935996 0.005891561 0.007988452 -0.05933612 0.005719244 0.008255004 -0.0594598 0.005884945 0.008578717 -0.05930864 0.005533397 0.008938193 -0.05942821 0.005672931 0.009106099 -0.05928695 0.005391478 0.009416043 -0.05927252 0.005052983 0.009415447 -0.05939894 0.005025506 0.009646415 -0.059255 0.004472494 0.009773969 -0.05923724 0.00442934 0.009551167 -0.05940753 0.004006683 0.009708642 -0.05921941 0.003892183 0.00944674 -0.05934613 0.003628611 0.009538114 -0.05920016 0.003479123 0.009115695 -0.05936002 0.003192603 0.009119212 -0.05917567 0.003208577 0.008673727 -0.05930024 0.002998054 0.008660793 -0.05915611 0.002949059 0.008241534 -0.05914288 0.003185451 0.007967948 -0.05926883 0.003071069 0.007686138 -0.05912119 0.003468871 0.007450222 -0.05924308 0.003307521 0.007321357 -0.05910813 0.00369662 0.006995975 -0.05908942 0.004044651 0.007052242 -0.05921232 0.004215478 0.006816625 -0.05906003 0.004710495 0.00683099 -0.05905151 0.004739224 0.007049381 -0.0591818 0.005168616 0.007000803 -0.05902928 0.005376875 0.007401883 -0.05915027 0.005728662 0.007540285 -0.05900114 0.005690038 0.008069694 -0.05911707 0.00590986 0.008156716 -0.05897486 0.005873978 0.008633494 -0.05896246 0.005617022 0.008812367 -0.05908429 0.005695939 0.009065628 -0.05893856 0.005376815 0.009427845 -0.05891788 0.005092024 0.009383559 -0.05905085 0.004905879 0.009698748 -0.05890154 0.004393577 0.009579479 -0.05901926 0.004351615 0.009772062 -0.05887526 0.003876984 0.009667575 -0.05886125 0.003736436 0.009341657 -0.0590257 0.003412961 0.009377479 -0.05884253 0.003407239 0.009052515 -0.0589689 0.003059208 0.008867681 -0.05882275 0.003156721 0.008457481 -0.05894017 0.002945542 0.008252978 -0.0587964 0.003225266 0.007869303 -0.05891406 0.003034889 0.0077551 -0.05877363 0.003473103 0.007446587 -0.05889272 0.003375113 0.007243692 -0.0587517 0.003908038 0.007119119 -0.05886918 0.003991901 0.006866991 -0.05874609 0.004458606 0.007010757 -0.0588442 0.004487335 0.006796479 -0.0586996 0.004969477 0.007131874 -0.05882132 0.005157947 0.006990134 -0.05868154 0.005357086 0.007407128 -0.05880004 0.005576431 0.007338941 -0.05865603 0.005633056 0.007862687 -0.05877691 0.005841851 0.007833361 -0.05864012 0.005707502 0.00836271 -0.0587545 0.005915164 0.008249402 -0.05861783 0.00584805 0.008731186 -0.05860388 0.005585312 0.008826076 -0.05873346 0.00560224 0.009197056 -0.05858349 0.005192458 0.009329199 -0.05870598 0.005116224 0.009616792 -0.0585587 0.004629135 0.009534537 -0.0587148 0.004494309 0.00976938 -0.0585345 0.003973484 0.00949496 -0.05865001 0.003953158 0.009694457 -0.05851519 0.00347644 0.009428381 -0.05849683 0.00348401 0.009122431 -0.05865865 0.003032326 0.008802115 -0.05847734 0.003200292 0.008644521 -0.05859851 0.002945721 0.008176505 -0.05844146 0.003166794 0.008122503 -0.05857563 0.003352403 0.007598996 -0.05855149 0.003092229 0.007645249 -0.05842006 0.003577411 0.007061004 -0.05839765 0.00374788 0.007207751 -0.05852705 0.004207313 0.007034599 -0.05850517 0.004157423 0.006830692 -0.05836755 0.004725694 0.006830036 -0.05834579 0.004867911 0.00706923 -0.05847585 0.005321025 0.007089614 -0.05832785 0.005423784 0.007487893 -0.05844545 0.005729198 0.007558584 -0.05829989 0.005702376 0.008067131 -0.05841773 0.005922496 0.008324086 -0.05826818 0.005609869 0.008786022 -0.05838584 0.005815744 0.008816182 -0.05825418 0.005518078 0.009308278 -0.05822306 0.005181968 0.009335637 -0.05835545 0.005255222 0.009513854 -0.05823707 0.004878282 0.009706318 -0.0581994 0.004482686 0.00956875 -0.0583226 0.004382669 0.009773671 -0.05817353 0.003959417 0.009472548 -0.0582993 0.00389868 0.009672999 -0.05816602 0.003392279 0.009061455 -0.05826842 0.003490447 0.009433388 -0.05814313 0.003150761 0.009040296 -0.05812376 0.002974271 0.008575856 -0.05810666 0.003160774 0.008405864 -0.05823802 0.002966761 0.008058845 -0.05808889 0.003280222 0.007690966 -0.05820655 0.003252148 0.007364332 -0.05805993 0.003785669 0.007187604 -0.05817455 0.003756701 0.006965279 -0.0580337 0.004201352 0.006823062 -0.05802458 0.004474341 0.006991803 -0.05814313 0.004651784 0.006817758 -0.05799633 0.005144894 0.0069893 -0.05797815 0.005200922 0.007265746 -0.0581097 0.005575478 0.007337749 -0.05795788 0.005561113 0.007690429 -0.0580852 0.005832254 0.007796049 -0.05794298 0.005712747 0.008278965 -0.0580585 0.005914449 0.008317887 -0.0579186 0.0055871 0.008829891 -0.05803376 0.005839765 0.008745849 -0.05789911 0.005639553 0.009154736 -0.05788612 0.005255103 0.00926727 -0.05800902 0.005144298 0.009595453 -0.05785453 0.00454998 0.009579122 -0.05797511 0.004706144 0.009741902 -0.0578649 0.004394531 0.009777486 -0.05782914 0.003818511 0.00940901 -0.05794274 0.003857135 0.009657502 -0.05781054 0.003277897 0.009226977 -0.05780494 0.003310918 0.008932113 -0.05791246 0.002964973 0.008535265 -0.05775439 0.003156304 0.008277416 -0.0578826 0.002970218 0.007988214 -0.05773562 0.003252446 0.007789492 -0.05786091 0.003220558 0.007420301 -0.05771583 0.0036664 0.007254004 -0.05783081 0.003720879 0.006979465 -0.05768626 0.004267632 0.007019162 -0.0578022 0.00426793 0.006809115 -0.05766123 0.005016386 0.007132232 -0.05776983 0.004836738 0.006861746 -0.05764234 0.005407035 0.007155179 -0.05761748 0.005626797 0.007795095 -0.05773073 0.005781531 0.007675528 -0.0575934 0.005918502 0.008239924 -0.05757278 0.005688011 0.008533358 -0.05769705 0.005791306 0.00890237 -0.05754989 0.00547403 0.009017825 -0.05767387 0.005448043 0.009379327 -0.05752223 0.004993021 0.009452998 -0.05764502 0.004883289 0.009706974 -0.05750024 0.004223108 0.009553015 -0.05761164 0.004335224 0.009769797 -0.05747896 0.003858029 0.009658217 -0.05745828 0.003684401 0.009325087 -0.05758583 0.003432929 0.00938785 -0.05744296 0.003286123 0.008864283 -0.05755913 0.003127038 0.008998274 -0.05742287 0.002935349 0.008253514 -0.05739647 0.003152132 0.008283674 -0.05753266 0.003256261 0.007797241 -0.05751079 0.003085732 0.007659435 -0.05737 0.003523886 0.007388055 -0.05748927 0.003353536 0.007269382 -0.05736172 0.003910124 0.007124125 -0.05746883 0.003750681 0.006962835 -0.05733448 0.004453361 0.007008254 -0.05744469 0.004280447 0.006810486 -0.05731314 0.004772305 0.006842195 -0.05729192 0.005019307 0.007151246 -0.05741906 0.00524801 0.007046699 -0.05727416 0.005450129 0.007541 -0.05742853 0.005638837 0.007427811 -0.05725473 0.005700349 0.008049488 -0.05736792 0.005850255 0.007856965 -0.05723339 0.00591731 0.008313179 -0.05721759 0.005615651 0.00877124 -0.05733609 0.005804955 0.008847057 -0.05719786 0.005593717 0.009208977 -0.05718517 0.005152225 0.009364068 -0.0573039 0.005250215 0.009529232 -0.05716568 0.00452274 0.009778499 -0.0571587 0.004280149 0.009572386 -0.0572642 0.003893613 0.009676575 -0.05711114 0.003682851 0.009317994 -0.0572353 0.003430008 0.009384751 -0.05709129 0.003339588 0.008953034 -0.05721336 0.003095328 0.008947014 -0.05706989 0.003137409 0.008275806 -0.05718278 0.002939522 0.008311867 -0.05704188 0.003102362 0.007615983 -0.05701684 0.003443241 0.007453083 -0.0571441 0.003404617 0.007214725 -0.05700618 0.003864347 0.006915092 -0.05697584 0.004003286 0.007088303 -0.05711454 0.004640877 0.007012128 -0.05708676 0.004538118 0.006796777 -0.05695354 0.005146682 0.0069893 -0.05692911 0.00529617 0.007346212 -0.05705392 0.005571603 0.007335543 -0.0569092 0.005590319 0.007754087 -0.05703169 0.005809783 0.007741093 -0.0568909 0.0057047 0.008231997 -0.05701035 0.00591135 0.008205354 -0.05687284 0.005624175 0.008698701 -0.05702817 0.005840003 0.008763909 -0.05685442 0.005378603 0.009145557 -0.05696696 0.005573749 0.009237229 -0.0568304 0.005041301 0.009650647 -0.05681121 0.00473982 0.009546935 -0.05693411 0.004207193 0.009762823 -0.05677378 0.004028916 0.009498417 -0.05690217 0.003684341 0.009572088 -0.05675446 0.0034886 0.009165346 -0.05687445 0.003249287 0.009198665 -0.0567367 0.0032081 0.008642077 -0.05684852 0.00299251 0.00864768 -0.05670827 0.003165602 0.008066356 -0.05682367 0.002957046 0.008102536 -0.05668902 0.00313127 0.007562339 -0.0566619 0.003405034 0.007530093 -0.05679738 0.003510177 0.0071249 -0.05664515 0.003918647 0.007103919 -0.05676853 0.004033684 0.006854712 -0.05664455 0.004536211 0.007018208 -0.0567404 0.004756629 0.006839036 -0.05659574 0.005071401 0.00717777 -0.0567162 0.005215406 0.00702697 -0.05658113 0.00559169 0.007360994 -0.05655342 0.005457401 0.007531702 -0.05669325 0.005829572 0.007789909 -0.05653893 0.005694389 0.008066594 -0.05666792 0.005918979 0.008328378 -0.05651944 0.005627393 0.008759081 -0.05663728 0.005844593 0.008734583 -0.05650532 0.00563842 0.009148359 -0.05648529 0.00529474 0.009208619 -0.05664891 0.005248606 0.009528696 -0.05646592 0.004717648 0.009545505 -0.05658274 0.004839062 0.009712934 -0.05644339 0.004473388 0.009769618 -0.05643618 0.003957867 0.009481668 -0.05654931 0.003900468 0.009678125 -0.05641692 0.003505289 0.009163737 -0.05652505 0.003421485 0.009380698 -0.05638855 0.003088474 0.008917033 -0.05636966 0.003239452 0.008743286 -0.05650341 0.002965748 0.008503437 -0.05635607 0.003155469 0.008080482 -0.05647444 0.002955377 0.008097887 -0.05633652 0.003128826 0.007577478 -0.05631715 0.003476798 0.007461607 -0.05648022 0.003439009 0.00718367 -0.05629569 0.003886699 0.007124066 -0.05641955 0.003887832 0.006903409 -0.0562753 0.004436254 0.006804525 -0.05625677 0.004584252 0.007014095 -0.05638861 0.004977166 0.006898522 -0.0562343 0.005117356 0.007228076 -0.05640017 0.005250871 0.007055699 -0.05624628 0.005519628 0.007610559 -0.0563392 0.005593001 0.007359325 -0.05620741 0.00584042 0.007810473 -0.05618268 0.005719959 0.008307754 -0.05630749 0.005914032 0.008355379 -0.05616825 0.005795121 0.008869051 -0.05614787 0.005552113 0.008868515 -0.05631774 0.005499899 0.009322047 -0.05612766 0.005206227 0.009307086 -0.05625641 0.004956245 0.009684562 -0.05610024 0.004639267 0.009550213 -0.05622923 0.004288196 0.009767055 -0.05607807 0.004110455 0.009523808 -0.05620646 0.00377959 0.00962311 -0.05605626 0.003527462 0.009208858 -0.05617791 0.003359794 0.009310901 -0.05604052 0.003094375 0.008934199 -0.05601745 0.003188312 0.008594036 -0.05614662 0.002957224 0.008466541 -0.05600249 0.003176331 0.008072316 -0.05612337 0.003009796 0.007842481 -0.05597287 0.003400146 0.007514595 -0.05609625 0.003283917 0.007333636 -0.05595588 0.003702282 0.006990492 -0.0559349 0.003878295 0.007141053 -0.05607038 0.00423634 0.006806313 -0.05592304 0.004377245 0.00700879 -0.05604809 0.004872381 0.00687021 -0.05589276 0.00491023 0.007118582 -0.05606287 0.005300104 0.007347941 -0.0560041 0.00531286 0.007092475 -0.05587273 0.005713701 0.007515907 -0.05585139 0.005691289 0.007992029 -0.05597162 0.005906403 0.008062839 -0.05582296 0.005571663 0.00890702 -0.05592906 0.005848824 0.008731544 -0.05580353 0.005600631 0.009205222 -0.05577772 0.005218386 0.009546458 -0.05576354 0.004994928 0.009436607 -0.0558961 0.004745483 0.009740352 -0.05575025 0.004425644 0.009567916 -0.05587035 0.004199147 0.009756267 -0.05572062 0.003807008 0.009407639 -0.05584233 0.003666996 0.009558856 -0.05570286 0.003228247 0.009168863 -0.05568182 0.003257274 0.008837759 -0.05580741 0.002988874 0.008633136 -0.05565762 0.003168165 0.008081436 -0.05577385 0.002961039 0.008065104 -0.05563598 0.003346562 0.007617831 -0.05575203 0.003137588 0.007557988 -0.05561226 0.003446459 0.007176637 -0.05559772 0.003730714 0.007216393 -0.05572795 0.003901302 0.006898105 -0.05558139 0.004199743 0.007045745 -0.05574536 0.004437446 0.006801545 -0.05555456 0.00480169 0.007060945 -0.05567932 0.004965245 0.006906211 -0.05554062 0.005414009 0.007167518 -0.05552154 0.005291402 0.007344424 -0.05565446 0.005610346 0.007790267 -0.05562984 0.005713343 0.007522761 -0.05549973 0.005910336 0.008238196 -0.05549436 0.005699455 0.008556962 -0.05559581 0.005779802 0.008901536 -0.05546873 0.005289733 0.009237527 -0.05556452 0.005333423 0.009462475 -0.05543994 0.004729151 0.009536564 -0.05553311 0.004032492 0.009507298 -0.05550205 0.003563106 0.00922209 -0.05547845 0.004265129 0.009559512 -0.06118494 0.003754913 0.009379029 -0.06117379 0.003285944 0.008870124 -0.06113392 0.00315231 0.008224725 -0.06110477 0.003397464 0.007510721 -0.06106883 0.004039406 0.007066786 -0.06103676 0.004729509 0.007037103 -0.06100672 0.00544089 0.007475495 -0.06096959 0.005698978 0.00814414 -0.06093835 0.005617856 0.008787333 -0.06090968 0.005217671 0.009293615 -0.06088155 0.004701733 0.009539186 -0.06085664 0.003973245 0.009497165 -0.0608235 0.00335282 0.008988559 -0.06078886 0.003139436 0.008188247 -0.06075239 0.003460109 0.00744754 -0.06071764 0.003978371 0.007092297 -0.06068956 0.004441261 0.007013916 -0.06066906 0.0049811 0.007131457 -0.06064474 0.005426049 0.007485508 -0.06061959 0.005656361 0.007941305 -0.06059753 0.005686044 0.008610427 -0.06056779 0.005321919 0.009198546 -0.06053805 0.004859268 0.009498775 -0.06051319 0.004140615 0.009539663 -0.0604822 0.00358659 0.009247541 -0.06045365 0.003179728 0.008622407 -0.06042116 0.003212749 0.007903993 -0.06039041 0.003523826 0.007382631 -0.06036323 0.004070699 0.007057487 -0.06033521 0.004808664 0.007055222 -0.06030279 0.005319356 0.007375836 -0.0602765 0.005663573 0.007906675 -0.06024926 0.00568372 0.008516132 -0.06022202 0.005477607 0.009027481 -0.06019765 0.004890859 0.009496569 -0.06016469 0.004162371 0.009539186 -0.06013208 0.003280162 0.00887078 -0.06008362 0.003157734 0.008273959 -0.06005644 0.003306567 0.007655918 -0.06002837 0.004320859 0.006997704 -0.05997335 0.00507462 0.007179796 -0.05994009 0.005505084 0.007594347 -0.05991423 0.005723834 0.008262991 -0.05988222 0.005493342 0.009009659 -0.05984908 0.00497049 0.009450316 -0.05981826 0.004407465 0.009565412 -0.05979323 0.003932595 0.009459257 -0.05977225 0.003485858 0.009154856 -0.05974864 0.003236293 0.008724749 -0.05972653 0.003152668 0.008120357 -0.05969959 0.003444969 0.007470548 -0.0596683 0.003899872 0.007127881 -0.05964344 0.004407405 0.007007658 -0.05962032 0.004945099 0.007122099 -0.05959683 0.005435049 0.007479071 -0.05956953 0.005719244 0.008235871 -0.05953466 0.00555396 0.008899271 -0.05950367 0.005062282 0.009413123 -0.05947285 0.0039016 0.009458005 -0.0594207 0.003210127 0.00866568 -0.05937421 0.00316447 0.008098185 -0.05934798 0.003491342 0.007396399 -0.05931431 0.004120886 0.007048785 -0.05928355 0.004699468 0.007037162 -0.05925768 0.005340576 0.007368266 -0.05922603 0.005689561 0.008044302 -0.05919194 0.00567305 0.00856781 -0.05916965 0.005400717 0.009138882 -0.05914241 0.004891812 0.009474873 -0.05911517 0.004263341 0.009566903 -0.05908709 0.003264188 0.008842408 -0.05903154 0.003159582 0.008221209 -0.05900412 0.003320455 0.007637262 -0.05897796 0.003751039 0.007209002 -0.05895084 0.004212617 0.007032096 -0.0589292 0.004787981 0.007052302 -0.05890417 0.005325317 0.007378697 -0.05887591 0.005673587 0.007935464 -0.05884701 0.005655169 0.008658885 -0.05881607 0.005272626 0.009270071 -0.05878329 0.004008412 0.00950551 -0.05872541 0.003201365 0.00864917 -0.05867278 0.00318402 0.007988929 -0.05864423 0.003560006 0.007332205 -0.05860984 0.004322052 0.007004022 -0.05857396 0.004938185 0.007119357 -0.0585469 0.005472362 0.007517635 -0.05851715 0.005719661 0.008345365 -0.05847996 0.005492031 0.009002387 -0.05844902 0.004961013 0.009463369 -0.05841803 0.00436002 0.009558856 -0.05839151 0.00377953 0.0093984 -0.0583648 0.003366708 0.008986592 -0.05833977 0.003156781 0.008448719 -0.0583139 0.00321716 0.007900953 -0.05828982 0.003488004 0.007421612 -0.0582661 0.003983139 0.007088661 -0.05823874 0.004755318 0.007033348 -0.05820518 0.005343735 0.007397353 -0.05817544 0.005680561 0.007967114 -0.05814588 0.005670726 0.008578717 -0.05811923 0.005380272 0.009164392 -0.05809032 0.004842162 0.009492814 -0.05806285 0.004213035 0.009559452 -0.05803561 0.00366044 0.009301483 -0.05800837 0.003239393 0.008789956 -0.0579791 0.003191947 0.007917046 -0.05794066 0.003673493 0.007247269 -0.05790364 0.00443226 0.006997764 -0.05786997 0.005019843 0.007158815 -0.05784279 0.005466639 0.007528603 -0.05781716 0.005679726 0.008033573 -0.05779355 0.005677521 0.008575856 -0.05776894 0.005358934 0.009181499 -0.0577389 0.004782557 0.009515345 -0.05771052 0.004179179 0.009548366 -0.05768322 0.003560662 0.009228229 -0.05765283 0.003264307 0.008801877 -0.05763041 0.003150403 0.008242666 -0.05760455 0.003365814 0.007563173 -0.05757337 0.003979325 0.00708276 -0.05753988 0.004582822 0.007021486 -0.05751287 0.005130648 0.007214486 -0.0574873 0.005701065 0.008116722 -0.05743902 0.005584061 0.008875787 -0.05740594 0.005052745 0.009406566 -0.05737268 0.004580795 0.009553492 -0.05735099 0.003947377 0.009482443 -0.05732345 0.003300726 0.008920371 -0.05728375 0.003159821 0.008070707 -0.05724799 0.003448545 0.007474303 -0.05721867 0.00395596 0.007089257 -0.05719029 0.004588663 0.007023811 -0.05716311 0.005056917 0.00717169 -0.0571404 0.005433499 0.00750333 -0.05711907 0.005702972 0.008070468 -0.05709195 0.005371332 0.009159445 -0.05704027 0.00494033 0.0094558 -0.05701738 0.004401385 0.009567916 -0.05699366 0.003746926 0.009378015 -0.05696237 0.003233313 0.008767306 -0.05692875 0.003189921 0.007924377 -0.0568903 0.003673732 0.007245361 -0.05685484 0.004463016 0.006996393 -0.05681735 0.005170166 0.007241129 -0.05678516 0.005561947 0.007691442 -0.05675929 0.005700826 0.008169949 -0.05673718 0.00562793 0.008745789 -0.05671161 0.004783689 0.009529292 -0.05665898 0.004014313 0.009502768 -0.05662584 0.003467381 0.009130418 -0.05659735 0.003167808 0.008533954 -0.05656737 0.003227293 0.007851302 -0.0565375 0.003904819 0.007123351 -0.05649274 0.004549741 0.007005512 -0.05646395 0.00554502 0.007646262 -0.05641084 0.005711853 0.008322596 -0.05638045 0.005303442 0.009216845 -0.05633628 0.004855632 0.009495913 -0.05631315 0.004208385 0.009552478 -0.05628514 0.003578484 0.009248912 -0.05625385 0.003255188 0.008775889 -0.05622911 0.003150701 0.0082767 -0.05620676 0.003287613 0.007716178 -0.05618071 0.00379914 0.007155716 -0.05614858 0.004464149 0.007015168 -0.05611824 0.00541073 0.007461547 -0.05607092 0.005684792 0.008029818 -0.05604356 0.005665004 0.008631229 -0.05601626 0.005300045 0.009237885 -0.05598628 0.004756987 0.009520411 -0.05595898 0.004180133 0.009545207 -0.05593341 0.003510951 0.0091964 -0.05590021 0.003179013 0.008552432 -0.05586796 0.003199338 0.007934153 -0.05584138 0.003581404 0.007317483 -0.05580991 0.00484389 0.007063269 -0.05575186 0.005408525 0.007467508 -0.05572092 0.005699992 0.008054018 -0.05569118 0.005599915 0.008820056 -0.05565863 0.005129277 0.009368956 -0.05562609 0.004312753 0.009578645 -0.05559009 0.003492832 0.009179651 -0.05554836 0.003178417 0.008536696 -0.05551797 0.003217577 0.007847964 -0.05548828 0.003471434 0.007164537 -0.06117963 0.003199338 0.008942544 -0.06118369 0.003040611 0.007835626 -0.06118363 0.003918886 0.006899356 -0.0611723 0.004963696 0.009668409 -0.06098109 0.004411935 0.009766221 -0.06095969 0.004018068 0.009706139 -0.06059515 0.003517687 0.009453594 -0.06057286 0.003712177 0.009589731 -0.05953258 0.003005146 0.008673906 -0.05948781 0.004955172 0.006898939 -0.05936551 0.005773603 0.007671833 -0.05932199 0.005501449 0.007270038 -0.05899077 0.003775179 0.006961047 -0.05871158 0.003191351 0.009095311 -0.05845481 0.003380417 0.0072456 -0.05837959 0.005870938 0.007947266 -0.05826115 0.003086805 0.007675468 -0.05804961 0.003445506 0.009392261 -0.05777043 0.003107786 0.008946537 -0.05774831 0.002970993 0.008531749 -0.0573827 0.004607319 0.009759664 -0.05711716 0.004651129 0.009755432 -0.05676919 0.004190683 0.006814241 -0.05659419 0.005855262 0.00789088 -0.05546361 0.005600214 0.00879544 -0.05518609 0.005336582 0.009211242 -0.0551868 0.005665242 0.008989036 -0.05526447 0.005639433 0.009125232 -0.05538606 0.00572586 0.008288621 -0.05518966 0.005802333 0.008529365 -0.05523931 0.005820393 0.008760929 -0.05537247 0.005872189 0.008405685 -0.05530899 0.005627095 0.007781982 -0.05518943 0.005844891 0.008031725 -0.05528777 0.005740225 0.007691621 -0.05529314 0.005203187 0.007261037 -0.055188 0.005539 0.007452189 -0.05523645 0.005592882 0.00737214 -0.05542349 0.005222856 0.007141232 -0.05524533 0.005269646 0.007094562 -0.05532991 0.004556119 0.006993591 -0.05518919 0.004862785 0.007005453 -0.05521702 0.004896342 0.006906688 -0.05534052 0.004083931 0.00706762 -0.055184 0.004602849 0.006851673 -0.05531209 0.004131495 0.006909012 -0.05525481 0.004212558 0.006819784 -0.05542492 0.003812432 0.007114291 -0.05519878 0.003811061 0.006944179 -0.05542421 0.003631532 0.007111847 -0.05527889 0.003507673 0.007132411 -0.05541747 0.003392875 0.007396697 -0.05522716 0.003220319 0.007772803 -0.05519163 0.003241598 0.007460355 -0.05530905 0.003041148 0.007865548 -0.0553258 0.003096699 0.008169114 -0.05520826 0.003189265 0.008666455 -0.0551871 0.002988755 0.008238971 -0.05530261 0.002948284 0.008334279 -0.05543303 0.003045916 0.008664309 -0.0552898 0.00327444 0.009012579 -0.05522316 0.00313121 0.00895071 -0.05534124 0.003618359 0.009325146 -0.05519336 0.003324091 0.009218037 -0.05531001 0.003648221 0.009518384 -0.05532449 0.003866434 0.009581506 -0.05526095 0.004238247 0.009568691 -0.05518847 0.004253447 0.009682178 -0.05525839 0.004692077 0.009658396 -0.0552417 0.004904925 0.009546935 -0.05520981 0.004796266 0.009705543 -0.05536109 0.005239605 0.009457349 -0.05526703 0.005372166 0.009411454 -0.05536282 0.002270817 0.00667119 -0.0613591 0.00256735 0.006337523 -0.06137335 0.002636492 0.006364166 -0.06124931 0.002360403 0.006777286 -0.06119692 0.002901613 0.006075859 -0.06133365 0.003324627 0.00582683 -0.06136262 0.003136873 0.006113588 -0.06118994 0.00333935 0.005891561 -0.06125521 0.00372529 0.00568372 -0.06137657 0.003903925 0.005699992 -0.06125736 0.004014551 0.00578016 -0.06119138 0.004233181 0.005591809 -0.06138354 0.004553139 0.0056656 -0.06124103 0.004879832 0.005624651 -0.06136792 0.004992187 0.005817413 -0.06118988 0.005130648 0.005708217 -0.06130754 0.005574703 0.00584352 -0.06135749 0.005441188 0.005937755 -0.0611968 0.006102323 0.00617218 -0.06135141 0.006073117 0.006234765 -0.06124365 0.006178438 0.006475329 -0.06118857 0.00653696 0.006589651 -0.06138068 0.006573498 0.006762325 -0.06124818 0.006764769 0.0073058 -0.06118881 0.006842553 0.007086515 -0.06133657 0.006998538 0.007500708 -0.06132173 0.007056772 0.00791049 -0.06127631 0.007124125 0.008042454 -0.06139361 0.00694853 0.0079782 -0.06118941 0.00712043 0.00843358 -0.06135386 0.007023632 0.008685529 -0.06123846 0.007041394 0.008977174 -0.06136095 0.006790339 0.009197533 -0.06118941 0.006831228 0.009509563 -0.0613467 0.006794929 0.009425818 -0.06124651 0.006572008 0.009918272 -0.06132853 0.006400227 0.009896814 -0.06119358 0.00629568 0.01023894 -0.06136274 0.006084501 0.01030367 -0.06122744 0.005768477 0.01062762 -0.06134021 0.005332887 0.01065874 -0.06118673 0.005158901 0.01089167 -0.06138527 0.00514698 0.01084899 -0.06127882 0.004562616 0.01097971 -0.0613501 0.004530906 0.01085269 -0.06120425 0.003978729 0.01095342 -0.06138682 0.003955364 0.01088517 -0.06125491 0.003310382 0.01055771 -0.06118559 0.003492295 0.01081889 -0.06137943 0.003366708 0.01069861 -0.06124973 0.003020465 0.01059061 -0.06137979 0.002784073 0.01033079 -0.06124085 0.002581894 0.01024824 -0.06134343 0.002160131 0.009405493 -0.06118822 0.002242982 0.009874105 -0.06140023 0.002393722 0.009842813 -0.06120508 0.002171039 0.009680986 -0.06127405 0.001992762 0.009449958 -0.0613777 0.001860082 0.009067237 -0.06132662 0.001764297 0.008665323 -0.06133747 0.001894295 0.008246421 -0.06118947 0.001872181 0.008732736 -0.06122428 0.001740217 0.008177697 -0.06132954 0.001811385 0.007876455 -0.06127089 0.001860737 0.007461965 -0.06136095 0.002037882 0.007394134 -0.06119346 0.002090096 0.006956517 -0.06134581 0.002438843 0.006473124 -0.06401312 0.004352152 0.005586147 -0.06398689 0.005725145 0.005917966 -0.06398916 0.006067395 0.006147921 -0.0640183 0.006485879 0.006538808 -0.06400883 0.006758093 0.006938219 -0.06403928 0.006947159 0.007334053 -0.06402361 0.007059931 0.007680475 -0.06400275 0.007116854 0.008498668 -0.06401747 0.007026314 0.009030103 -0.06399655 0.005716323 0.01065355 -0.06402939 0.004952907 0.01093798 -0.06398397 0.003980875 0.01094537 -0.06400334 0.003491103 0.0108273 -0.06397211 0.00290364 0.01051712 -0.06397175 0.00257802 0.01024693 -0.06400489 0.001930832 0.009316444 -0.06398189 0.001763403 0.008699297 -0.06401175 0.001747429 0.007959842 -0.06400287 0.001952409 0.007210314 -0.06398952 0.002107262 0.006924092 -0.06403636 0.002444326 0.006586909 -0.06413537 0.002259612 0.006982862 -0.06417864 0.001904189 0.007514119 -0.0641092 0.00189948 0.00791651 -0.06417268 0.001900494 0.008413612 -0.06417679 0.001826703 0.008639097 -0.06412655 0.001979172 0.009264409 -0.06411075 0.002199769 0.009475946 -0.06418085 0.002303242 0.009853839 -0.06411468 0.002212643 0.00982511 -0.06400477 0.002780318 0.01029527 -0.0641461 0.003100275 0.01057726 -0.06410282 0.003163695 0.01045972 -0.0641812 0.003539502 0.01079607 -0.06407707 0.003725171 0.01072478 -0.06417649 0.004164695 0.01091313 -0.06411284 0.004448056 0.01098537 -0.06400644 0.004540741 0.01079428 -0.06418138 0.004804313 0.01089656 -0.06411582 0.005216002 0.01076596 -0.06414419 0.00533986 0.0108174 -0.0640341 0.005709111 0.01049602 -0.06417578 0.006135523 0.01037162 -0.06403201 0.006331026 0.009969532 -0.06417882 0.006497561 0.01001113 -0.06403809 0.006744027 0.009552299 -0.06411921 0.006835043 0.00951606 -0.06399482 0.006928145 0.008891761 -0.06416493 0.007032155 0.008811295 -0.06409102 0.006938338 0.008499801 -0.06418186 0.007030248 0.008087277 -0.06413877 0.007113635 0.008028745 -0.06402212 0.006859719 0.007487475 -0.06417191 0.00661242 0.006962776 -0.06416881 0.006347954 0.006446897 -0.06408858 0.006213426 0.006486654 -0.06417977 0.005764901 0.006029009 -0.06412184 0.005249261 0.005726993 -0.06404507 0.005419492 0.005943775 -0.06417459 0.004808485 0.005622863 -0.0640195 0.004539132 0.005676388 -0.06414073 0.004072606 0.005770683 -0.0641781 0.003757059 0.005723774 -0.06410264 0.003777384 0.005666851 -0.06398248 0.003313541 0.006005406 -0.0641784 0.003307104 0.005838394 -0.06400972 0.002913296 0.006136 -0.06412041 0.002868056 0.00608772 -0.064013 -0.005733609 0.07099997 -5.97399e-4 -0.005837202 0.06278079 -0.00197196 -0.005329668 0.06278133 0.001619994 -0.004920005 0.07099997 0.002949714 -0.004187762 0.06277942 0.004623472 -0.003500938 0.07099997 0.005886375 -0.002709448 0.06278079 0.007097899 -0.001595199 0.07099997 0.008483171 -8.57707e-4 0.06278014 0.009202063 8.53036e-4 0.07099997 0.01063799 0.001002252 0.06277942 0.01074546 0.002919137 0.07099997 0.01191836 0.003830015 0.06278133 0.0123865 0.005521893 0.07099997 0.01301038 0.007701635 0.06277841 0.01355296 0.009089648 0.07099997 0.01372772 0.01136898 0.06278079 0.01374047 0.01274043 0.07099997 0.01360267 0.01456969 0.06278079 0.01323199 0.01551181 0.07099997 0.01294112 0.01683205 0.06278073 0.01243311 0.01846772 0.07099997 0.01166099 0.01902478 0.06278079 0.01131224 0.0217151 0.07099997 0.009239196 0.02159261 0.06278079 0.009334921 0.02371764 0.06278079 0.006888031 0.0238083 0.07099997 0.006737887 0.02503669 0.07099997 0.004640519 0.02531576 0.06278079 0.004068553 0.02593886 0.07099997 0.002383351 0.02631747 0.06278234 0.001015901 0.02656233 0.07099997 -3.69363e-4 0.0266447 0.06278073 -0.001389324 0.02664917 0.07099997 -0.004007458 0.02664756 0.06278079 -0.003852009 0.02606737 0.06278234 -0.00701195 0.02599871 0.07099997 -0.00720334 0.02496314 0.07099997 -0.009829044 0.02520442 0.06278073 -0.0092808 0.02402913 0.06278079 -0.01144504 0.02322411 0.07099997 -0.01256382 0.02172309 0.06278133 -0.01424545 0.02126544 0.07099997 -0.01463317 0.01901268 0.07099997 -0.01633369 0.01918262 0.06277942 -0.01621282 0.016631 0.06278079 -0.01755332 0.01646459 0.07099997 -0.01760822 0.01414632 0.07099997 -0.01833921 0.01355433 0.06278234 -0.01847863 0.01174503 0.07099997 -0.01871651 0.01029938 0.06278079 -0.01878106 0.008922696 0.07099997 -0.0187118 0.007077157 0.06278079 -0.01843273 0.005356371 0.07099997 -0.01798689 0.003988027 0.06278079 -0.01745289 0.002040684 0.07099997 -0.0164535 0.001524627 0.06278014 -0.01611584 -2.55996e-4 0.07099997 -0.01476746 -3.93975e-4 0.06277942 -0.01464587 -0.002482473 0.07099997 -0.01243966 -0.002091109 0.06278014 -0.01288664 -0.003491163 0.06277942 -0.01091659 -0.004358172 0.07099997 -0.009305059 -0.004729926 0.0627796 -0.008418798 -0.005306005 0.07099997 -0.006618142 -0.005607187 0.06278163 -0.005310595 -0.005791485 0.07099997 -0.003837704 -0.002577424 0.06199985 -2.31419e-4 -0.001429855 0.06199997 0.003203809 7.56894e-4 0.06199991 0.00643748 0.004625558 0.06199985 0.009348571 0.009059727 0.06199991 0.01059579 0.01401448 0.06199985 0.01023793 0.01896828 0.06199985 0.007574141 0.02221357 0.06199985 0.003465414 0.02349466 0.06199997 -9.41454e-4 0.02324306 0.06199979 -0.005754888 0.02060043 0.06199985 -0.01097375 0.0175696 0.06199997 -0.01356333 0.01338446 0.06199985 -0.01539212 0.008137226 0.06199991 -0.01550197 0.003517687 0.06199985 -0.01373916 9.57571e-5 0.06199997 -0.01065582 -0.002352952 0.06199973 -0.006036698 -0.002299547 0.07099997 0.009156167 3.30919e-4 0.07099997 0.01153808 -0.004149615 0.07099997 0.006763458 -0.005476653 0.07099997 0.004197716 0.003719627 0.07099997 0.01340872 -0.006418943 0.07099997 0.001338362 0.007298469 0.07099997 0.0144996 -0.006810545 0.07099997 -0.001646578 0.01116788 0.07099997 0.0147534 -0.006728172 0.07099997 -0.004534006 0.01384794 0.07099997 0.01440775 -0.006099522 0.07099997 -0.007492482 0.01633602 0.07099997 0.01372331 -0.005000233 0.07099997 -0.01027971 0.01868188 0.07099997 0.01264834 0.02085757 0.07099997 0.01126098 -0.003582894 0.07099997 -0.01258045 -0.00193572 0.07099997 -0.01456677 0.02338552 0.07099997 0.008927524 2.63794e-4 0.07099997 -0.01646083 0.02515697 0.07099997 0.006493449 0.003198742 0.07099997 -0.01821523 0.02646565 0.07099997 0.003918111 0.006482064 0.07099997 -0.01931351 0.02750796 0.07099997 1.98235e-4 0.009445786 0.07099997 -0.01975512 0.02768015 0.07099997 -0.002937257 0.01288282 0.07099997 -0.0196079 0.02742075 0.07099997 -0.005626976 0.01544171 0.07099997 -0.01901751 0.02646565 0.07099997 -0.008931994 0.01781427 0.07099997 -0.01812481 0.02510309 0.07099997 -0.01160061 0.02041864 0.07099997 -0.01658654 0.02301633 0.07099997 -0.01436316 0.02768933 0.06200146 -0.002506911 0.02746862 0.06200063 -0.00535351 0.02656674 0.06200063 -0.008673429 0.02502489 0.06200063 -0.0117489 0.02290427 0.06200063 -0.01445782 0.02028888 0.06200063 -0.01669287 0.01728242 0.06200063 -0.01836538 0.01400429 0.06200063 -0.019409 0.01058423 0.06200063 -0.01978236 0.007158041 0.06200063 -0.01947069 0.003861606 0.06200063 -0.01848626 8.2557e-4 0.06200063 -0.01686823 -0.001909673 0.06200152 -0.01460635 -0.004043698 0.06199932 -0.01193416 -0.005244135 0.06200057 -0.009724199 -0.006193697 0.06200152 -0.00723201 -0.006746232 0.06199806 -0.004225552 -0.006800413 0.06200152 -0.001169145 -0.006298243 0.06200146 0.001752257 -0.005482554 0.06199967 0.00420016 -0.003854274 0.06200212 0.007230937 -0.001435697 0.06200063 0.01005101 6.61055e-4 0.06200093 0.01171964 0.002620935 0.06199884 0.01289039 0.005746662 0.06200212 0.01413363 0.00941205 0.06200063 0.01473927 0.0120908 0.06200093 0.01466977 0.01434475 0.06199884 0.01430678 0.01645457 0.06200057 0.01366132 0.01907199 0.06200212 0.01246374 0.02185398 0.06199967 0.01043963 0.02365106 0.06200146 0.008588016 0.02516245 0.06199967 0.006496727 0.02656674 0.06200063 0.003659546 0.02746862 0.06200063 3.3964e-4 0.02372056 0.06099992 -0.002117156 0.02315616 0.06099992 -0.00643289 0.02042108 0.06099975 -0.01141166 0.0149455 0.06099969 -0.01510614 0.008369803 0.06099975 -0.01573222 0.004040777 0.06099998 -0.01413869 3.50494e-4 0.06099975 -0.01131463 -0.00271219 0.06099963 -0.005163371 -0.002425491 0.06099987 0.00104469 3.5052e-4 0.06099975 0.006300747 0.004950582 0.06099992 0.0096336 0.009826302 0.06099987 0.0108152 0.01402533 0.06099992 0.01027667 0.0178892 0.06099987 0.00854665 0.02119141 0.06099992 0.005302727 0.0230152 0.06099992 0.00178337 -0.005733609 0.07099997 -5.97399e-4 -0.005837202 0.06278079 -0.00197196 -0.005329668 0.06278133 0.001619994 -0.004920005 0.07099997 0.002949714 -0.004187762 0.06277942 0.004623472 -0.003500938 0.07099997 0.005886375 -0.002709448 0.06278079 0.007097899 -0.001595199 0.07099997 0.008483171 -8.57707e-4 0.06278014 0.009202063 8.53036e-4 0.07099997 0.01063799 0.001002252 0.06277942 0.01074546 0.002919137 0.07099997 0.01191836 0.003830015 0.06278133 0.0123865 0.005521893 0.07099997 0.01301038 0.007701635 0.06277841 0.01355296 0.009089648 0.07099997 0.01372772 0.01136898 0.06278079 0.01374047 0.01274043 0.07099997 0.01360267 0.01456969 0.06278079 0.01323199 0.01551181 0.07099997 0.01294112 0.01683205 0.06278073 0.01243311 0.01846772 0.07099997 0.01166099 0.01902478 0.06278079 0.01131224 0.0217151 0.07099997 0.009239196 0.02159261 0.06278079 0.009334921 0.02371764 0.06278079 0.006888031 0.0238083 0.07099997 0.006737887 0.02503669 0.07099997 0.004640519 0.02531576 0.06278079 0.004068553 0.02593886 0.07099997 0.002383351 0.02631747 0.06278234 0.001015901 0.02656233 0.07099997 -3.69363e-4 0.0266447 0.06278073 -0.001389324 0.02664917 0.07099997 -0.004007458 0.02664756 0.06278079 -0.003852009 0.02606737 0.06278234 -0.00701195 0.02599871 0.07099997 -0.00720334 0.02496314 0.07099997 -0.009829044 0.02520442 0.06278073 -0.0092808 0.02402913 0.06278079 -0.01144504 0.02322411 0.07099997 -0.01256382 0.02172309 0.06278133 -0.01424545 0.02126544 0.07099997 -0.01463317 0.01901268 0.07099997 -0.01633369 0.01918262 0.06277942 -0.01621282 0.016631 0.06278079 -0.01755332 0.01646459 0.07099997 -0.01760822 0.01414632 0.07099997 -0.01833921 0.01355433 0.06278234 -0.01847863 0.01174503 0.07099997 -0.01871651 0.01029938 0.06278079 -0.01878106 0.008922696 0.07099997 -0.0187118 0.007077157 0.06278079 -0.01843273 0.005356371 0.07099997 -0.01798689 0.003988027 0.06278079 -0.01745289 0.002040684 0.07099997 -0.0164535 0.001524627 0.06278014 -0.01611584 -2.55996e-4 0.07099997 -0.01476746 -3.93975e-4 0.06277942 -0.01464587 -0.002482473 0.07099997 -0.01243966 -0.002091109 0.06278014 -0.01288664 -0.003491163 0.06277942 -0.01091659 -0.004358172 0.07099997 -0.009305059 -0.004729926 0.0627796 -0.008418798 -0.005306005 0.07099997 -0.006618142 -0.005607187 0.06278163 -0.005310595 -0.005791485 0.07099997 -0.003837704 -0.002577424 0.06199985 -2.31419e-4 -0.001429855 0.06199997 0.003203809 7.56894e-4 0.06199991 0.00643748 0.004625558 0.06199985 0.009348571 0.009059727 0.06199991 0.01059579 0.01401448 0.06199985 0.01023793 0.01896828 0.06199985 0.007574141 0.02221357 0.06199985 0.003465414 0.02349466 0.06199997 -9.41454e-4 0.02324306 0.06199979 -0.005754888 0.02060043 0.06199985 -0.01097375 0.0175696 0.06199997 -0.01356333 0.01338446 0.06199985 -0.01539212 0.008137226 0.06199991 -0.01550197 0.003517687 0.06199985 -0.01373916 9.57571e-5 0.06199997 -0.01065582 -0.002352952 0.06199973 -0.006036698 -0.002299547 0.07099997 0.009156167 3.30919e-4 0.07099997 0.01153808 -0.004149615 0.07099997 0.006763458 -0.005476653 0.07099997 0.004197716 0.003719627 0.07099997 0.01340872 -0.006418943 0.07099997 0.001338362 0.007298469 0.07099997 0.0144996 -0.006810545 0.07099997 -0.001646578 0.01116788 0.07099997 0.0147534 -0.006728172 0.07099997 -0.004534006 0.01384794 0.07099997 0.01440775 -0.006099522 0.07099997 -0.007492482 0.01633602 0.07099997 0.01372331 -0.005000233 0.07099997 -0.01027971 0.01868188 0.07099997 0.01264834 0.02085757 0.07099997 0.01126098 -0.003582894 0.07099997 -0.01258045 -0.00193572 0.07099997 -0.01456677 0.02338552 0.07099997 0.008927524 2.63794e-4 0.07099997 -0.01646083 0.02515697 0.07099997 0.006493449 0.003198742 0.07099997 -0.01821523 0.02646565 0.07099997 0.003918111 0.006482064 0.07099997 -0.01931351 0.02750796 0.07099997 1.98235e-4 0.009445786 0.07099997 -0.01975512 0.02768015 0.07099997 -0.002937257 0.01288282 0.07099997 -0.0196079 0.02742075 0.07099997 -0.005626976 0.01544171 0.07099997 -0.01901751 0.02646565 0.07099997 -0.008931994 0.01781427 0.07099997 -0.01812481 0.02510309 0.07099997 -0.01160061 0.02041864 0.07099997 -0.01658654 0.02301633 0.07099997 -0.01436316 0.02768933 0.06200146 -0.002506911 0.02746862 0.06200063 -0.00535351 0.02656674 0.06200063 -0.008673429 0.02502489 0.06200063 -0.0117489 0.02290427 0.06200063 -0.01445782 0.02028888 0.06200063 -0.01669287 0.01728242 0.06200063 -0.01836538 0.01400429 0.06200063 -0.019409 0.01058423 0.06200063 -0.01978236 0.007158041 0.06200063 -0.01947069 0.003861606 0.06200063 -0.01848626 8.2557e-4 0.06200063 -0.01686823 -0.001909673 0.06200152 -0.01460635 -0.004043698 0.06199932 -0.01193416 -0.005244135 0.06200057 -0.009724199 -0.006193697 0.06200152 -0.00723201 -0.006746232 0.06199806 -0.004225552 -0.006800413 0.06200152 -0.001169145 -0.006298243 0.06200146 0.001752257 -0.005482554 0.06199967 0.00420016 -0.003854274 0.06200212 0.007230937 -0.001435697 0.06200063 0.01005101 6.61055e-4 0.06200093 0.01171964 0.002620935 0.06199884 0.01289039 0.005746662 0.06200212 0.01413363 0.00941205 0.06200063 0.01473927 0.0120908 0.06200093 0.01466977 0.01434475 0.06199884 0.01430678 0.01645457 0.06200057 0.01366132 0.01907199 0.06200212 0.01246374 0.02185398 0.06199967 0.01043963 0.02365106 0.06200146 0.008588016 0.02516245 0.06199967 0.006496727 0.02656674 0.06200063 0.003659546 0.02746862 0.06200063 3.3964e-4 0.02372056 0.06099992 -0.002117156 0.02315616 0.06099992 -0.00643289 0.02042108 0.06099975 -0.01141166 0.0149455 0.06099969 -0.01510614 0.008369803 0.06099975 -0.01573222 0.004040777 0.06099998 -0.01413869 3.50494e-4 0.06099975 -0.01131463 -0.00271219 0.06099963 -0.005163371 -0.002425491 0.06099987 0.00104469 3.5052e-4 0.06099975 0.006300747 0.004950582 0.06099992 0.0096336 0.009826302 0.06099987 0.0108152 0.01402533 0.06099992 0.01027667 0.0178892 0.06099987 0.00854665 0.02119141 0.06099992 0.005302727 0.0230152 0.06099992 0.00178337 0.01581233 0.05869513 0.001922786 0.01569235 0.05899512 0.002221643 0.01550209 0.05869513 0.002479135 0.01531785 0.05899512 0.002639114 0.01503068 0.05869513 0.00278306 0.01461821 0.05899512 0.002847552 0.01444178 0.05869513 0.002802789 0.01389288 0.05869513 0.002520799 0.01401805 0.05899512 0.002607643 0.01369649 0.05899512 0.002255201 0.01358836 0.05869513 0.001983642 0.01354098 0.05899512 0.001570999 0.01359444 0.05869513 0.001338422 0.01391166 0.05899512 8.47356e-4 0.01399171 0.05869513 7.94669e-4 0.01445204 0.05869513 5.86984e-4 0.01460909 0.05899512 5.53054e-4 0.01501286 0.05869513 6.01422e-4 0.0152108 0.05899512 6.89838e-4 0.01565617 0.05869513 0.001067876 0.01557612 0.05899512 9.96123e-4 0.01582509 0.05899512 0.001561641 0.01236146 0.05899512 0.002164781 0.01239222 0.05869513 0.002259671 0.0128504 0.05869513 0.003209352 0.01271408 0.05899512 0.002989828 0.0133177 0.05899512 0.003629803 0.01369702 0.05869513 0.00383985 0.01412099 0.05899512 0.003984928 0.01460713 0.05869513 0.004063069 0.01492065 0.05899512 0.004047214 0.0155307 0.05869513 0.003900051 0.01576316 0.05899512 0.003797471 0.01643055 0.05869513 0.003314375 0.01659333 0.05899512 0.003116011 0.01697999 0.05869513 0.002279281 0.01700365 0.05899512 0.002144634 0.01700133 0.05869513 0.001166343 0.01699817 0.05899512 0.001167058 0.01654618 0.05899512 2.3508e-4 0.0163787 0.05869513 1.60502e-5 0.01597815 0.05899512 -2.74266e-4 0.01519578 0.05869513 -6.28653e-4 0.0151745 0.05899512 -6.28018e-4 0.01423585 0.05899512 -6.20211e-4 0.01408338 0.05869513 -5.92364e-4 0.01336389 0.05899512 -2.7725e-4 0.01311218 0.05869513 -8.74588e-5 0.01273822 0.05899512 3.6744e-4 0.0125705 0.05869513 6.57028e-4 0.01239055 0.05899512 0.001110613 0.01234084 0.05869513 0.001382172 0.006953418 0.06444519 0.001078903 0.006834387 0.06443893 0.00115329 0.006519794 0.06444507 7.65309e-4 0.007149457 0.06444609 0.001512587 0.006370604 0.06444483 8.59323e-4 0.007020175 0.06444501 0.001613855 0.006085097 0.06444519 7.21906e-4 0.005938112 0.06444519 8.33528e-4 0.005714416 0.06444531 8.33943e-4 0.006945669 0.06444495 0.002321362 0.005346417 0.06443983 0.001181125 0.006664037 0.0644319 0.002401471 0.006644189 0.0644524 0.002565681 0.006298899 0.06445544 0.0026654 0.005913436 0.06445181 0.002633213 0.005448937 0.06444346 0.002338409 0.005800664 0.05870735 0.00259906 0.006252348 0.05874311 0.002688705 0.00702089 0.05869901 0.001729726 0.006390035 0.05869507 0.002586305 0.00667119 0.05876642 0.00255227 0.007004737 0.05877685 0.002248227 0.006851673 0.05869489 0.002264976 0.007137119 0.05879807 0.001964092 0.007158756 0.05881744 0.001529514 0.006971895 0.05870538 0.001424252 0.007008373 0.05882775 0.001141369 0.006686866 0.05874323 0.00100857 0.006750881 0.05882722 8.90356e-4 0.006303966 0.05884623 7.18971e-4 0.006106853 0.05877155 8.51659e-4 0.005957186 0.0588811 7.29627e-4 0.005605816 0.05879795 0.001082301 0.005564212 0.05889594 9.32687e-4 0.005340576 0.05890685 0.001183986 0.005373537 0.0588206 0.001483082 0.005203425 0.05892699 0.001580178 0.00538975 0.05884462 0.001984179 0.005262434 0.05894446 0.00206542 0.005452871 0.05894303 0.002346515 0.005688965 0.05886805 0.002370595 0.005647957 0.05897414 0.002523422 0.006153225 0.05889183 0.002541303 0.006054162 0.05898314 0.00267291 0.006495833 0.05900311 0.002637922 0.006419718 0.0588752 0.002497613 0.006863534 0.05893033 0.002196192 0.006850183 0.05902463 0.002430737 0.00710839 0.05904078 0.002043724 0.006987869 0.05891555 0.001906037 0.007167041 0.05905359 0.001690447 0.006994962 0.05894011 0.001521766 0.007117211 0.05906546 0.001369178 0.006871044 0.05895113 0.001232087 0.006978929 0.0590831 0.001111865 0.006568193 0.05897521 9.57278e-4 0.006705522 0.05909442 8.59496e-4 0.006345808 0.05911189 7.20126e-4 0.006194591 0.05898857 8.61784e-4 0.005864858 0.05912971 7.56999e-4 0.005796551 0.05901253 9.63599e-4 0.00547564 0.05915111 0.001009464 0.005461275 0.05905926 0.001261651 0.005284011 0.05916488 0.001295566 0.005201101 0.05916821 0.001624643 0.005356669 0.05905282 0.001709818 0.005245327 0.05919355 0.002003788 0.005466639 0.05907851 0.002114236 0.005424201 0.05921 0.002316534 0.005747795 0.05909425 0.002400338 0.005697369 0.05921685 0.002551555 0.00597614 0.05923479 0.00265944 0.006272256 0.05914705 0.002537131 0.006378829 0.05924957 0.002663314 0.006747424 0.05914312 0.002305507 0.006805598 0.0592665 0.002470552 0.006986618 0.05919194 0.001977384 0.006998896 0.05928415 0.002259016 0.007155597 0.05929803 0.001862704 0.006976068 0.05921953 0.001401484 0.007153153 0.05931204 0.001504123 0.007038116 0.05932641 0.001209139 0.006825923 0.05934077 9.46123e-4 0.006670176 0.05924367 0.001007199 0.006555318 0.05934941 7.81426e-4 0.006208598 0.05926704 8.52575e-4 0.006187975 0.05936598 7.10399e-4 0.005857646 0.05938094 7.67648e-4 0.005765855 0.05926227 9.79034e-4 0.005571305 0.05939733 9.23112e-4 0.005459547 0.0592826 0.001289367 0.005338072 0.05940455 0.001193583 0.005353629 0.05930662 0.001674413 0.005207538 0.0594235 0.001557826 0.00523287 0.05944156 0.001953244 0.005431056 0.05931985 0.002040028 0.00539726 0.05945515 0.002281427 0.00570625 0.05934375 0.002374291 0.005644857 0.0594666 0.002522468 0.006180882 0.05939263 0.002536475 0.006013095 0.05948895 0.00266546 0.006389856 0.05949646 0.002658367 0.006726026 0.05942004 0.002353489 0.006803035 0.05952501 0.00247395 0.007107079 0.05953717 0.002063691 0.006945252 0.05940932 0.002033829 0.007169246 0.05955553 0.001661956 0.007009029 0.05946379 0.001525342 0.007098913 0.05957055 0.001331686 0.006809353 0.05948472 0.001134455 0.006922721 0.05958384 0.00103712 0.006654977 0.05959624 8.27695e-4 0.006368398 0.05950927 8.653e-4 0.006308317 0.05961048 7.19714e-4 0.005961596 0.05962711 7.33597e-4 0.005815625 0.05953633 9.3856e-4 0.00558561 0.05964547 9.0996e-4 0.005445718 0.05953013 0.0013116 0.005301833 0.05964452 0.001241743 0.005357682 0.05955439 0.001598238 0.005206227 0.05968201 0.001825213 0.005388319 0.05959272 0.001951396 0.005417585 0.05970573 0.002331256 0.005668759 0.05961728 0.002370178 0.005854487 0.05972671 0.002625465 0.006211936 0.0596441 0.002537906 0.006255269 0.05974924 0.002684772 0.006696164 0.05966901 0.002365529 0.006740868 0.05976653 0.00251311 0.007017493 0.05978268 0.00222212 0.006998777 0.05969429 0.001925826 0.007168829 0.05979377 0.001831471 0.006962716 0.059722 0.001359105 0.007109522 0.05982315 0.00134164 0.006909191 0.05983471 0.001029133 0.006641745 0.05971938 0.001001715 0.00655651 0.05985254 7.75155e-4 0.00616616 0.05976915 8.4869e-4 0.006042122 0.05986815 7.10934e-4 0.005740106 0.05979049 9.89064e-4 0.005530774 0.05989867 9.49107e-4 0.005448698 0.05979245 0.001298546 0.005284428 0.05991417 0.001297414 0.005340516 0.05983453 0.001777231 0.005192995 0.05993175 0.00173062 0.005315363 0.05994284 0.002170145 0.005539417 0.05983155 0.002216339 0.005624949 0.05997079 0.002508223 0.005877494 0.05985468 0.002465665 0.005981683 0.0599842 0.002658784 0.006169199 0.05986279 0.002524495 0.006337046 0.05999481 0.002668142 0.006545841 0.05988627 0.002439379 0.006718575 0.06001859 0.002529323 0.006847798 0.05990517 0.002198815 0.007035791 0.06003642 0.00219798 0.007153093 0.06004297 0.001890301 0.006982266 0.05991137 0.00192219 0.007014393 0.05996221 0.001549959 0.007149875 0.06006252 0.001489877 0.0069772 0.06007957 0.001102983 0.00682193 0.0599839 0.001150369 0.006654977 0.06009531 8.28864e-4 0.006559252 0.05997401 9.51646e-4 0.006227672 0.06011539 7.02273e-4 0.006059706 0.06002414 8.63356e-4 0.005757272 0.06013822 8.06069e-4 0.005762696 0.06000828 9.80936e-4 0.00540781 0.06015676 0.001079618 0.00547409 0.06003481 0.001269102 0.00527805 0.06014823 0.001317143 0.005354523 0.06005305 0.001673042 0.005198538 0.06017935 0.001616299 0.00529313 0.0602011 0.002130746 0.005436003 0.06007546 0.002047717 0.005577445 0.06021457 0.00247085 0.00570023 0.06011861 0.002380967 0.00584656 0.06022709 0.002620518 0.005943238 0.06010413 0.002487361 0.006310462 0.06024384 0.002678573 0.00644958 0.06015586 0.002499341 0.00678879 0.06026649 0.002483367 0.006855964 0.06015485 0.002186894 0.007035136 0.06028497 0.002201318 0.007035791 0.06020575 0.0016855 0.007181406 0.06030589 0.001695156 0.006995916 0.06032729 0.001119434 0.006858348 0.06023091 0.001196086 0.006556987 0.06024968 9.4313e-4 0.00662887 0.06035274 8.12363e-4 0.006225109 0.06036037 7.10934e-4 0.006276965 0.06023424 8.67087e-4 0.005928397 0.06037807 7.43082e-4 0.005811929 0.06026285 9.51213e-4 0.005593478 0.06039589 9.03122e-4 0.005559563 0.06027513 0.001148998 0.005320429 0.06040936 0.001224756 0.005341768 0.06032764 0.001629829 0.005202174 0.06042218 0.001591265 0.005228698 0.06043958 0.001920163 0.005467832 0.06035214 0.002134084 0.005350649 0.06045079 0.002220153 0.005586147 0.0604676 0.002482771 0.005843639 0.06035399 0.002454876 0.005953371 0.06048476 0.002651214 0.006341934 0.06040042 0.002536058 0.0063048 0.06049758 0.002673268 0.00660479 0.06050729 0.002584755 0.006875813 0.06043118 0.002184271 0.006868898 0.06052327 0.002400755 0.007120072 0.06053751 0.002034902 0.007011532 0.06042432 0.001790106 0.007166028 0.06055939 0.001558661 0.006906867 0.06047815 0.001243889 0.006921112 0.06058162 0.001030743 0.006519079 0.06050199 9.28916e-4 0.006451725 0.0606001 7.37095e-4 0.006155252 0.06049221 8.64915e-4 0.005972027 0.06062686 7.25943e-4 0.005745291 0.06050908 9.90615e-4 0.005549848 0.06064569 9.37801e-4 0.005476832 0.06055718 0.001223385 0.005283415 0.06066811 0.001290798 0.005195975 0.06067806 0.001705825 0.005351722 0.06058943 0.001885116 0.005286514 0.06069397 0.002098143 0.005496323 0.06071269 0.002400815 0.005684137 0.06059247 0.002357184 0.005845963 0.06072765 0.002620577 0.006074309 0.06061202 0.002516508 0.006175041 0.06074208 0.002679407 0.006575465 0.0606622 0.002444565 0.006560325 0.06075829 0.002608358 0.006898522 0.06077283 0.002376794 0.006963789 0.06068903 0.002028822 0.007123589 0.06079643 0.002009391 0.007178723 0.06079757 0.001652479 0.00698179 0.0606873 0.001449704 0.007026433 0.06082642 0.001175284 0.006803154 0.06073504 0.001116216 0.006772398 0.06084191 9.05148e-4 0.006303846 0.06073242 8.71322e-4 0.006413221 0.06086421 7.30504e-4 0.006076276 0.06077319 8.64271e-4 0.006051421 0.06085711 7.2163e-4 0.005539059 0.06089282 9.38352e-4 0.00561285 0.06079781 0.001068234 0.005243837 0.06091576 0.001384794 0.00535345 0.06082427 0.001561403 0.0052073 0.06093335 0.00181812 0.005418956 0.06084769 0.002042829 0.005339026 0.06094956 0.00220555 0.005758762 0.06084549 0.00240755 0.005614221 0.06096708 0.002496659 0.005954742 0.06098425 0.002657413 0.006023168 0.06088548 0.002513825 0.006436765 0.06090515 0.002498865 0.006494045 0.06100213 0.002639234 0.006800174 0.06092607 0.002263545 0.006838858 0.06102204 0.002431154 0.007071852 0.06104087 0.002128064 0.006973147 0.06091791 0.001963198 0.007172405 0.06104713 0.001751303 0.006972908 0.06097018 0.001378417 0.007097423 0.06107145 0.001316189 0.006872236 0.06108593 9.90693e-4 0.006601691 0.06099766 9.61978e-4 0.00660479 0.06109905 8.02638e-4 0.006092429 0.06099498 8.68895e-4 0.006140351 0.06111913 7.03132e-4 0.005827903 0.06103587 9.35862e-4 0.005638837 0.06114459 8.69433e-4 0.005462348 0.06105858 0.001257479 0.00535506 0.06115764 0.001161813 0.005223035 0.06116759 0.001458287 0.005346834 0.06108218 0.00172472 0.005219101 0.06118971 0.001901328 0.005425035 0.06106805 0.002022981 0.005359709 0.06119889 0.002236187 0.005667269 0.06109207 0.002343416 0.005597829 0.06121456 0.002484023 0.005929768 0.06123089 0.002649247 0.005954563 0.06110358 0.002490639 0.006392717 0.06115341 0.002512931 0.006428122 0.06125169 0.002659022 0.006773173 0.06114757 0.002277076 0.006839632 0.06126993 0.002432823 0.006964147 0.06116598 0.001981139 0.007037222 0.06128287 0.002191483 0.007174134 0.06130266 0.001819908 0.007011771 0.06121206 0.001557826 0.007091104 0.06132292 0.001306116 0.006839096 0.06120419 0.001188635 0.006864249 0.06133085 9.77156e-4 0.006580591 0.06122231 9.66595e-4 0.006591916 0.0613529 7.94631e-4 0.006166338 0.06123608 8.5974e-4 0.006219387 0.06136649 7.11705e-4 0.005948007 0.06127935 8.90055e-4 0.00584644 0.06138068 7.65671e-4 0.005674779 0.06126874 0.001040399 0.00550121 0.06139713 9.88177e-4 0.00526911 0.06141263 0.001317203 0.005376636 0.06131911 0.001452624 0.005200684 0.06143677 0.001708805 0.005366683 0.06130856 0.001822888 0.005268096 0.0614435 0.00206089 0.005540251 0.06133121 0.002220749 0.005457162 0.0614587 0.002359926 0.005825757 0.06147825 0.002617299 0.00598973 0.0613836 0.002520442 0.006181538 0.06149196 0.002681195 0.006514608 0.06150597 0.00262618 0.00649023 0.0614081 0.002475321 0.00684607 0.06152135 0.002428054 0.006764173 0.06139695 0.002291858 0.007047832 0.06153237 0.002180159 0.00703758 0.06145262 0.001740634 0.007174491 0.06155556 0.001713216 0.007103145 0.06156295 0.00132519 0.006859242 0.06148123 0.00119245 0.006816983 0.0615952 9.31754e-4 0.00654751 0.06150037 9.42404e-4 0.006382286 0.06160628 7.22936e-4 0.006147146 0.06151962 8.52121e-4 0.005866885 0.0616284 7.58018e-4 0.005647778 0.06154561 0.001043021 0.005497694 0.06164741 9.87516e-4 0.005374968 0.06154394 0.001503705 0.005261063 0.06166476 0.001341044 0.005371987 0.06155937 0.001862645 0.005201816 0.06168162 0.001782596 0.00544691 0.06160014 0.00209254 0.005320489 0.06170934 0.002180635 0.005554556 0.06171244 0.002456188 0.005812227 0.06162524 0.00245738 0.005935192 0.06173229 0.002654969 0.006461262 0.0616557 0.002503335 0.006317079 0.06174665 0.00266993 0.006643772 0.06176167 0.002568066 0.006936192 0.06177759 0.002341628 0.006893575 0.06165933 0.002131521 0.007129728 0.06179159 0.00198394 0.007026553 0.06170845 0.001635968 0.007169723 0.06180262 0.001616597 0.007041513 0.06182497 0.001201808 0.006904959 0.06169849 0.001280725 0.0066545 0.0617184 0.001015126 0.006781518 0.06184047 9.10904e-4 0.006424009 0.06185626 7.32076e-4 0.006313621 0.06173586 8.74953e-4 0.005903303 0.06175565 9.14696e-4 0.005940556 0.06188094 7.30409e-4 0.005521535 0.06189602 9.67148e-4 0.005576968 0.06177282 0.001133084 0.005319833 0.06190973 0.001231431 0.005374789 0.06181895 0.001458406 0.005198478 0.06193 0.001605689 0.005405902 0.06184619 0.002031087 0.005241632 0.06194007 0.001989185 0.005436718 0.06195694 0.002333223 0.005770087 0.06187266 0.002426445 0.00573343 0.06197667 0.002577066 0.006090402 0.06198745 0.002682387 0.006319046 0.06189966 0.002535521 0.006478369 0.06200063 0.00263828 0.006869375 0.0620191 0.002409338 0.006754517 0.06190049 0.002298295 0.006988048 0.06194382 0.001938223 0.007098972 0.06203782 0.002068817 0.007177531 0.06205415 0.001712381 0.007000923 0.0619359 0.00155425 0.007071137 0.06208252 0.001245319 0.006863474 0.06198108 0.001191198 0.006773471 0.06208306 8.95794e-4 0.006392955 0.06197261 8.8258e-4 0.006216704 0.0620169 8.54407e-4 0.006371021 0.06210976 7.25161e-4 0.005923211 0.06212753 7.36711e-4 0.005794644 0.06203728 9.53052e-4 0.005516469 0.06215023 9.64804e-4 0.005515158 0.06202924 0.001211047 0.005215704 0.06216543 0.001461923 0.005384922 0.06204402 0.001494407 0.005370318 0.06206226 0.001857101 0.005208671 0.06218928 0.001865267 0.005615532 0.06211429 0.002329766 0.005396246 0.06220722 0.002288997 0.005643188 0.06221801 0.002513527 0.00599128 0.06223022 0.002664089 0.006217896 0.06214445 0.00254327 0.006335675 0.0622493 0.002672791 0.006729066 0.06217074 0.002337217 0.006676912 0.06226223 0.002548456 0.006906151 0.06227648 0.0023669 0.006985604 0.06219339 0.001951515 0.0070858 0.06228727 0.002094388 0.007175385 0.06230258 0.00170511 0.006983458 0.06218761 0.001466512 0.007108628 0.06232011 0.001339972 0.006852209 0.06220805 0.001199662 0.006851732 0.0623362 9.6065e-4 0.006530106 0.06225132 9.25298e-4 0.006533145 0.06235373 7.64204e-4 0.006023705 0.06224781 8.79184e-4 0.006022453 0.06237703 7.15188e-4 0.005729734 0.06226897 0.00100249 0.005605041 0.06238949 9.01111e-4 0.005455374 0.06228065 0.001300752 0.005331516 0.06240683 0.001186609 0.005359649 0.06230288 0.001605629 0.005198776 0.0624324 0.001589477 0.00544399 0.06235146 0.002112805 0.0052616 0.06244343 0.002044439 0.005505263 0.06246376 0.002413272 0.005883693 0.06237822 0.002482354 0.005865097 0.0624721 0.002632677 0.006444931 0.06240493 0.002503156 0.00632292 0.06249886 0.002673685 0.006745159 0.06251442 0.00250858 0.006908714 0.06243431 0.002133667 0.007052361 0.06253588 0.002177536 0.007024168 0.06245845 0.001627564 0.007177174 0.06256216 0.001594066 0.006957888 0.06243985 0.001385927 0.006965398 0.06258195 0.001085042 0.006672978 0.06249308 0.001011908 0.006643235 0.06259441 8.17153e-4 0.006253778 0.06251502 8.56341e-4 0.006266832 0.06261593 7.15021e-4 0.005943417 0.06262207 7.40686e-4 0.005707025 0.06254178 9.91114e-4 0.005624592 0.0626406 8.82493e-4 0.005392551 0.06266009 0.00111258 0.005383789 0.06256872 0.001442015 0.005246102 0.06266504 0.001401722 0.005201816 0.06268227 0.001816987 0.005374193 0.06259149 0.001927316 0.005358934 0.06270509 0.002233207 0.005712687 0.06262004 0.002402722 0.005615651 0.06271922 0.002497553 0.005919575 0.06273347 0.002647936 0.00624454 0.06264567 0.002532601 0.006213128 0.06274181 0.002679288 0.006621956 0.06275194 0.002589046 0.006745815 0.06267195 0.002334296 0.006939232 0.06277799 0.002333045 0.007021546 0.06269961 0.001816809 0.007111489 0.06279063 0.002028644 0.007176578 0.0628069 0.001615762 0.006949365 0.0626958 0.001370131 0.00694859 0.06281566 0.001072287 0.006652891 0.06272095 0.001004517 0.006756424 0.06284284 8.84067e-4 0.006388366 0.06286013 7.24511e-4 0.006347417 0.06273186 8.79854e-4 0.005943357 0.06287783 7.36719e-4 0.005858182 0.06278443 9.19314e-4 0.005578458 0.06289863 9.17733e-4 0.005603134 0.06277203 0.001101016 0.005287706 0.06290864 0.001268148 0.005350649 0.0628246 0.001565456 0.005201399 0.06293106 0.001701653 0.005294919 0.06294965 0.002132713 0.005435585 0.0628491 0.00207895 0.005563914 0.06296014 0.002470672 0.005725324 0.06287014 0.002394378 0.005963504 0.06298202 0.00265187 0.00595659 0.06285291 0.002494215 0.006305277 0.06299519 0.002677083 0.006370604 0.06287395 0.00250566 0.006816506 0.06300359 0.002454638 0.006824254 0.06292724 0.002248764 0.007126033 0.06302678 0.001994132 0.007036149 0.06295531 0.001681983 0.007178485 0.06305527 0.001723706 0.00706011 0.06307715 0.001227319 0.006833136 0.06298321 0.00115776 0.006691753 0.06309336 8.43404e-4 0.006357491 0.06301015 8.62298e-4 0.006250977 0.06311219 7.08943e-4 0.00583738 0.06301218 9.42013e-4 0.005941867 0.06313312 7.38203e-4 0.005481243 0.06314766 9.91202e-4 0.005527675 0.06302541 0.001188039 0.005248546 0.06316733 0.001390993 0.005371272 0.06304925 0.001544058 0.00520575 0.0631867 0.001866221 0.005402445 0.06309682 0.002025008 0.005440354 0.0632103 0.002349615 0.005748689 0.06312137 0.002410233 0.005839288 0.06322038 0.002625346 0.006284058 0.06314694 0.002543449 0.006351232 0.06325149 0.002672135 0.006779789 0.06326967 0.002481102 0.006837248 0.06317824 0.002235412 0.007012069 0.06328153 0.002233803 0.007174313 0.06329959 0.001780152 0.006981372 0.06316971 0.001924693 0.007000744 0.06321561 0.001490771 0.007110655 0.06331628 0.001359939 0.006769061 0.0632373 0.001089632 0.006917238 0.06333523 0.001030087 0.006579637 0.06334966 7.92961e-4 0.00640732 0.06323027 8.96533e-4 0.006196618 0.06336408 7.0551e-4 0.005974888 0.06325769 8.88626e-4 0.005790233 0.06338506 7.8551e-4 0.005684375 0.06326222 0.00102812 0.005365788 0.06341028 0.001133084 0.005426764 0.06328958 0.001365423 0.005196332 0.06342446 0.001635193 0.005356192 0.06330829 0.0017699 0.005298614 0.06345117 0.002137005 0.005476176 0.06332474 0.002124428 0.005592584 0.06346088 0.002486526 0.00580573 0.06335204 0.002438306 0.005953609 0.06348454 0.002653062 0.00637573 0.06340175 0.00252074 0.006467819 0.06350249 0.002650499 0.006779551 0.06342494 0.002283513 0.006958723 0.06353014 0.002316772 0.00701785 0.06344807 0.001858413 0.007156074 0.06354564 0.001873314 0.007154881 0.06356233 0.001526951 0.006912589 0.06347656 0.001257181 0.007010757 0.06357729 0.00115168 0.006704866 0.06359606 8.56036e-4 0.006516158 0.06350207 9.23924e-4 0.006294012 0.06361353 7.11476e-4 0.006087899 0.06349831 8.73015e-4 0.005892515 0.06362926 7.53782e-4 0.005731046 0.06354129 9.92113e-4 0.005638897 0.06364023 8.73721e-4 0.00532943 0.06365704 0.001194477 0.005397856 0.06356543 0.001374065 0.005196213 0.06368148 0.001666963 0.005384564 0.06359308 0.001963734 0.005282163 0.06369513 0.002108991 0.005561411 0.06371462 0.002461552 0.005690217 0.06359362 0.002363681 0.005850076 0.06372648 0.002618551 0.005983054 0.06360596 0.002498686 0.006328642 0.06374329 0.002681851 0.006434261 0.06365483 0.002498865 0.00682491 0.06376993 0.002452611 0.006801962 0.06364971 0.002253293 0.007112085 0.06379765 0.002052009 0.007021546 0.06369966 0.001823902 0.007171094 0.06380337 0.00163412 0.006927013 0.06372499 0.001294851 0.007051587 0.06382203 0.001225233 0.006831526 0.06384384 9.47878e-4 0.0065943 0.0637483 9.61339e-4 0.006463527 0.06384897 7.48783e-4 0.006297111 0.06373649 8.7283e-4 0.006111264 0.06387084 7.08215e-4 0.005822777 0.06378597 9.35778e-4 0.005771696 0.06388509 8.02475e-4 0.005463957 0.06390374 0.001020491 0.005488932 0.06380701 0.001227617 0.005263566 0.0639168 0.001341581 0.005355894 0.0638253 0.00158447 0.005202233 0.06392467 0.001623809 0.005276799 0.06394153 0.002096414 0.005426228 0.06384932 0.002075016 0.00562191 0.0639711 0.002512514 0.005872011 0.06387805 0.00248301 0.006036043 0.0639835 0.002667367 0.006392955 0.06390321 0.002508819 0.006376981 0.06399881 0.002664208 0.0067932 0.06401818 0.002478063 0.006721854 0.06389307 0.002323865 0.006953001 0.06393921 0.002033174 0.00710994 0.06403928 0.002058386 0.007003486 0.06393653 0.001544415 0.007168412 0.06406605 0.001598358 0.007083356 0.06407034 0.001284718 0.006816029 0.06398493 0.001125574 0.006825625 0.06409096 9.3936e-4 0.006486713 0.06410294 7.5145e-4 0.006265759 0.06401413 8.50227e-4 0.00617063 0.06411671 7.10958e-4 0.005837261 0.0641312 7.74288e-4 0.005776405 0.06403839 9.64219e-4 0.005446493 0.06415122 0.001028597 0.00557661 0.06402307 0.001137554 0.00539714 0.06404358 0.001434445 0.005221009 0.06416344 0.001482009 0.00539118 0.06409513 0.002005696 0.00520724 0.06418865 0.001864135 0.005432426 0.06420594 0.002338707 0.005640506 0.06408625 0.002318263 0.005800426 0.06422817 0.002609729 0.006031751 0.0641359 0.002521693 0.00632286 0.06424552 0.00267601 0.006513893 0.06415903 0.002470493 0.006676018 0.06426328 0.002550959 0.006828665 0.06415402 0.002212285 0.006944239 0.06427693 0.002329409 0.006998419 0.06417059 0.001867949 0.007114708 0.06429183 0.002021491 0.007172346 0.06431221 0.001619994 0.006984829 0.06421804 0.001441359 0.007027983 0.06432127 0.001177191 0.006679415 0.06424337 0.001002311 0.006736278 0.06434321 8.75075e-4 0.006337344 0.06436008 7.15521e-4 0.006175875 0.0642687 8.57261e-4 0.005909502 0.06437647 7.49514e-4 0.005760669 0.06425869 9.82365e-4 0.005628824 0.06438899 8.78841e-4 0.00550127 0.0643059 0.001198351 0.005422055 0.06440311 0.00107032 0.005209803 0.06442862 0.00154525 0.005356073 0.06430214 0.001676261 0.005444884 0.06432259 0.00206995 0.005747675 0.06437259 0.002419888 0.006220281 0.0643953 0.002531349 0.006954073 0.06444329 0.002032101 0.00673151 0.05869591 0.001043677 0.006284415 0.05870324 8.61064e-4 0.005924642 0.05871087 8.86338e-4 0.005571842 0.05874657 0.00110495 0.00534439 0.0587756 0.001633107 0.005489826 0.05880302 0.002181589 0.005914628 0.05882769 0.002489626 0.006730496 0.05886912 0.002340078 0.005458891 0.05900704 0.001267552 0.006100416 0.05908668 0.002533555 0.006470203 0.05910468 0.002478063 0.006971478 0.05913984 0.001979112 0.007014751 0.05916053 0.001540422 0.00679481 0.05918347 0.001117348 0.006299495 0.05921036 8.49649e-4 0.006077527 0.05933558 0.002534329 0.006612122 0.05936211 0.002422571 0.007029235 0.05940485 0.001659274 0.006805539 0.05943405 0.001112341 0.006250441 0.05946314 8.51418e-4 0.005727231 0.05948889 9.86994e-4 0.005452752 0.05954891 0.002107858 0.005885243 0.05957674 0.002494096 0.006563246 0.05960899 0.002459645 0.006938815 0.0596351 0.002062737 0.007024466 0.0596556 0.001646757 0.006904661 0.05967432 0.001272082 0.006096959 0.05971968 8.44663e-4 0.00557518 0.05974829 0.001116216 0.005353868 0.05978375 0.001805424 0.006976902 0.05991822 0.001378297 0.006238102 0.05996316 8.51716e-4 0.005578041 0.06005847 0.002272427 0.006389141 0.06010127 0.002523422 0.007031023 0.0601536 0.001686275 0.006814777 0.06018346 0.001122772 0.00541073 0.06026291 0.001382946 0.005348086 0.060283 0.001795649 0.005570113 0.06030869 0.002274334 0.006407678 0.06035131 0.002510905 0.006822466 0.06037509 0.002241611 0.006954908 0.06041932 0.001364231 0.006652176 0.06044274 9.89441e-4 0.005385875 0.06051421 0.001404762 0.005393564 0.0605427 0.00198704 0.006519496 0.06060707 0.002476572 0.006985127 0.06063824 0.001998066 0.006667852 0.06069165 0.001001358 0.005791008 0.06073516 9.48112e-4 0.005474627 0.06075632 0.0012542 0.005344986 0.06077611 0.001642405 0.005476593 0.06080114 0.002158105 0.00623089 0.06084293 0.002536535 0.006682693 0.06086623 0.002371907 0.007024645 0.06090921 0.001574218 0.006835818 0.06093025 0.001172602 0.006482303 0.06095135 9.02371e-4 0.00562787 0.06099486 0.001063048 0.005356132 0.06102025 0.001523315 0.00641489 0.06110203 0.0025056 0.007013261 0.0611611 0.001529395 0.005423724 0.06126046 0.001328825 0.00584048 0.06132382 0.002455294 0.006279647 0.06134545 0.0025357 0.006955265 0.061387 0.002029418 0.007016956 0.06141108 0.001541197 0.006722509 0.06143832 0.001038551 0.006203293 0.06146514 8.52724e-4 0.005645155 0.06149363 0.001034677 0.005592703 0.06155979 0.00229597 0.006002962 0.06158196 0.002512395 0.00648117 0.06160539 0.002488493 0.007024228 0.06165057 0.001751065 0.00536108 0.06177031 0.001528501 0.005408346 0.06179428 0.002026319 0.005791127 0.06182181 0.002445757 0.006330251 0.06184804 0.002524375 0.00697112 0.06188845 0.002004086 0.006807625 0.06193268 0.001126646 0.005840897 0.06198269 9.2386e-4 0.005586206 0.06205916 0.002284646 0.006034374 0.06208449 0.002527236 0.006502568 0.06210637 0.002470076 0.006837368 0.06212604 0.002225816 0.007017493 0.06214791 0.001810073 0.006465256 0.06220257 9.02003e-4 0.005421459 0.06229513 0.002036809 0.005679368 0.06231516 0.002367973 0.006113767 0.06233727 0.002531111 0.006634831 0.06236368 0.002417266 0.007001638 0.06239277 0.001921713 0.006681382 0.06244134 0.001008987 0.006180763 0.06246602 8.53419e-4 0.005678892 0.06249135 0.001015961 0.00536853 0.06251847 0.001481592 0.005420804 0.06254637 0.002068281 0.005769133 0.06256991 0.002419471 0.006230592 0.0625928 0.002543509 0.006705462 0.06261771 0.002351582 0.007001876 0.06264275 0.001933395 0.006003856 0.06272464 8.77617e-4 0.005403697 0.06276339 0.001389145 0.00535345 0.06278353 0.001802623 0.005528628 0.06280523 0.002223312 0.006860613 0.06287795 0.002216517 0.0070225 0.06290215 0.001717329 0.006938159 0.0629217 0.001324176 0.006655931 0.06294256 9.99726e-4 0.006247818 0.06296277 8.58026e-4 0.00540775 0.06304526 0.002028524 0.005802929 0.06307214 0.002450764 0.006344318 0.06309825 0.002523064 0.006761074 0.06312108 0.002305567 0.007022738 0.06315571 0.001648902 0.006844758 0.0631805 0.00116074 0.006102323 0.06333673 0.00253582 0.006580948 0.06336051 0.002435207 0.006913185 0.06338274 0.002118587 0.007026076 0.06340754 0.001603186 0.00685513 0.06342881 0.001195311 0.00649333 0.06345081 9.06658e-4 0.005631983 0.06349408 0.001049637 0.005371689 0.06351852 0.001494944 0.005383253 0.06354123 0.001959562 0.006369113 0.06360018 0.002516865 0.007009506 0.06364607 0.001844108 0.006985127 0.06366568 0.001437962 0.006727635 0.06368786 0.001052379 0.006046116 0.06372237 8.69548e-4 0.005670905 0.0637421 0.001029968 0.005361199 0.06376814 0.001484751 0.005404829 0.06379294 0.001999318 0.005681037 0.06381559 0.002372145 0.00625056 0.06384426 0.002544522 0.006993472 0.06389105 0.001947522 0.006765604 0.06393557 0.001083433 0.006358206 0.06395739 8.74992e-4 0.005913496 0.0639792 8.97472e-4 0.005359828 0.06403851 0.001890301 0.006042242 0.06408435 0.002533078 0.006567716 0.0641095 0.002442002 0.006956875 0.06417 0.001346111 0.00664407 0.06419253 9.95691e-4 0.006203532 0.06421476 8.48705e-4 0.005454838 0.06425791 0.001281917 0.005811631 0.06432288 0.002456426 0.00639075 0.06435102 0.002515375 0.006835341 0.06437587 0.002230942 0.007033407 0.06440228 0.001718461 0.005239546 0.05869847 0.001988172 0.005320072 0.05869632 0.001266658 0.005484163 0.05870914 0.002389848 0.006549894 0.05886739 7.77153e-4 0.005252003 0.05968183 0.001366138 0.007058322 0.06058895 0.001241564 0.005824625 0.06089729 7.75015e-4 0.007078111 0.06283724 0.001284956 0.006634771 0.0630269 0.002572 0.007005274 0.06304657 0.0022372 0.00697571 0.06468492 0.001932859 0.007034122 0.06466752 0.001644253 0.007130444 0.06456661 0.001788079 0.006543934 0.06469166 0.002404689 0.007157206 0.06444567 0.00184077 0.007061183 0.06454133 0.002092897 0.00690639 0.0646401 0.002224206 0.006861746 0.06453913 0.002379059 0.006637454 0.0646485 0.002457201 0.00620073 0.06469255 0.002474308 0.006386816 0.06455796 0.002629995 0.006332039 0.06464689 0.002566576 0.006003677 0.06466811 0.00252211 0.005589783 0.0646944 0.002211868 0.00602746 0.06455177 0.002642691 0.005756199 0.06464266 0.002476096 0.005727887 0.06445163 0.002566933 0.005478262 0.06464987 0.002218186 0.005560398 0.06455165 0.002422451 0.005407929 0.06453698 0.002262949 0.005346417 0.06466335 0.001870214 0.005408108 0.06469112 0.001479089 0.005301475 0.06455969 0.002058029 0.00523144 0.0644356 0.001957058 0.005270659 0.0646159 0.001701593 0.005218088 0.06450718 0.001583397 0.005283474 0.06457585 0.001417517 0.00542277 0.06464266 0.001233339 0.006134629 0.06469196 8.95357e-4 0.005347073 0.06450438 0.001198053 0.00568521 0.06467807 0.001034975 0.005545854 0.06455194 9.8162e-4 0.005875885 0.06462055 8.27377e-4 0.005861937 0.0645346 7.85045e-4 0.006218492 0.06453871 7.31583e-4 0.00659722 0.06468987 0.00100708 0.006440877 0.06462746 8.21472e-4 0.006601333 0.06455767 8.33275e-4 0.006899416 0.06461805 0.001115262 0.006924211 0.06468558 0.001334607 0.006912231 0.06453347 0.001053273 0.007108747 0.06455808 0.001440167 0.006597876 0.05752593 9.83061e-4 0.007020831 0.05752712 0.001719951 0.005774438 0.0575245 9.80788e-4 0.005361914 0.05752521 0.001693665 0.00577265 0.05752557 0.002407371 0.006622195 0.05752265 0.002410471 0.006627738 0.05680638 9.31027e-4 0.005745112 0.05680632 9.29358e-4 0.006624996 0.05680638 0.002460598 0.007065296 0.05680721 0.001693606 0.005742251 0.05680632 0.002458989 0.005302131 0.05680632 0.001693308 0.004640877 0.05679512 6.42062e-4 0.005161583 0.05679512 1.37084e-4 0.005982577 0.05679512 -1.76401e-4 0.004309415 0.05679512 0.001538991 0.004510819 0.05679512 0.002536356 0.006940722 0.05679512 -1.59131e-5 0.007651388 0.05679512 5.25822e-4 0.005011558 0.05679512 0.003143191 0.005664229 0.05679512 0.003491222 0.008061408 0.05679512 0.001507222 0.00658822 0.05679512 0.003529191 0.007903873 0.05679512 0.002419412 0.007448673 0.05679512 0.003078937 0.004368424 0.05869513 0.002124905 0.004812479 0.05869513 0.002989828 0.005591809 0.05869513 0.003461241 0.006278395 0.05869513 0.003560721 0.007250249 0.05869513 0.003256976 0.0078426 0.05869513 0.002544641 0.008045136 0.05869513 0.001881062 0.007987916 0.05869513 0.001235961 0.00772202 0.05869513 6.29018e-4 0.006988108 0.05869513 -7.54922e-6 0.00609225 0.05869513 -1.68718e-4 0.005259573 0.05869513 6.10629e-5 0.004653334 0.05869513 6.32782e-4 0.00435096 0.05869513 0.001324176 0.01523452 0.06444197 -0.007434546 0.01515203 0.06444519 -0.007667899 0.01546084 0.06443309 -0.00712043 0.01487076 0.06444483 -0.0076406 0.01478683 0.06444513 -0.007779955 0.01552325 0.06444549 -0.006694495 0.01443815 0.06444519 -0.007666468 0.01562398 0.06444805 -0.006505548 0.01537317 0.06443846 -0.006326615 0.01528137 0.06444936 -0.006013393 0.0140891 0.06444501 -0.007584214 0.01387733 0.06444174 -0.00734812 0.01511996 0.06443184 -0.006076335 0.01372498 0.06444156 -0.007011234 0.01485192 0.06444597 -0.005835056 0.01462471 0.0644446 -0.005872786 0.01427936 0.06444913 -0.005902528 0.01391655 0.06444191 -0.006194055 0.01414728 0.0586996 -0.005981922 0.01455038 0.05873829 -0.00583136 0.01490563 0.05874967 -0.005841493 0.01467645 0.05869507 -0.005877077 0.01552706 0.05870163 -0.006898581 0.01521819 0.05876535 -0.005979299 0.01511967 0.05869501 -0.006021082 0.01551055 0.05877846 -0.00626111 0.01540732 0.05869537 -0.006345212 0.0156672 0.0588026 -0.006677269 0.01560586 0.05882024 -0.007165551 0.0154224 0.05883193 -0.007460534 0.01535332 0.05870866 -0.007301807 0.01492214 0.05875635 -0.007625281 0.01504993 0.05885106 -0.007727742 0.0145576 0.05887347 -0.007784962 0.01436901 0.05878341 -0.007581532 0.01409518 0.05888992 -0.007603883 0.01396757 0.05880844 -0.007258236 0.01378673 0.05891489 -0.007214665 0.01370114 0.05892533 -0.006841778 0.01385021 0.05881339 -0.006802201 0.013749 0.05894225 -0.006505727 0.01390844 0.05882108 -0.006502628 0.01391619 0.05895996 -0.006182968 0.01425677 0.05884766 -0.006088614 0.01429694 0.05897611 -0.00589329 0.0145685 0.05888724 -0.005971491 0.01469045 0.05899113 -0.005817472 0.01510584 0.05891317 -0.006067574 0.015105 0.05901175 -0.005910694 0.0154637 0.05901789 -0.006185889 0.01545941 0.05891627 -0.006503403 0.01564544 0.05904561 -0.006566584 0.01551395 0.05896574 -0.007010281 0.01566064 0.05906444 -0.00695914 0.01549214 0.05908071 -0.007377505 0.01523333 0.05896425 -0.007423937 0.01514881 0.05909305 -0.007675886 0.01487773 0.058981 -0.007613778 0.01477628 0.05911493 -0.007789134 0.01450061 0.05899971 -0.007610321 0.01439452 0.05913305 -0.007744133 0.01422369 0.0590412 -0.007507801 0.01410341 0.05913954 -0.007600367 0.0138815 0.05915445 -0.007372677 0.01389211 0.05906611 -0.007103383 0.01370167 0.05917412 -0.006950259 0.01389062 0.05909502 -0.006507515 0.0137704 0.05919218 -0.006430149 0.01398354 0.05921727 -0.006114482 0.01427704 0.05912286 -0.006063342 0.01426845 0.05922341 -0.005909204 0.01468878 0.05924183 -0.005814611 0.01472097 0.05912071 -0.005977869 0.01515835 0.05925822 -0.00593698 0.0152294 0.05917054 -0.006147861 0.01545459 0.05928134 -0.006189346 0.01563555 0.05928885 -0.006542026 0.01550638 0.05919754 -0.006631553 0.01566308 0.05931317 -0.006990134 0.01548057 0.05921876 -0.007081031 0.01540952 0.05933374 -0.007481455 0.01513296 0.05924642 -0.007528722 0.01503688 0.05935597 -0.007728338 0.01463228 0.05924528 -0.007632553 0.01452004 0.05937558 -0.007784903 0.01419538 0.05926215 -0.007480382 0.01411241 0.05939275 -0.007610559 0.01399338 0.05930685 -0.007278263 0.01383644 0.05940818 -0.007317483 0.01369714 0.05942273 -0.006890952 0.01388257 0.05928832 -0.007029473 0.0138902 0.05931884 -0.006566226 0.01375937 0.05944138 -0.006474733 0.01398217 0.05945724 -0.006105244 0.01404821 0.05932849 -0.006277203 0.01434606 0.05937665 -0.006039381 0.01429158 0.05947756 -0.005895793 0.01486474 0.05940192 -0.005972623 0.01468831 0.05949693 -0.005820512 0.01510804 0.05951219 -0.005908012 0.01542466 0.05952328 -0.006145358 0.01535207 0.05942946 -0.006289422 0.01566493 0.05954688 -0.006634831 0.01553714 0.05945754 -0.006865203 0.01561361 0.05956798 -0.007138788 0.01523131 0.0594902 -0.007457315 0.0153892 0.05958795 -0.007497906 0.01513922 0.05959773 -0.007679045 0.01481032 0.05961173 -0.007781624 0.01491802 0.05947488 -0.007605314 0.01441389 0.05962747 -0.007758617 0.01445198 0.05950278 -0.007603108 0.01403456 0.05964076 -0.007543146 0.01411479 0.05952227 -0.007402598 0.01387256 0.05956918 -0.0070495 0.01382726 0.05966013 -0.007291257 0.01371687 0.05967289 -0.006982505 0.01372009 0.05968946 -0.006600141 0.01389706 0.05959439 -0.006513357 0.01387035 0.05970299 -0.006251811 0.01421266 0.059601 -0.006113886 0.01409518 0.0597189 -0.006016969 0.01450324 0.05973541 -0.005827963 0.01476335 0.0596466 -0.005959689 0.0148074 0.05973148 -0.005831003 0.01511096 0.0597608 -0.005912423 0.01518255 0.05964541 -0.006138265 0.01544821 0.05978012 -0.006177008 0.01541095 0.05965566 -0.006397306 0.01563894 0.05979484 -0.006551563 0.01552122 0.05970913 -0.006884276 0.01564538 0.05981308 -0.007063329 0.01537847 0.05970269 -0.007258236 0.01539349 0.05983346 -0.007492005 0.0149542 0.05975514 -0.007613837 0.01503527 0.05985814 -0.007730782 0.01461315 0.05986833 -0.007791996 0.01445299 0.05977952 -0.007607281 0.01416075 0.05989056 -0.007641732 0.01405805 0.05980145 -0.007374048 0.01389306 0.05990421 -0.007392346 0.01375257 0.05991518 -0.007118523 0.01383274 0.05983114 -0.006794154 0.01370191 0.05993008 -0.006709396 0.01382565 0.05995357 -0.006316542 0.0140146 0.05985629 -0.006304383 0.01421362 0.05997204 -0.00592786 0.01436311 0.05987721 -0.006025969 0.01474004 0.05999809 -0.005816936 0.01492023 0.05990403 -0.005989313 0.01507496 0.06000477 -0.005894482 0.01546418 0.06003028 -0.006192743 0.01530885 0.05992662 -0.006248295 0.01551681 0.05994826 -0.006650865 0.01562178 0.06004226 -0.006506145 0.01567232 0.06005018 -0.006808638 0.01547425 0.05994182 -0.007064044 0.01557791 0.06007134 -0.007229924 0.01514017 0.05999553 -0.007523715 0.01528692 0.06009101 -0.007590115 0.01490563 0.0601086 -0.007766783 0.01461434 0.06002163 -0.007641315 0.0144596 0.06012952 -0.007767677 0.01417589 0.06004399 -0.007476866 0.01404207 0.06014102 -0.007559001 0.01397633 0.06003242 -0.007239758 0.01377946 0.06016129 -0.007195055 0.01384431 0.06008195 -0.00677067 0.01369678 0.06017613 -0.006875813 0.01374739 0.06019383 -0.006475269 0.01390987 0.06006592 -0.006507992 0.01418483 0.06011742 -0.006128311 0.01397222 0.06021171 -0.006121516 0.01430279 0.06022667 -0.005895137 0.01467716 0.06011027 -0.005969226 0.01463752 0.06024008 -0.005824148 0.01493275 0.06015503 -0.0059973 0.01499485 0.060256 -0.005866885 0.01534128 0.06027096 -0.006068885 0.01537358 0.06018096 -0.006314277 0.01559871 0.06028383 -0.006427168 0.01551175 0.06017452 -0.006731152 0.01567834 0.06031101 -0.006761312 0.0155667 0.06032198 -0.007251679 0.01542085 0.06022596 -0.007217228 0.01531195 0.06033748 -0.007566452 0.01519203 0.06021279 -0.007465481 0.01498007 0.060359 -0.007745027 0.01475578 0.060265 -0.007639169 0.01458305 0.0603649 -0.007789552 0.01431179 0.0602861 -0.007562279 0.01419687 0.06039017 -0.007661998 0.01385551 0.06041067 -0.007344782 0.01392078 0.06031304 -0.007168412 0.01371514 0.0604189 -0.00701034 0.0138747 0.06030905 -0.006603956 0.01372826 0.06043398 -0.006576001 0.0139603 0.06035131 -0.00638169 0.01386225 0.06045329 -0.0062595 0.01429897 0.06037455 -0.006055057 0.01417768 0.06046855 -0.005951941 0.01472973 0.06048989 -0.005817472 0.0148223 0.06039941 -0.005971074 0.01507955 0.06050938 -0.005904078 0.01530504 0.06039708 -0.006247639 0.01540356 0.06052285 -0.006126821 0.01547682 0.06042051 -0.006539285 0.0156216 0.06053769 -0.006491422 0.01565229 0.06056046 -0.00701934 0.01551222 0.06046134 -0.006922125 0.01535034 0.0604822 -0.007326781 0.01544642 0.06057548 -0.00743848 0.01513487 0.06046539 -0.007505774 0.01511371 0.06060099 -0.007699429 0.01467669 0.06051826 -0.00764513 0.0146889 0.06061732 -0.007791221 0.01437872 0.0606305 -0.007739067 0.01423728 0.06050938 -0.007507026 0.01407599 0.06064504 -0.007578253 0.01402193 0.06053215 -0.007308781 0.01384472 0.0606566 -0.00731939 0.01383554 0.06057804 -0.006852388 0.01370573 0.06067639 -0.006936192 0.01376718 0.06069093 -0.006424844 0.01396822 0.06057476 -0.006386578 0.01404368 0.06071794 -0.006056547 0.01429021 0.06062358 -0.006065547 0.01443278 0.06073194 -0.005848288 0.01464861 0.06061512 -0.005980312 0.0148347 0.0607441 -0.005829989 0.01509493 0.06066298 -0.006058335 0.01519221 0.06076383 -0.005960881 0.01549929 0.06077796 -0.006240069 0.0154246 0.06066095 -0.006429374 0.01565355 0.06079655 -0.006598651 0.01552182 0.06070637 -0.00681734 0.01564556 0.06081598 -0.007060289 0.0154258 0.06072539 -0.007202565 0.01542079 0.06083756 -0.00746119 0.01499682 0.0607534 -0.007601737 0.01504874 0.06085366 -0.007726907 0.01469534 0.06086707 -0.007792651 0.01439768 0.06078201 -0.007595837 0.01434355 0.06087797 -0.007728636 0.01403135 0.06089586 -0.007543027 0.01393932 0.06080967 -0.0072214 0.01379054 0.06091618 -0.007222175 0.01371198 0.06090807 -0.00694102 0.01385599 0.06083661 -0.006679117 0.01370149 0.06093746 -0.006679534 0.01401519 0.0608561 -0.006301999 0.01387786 0.06095349 -0.006236016 0.01438355 0.06085526 -0.006030023 0.01423513 0.06097686 -0.005921006 0.01472008 0.06098973 -0.005817115 0.01479661 0.060871 -0.005984663 0.01514637 0.06089055 -0.006114482 0.015087 0.06100857 -0.005906283 0.01540797 0.06102526 -0.006125092 0.01548165 0.06094133 -0.006515622 0.01565325 0.06104791 -0.006591677 0.01548653 0.06096827 -0.007067322 0.01562356 0.06107056 -0.007127702 0.01538604 0.06108444 -0.007500112 0.01530337 0.06095433 -0.007362484 0.01509582 0.06109964 -0.007702112 0.01486849 0.06100904 -0.007629692 0.01462841 0.06111866 -0.007795631 0.01442176 0.06103098 -0.007599115 0.01418411 0.06113868 -0.007655501 0.01406347 0.06105113 -0.007373869 0.01383131 0.06115877 -0.007312357 0.01388549 0.06104105 -0.007033348 0.01369875 0.06117808 -0.006862044 0.01387923 0.06107014 -0.00660026 0.01377081 0.06119173 -0.006419718 0.01412332 0.06111419 -0.006176233 0.01406359 0.06121891 -0.006038486 0.01445919 0.06122905 -0.005836844 0.01447427 0.06110417 -0.006002545 0.01484674 0.06115078 -0.005978882 0.01502996 0.06126016 -0.005874454 0.01525384 0.06115049 -0.006200909 0.01535367 0.06127178 -0.006082952 0.01559358 0.06128293 -0.006403446 0.01546818 0.06116318 -0.006534039 0.0155127 0.06118649 -0.00687319 0.01566874 0.06131261 -0.006888449 0.01553916 0.06132525 -0.00730884 0.01539462 0.06119608 -0.007229387 0.01515924 0.06121969 -0.007486641 0.01527529 0.06134152 -0.007595777 0.01486194 0.06135761 -0.007780313 0.0147686 0.06123971 -0.007629334 0.01441639 0.06137919 -0.007753729 0.01446777 0.0612505 -0.007603287 0.0140255 0.06139397 -0.007543146 0.01402294 0.06130385 -0.007338285 0.0137754 0.06141573 -0.007185459 0.0138486 0.06132841 -0.006849706 0.01369833 0.06142681 -0.006794452 0.01387423 0.06130945 -0.00662142 0.01378238 0.06144464 -0.006407737 0.01409667 0.06136232 -0.006206989 0.01395082 0.06146383 -0.006146252 0.01422768 0.06147253 -0.005935907 0.01445847 0.06135475 -0.006008148 0.01452928 0.06148338 -0.005831658 0.01485168 0.06140124 -0.005982935 0.01489794 0.06150031 -0.00584203 0.01529353 0.06142514 -0.006216108 0.01521956 0.06151455 -0.00598073 0.01554316 0.06154024 -0.006296873 0.01566135 0.06154584 -0.006639957 0.01550406 0.06144738 -0.006633877 0.01561373 0.06157094 -0.007165789 0.01547545 0.06147092 -0.007111608 0.01538181 0.061585 -0.007512032 0.01512795 0.06149578 -0.007520556 0.0149818 0.06160098 -0.007748663 0.01465851 0.06149089 -0.007636606 0.01454097 0.06162774 -0.007781267 0.0142768 0.06153821 -0.007545351 0.0141645 0.06163066 -0.007647097 0.01388823 0.06156623 -0.007098853 0.01383441 0.06165766 -0.007315158 0.01369577 0.06168514 -0.006875336 0.01389491 0.06159496 -0.006502151 0.0137844 0.06169158 -0.006383597 0.01429611 0.06162452 -0.006048381 0.01408487 0.06171464 -0.006024837 0.01443237 0.06173104 -0.005843997 0.01475751 0.06162041 -0.005977869 0.01509046 0.06174844 -0.005898296 0.01523292 0.06167119 -0.006158292 0.01556652 0.06178534 -0.006349146 0.01549315 0.06167006 -0.006617009 0.01567745 0.06180381 -0.006798744 0.01548826 0.06171798 -0.007070124 0.01561164 0.06180256 -0.007131695 0.01549988 0.06183016 -0.007368803 0.01516157 0.06172102 -0.007485985 0.01512992 0.06184858 -0.00769329 0.01486676 0.06173127 -0.007615029 0.01464611 0.06186705 -0.007794499 0.01440614 0.06176036 -0.007591664 0.01427215 0.06188362 -0.007709324 0.01400637 0.06180572 -0.007298529 0.0138421 0.06190741 -0.007322549 0.01373529 0.06190276 -0.007065534 0.01385784 0.06180202 -0.006864666 0.01369386 0.06193149 -0.006799519 0.01392745 0.0618487 -0.006417632 0.01380443 0.06194841 -0.006353437 0.01407051 0.06196397 -0.006031155 0.0143491 0.06187689 -0.006033062 0.01439756 0.06198173 -0.00585711 0.01482623 0.06187474 -0.005987703 0.01480424 0.06199514 -0.005826532 0.01507866 0.06201118 -0.005898058 0.01513409 0.06188893 -0.006111145 0.01546001 0.06203013 -0.006187617 0.01540511 0.06190764 -0.006388366 0.01564806 0.06204599 -0.006589412 0.01551711 0.06193256 -0.006840169 0.0156607 0.06205719 -0.006935119 0.01549983 0.06207698 -0.007373929 0.01535993 0.06195008 -0.007293999 0.01510047 0.061998 -0.007539808 0.01511704 0.06209814 -0.007695257 0.0145846 0.06199985 -0.007630884 0.01477497 0.0621131 -0.007788419 0.01425385 0.06213194 -0.007696628 0.01415526 0.06204521 -0.007460176 0.01393949 0.06215155 -0.007443964 0.01390337 0.06204032 -0.007074594 0.01375973 0.0621671 -0.007152736 0.01369708 0.06218314 -0.006739199 0.01384866 0.06208443 -0.00671935 0.01380056 0.06219571 -0.006366491 0.01398903 0.0621041 -0.006341457 0.01403898 0.06221348 -0.006056964 0.01425677 0.06212192 -0.006084382 0.01449531 0.06223511 -0.005830883 0.01475298 0.06214654 -0.005958795 0.01492744 0.06225258 -0.005846679 0.01535826 0.06227028 -0.006072402 0.01523929 0.06214749 -0.006188273 0.01552146 0.06219655 -0.006632685 0.01564383 0.06229197 -0.006546795 0.01564669 0.06231057 -0.007016777 0.01546645 0.06219303 -0.007089495 0.01550984 0.06232857 -0.007351577 0.01521188 0.06224119 -0.007454812 0.01514548 0.06234884 -0.007683694 0.01476365 0.06226468 -0.007650256 0.01456618 0.06237393 -0.00779426 0.01413577 0.06229573 -0.007459998 0.0140202 0.06239628 -0.00754255 0.01376247 0.06241381 -0.007153153 0.0138632 0.06232291 -0.006969034 0.0137034 0.06243753 -0.00665456 0.01390665 0.0623157 -0.006516158 0.01401746 0.06235635 -0.006298363 0.01388382 0.0624569 -0.006227612 0.01415771 0.06246 -0.005966663 0.01444655 0.06238216 -0.005988121 0.01451408 0.06248605 -0.00583148 0.01495248 0.06250309 -0.005850255 0.01501089 0.06240862 -0.006029009 0.01533627 0.06251937 -0.006061375 0.01538908 0.06240761 -0.006361126 0.01554912 0.06253921 -0.00632441 0.0155332 0.06245708 -0.006839573 0.01567089 0.06254839 -0.006762981 0.01563006 0.06256639 -0.007093966 0.01531428 0.06246131 -0.00734812 0.01543724 0.06258314 -0.007451117 0.01499557 0.06247383 -0.007572948 0.01489698 0.06260734 -0.00777626 0.01457911 0.06249696 -0.007629573 0.01439982 0.06262868 -0.007751166 0.01415103 0.06254541 -0.00746268 0.01406574 0.06264352 -0.007575273 0.01381176 0.06265985 -0.007263302 0.01386654 0.06257116 -0.007002055 0.01370537 0.06267458 -0.006903111 0.01388436 0.0625925 -0.00655663 0.01372748 0.06268978 -0.006569325 0.01396483 0.06270623 -0.006117522 0.01418489 0.06261849 -0.006116688 0.01446962 0.06273311 -0.005836606 0.01476788 0.06264698 -0.005963206 0.01496279 0.06275343 -0.005855977 0.01524412 0.06267213 -0.006175518 0.01527571 0.06276971 -0.006018161 0.01551854 0.06278192 -0.006279528 0.01549124 0.06269395 -0.006569147 0.01566153 0.06279468 -0.00665605 0.0154944 0.06268513 -0.006988346 0.015643 0.0628243 -0.007069647 0.0153675 0.06270498 -0.007277846 0.01535958 0.062837 -0.007539153 0.01509726 0.06272095 -0.007522106 0.01499813 0.06285011 -0.007739245 0.01472467 0.06273835 -0.007636249 0.01452189 0.06287282 -0.00778383 0.01437109 0.06276035 -0.007574319 0.01412642 0.06289368 -0.00761491 0.01403528 0.06277471 -0.007319211 0.01389068 0.06290125 -0.007383584 0.0138598 0.0628215 -0.00700283 0.01370668 0.06292462 -0.006984531 0.01374727 0.06293755 -0.006509006 0.01392024 0.06281989 -0.006489634 0.0141133 0.06286346 -0.006187379 0.01390135 0.06295514 -0.006201922 0.01414036 0.06297212 -0.005984723 0.01445025 0.06288176 -0.006005883 0.01460826 0.06298613 -0.005812406 0.01486265 0.06290173 -0.005976915 0.01504284 0.06300866 -0.00588721 0.01518428 0.06288975 -0.00614202 0.01536142 0.06301879 -0.006088018 0.01546585 0.06294023 -0.006486058 0.01554393 0.06303453 -0.00631386 0.01566785 0.0630564 -0.006693542 0.0154947 0.06294101 -0.006993472 0.01560783 0.06306761 -0.00716418 0.0152834 0.06295841 -0.007380306 0.01535511 0.06308442 -0.007530391 0.01500773 0.0630024 -0.007576942 0.0149241 0.06310796 -0.007769048 0.01456683 0.06302386 -0.007641136 0.0144928 0.06312578 -0.007770001 0.01418304 0.06313544 -0.007650017 0.01434916 0.06300234 -0.007569074 0.01396352 0.06305915 -0.007237851 0.01387435 0.06315392 -0.00738126 0.01386332 0.06305271 -0.00690037 0.01369756 0.06317549 -0.006906509 0.01391094 0.06309634 -0.006474912 0.01377463 0.06320655 -0.006400823 0.01400697 0.06319659 -0.00608927 0.01411825 0.06308543 -0.006195306 0.01451569 0.06323128 -0.005827546 0.01460605 0.06313973 -0.005957722 0.01493304 0.0632525 -0.005853652 0.01508969 0.06313896 -0.006081104 0.01524567 0.06326276 -0.005995988 0.01553076 0.06328248 -0.006284415 0.01536297 0.06315439 -0.006324529 0.01549464 0.06316888 -0.006630599 0.01567661 0.06330102 -0.006772816 0.01548373 0.06318861 -0.00703442 0.01553857 0.06330984 -0.007295012 0.01529121 0.06321066 -0.007368147 0.0153113 0.06334006 -0.007576465 0.01490873 0.06325787 -0.007626056 0.01490676 0.06335771 -0.007770717 0.01457315 0.06337565 -0.007785797 0.01434093 0.06328457 -0.007573425 0.01419162 0.06338655 -0.007656872 0.01389789 0.06340265 -0.007404506 0.01395213 0.06331014 -0.007226288 0.01374328 0.06341868 -0.007084846 0.01384836 0.06333202 -0.00677365 0.0137009 0.06344127 -0.006664693 0.01394593 0.06332832 -0.006427168 0.01387876 0.06345319 -0.006230294 0.01422715 0.06337004 -0.006102561 0.01418888 0.06346964 -0.005953013 0.014481 0.06348526 -0.005842387 0.01461905 0.06339013 -0.005968034 0.01482921 0.06349754 -0.005829095 0.01497298 0.06337475 -0.006028234 0.01515823 0.06350958 -0.005940496 0.01524621 0.06339973 -0.006192445 0.01545876 0.06353014 -0.006190598 0.0154677 0.06341415 -0.006534934 0.01563692 0.06354278 -0.006548285 0.0155093 0.06343656 -0.006922364 0.01566308 0.06356477 -0.006966054 0.0155673 0.06356984 -0.007248222 0.01533722 0.06345427 -0.007316768 0.01532441 0.06358975 -0.007555603 0.01505446 0.06347554 -0.007545113 0.01508426 0.06360065 -0.007707118 0.01477146 0.06361436 -0.007784068 0.01460075 0.0635221 -0.007644951 0.01446539 0.06362575 -0.007767558 0.01418852 0.06363713 -0.007659375 0.01409423 0.06354838 -0.007411479 0.01382923 0.06365799 -0.007311582 0.01383322 0.06357908 -0.006840944 0.01369363 0.06368088 -0.006790637 0.01382428 0.06369274 -0.006319582 0.01400488 0.06360518 -0.006313145 0.01412737 0.06371927 -0.005980253 0.01416981 0.06358981 -0.006150603 0.01458746 0.06363844 -0.005973458 0.01454526 0.06373608 -0.005828738 0.01485115 0.06374901 -0.005831897 0.01500028 0.06365853 -0.006025075 0.01516413 0.06376153 -0.005940973 0.01542425 0.06368482 -0.006384074 0.01547819 0.06377846 -0.006205916 0.0156567 0.06379657 -0.006611585 0.01551026 0.06371492 -0.007005095 0.01566153 0.06381428 -0.006949305 0.01552188 0.06382536 -0.007325112 0.01522845 0.06374025 -0.007445156 0.01525884 0.06383979 -0.007611155 0.01485037 0.06376022 -0.007625758 0.01471477 0.06386089 -0.007796049 0.01445198 0.06375563 -0.007600724 0.01424986 0.06388831 -0.007691323 0.01418203 0.06379383 -0.007476806 0.01396238 0.06389945 -0.007474303 0.01390773 0.06379383 -0.007098317 0.01378428 0.0639134 -0.007211863 0.01370602 0.06392496 -0.006921648 0.01387006 0.06384116 -0.006584346 0.01372522 0.06393474 -0.006569147 0.01388764 0.06395214 -0.006228446 0.01406812 0.06383013 -0.006245136 0.01415354 0.06396949 -0.005971133 0.01447844 0.06388366 -0.005977809 0.01467394 0.06399583 -0.005807757 0.0149517 0.06388115 -0.006019592 0.0152325 0.06401693 -0.005978465 0.01529449 0.06389564 -0.006239473 0.0154438 0.06401163 -0.006184875 0.01548302 0.06391954 -0.006576061 0.01560312 0.06404167 -0.006435155 0.0155093 0.06396448 -0.006990611 0.01566791 0.06405729 -0.006844997 0.01559513 0.06406927 -0.007186591 0.01531243 0.06398445 -0.007355034 0.01541531 0.06408452 -0.007462382 0.01512801 0.06410068 -0.007686078 0.01497983 0.06400394 -0.007594764 0.01473015 0.06409978 -0.007792472 0.01456844 0.06402385 -0.007632195 0.01416003 0.06413817 -0.007644593 0.01420021 0.06404227 -0.007490336 0.01387894 0.06415492 -0.007375419 0.01394945 0.06406134 -0.007202148 0.01370131 0.06417506 -0.006935 0.01386594 0.06405007 -0.006896257 0.01389491 0.06406635 -0.00655198 0.01373714 0.0641908 -0.006521522 0.01392251 0.06420159 -0.006179988 0.01419693 0.06411886 -0.006109297 0.01422625 0.06422215 -0.005931735 0.01457202 0.06424301 -0.005824327 0.01457244 0.06410896 -0.005981981 0.01505601 0.06425774 -0.005883336 0.01502531 0.06413769 -0.006045162 0.01540929 0.06427627 -0.006128251 0.01540696 0.06418454 -0.006371736 0.0155816 0.06428408 -0.006388485 0.01552534 0.06420624 -0.00681883 0.01567351 0.06430709 -0.006825029 0.0155909 0.06432193 -0.007211029 0.01541084 0.06422632 -0.007223904 0.01531851 0.0643391 -0.007564485 0.01514363 0.06424504 -0.007505953 0.01503539 0.06434959 -0.007729709 0.0147261 0.06426656 -0.007647335 0.01457959 0.06437236 -0.007787168 0.0142191 0.06429117 -0.007509529 0.01416164 0.06439161 -0.007642805 0.01390409 0.06439989 -0.007403969 0.01389729 0.06431633 -0.007101416 0.01370209 0.06440842 -0.006928205 0.01385444 0.06433433 -0.006729006 0.01397532 0.06434965 -0.006356716 0.01409691 0.06432282 -0.00621277 0.01444786 0.06435441 -0.006011486 0.0148819 0.06440335 -0.005988299 0.01499301 0.05869781 -0.007588684 0.01452499 0.05870991 -0.007642328 0.01407182 0.05874657 -0.007395029 0.01403868 0.05880618 -0.006266057 0.01486098 0.05884921 -0.005972683 0.01529139 0.05887299 -0.006228744 0.01549738 0.05891537 -0.007041335 0.014131 0.05899441 -0.007435202 0.01389747 0.05901449 -0.007092595 0.01385909 0.05903637 -0.006641685 0.01401859 0.05905395 -0.006303191 0.01429396 0.05907177 -0.006060719 0.01510536 0.05911183 -0.006076574 0.01540935 0.05913269 -0.006382465 0.01552945 0.05915474 -0.006834089 0.01534485 0.05918008 -0.007331252 0.01499527 0.05920058 -0.00758022 0.01441198 0.05932754 -0.006003558 0.01498311 0.05935591 -0.006012916 0.01537925 0.05937951 -0.006331324 0.0155344 0.05940538 -0.006857514 0.01532161 0.05943173 -0.007352292 0.01383531 0.05952262 -0.006918728 0.0140087 0.05955421 -0.00629884 0.0147047 0.05959194 -0.0059641 0.01552945 0.05965387 -0.006818175 0.01511746 0.0596944 -0.007527947 0.01459771 0.05971974 -0.007646679 0.01417332 0.05974191 -0.007466495 0.01387965 0.05976527 -0.00707215 0.0139082 0.05979561 -0.006463408 0.01425051 0.0598191 -0.006088435 0.01462548 0.05983787 -0.005970537 0.01506149 0.05985915 -0.00604844 0.01547682 0.05988866 -0.006489574 0.01524615 0.05993711 -0.007442593 0.01473814 0.05996328 -0.007644891 0.01431459 0.0599839 -0.0075562 0.01385998 0.06002098 -0.006957292 0.01418113 0.06006616 -0.00612235 0.01527756 0.06012105 -0.00618577 0.01547211 0.06016743 -0.007094621 0.01472944 0.06021451 -0.007654666 0.01420724 0.06023985 -0.00749576 0.0138933 0.06026405 -0.0071038 0.01419824 0.06031668 -0.006108582 0.0146529 0.06033921 -0.005970597 0.01502037 0.06035715 -0.006036341 0.01547503 0.06041771 -0.007104277 0.01473808 0.06046342 -0.007649898 0.01384526 0.06052637 -0.006846368 0.01426547 0.06057047 -0.00607115 0.01508092 0.06061047 -0.006057918 0.0155254 0.06065922 -0.006918489 0.0152769 0.0606848 -0.007404983 0.01476478 0.06071227 -0.007651627 0.01424694 0.06073755 -0.007520616 0.01393991 0.06075948 -0.007194578 0.01384824 0.06078559 -0.006661653 0.01410526 0.0608105 -0.00619769 0.01542955 0.06088423 -0.006416976 0.01552492 0.06090748 -0.006889164 0.01482141 0.06095904 -0.007644712 0.01420593 0.06099027 -0.00750643 0.01401019 0.0610544 -0.006290853 0.01497781 0.06110477 -0.006013631 0.01412308 0.0612449 -0.007431447 0.0138852 0.06126624 -0.007053613 0.0140382 0.06130689 -0.006257832 0.01493054 0.06135237 -0.005996346 0.01533275 0.06137573 -0.006270885 0.01552689 0.06139975 -0.006723344 0.01543629 0.06142121 -0.007171988 0.01515138 0.06144249 -0.007510423 0.01421403 0.06148952 -0.007497608 0.01391899 0.06151151 -0.007155478 0.01385384 0.06153422 -0.0066787 0.01402825 0.06155508 -0.006283879 0.014333 0.06157338 -0.006046414 0.01525866 0.06162077 -0.006176173 0.01546645 0.06166923 -0.007131755 0.01416325 0.0617426 -0.007465362 0.01391339 0.06176251 -0.007128357 0.01396244 0.06179994 -0.006366312 0.01438593 0.06182664 -0.006015002 0.01492071 0.06195485 -0.007617115 0.01410263 0.06199592 -0.007418274 0.01385903 0.06203603 -0.006641387 0.0141291 0.06206291 -0.006165266 0.01456469 0.06208473 -0.005977392 0.01496887 0.06210446 -0.006014287 0.01549971 0.06214284 -0.006587684 0.01525783 0.06218641 -0.007437348 0.01477169 0.06221151 -0.007637143 0.01429969 0.06223446 -0.007560074 0.01392096 0.06226092 -0.007160127 0.01385158 0.06228059 -0.00676155 0.01417815 0.0623151 -0.006132841 0.01468157 0.06234043 -0.005958497 0.01512473 0.06236267 -0.006093382 0.01552647 0.06241011 -0.006933987 0.0140627 0.06249868 -0.007383227 0.01384776 0.06252497 -0.006879687 0.01395666 0.06254941 -0.006374478 0.01447182 0.06258064 -0.005974233 0.01510632 0.06261187 -0.0060727 0.01547336 0.06263846 -0.006495535 0.01384341 0.06277513 -0.006869435 0.01423132 0.06281846 -0.006088793 0.01474976 0.06284409 -0.005966484 0.015504 0.06289237 -0.006576538 0.01485949 0.06295752 -0.007629394 0.01403295 0.06300097 -0.007338345 0.01386845 0.06303763 -0.006614744 0.01459878 0.06308704 -0.005964279 0.01491653 0.06320494 -0.007613897 0.01450741 0.06322419 -0.007622778 0.01413983 0.0632441 -0.007443249 0.01385319 0.06327033 -0.006982207 0.01409554 0.06330984 -0.006206989 0.0145176 0.06333273 -0.005978941 0.0146991 0.06346553 -0.007646381 0.01411956 0.06349378 -0.007449805 0.01385748 0.06352186 -0.006936371 0.01389247 0.06354171 -0.006528675 0.01436346 0.0635755 -0.006029486 0.01488149 0.06360071 -0.005979061 0.01540172 0.06363081 -0.006345748 0.01552164 0.06365883 -0.006923556 0.01525205 0.06368744 -0.007437586 0.01472938 0.06371366 -0.007646381 0.01406854 0.06374859 -0.007374525 0.01385229 0.06378376 -0.006697833 0.01449525 0.06383162 -0.005987524 0.01547259 0.06391882 -0.007116913 0.01514244 0.06394302 -0.007509887 0.01459592 0.06396955 -0.007653295 0.01401841 0.06400257 -0.007333755 0.01412326 0.06406205 -0.00617814 0.01530903 0.0641244 -0.006234228 0.01553839 0.06415396 -0.006807684 0.01531487 0.06418257 -0.007366061 0.01483893 0.06420832 -0.007637619 0.01436197 0.06423175 -0.00757718 0.01397538 0.06425499 -0.007269442 0.01384598 0.06428426 -0.006681323 0.01490062 0.06435114 -0.005988419 0.01530963 0.0643742 -0.006243407 0.01550805 0.06439518 -0.006637752 0.01374453 0.05869877 -0.006488919 0.01381999 0.05869632 -0.007233202 0.01408934 0.05873304 -0.006011068 0.01440697 0.06049621 -0.005862772 0.01566743 0.06056839 -0.006755113 0.01472973 0.06175959 -0.005824208 0.01538866 0.06178957 -0.006118416 0.01402282 0.06191235 -0.007533848 0.01448202 0.06214112 -0.007766902 0.01510584 0.06261485 -0.00769329 0.01419693 0.06323689 -0.00595045 0.01563864 0.06333065 -0.007063031 0.01499938 0.06386965 -0.007735848 0.0145936 0.06413686 -0.007792055 0.01545619 0.06469506 -0.006869077 0.01552814 0.06467509 -0.00684309 0.01561957 0.06459105 -0.00677061 0.01517367 0.06469035 -0.006168842 0.01538133 0.06467783 -0.006360471 0.0155375 0.06461626 -0.0064556 0.0154463 0.06452655 -0.006204664 0.01526033 0.06462377 -0.006100535 0.01495945 0.06465929 -0.005984723 0.01475501 0.06468862 -0.006002962 0.01506119 0.06454777 -0.005924105 0.01478642 0.06457269 -0.005860805 0.01414906 0.0646941 -0.00623095 0.01452314 0.06466817 -0.005974948 0.01444131 0.06458288 -0.005896806 0.01460719 0.06450939 -0.005837798 0.01422697 0.06465357 -0.006059527 0.0143373 0.06452411 -0.005902469 0.01415586 0.06457155 -0.00602132 0.0139364 0.06463307 -0.006307661 0.01392495 0.06453466 -0.006206214 0.01387846 0.06468385 -0.006640553 0.01379996 0.06459826 -0.006526052 0.01375633 0.0644477 -0.006477653 0.01404953 0.06469476 -0.00725764 0.0137155 0.06452423 -0.006786704 0.01377373 0.0646187 -0.006811738 0.01390254 0.06466072 -0.007176935 0.01378661 0.06455916 -0.007137596 0.01393908 0.06453806 -0.007414102 0.01414173 0.06461107 -0.007554709 0.01431405 0.06467509 -0.007552206 0.01458942 0.06468999 -0.007595539 0.01432096 0.06451153 -0.007703661 0.01452845 0.06461107 -0.007712781 0.01512521 0.06469178 -0.007462382 0.01454401 0.06445252 -0.007779538 0.01493048 0.06465822 -0.00764358 0.01487398 0.06455737 -0.007744252 0.01512187 0.06464141 -0.007578253 0.01513779 0.06454789 -0.007651329 0.01537936 0.06467682 -0.007254421 0.0153588 0.0645976 -0.007450759 0.01546001 0.064453 -0.007414877 0.01554071 0.06461155 -0.00714606 0.015612 0.06445384 -0.00713396 0.01567006 0.06445795 -0.006859004 0.01509809 0.05752521 -0.007517397 0.01552087 0.05752712 -0.006779968 0.01427471 0.05752521 -0.007518708 0.01386129 0.0575245 -0.006806254 0.01427292 0.05752623 -0.006093025 0.01512217 0.05752265 -0.006089448 0.01424515 0.05680632 -0.007570624 0.01512771 0.05680638 -0.007568955 0.01512497 0.05680638 -0.006039321 0.01556527 0.05680721 -0.006806313 0.01424217 0.05680608 -0.006040811 0.01380228 0.05680656 -0.006806612 0.01326781 0.05679512 -0.008055925 0.01416426 0.05679512 -0.008601188 0.0148707 0.05679512 -0.00865817 0.01286107 0.05679512 -0.007188737 0.01283979 0.05679512 -0.006541669 0.01555186 0.05679512 -0.008462369 0.0162748 0.05679512 -0.007813274 0.013148 0.05679512 -0.005718648 0.0139569 0.05679512 -0.005077004 0.01656186 0.05679512 -0.006804943 0.01487171 0.05679512 -0.004941582 0.01638287 0.05679512 -0.006038963 0.01584976 0.05679512 -0.005319952 0.0130831 0.05869513 -0.005807816 0.01376599 0.05869513 -0.005183279 0.01460677 0.05869513 -0.004924237 0.01555186 0.05869513 -0.005147576 0.01629418 0.05869513 -0.005821824 0.0165463 0.05869513 -0.006697356 0.01641708 0.05869513 -0.00753498 0.01585072 0.05869513 -0.008266329 0.01523423 0.05869513 -0.008584678 0.01435786 0.05869513 -0.008661806 0.01349663 0.05869513 -0.008244693 0.01297599 0.05869513 -0.007576227 0.01281929 0.05869513 -0.00674355 0.01579511 0.05869513 -0.00658971 0.01569235 0.05899512 -0.006278336 0.01558357 0.05869513 -0.006100535 0.01520192 0.05899512 -0.005776464 0.01513338 0.05869513 -0.00576514 0.0145809 0.05869513 -0.005668163 0.01450675 0.05899512 -0.005682587 0.01407939 0.05869513 -0.005850493 0.01399171 0.05899512 -0.005904614 0.01373559 0.05869513 -0.006180703 0.01359444 0.05899512 -0.006448388 0.01354432 0.05869513 -0.006767153 0.01358836 0.05899512 -0.007093667 0.01376211 0.05869513 -0.007492363 0.01391166 0.05899512 -0.00765264 0.01436787 0.05869513 -0.007898747 0.01452499 0.05899512 -0.007930099 0.0149008 0.05869513 -0.007916569 0.01513725 0.05899512 -0.007853269 0.0154432 0.05869513 -0.007663846 0.01557612 0.05899512 -0.007503867 0.01578813 0.05869513 -0.0070858 0.01582509 0.05899512 -0.006938278 0.01234042 0.05899512 -0.006570279 0.01239222 0.05869513 -0.006240248 0.01262992 0.05899512 -0.005595803 0.0128504 0.05869513 -0.005290627 0.01366817 0.05899512 -0.004648089 0.01369702 0.05869513 -0.004660069 0.01454854 0.05869513 -0.004443705 0.01486223 0.05899512 -0.004443645 0.01530629 0.05869513 -0.004532575 0.01576316 0.05899512 -0.004702448 0.01600199 0.05869513 -0.004840135 0.01659333 0.05899512 -0.005383968 0.01660096 0.05869513 -0.005427658 0.01697999 0.05869513 -0.006220638 0.01700365 0.05899512 -0.006355345 0.01700133 0.05869513 -0.007333636 0.01699817 0.05899512 -0.007332861 0.01654618 0.05899512 -0.008264899 0.0163787 0.05869513 -0.008483946 0.01597815 0.05899512 -0.00877422 0.01538205 0.05869513 -0.009063899 0.0151745 0.05899512 -0.009127974 0.01456767 0.05869513 -0.009161472 0.01423585 0.05899512 -0.009120166 0.01352775 0.05869513 -0.008889853 0.01336389 0.05899512 -0.008777201 0.01266473 0.05869513 -0.008039712 0.01273822 0.05899512 -0.008132517 0.01239055 0.05899512 -0.007389307 0.01234084 0.05869513 -0.007117807 0.006768941 0.06444096 -0.007405877 0.006601512 0.06444513 -0.007698416 0.006982088 0.06443148 -0.007062375 0.007106482 0.06445783 -0.007155478 0.006370663 0.06444483 -0.007640659 0.00607568 0.06444513 -0.007784247 0.005938112 0.06444519 -0.007666468 0.00697124 0.06444537 -0.006486356 0.00544089 0.06443375 -0.007431507 0.006643056 0.06443142 -0.006084859 0.006960928 0.06444531 -0.006205201 0.005311608 0.06443983 -0.007262647 0.006570279 0.06444603 -0.005896687 0.006021499 0.0644499 -0.005839645 0.005545973 0.0644471 -0.006058275 0.005834579 0.05871224 -0.005886316 0.006192028 0.05874323 -0.005818009 0.007027149 0.05870151 -0.006885647 0.006597459 0.05875545 -0.005904674 0.006390035 0.05869507 -0.005913615 0.006906688 0.05877906 -0.006138861 0.007113993 0.05878657 -0.006461262 0.006851673 0.05869489 -0.006234943 0.007160663 0.05881279 -0.006989836 0.006826877 0.05873376 -0.007350623 0.006961345 0.05883085 -0.007414102 0.006708383 0.05884522 -0.007638275 0.00636506 0.05875957 -0.00763303 0.006408929 0.05885738 -0.007761776 0.006075859 0.05887079 -0.007786333 0.005868971 0.05878341 -0.007581472 0.005763888 0.05888611 -0.007693767 0.005478501 0.05880755 -0.007271349 0.005499184 0.05889689 -0.007508575 0.005300998 0.05891454 -0.007243275 0.005202174 0.05892509 -0.006875157 0.005353808 0.0588057 -0.006832659 0.005269467 0.0589416 -0.006430387 0.005436837 0.05882066 -0.006455898 0.005662739 0.058842 -0.006159424 0.005465745 0.05896502 -0.006130516 0.005813002 0.05897694 -0.005890786 0.005963265 0.05885541 -0.006008923 0.006210744 0.05898869 -0.005816698 0.00630933 0.05887264 -0.00598222 0.006632447 0.05901688 -0.005924701 0.006717979 0.05892056 -0.006160259 0.006930708 0.05902558 -0.006154298 0.006948292 0.05893868 -0.006455957 0.007132589 0.05904322 -0.006507813 0.007020473 0.05895841 -0.006863415 0.007153093 0.05905336 -0.007038712 0.00685811 0.05898159 -0.007321238 0.006817042 0.05908662 -0.007565319 0.006393849 0.05900824 -0.007622122 0.006445467 0.05910623 -0.007758378 0.00609368 0.0591225 -0.007786154 0.005902588 0.05903184 -0.007597088 0.005810916 0.05913078 -0.007716238 0.00548619 0.05914652 -0.00750482 0.005578458 0.05902588 -0.007370889 0.005263984 0.05916643 -0.007153451 0.00533384 0.05907839 -0.006853342 0.005199134 0.05917888 -0.006753623 0.005281209 0.05919438 -0.006417334 0.005500197 0.05910497 -0.00631982 0.005459189 0.05920767 -0.006137907 0.005916476 0.05913054 -0.005999743 0.005954682 0.05923092 -0.005835115 0.006527245 0.05925625 -0.005872726 0.006450474 0.05915558 -0.006007909 0.006912171 0.05927544 -0.0061329 0.006874501 0.05918115 -0.006311058 0.007153928 0.05929374 -0.006578445 0.00701487 0.05920147 -0.006720662 0.006976068 0.05921953 -0.007098436 0.007123947 0.05932068 -0.007127821 0.006893813 0.05932939 -0.007503509 0.006603837 0.05924803 -0.007545948 0.006501436 0.05935454 -0.007737219 0.006098926 0.05936729 -0.007789313 0.006043791 0.05927455 -0.007634639 0.005731582 0.05938768 -0.007684588 0.005566596 0.05930089 -0.007384598 0.00544703 0.05940127 -0.00745362 0.005236268 0.05941611 -0.007091462 0.005339384 0.05932843 -0.006847262 0.00521326 0.05943614 -0.00661081 0.005501747 0.05932682 -0.006333529 0.005526661 0.0594629 -0.00605899 0.005678713 0.05936735 -0.006134629 0.005943477 0.05948096 -0.005840599 0.006199717 0.05939328 -0.005953371 0.006540715 0.05950492 -0.005873084 0.006688237 0.05941921 -0.006135284 0.006938159 0.05952662 -0.006171643 0.006990611 0.05944269 -0.00653696 0.007146775 0.05954688 -0.006561517 0.007163643 0.05955898 -0.006910264 0.006989836 0.05944091 -0.006988763 0.007082998 0.05956757 -0.007211208 0.006813883 0.05948483 -0.007369756 0.006802558 0.05958843 -0.007582426 0.006435215 0.0594784 -0.007599055 0.006412208 0.05961018 -0.007763862 0.006053626 0.05949819 -0.007621884 0.005968749 0.05962175 -0.007771313 0.005698978 0.05952 -0.007478058 0.005638599 0.0596435 -0.007630109 0.005342483 0.05965888 -0.00731486 0.005379557 0.05956834 -0.007065474 0.005191385 0.05967932 -0.006861805 0.00538659 0.05956554 -0.006582319 0.005311608 0.05969423 -0.006343066 0.005606353 0.05961334 -0.00619471 0.005564093 0.0597195 -0.006037592 0.006128132 0.0596404 -0.005953848 0.005942404 0.05973309 -0.005849361 0.006339788 0.05974787 -0.005824863 0.006680369 0.05966818 -0.006124973 0.006709694 0.05976474 -0.005973637 0.006967604 0.05977869 -0.006201922 0.006957352 0.05968958 -0.006474971 0.007103443 0.05977445 -0.006452322 0.00701636 0.05971163 -0.006938636 0.007167994 0.05980235 -0.006683468 0.007120132 0.05981558 -0.007123053 0.006830811 0.05970835 -0.007321059 0.006956875 0.05983877 -0.007425189 0.006566762 0.05972188 -0.007538318 0.006599724 0.05984675 -0.007700741 0.0061118 0.05977112 -0.007654249 0.006232023 0.05986744 -0.007788956 0.005912244 0.05987554 -0.007750272 0.005597054 0.05979889 -0.007406711 0.005572378 0.05989664 -0.0075773 0.005339443 0.05990791 -0.007313787 0.005350351 0.05982345 -0.00694549 0.005198657 0.05992436 -0.006884217 0.005261659 0.0599423 -0.006460547 0.005419313 0.0598191 -0.006492197 0.00542581 0.05995738 -0.006179809 0.005604267 0.05983626 -0.006217062 0.005776286 0.05997812 -0.00590074 0.0060395 0.05988609 -0.005964457 0.006224274 0.05999565 -0.005818188 0.006571829 0.0600056 -0.005896747 0.006601572 0.05991339 -0.006074547 0.00687766 0.06002306 -0.006103813 0.006935596 0.05990552 -0.006440937 0.007063269 0.06003636 -0.006361067 0.007007837 0.05994749 -0.006633877 0.007177293 0.06005299 -0.00678879 0.007006347 0.05993139 -0.006938815 0.007043957 0.06007826 -0.007300853 0.006741404 0.0599898 -0.007450222 0.006762504 0.06009131 -0.007606804 0.006433069 0.06010466 -0.007764816 0.006224572 0.06001609 -0.007643699 0.005986511 0.06012183 -0.007768511 0.005734384 0.06001901 -0.007507383 0.005676567 0.06014353 -0.007649362 0.005369722 0.06015837 -0.007369637 0.005437374 0.06003564 -0.007164776 0.005220949 0.06016558 -0.007041573 0.005343079 0.06008362 -0.006736397 0.005240738 0.06019431 -0.006500542 0.005594968 0.06007748 -0.006210625 0.005499839 0.06020432 -0.006091654 0.005782544 0.06012356 -0.006060063 0.005870819 0.06023085 -0.005865395 0.006311118 0.06014877 -0.005972564 0.006338298 0.06025266 -0.005829811 0.006666123 0.06026279 -0.005942642 0.00674051 0.06014347 -0.006186723 0.006926178 0.06027144 -0.006154894 0.006928324 0.0601865 -0.006417036 0.007161319 0.06029468 -0.006608366 0.00702697 0.06020873 -0.00686866 0.007119297 0.06031781 -0.007137715 0.006778359 0.06023752 -0.007418274 0.006816744 0.0603463 -0.007577359 0.006254971 0.06036216 -0.007796525 0.00616455 0.06026917 -0.007655322 0.005744397 0.06037932 -0.00769031 0.005691051 0.06029343 -0.007480204 0.005505502 0.06039899 -0.007526099 0.005413591 0.06029123 -0.007114887 0.005258798 0.06041812 -0.007151365 0.005202591 0.06043785 -0.006706655 0.005360126 0.06030809 -0.006724774 0.005289316 0.06044369 -0.006389081 0.005490601 0.06032407 -0.006354391 0.005528748 0.06046146 -0.00606805 0.005756974 0.0603457 -0.006093919 0.005824744 0.06047719 -0.005891859 0.006157517 0.06036239 -0.005972921 0.006215274 0.06049615 -0.005815207 0.006456613 0.06040632 -0.006009161 0.006647646 0.0605126 -0.005928397 0.00678724 0.06042516 -0.006227016 0.006946682 0.06052607 -0.006177842 0.006998717 0.06044495 -0.006578505 0.007106959 0.06053936 -0.006451249 0.007173001 0.06055551 -0.006873786 0.006939113 0.06047558 -0.007214546 0.007038414 0.06057298 -0.007299304 0.006751656 0.06059795 -0.007617294 0.006610691 0.06047189 -0.007521271 0.006338834 0.06060636 -0.007781505 0.006071925 0.06050235 -0.007632255 0.00588411 0.06063497 -0.007746696 0.005597591 0.06062656 -0.007593274 0.005561292 0.06055074 -0.007382929 0.005293548 0.06064659 -0.007224202 0.005393385 0.06053996 -0.007057964 0.005210936 0.06067669 -0.006953775 0.005389571 0.06059515 -0.006513237 0.00523591 0.06069391 -0.006531119 0.005431413 0.06070464 -0.006165504 0.00568962 0.06059187 -0.006140887 0.005798518 0.06073004 -0.005897283 0.006059467 0.06060922 -0.00598526 0.006211757 0.06074517 -0.005811274 0.006507337 0.06065827 -0.006024062 0.006533801 0.06075417 -0.005878567 0.006868004 0.06077158 -0.00609374 0.006857752 0.06068027 -0.00630635 0.00709635 0.06078857 -0.006416261 0.007025301 0.0607022 -0.006725907 0.007169425 0.06080782 -0.006863474 0.007094442 0.06082123 -0.007194399 0.00692141 0.06069952 -0.007184326 0.006892085 0.06083023 -0.00748974 0.006718575 0.06071329 -0.007433593 0.006432831 0.06072813 -0.007597029 0.006612896 0.06085103 -0.007691323 0.006287574 0.06086146 -0.007785856 0.006076335 0.06077319 -0.007635712 0.005795419 0.06088417 -0.007719695 0.005654931 0.06079524 -0.007460713 0.005386054 0.06090778 -0.007387161 0.005400478 0.06081688 -0.007095515 0.005235254 0.06091868 -0.007061898 0.005199313 0.06093066 -0.006761789 0.005356013 0.0608381 -0.006643176 0.005294084 0.06094563 -0.00636816 0.005638957 0.0608415 -0.006174385 0.00560075 0.06096434 -0.006012201 0.005918145 0.06088036 -0.006007373 0.005905151 0.06098419 -0.005859375 0.00629729 0.06099164 -0.005825996 0.006456553 0.06090581 -0.006001412 0.006624519 0.06101107 -0.005921423 0.006822705 0.0609281 -0.006266117 0.006946921 0.06103008 -0.006172239 0.007000029 0.06094592 -0.006603479 0.007140278 0.06104439 -0.006565868 0.007166326 0.06105852 -0.006901562 0.007002294 0.06093549 -0.006922483 0.007020294 0.06107974 -0.007339656 0.006876885 0.06095105 -0.007266223 0.006608724 0.06097263 -0.007517993 0.006645441 0.06109261 -0.007686078 0.006166636 0.061019 -0.007647931 0.006245017 0.0611155 -0.007785022 0.005924999 0.06112736 -0.007755696 0.005699038 0.061015 -0.007478654 0.005632579 0.06114196 -0.007619976 0.005457758 0.06105947 -0.0072245 0.005301535 0.06116372 -0.00726217 0.005342245 0.06108373 -0.006739556 0.005198776 0.06116431 -0.00679928 0.005388975 0.06119751 -0.006209015 0.005561828 0.06110984 -0.006234586 0.005767881 0.06122386 -0.005910515 0.00602591 0.06113588 -0.005976676 0.006142079 0.06124585 -0.005817592 0.006475806 0.06115722 -0.006018519 0.006583392 0.06125992 -0.005898296 0.006854712 0.06117922 -0.006292045 0.006915926 0.06126749 -0.006143271 0.007110834 0.06129276 -0.006453156 0.007036209 0.06120759 -0.006870329 0.007167816 0.06130647 -0.006859421 0.007052481 0.06132251 -0.007285475 0.00677812 0.06123715 -0.007403969 0.006803989 0.061342 -0.007572829 0.006299674 0.06123328 -0.007629573 0.006517052 0.06135421 -0.007728576 0.006192743 0.06136548 -0.00779128 0.005998909 0.06127679 -0.007625281 0.005880773 0.06137818 -0.007740497 0.00559014 0.06129944 -0.007397949 0.005585372 0.06139367 -0.007589101 0.005325257 0.06140798 -0.007289588 0.005340039 0.06132507 -0.006906211 0.005218684 0.06142491 -0.0069983 0.005236029 0.06143945 -0.006515622 0.005418539 0.0613166 -0.006500244 0.005597412 0.06133747 -0.006220519 0.005493998 0.0614674 -0.006098628 0.005846679 0.0614745 -0.005874037 0.005858957 0.06134802 -0.006044924 0.006219327 0.06136947 -0.005977809 0.006386697 0.06149893 -0.005832314 0.006558954 0.06138658 -0.006065011 0.006828844 0.06151795 -0.006057202 0.0069139 0.06143474 -0.006381094 0.007081568 0.06153649 -0.006378233 0.007010042 0.06142425 -0.006707131 0.007169067 0.06155669 -0.006738722 0.007121324 0.06156706 -0.00711137 0.006964981 0.0614404 -0.007092297 0.006913423 0.06158369 -0.007477283 0.006699621 0.06146764 -0.007457733 0.006541907 0.06160056 -0.007722556 0.006305515 0.06151235 -0.007633626 0.006143569 0.06161594 -0.00779587 0.005892097 0.06150764 -0.007580578 0.005564987 0.06163966 -0.00758022 0.005503714 0.06155538 -0.007310152 0.005304396 0.06166273 -0.007242381 0.005200386 0.06167829 -0.006875038 0.005353033 0.06155008 -0.006818413 0.005234241 0.06168866 -0.006530284 0.005425035 0.06157577 -0.006468474 0.005464494 0.06171262 -0.006128787 0.005796134 0.06162452 -0.006048381 0.005749762 0.06171822 -0.005911529 0.006250202 0.06174588 -0.005819618 0.006314694 0.06164914 -0.005977213 0.006762981 0.06176626 -0.005992829 0.006745934 0.06164109 -0.006188631 0.006899654 0.06168395 -0.006368815 0.00709629 0.06178861 -0.006422698 0.007018864 0.06170189 -0.006729245 0.007171034 0.06180882 -0.006843626 0.006940484 0.06170046 -0.007152974 0.007083952 0.06182086 -0.007224082 0.006743371 0.06184518 -0.00762403 0.006694555 0.06171268 -0.007457673 0.006430864 0.06185513 -0.007763922 0.006348848 0.06173712 -0.007617175 0.006038248 0.06187039 -0.0077762 0.005978941 0.06174886 -0.007608532 0.005726039 0.06188917 -0.007677674 0.005678832 0.06176966 -0.007457613 0.005451679 0.06189739 -0.00746417 0.005421698 0.06181335 -0.007158339 0.005264103 0.06191337 -0.007148146 0.005356371 0.06183844 -0.00662893 0.005197346 0.06192874 -0.006834328 0.005292117 0.06194549 -0.006373345 0.005641877 0.06186527 -0.00616008 0.005517721 0.06196498 -0.006072223 0.005983173 0.06198704 -0.005833268 0.006100714 0.06188917 -0.005967557 0.006476104 0.06200087 -0.005860626 0.006562829 0.06191176 -0.006053209 0.006909072 0.0620253 -0.006123244 0.006965339 0.06193894 -0.006460785 0.007144212 0.06204897 -0.006571233 0.007163941 0.06206309 -0.006965279 0.006994247 0.06193751 -0.006979405 0.007057428 0.06207221 -0.007275938 0.006782948 0.06198751 -0.00742048 0.006773412 0.06209027 -0.00760591 0.006327927 0.06210678 -0.007779419 0.006180524 0.06201839 -0.007649958 0.005890786 0.06212776 -0.007753968 0.005813002 0.06200963 -0.007546544 0.005514383 0.06214874 -0.007533788 0.005524814 0.06202834 -0.007302403 0.005234539 0.06216603 -0.007089912 0.005362808 0.06204825 -0.006933391 0.005206406 0.06218779 -0.006635606 0.005436897 0.06210011 -0.006408989 0.00539571 0.06220924 -0.006213188 0.005736708 0.06222504 -0.005921661 0.005769014 0.06209683 -0.006088256 0.006249368 0.0622372 -0.005811631 0.006093263 0.06211143 -0.005985438 0.006445765 0.06212991 -0.006016254 0.00686109 0.06225568 -0.006080269 0.006878852 0.06218135 -0.006312012 0.007088482 0.06228792 -0.006382465 0.007025837 0.06221097 -0.006928086 0.007172644 0.06230461 -0.006796896 0.0070858 0.06232076 -0.007229864 0.006797015 0.06223595 -0.007377028 0.006687104 0.06234115 -0.007653772 0.006364822 0.06225943 -0.00763446 0.006274163 0.06236565 -0.00778979 0.005801379 0.06238532 -0.007718384 0.005878508 0.06228321 -0.007583022 0.005520522 0.06239384 -0.007534265 0.005574464 0.06227189 -0.007364213 0.0052917 0.06240874 -0.007228732 0.005401611 0.06229555 -0.00707215 0.005201578 0.0624293 -0.006823539 0.005370676 0.0623424 -0.006563663 0.005261898 0.06244015 -0.006453633 0.005395174 0.06245636 -0.006212532 0.005738854 0.06234306 -0.006099462 0.005741477 0.0624746 -0.005917251 0.006013095 0.06238514 -0.005975782 0.006188929 0.06249737 -0.005818903 0.006562709 0.06250709 -0.005892217 0.006474077 0.06240719 -0.006021082 0.006792783 0.06242501 -0.00622493 0.00689423 0.06251776 -0.006115019 0.007080078 0.06253927 -0.006397247 0.007016241 0.06244903 -0.006658256 0.007166087 0.06254971 -0.00672388 0.0069471 0.06244713 -0.007131338 0.007140517 0.06256467 -0.007057666 0.006957888 0.06258493 -0.007422029 0.00668776 0.06249231 -0.007478952 0.006626486 0.06260013 -0.007685899 0.006232976 0.06248509 -0.007635951 0.006300508 0.06261301 -0.007785916 0.005963683 0.06252843 -0.007616937 0.005938589 0.06262791 -0.007757246 0.005668997 0.06263744 -0.007649242 0.005726218 0.06250816 -0.007503509 0.005350053 0.06265741 -0.007335424 0.005436956 0.06253772 -0.007158935 0.00520569 0.06266999 -0.006924688 0.005356252 0.06255537 -0.006767749 0.005224883 0.06268823 -0.006589651 0.005522251 0.06260699 -0.00627762 0.005355536 0.06270587 -0.00627315 0.005603849 0.06271737 -0.006009995 0.006041705 0.06263607 -0.005968272 0.005868375 0.06272929 -0.005871295 0.006345152 0.06274396 -0.005823075 0.006628394 0.06266516 -0.006082832 0.00675559 0.06276756 -0.006002366 0.007000327 0.06278467 -0.006253182 0.006962954 0.06269007 -0.006486356 0.007156133 0.06279623 -0.00661379 0.007016122 0.06271135 -0.006929039 0.007154047 0.06281352 -0.006984531 0.007059097 0.06282299 -0.007260501 0.006852805 0.06273132 -0.007309257 0.006879985 0.06283539 -0.007504642 0.006551444 0.06275027 -0.007561147 0.006551086 0.062846 -0.007728159 0.00608462 0.06274849 -0.007630169 0.006048738 0.06287848 -0.007785022 0.005710661 0.06288766 -0.007669389 0.005722165 0.06276297 -0.007497727 0.005444884 0.06289625 -0.007455468 0.005429148 0.06278675 -0.00715214 0.005264937 0.06291574 -0.00715363 0.00519526 0.06293714 -0.006702363 0.005358219 0.06281191 -0.006717622 0.005388915 0.06295549 -0.006217956 0.005521237 0.06285673 -0.006292462 0.005624353 0.06296533 -0.005992412 0.00590527 0.06287962 -0.006007432 0.005965948 0.06298303 -0.005847632 0.006316781 0.06299859 -0.005825877 0.006411552 0.06290405 -0.005994796 0.006628453 0.06301116 -0.005926609 0.006872773 0.0629304 -0.006304562 0.006965398 0.06302058 -0.00619179 0.007136344 0.0630474 -0.006530046 0.00701344 0.06293016 -0.006791412 0.007155179 0.0630632 -0.006979227 0.006892263 0.06297951 -0.007279813 0.006978869 0.06308317 -0.007401704 0.006636857 0.06309747 -0.007689714 0.006539344 0.06297355 -0.007552444 0.00616455 0.06311315 -0.007795035 0.006170153 0.06301885 -0.00764364 0.00572741 0.06304097 -0.007512688 0.005666971 0.06314337 -0.007650196 0.005301654 0.06315892 -0.007264614 0.005451381 0.06306076 -0.007205426 0.005358934 0.06305092 -0.006880342 0.005199432 0.06318074 -0.006730318 0.005423545 0.06306737 -0.006479322 0.005323708 0.06319904 -0.006324291 0.005605697 0.06309002 -0.006214618 0.005657911 0.06322205 -0.005961835 0.005907416 0.06310105 -0.006026268 0.006164431 0.06324422 -0.005815565 0.00628364 0.0631476 -0.005968928 0.006528615 0.0632556 -0.005879163 0.006706595 0.06314313 -0.006162106 0.006943404 0.06327259 -0.006156146 0.006967425 0.0631904 -0.006483376 0.007168591 0.06329989 -0.006692767 0.006988406 0.06318986 -0.007020711 0.007116615 0.06331712 -0.007130861 0.00679475 0.06321221 -0.007362842 0.00690037 0.06333273 -0.007486045 0.006504774 0.06322395 -0.007571876 0.006601989 0.06335204 -0.00770086 0.006104528 0.06337112 -0.007795333 0.00608021 0.06324809 -0.007627904 0.005620658 0.06329691 -0.007438778 0.005644857 0.06339055 -0.007629632 0.005363643 0.06340342 -0.00735253 0.005355358 0.06332409 -0.006949305 0.005220711 0.06341952 -0.007008492 0.005199193 0.06343436 -0.006708741 0.005393803 0.06331664 -0.006556749 0.005364 0.06345427 -0.006245374 0.005692958 0.06336826 -0.006113946 0.005735278 0.06347155 -0.005925118 0.006110966 0.06336355 -0.00597608 0.006036043 0.06348752 -0.005828917 0.006368279 0.06349867 -0.005838871 0.00665003 0.06341642 -0.006096303 0.006688416 0.0635119 -0.005951285 0.006951034 0.06353145 -0.006178557 0.006935775 0.06341224 -0.006450355 0.007166862 0.0635479 -0.006658375 0.007010996 0.06346458 -0.007005095 0.007105708 0.06356924 -0.007167339 0.006657779 0.06349492 -0.007510185 0.006841778 0.0635901 -0.00754249 0.006407499 0.06360894 -0.007773935 0.006118714 0.06352126 -0.007644653 0.00585252 0.06362545 -0.007739007 0.005621552 0.06354695 -0.007437229 0.005491852 0.06364756 -0.007508814 0.005366981 0.06354349 -0.006954669 0.005219936 0.06365495 -0.007022142 0.005373597 0.06359136 -0.006571352 0.005256593 0.06368702 -0.006471455 0.005630552 0.06358766 -0.006187677 0.005553722 0.06371688 -0.006033599 0.006015539 0.06363534 -0.005985498 0.006045877 0.06373101 -0.005828499 0.006434142 0.06365483 -0.006001055 0.006586432 0.06374359 -0.005899548 0.006832659 0.06364911 -0.006284236 0.007034957 0.06377601 -0.006297707 0.006992995 0.06369352 -0.006556749 0.007176101 0.06380146 -0.006758749 0.006990373 0.06371688 -0.007037818 0.007107973 0.06382107 -0.007171988 0.006757378 0.06373852 -0.007424294 0.006802499 0.06384021 -0.007579982 0.00622946 0.0637663 -0.007654488 0.006383299 0.06386405 -0.00777328 0.005958139 0.06387287 -0.007767081 0.005758762 0.06376612 -0.007516264 0.005562782 0.06389123 -0.007570445 0.00541681 0.06381368 -0.007156312 0.005329966 0.06390792 -0.007309138 0.00521332 0.06392461 -0.006997287 0.005354762 0.06383496 -0.006715357 0.005240738 0.06394165 -0.006509721 0.005468964 0.0638526 -0.006367981 0.005448043 0.06395816 -0.006150126 0.005811631 0.06387448 -0.006049394 0.005693793 0.06397169 -0.005954861 0.00604093 0.06398856 -0.005826592 0.006286919 0.06389808 -0.005970299 0.006521046 0.06400364 -0.005872607 0.006802618 0.06392526 -0.006216406 0.006920456 0.06402283 -0.006144762 0.007119655 0.06405037 -0.006473839 0.00702238 0.06395274 -0.006735742 0.007168233 0.06405204 -0.006961762 0.006931662 0.06397467 -0.007196724 0.006991207 0.06407958 -0.007373988 0.006514251 0.06400251 -0.007589161 0.006700813 0.06410038 -0.007647752 0.006251871 0.06411206 -0.007795095 0.005955219 0.06400406 -0.00760287 0.005793809 0.0641303 -0.007708251 0.005554556 0.06405168 -0.007372975 0.005541503 0.0641461 -0.007551431 0.005287349 0.06416809 -0.007226049 0.005338847 0.06407988 -0.006821274 0.005197048 0.06417608 -0.006761729 0.005495905 0.06410497 -0.006323039 0.00528717 0.06419587 -0.00640285 0.00550872 0.06421452 -0.00608313 0.005806744 0.06412434 -0.006059348 0.00588119 0.06422752 -0.005866885 0.006193876 0.06414335 -0.005963802 0.00632596 0.06424689 -0.00582391 0.00655955 0.06413245 -0.006063461 0.006836116 0.06427145 -0.006050407 0.00688225 0.06415927 -0.006354451 0.007104814 0.06428748 -0.006454646 0.006997883 0.06417042 -0.006655752 0.007170617 0.06430304 -0.00674057 0.006984889 0.06421798 -0.007058441 0.007126092 0.06431585 -0.007102549 0.006711184 0.06421595 -0.007448971 0.0069862 0.06432926 -0.007378637 0.006751298 0.06434345 -0.007616102 0.006361663 0.06423419 -0.007614195 0.006444513 0.06435596 -0.007755041 0.006050229 0.06437265 -0.007784366 0.005911052 0.06428098 -0.007600247 0.005648255 0.06438714 -0.007632911 0.005593717 0.06427454 -0.007383406 0.005311965 0.06439465 -0.007262945 0.005400121 0.06429046 -0.007069647 0.005200445 0.06443428 -0.006859421 0.005371689 0.06432044 -0.006615638 0.005474209 0.06431525 -0.006367385 0.005830705 0.06437629 -0.006046235 0.006206631 0.06439483 -0.005969226 0.00673151 0.05869591 -0.007456302 0.006284475 0.05870324 -0.007638871 0.005924642 0.05871087 -0.007613599 0.005571842 0.05874657 -0.007394969 0.006730556 0.05886912 -0.006159901 0.007010519 0.05889457 -0.006623625 0.006918668 0.0589258 -0.007246851 0.006439685 0.05895352 -0.007606387 0.005973637 0.05897593 -0.00761938 0.005372405 0.05901664 -0.007052898 0.005424797 0.05904692 -0.00642389 0.005795955 0.05907148 -0.006063222 0.006269872 0.0590946 -0.00596255 0.006692707 0.0591166 -0.006141364 0.006967365 0.05913811 -0.006483733 0.007002055 0.05916303 -0.007011353 0.00680375 0.0591827 -0.007367074 0.006415426 0.05920469 -0.00761944 0.005881369 0.05923074 -0.007590889 0.005513489 0.05925309 -0.007308542 0.005360066 0.05927169 -0.006941139 0.005379796 0.05928921 -0.006575524 0.005851507 0.0593245 -0.006034493 0.006379425 0.05935108 -0.005977451 0.006838083 0.05937623 -0.006274998 0.007010579 0.0593965 -0.006665527 0.00684452 0.05943 -0.007324337 0.005391955 0.0595144 -0.007107377 0.005638003 0.05956304 -0.006157517 0.006059348 0.05958473 -0.005979478 0.006498038 0.05960571 -0.006020009 0.006952762 0.05963599 -0.006430625 0.007000207 0.05966317 -0.007012724 0.006186842 0.05971562 -0.007642269 0.005758702 0.05973684 -0.007532715 0.005360841 0.05976688 -0.007041692 0.005880713 0.05982577 -0.00602746 0.006295144 0.05984592 -0.005968928 0.006726324 0.05986881 -0.006163239 0.006855607 0.05992877 -0.007306575 0.006542265 0.0599485 -0.007564663 0.006051242 0.05997204 -0.007640302 0.00535506 0.06003636 -0.006631493 0.005989432 0.06008148 -0.005991995 0.006366908 0.06009942 -0.005985498 0.007006049 0.06014418 -0.006614327 0.006969749 0.0601685 -0.007112979 0.006672024 0.06019109 -0.007489621 0.006261765 0.06021255 -0.007641315 0.005699455 0.06023931 -0.007508993 0.006713926 0.06036764 -0.006139039 0.007002949 0.06039386 -0.006608843 0.006974935 0.06041771 -0.007104575 0.00634551 0.06045806 -0.007628738 0.005640625 0.06049394 -0.007441997 0.005363225 0.06053984 -0.006580054 0.006583034 0.06061053 -0.006054401 0.006961405 0.06063723 -0.006475508 0.00701642 0.06065708 -0.00688064 0.005942881 0.06072771 -0.007613301 0.005517601 0.06075215 -0.007319033 0.005354702 0.06077349 -0.006911516 0.005432248 0.06079709 -0.00641334 0.006113886 0.06083738 -0.005966365 0.006609022 0.0608617 -0.006074249 0.006966233 0.0608884 -0.006482958 0.006146132 0.06096798 -0.007649421 0.005360305 0.06101882 -0.007013201 0.005409955 0.06104397 -0.006483912 0.005765676 0.06107044 -0.006062686 0.006344079 0.06109863 -0.005977988 0.006752729 0.06112039 -0.006186068 0.006974518 0.0611397 -0.006527483 0.007011473 0.06116181 -0.006987333 0.006712436 0.06118959 -0.007466256 0.00577414 0.0612359 -0.007543146 0.005446732 0.06125855 -0.007200896 0.005348443 0.06127697 -0.006835699 0.006843209 0.06137657 -0.006286203 0.006311714 0.06145977 -0.0076406 0.005504548 0.06150317 -0.007300734 0.005690515 0.06156605 -0.006124675 0.006258487 0.06159359 -0.005952894 0.00702846 0.06164932 -0.006697297 0.005416035 0.06176167 -0.007146239 0.005354046 0.06178385 -0.006686925 0.005509138 0.0618034 -0.006309747 0.005916774 0.06182807 -0.005999863 0.006577253 0.06186085 -0.00604403 0.006983578 0.06189012 -0.006529629 0.006759703 0.06193619 -0.007427573 0.006280481 0.06196159 -0.007640302 0.005426704 0.06204676 -0.006433904 0.006783664 0.06212234 -0.006222307 0.00699371 0.06214213 -0.006572484 0.00698328 0.06216758 -0.007085025 0.006630122 0.06219369 -0.007524609 0.00602281 0.06222343 -0.007642328 0.005351781 0.06228226 -0.006725251 0.005510687 0.06230413 -0.006299078 0.006268084 0.0623449 -0.0059641 0.006791174 0.06237256 -0.006209969 0.007023155 0.06239956 -0.006719291 0.006665706 0.06244212 -0.007499516 0.005448758 0.06254816 -0.006406843 0.005706906 0.06256651 -0.006117105 0.006159961 0.06258946 -0.005959093 0.006769716 0.06262105 -0.006178379 0.007015824 0.06264781 -0.006693184 0.006955564 0.06267005 -0.007150411 0.006580293 0.06269633 -0.007553398 0.005515098 0.06280469 -0.006291031 0.006035149 0.06283426 -0.005965292 0.00664705 0.06286394 -0.00609529 0.006940305 0.06288558 -0.006447672 0.006901204 0.06292623 -0.007252097 0.006067633 0.06297129 -0.007644593 0.005552113 0.06299996 -0.007366776 0.006360292 0.06309896 -0.005978345 0.006993353 0.06314194 -0.006554424 0.005698621 0.06324034 -0.00748521 0.005388796 0.06326478 -0.007100522 0.005605638 0.06331074 -0.006190121 0.006578922 0.06336092 -0.006056308 0.007025957 0.06340914 -0.006931722 0.006821334 0.06343126 -0.007344663 0.006415545 0.06345444 -0.007626295 0.005845725 0.06348282 -0.007574141 0.005527853 0.06350165 -0.007322967 0.005395829 0.06354165 -0.006527006 0.005990743 0.06358224 -0.0059821 0.006517648 0.06360685 -0.006030976 0.00703144 0.06365168 -0.006774604 0.006900906 0.06367492 -0.007240414 0.006620407 0.06369441 -0.00752151 0.006210029 0.06371456 -0.007645428 0.005420982 0.06376081 -0.007184922 0.00537461 0.0637896 -0.006567835 0.005732417 0.06381899 -0.006083428 0.006354331 0.06384855 -0.005973458 0.006892621 0.0638805 -0.006327152 0.007019281 0.06391036 -0.006945848 0.006755173 0.06393623 -0.007428467 0.006323754 0.06395906 -0.007631719 0.005533635 0.06400126 -0.007337749 0.005335152 0.06402856 -0.006812334 0.005537211 0.06405591 -0.006263256 0.006024539 0.06408345 -0.005972385 0.006989777 0.06416594 -0.007074713 0.005974173 0.06422585 -0.00762093 0.005796194 0.06432205 -0.006053686 0.006354212 0.06434929 -0.005976319 0.006762742 0.06437116 -0.006198406 0.007000505 0.06439304 -0.006585955 0.005239486 0.05869853 -0.006511688 0.005320012 0.05869632 -0.007233262 0.005502462 0.05870503 -0.006088912 0.00699234 0.05909502 -0.007372379 0.005729079 0.05923813 -0.005932092 0.005300581 0.0594629 -0.006380975 0.005413413 0.06066799 -0.007422924 0.005212962 0.06120264 -0.006625592 0.005881786 0.0616452 -0.007739424 0.006666839 0.06227815 -0.005946516 0.006930232 0.06234872 -0.007447004 0.005306839 0.06367635 -0.007246613 0.005200326 0.06369662 -0.006778001 0.006344854 0.06376385 -0.005832552 0.00678271 0.06378382 -0.006024181 0.007002711 0.06467753 -0.006672799 0.007130801 0.06457877 -0.006853938 0.006826817 0.0646888 -0.006311893 0.007162988 0.06444925 -0.006655454 0.007035255 0.06461811 -0.00646311 0.00705105 0.06454062 -0.006383061 0.006658017 0.06468856 -0.006156265 0.006818234 0.06456995 -0.00608921 0.006708145 0.06461399 -0.006052672 0.006141841 0.06469357 -0.006021738 0.006408393 0.0646575 -0.005968749 0.006465017 0.06459832 -0.005920588 0.006087183 0.0646342 -0.005912542 0.006316304 0.06454712 -0.005853772 0.005526661 0.06469506 -0.00637716 0.005740284 0.0646553 -0.00604844 0.006075561 0.06452441 -0.005843818 0.00583744 0.06454843 -0.005911231 0.005549848 0.06453895 -0.006074666 0.005374372 0.06463295 -0.00639975 0.005289733 0.06444811 -0.006387412 0.005303919 0.06465053 -0.006856262 0.005236327 0.06454378 -0.006633698 0.005441904 0.06469029 -0.007116258 0.005242526 0.06455433 -0.006984651 0.005687177 0.06468909 -0.007444381 0.005413472 0.06461954 -0.007293283 0.005503773 0.06451719 -0.007494628 0.005677103 0.06461042 -0.007571756 0.005967199 0.06465309 -0.007659435 0.005740404 0.06445544 -0.007686257 0.00628221 0.06469321 -0.007585287 0.006083369 0.06454432 -0.007760584 0.006391227 0.06463164 -0.007683634 0.006389856 0.06451296 -0.007754564 0.006720781 0.06455594 -0.007603287 0.006640553 0.06469154 -0.007466435 0.006901681 0.06461715 -0.00737828 0.006955265 0.06468987 -0.007051527 0.007041037 0.0646227 -0.007121086 0.006973862 0.0644465 -0.007392525 0.006597876 0.05752593 -0.00751692 0.007020831 0.05752712 -0.006779968 0.005774438 0.0575245 -0.007519185 0.005360722 0.05752468 -0.006804943 0.005774438 0.05752611 -0.006092905 0.006622195 0.05752265 -0.006089448 0.006627738 0.05680638 -0.007568955 0.005745232 0.05680656 -0.007570445 0.006624996 0.05680638 -0.006039321 0.007065296 0.05680721 -0.006806313 0.005744338 0.05680674 -0.006041228 0.0053007 0.05680572 -0.006804943 0.005161583 0.05679512 -0.008362889 0.006044149 0.05679512 -0.008688509 0.004640877 0.05679512 -0.007857918 0.004574894 0.05679512 -0.005838811 0.004301309 0.05679512 -0.006914436 0.006994903 0.05679512 -0.008486211 0.007651388 0.05679512 -0.007974147 0.005161583 0.05679512 -0.005247056 0.007990956 0.05679512 -0.007264733 0.005936622 0.05679512 -0.004943549 0.008033275 0.05679512 -0.006494522 0.006988108 0.05679512 -0.005102396 0.007701992 0.05679512 -0.005714476 0.004477202 0.05869513 -0.006069839 0.00485444 0.05869513 -0.005485713 0.005475401 0.05869513 -0.005083978 0.006200432 0.05869513 -0.004931092 0.007250249 0.05869513 -0.005242943 0.0078426 0.05869513 -0.005955338 0.008045136 0.05869513 -0.006618857 0.007987916 0.05869513 -0.007263958 0.00772202 0.05869513 -0.007870972 0.007119834 0.05869513 -0.008423745 0.006431639 0.05869513 -0.008652746 0.005784809 0.05869513 -0.008625566 0.005186259 0.05869513 -0.008378803 0.004526495 0.05869513 -0.007708311 0.004318118 0.05869513 -0.006696701 0.007282674 0.05869513 -0.006446301 0.007276713 0.05899512 -0.006488323 0.007045567 0.05899512 -0.006071448 0.006810963 0.05869513 -0.005853295 0.006620109 0.05899512 -0.005749464 0.006079792 0.05869513 -0.005655229 0.005921483 0.05899512 -0.005691289 0.005441606 0.05869513 -0.005948483 0.005408525 0.05899512 -0.005981087 0.005094408 0.05869513 -0.006458699 0.00510019 0.05899512 -0.006450235 0.005106985 0.05899512 -0.007207512 0.005075395 0.05869513 -0.007020235 0.005271852 0.05869513 -0.00748527 0.00557518 0.05899512 -0.007766664 0.005891144 0.05869513 -0.007921457 0.006223142 0.05899512 -0.007948815 0.006591141 0.05869513 -0.007864117 0.006922245 0.05899512 -0.007683277 0.007051765 0.05869513 -0.0075441 0.007289826 0.05899512 -0.007086217 0.007278621 0.05869513 -0.007092595 0.003840327 0.05899512 -0.006371736 0.003958404 0.05869513 -0.005951941 0.004314064 0.05899512 -0.005364239 0.004650533 0.05869513 -0.0050053 0.005017161 0.05899512 -0.004743576 0.005525231 0.05869513 -0.004529416 0.005851805 0.05899512 -0.004470229 0.006343722 0.05869513 -0.004454553 0.006613671 0.05899512 -0.004482567 0.007142364 0.05869513 -0.004637479 0.007434666 0.05899512 -0.004796624 0.008001446 0.05869513 -0.005281031 0.008178174 0.05899512 -0.00551784 0.008440911 0.05869513 -0.006109178 0.008508861 0.05899512 -0.00639528 0.008543133 0.05869513 -0.007081091 0.008511245 0.05899512 -0.007234275 0.008236765 0.05869513 -0.007968366 0.008111536 0.05899512 -0.008189857 0.007706463 0.05869513 -0.008617818 0.007478177 0.05899512 -0.00877422 0.006882071 0.05869513 -0.009063899 0.006674528 0.05899512 -0.009127974 0.005890488 0.05869513 -0.009157419 0.005369007 0.05899512 -0.009047627 0.004988372 0.05869513 -0.008840799 0.004441499 0.05899512 -0.008397579 0.004221022 0.05869513 -0.00814414 0.003952324 0.05899512 -0.007597386 0.003840804 0.05869513 -0.007117807 0.00730282 0.05899512 0.001901388 0.007335245 0.05869513 0.001742899 0.007094919 0.05869513 0.002372562 0.007083892 0.05899512 0.002387106 0.006637275 0.05869513 0.002743244 0.006516516 0.05899512 0.002801001 0.005939722 0.05869513 0.002812802 0.00576055 0.05899512 0.002751708 0.005399823 0.05869513 0.002513289 0.005271852 0.05899512 0.002375245 0.005088925 0.05869513 0.002013146 0.005046188 0.05899512 0.001770973 0.005075395 0.05869513 0.001479685 0.005156934 0.05899512 0.00122106 0.005271852 0.05869513 0.001014709 0.005482435 0.05899512 7.9881e-4 0.00581187 0.05869513 6.13133e-4 0.006109118 0.05899512 5.53053e-4 0.006606161 0.05869513 6.22507e-4 0.00672841 0.05899512 6.97584e-4 0.007223308 0.05899512 0.001195073 0.007139325 0.05869513 0.001078784 0.003892183 0.05869513 0.002259671 0.004009425 0.05899512 0.002632856 0.004317283 0.05869513 0.003160059 0.004631876 0.05899512 0.00348401 0.005091369 0.05869513 0.003787934 0.005506157 0.05899512 0.003960609 0.005931019 0.05869513 0.004046499 0.006498813 0.05899512 0.004043519 0.007036387 0.05869513 0.003916561 0.007573008 0.05899512 0.003625214 0.008001446 0.05869513 0.003218889 0.00835067 0.05899512 0.002672016 0.008440911 0.05869513 0.002390742 0.008546769 0.05899512 0.00167638 0.008543133 0.05869513 0.001418888 0.008380055 0.05899512 8.13346e-4 0.008236765 0.05869513 5.31603e-4 0.007758319 0.05899512 -8.74777e-5 0.007706463 0.05869513 -1.17875e-4 0.006882071 0.05869513 -5.63957e-4 0.006897807 0.05899512 -5.53211e-4 0.005849123 0.05899512 -6.65835e-4 0.005890488 0.05869513 -6.57434e-4 0.004883825 0.05869513 -2.84914e-4 0.004707098 0.05899512 -1.58593e-4 0.004164695 0.05869513 4.60271e-4 0.004102408 0.05899512 5.8194e-4 0.003840804 0.05869513 0.001382172 0.003816545 0.05899512 0.001536726 0.01549834 0.06444472 0.001138925 0.01523399 0.06444203 0.001064956 0.01546049 0.06443309 0.001378655 0.0148707 0.06444483 8.5934e-4 0.01567155 0.06444573 0.001657187 0.01551997 0.06444597 0.001861393 0.01443815 0.06444519 8.33527e-4 0.01432567 0.06444519 7.86456e-4 0.0152747 0.064435 0.002298951 0.01385778 0.06444281 0.00117582 0.01530146 0.06444513 0.002464592 0.01488852 0.06444483 0.00259298 0.01371854 0.0644375 0.001508295 0.01441472 0.06445068 0.002631902 0.01417481 0.06444811 0.002536118 0.0139777 0.05870085 0.00239253 0.01433777 0.05870091 0.002603411 0.01451534 0.05873787 0.002672195 0.01552712 0.05870181 0.001594543 0.01507556 0.05876123 0.002611517 0.01488995 0.05869507 0.002586305 0.01552206 0.05878239 0.002227187 0.01535171 0.05869489 0.002264976 0.01567369 0.05879765 0.00175625 0.01557391 0.05881994 0.001255869 0.01522928 0.05874091 0.001043558 0.01515537 0.05883204 8.23949e-4 0.01463985 0.05877012 8.45177e-4 0.01458519 0.05887037 7.09865e-4 0.0140872 0.05889123 9.00743e-4 0.01412528 0.05877637 0.001077771 0.01372981 0.05891615 0.001409351 0.01391506 0.05879354 0.001375257 0.01387059 0.0588119 0.001835405 0.013731 0.05893808 0.001953482 0.013938 0.05884915 0.002073228 0.01391965 0.05896615 0.002326726 0.01417475 0.05886739 0.002358198 0.01424437 0.05896806 0.00257647 0.01453548 0.05888557 0.002520024 0.01460295 0.05899345 0.002676784 0.0149098 0.05900186 0.002656638 0.01499551 0.05888086 0.002467155 0.01522576 0.05901545 0.002517759 0.01532757 0.05892747 0.002253115 0.01547765 0.05902343 0.002291381 0.01550143 0.05892229 0.001839458 0.01564884 0.05904573 0.001895129 0.01566094 0.05905908 0.001566529 0.01545274 0.05897349 0.001330912 0.01555871 0.05907469 0.001230359 0.01527452 0.05909317 9.03304e-4 0.01507085 0.05899906 9.48355e-4 0.01485419 0.05911511 7.1973e-4 0.01458066 0.05902266 8.56377e-4 0.01452213 0.05912041 7.19427e-4 0.01414191 0.05913746 8.75248e-4 0.01410281 0.05904853 0.001085102 0.01387923 0.05915349 0.00112164 0.01386737 0.05907154 0.001503944 0.01370894 0.05917268 0.001521766 0.01389896 0.05909579 0.00200802 0.01373445 0.05918961 0.001969218 0.01386314 0.05920523 0.002241134 0.01423507 0.05912029 0.002405107 0.01412129 0.05921626 0.002501487 0.01442235 0.05923032 0.002650201 0.01479232 0.05914711 0.002541542 0.0149964 0.05924952 0.002634286 0.01521956 0.05914485 0.002325356 0.01534503 0.05927151 0.002426445 0.01541841 0.05916059 0.002080917 0.01558142 0.05929231 0.002109825 0.01567256 0.05930018 0.001771926 0.01551043 0.05917757 0.001745581 0.01564031 0.0593155 0.001442551 0.01546549 0.05919373 0.001405954 0.01547324 0.05932945 0.001095294 0.01511752 0.05924713 9.64337e-4 0.01516896 0.05934512 8.34079e-4 0.01478481 0.05936497 7.13201e-4 0.01456356 0.05925095 8.72567e-4 0.01439607 0.05937856 7.50142e-4 0.01412796 0.05938988 8.79841e-4 0.01416671 0.05926519 0.001046657 0.01385992 0.05940598 0.00115478 0.01390522 0.05931496 0.001362264 0.01370251 0.05942654 0.001573503 0.01386648 0.0593394 0.001882135 0.01372867 0.05943298 0.001959025 0.01415872 0.05936664 0.002366364 0.01399558 0.0594682 0.002406895 0.01438218 0.05948084 0.002640306 0.01475495 0.05939644 0.002537906 0.01480633 0.05948996 0.00267744 0.0152291 0.05951982 0.002519428 0.01519089 0.05939704 0.002350568 0.01549255 0.05952626 0.00225687 0.01542174 0.05940639 0.002070844 0.01550745 0.0594272 0.001799404 0.0156328 0.05954533 0.001963436 0.01566058 0.05955821 0.00150305 0.01545763 0.05944526 0.001390755 0.01543754 0.05958563 0.001047015 0.01519805 0.05946469 0.001040399 0.0149973 0.05960148 7.56017e-4 0.01483845 0.05948567 8.83389e-4 0.01449227 0.05963218 7.16848e-4 0.01445269 0.059502 8.966e-4 0.0140413 0.05963957 9.46223e-4 0.01412802 0.05952143 0.001086413 0.01389056 0.05956679 0.001402258 0.01378339 0.05966329 0.001290678 0.01369923 0.05967968 0.001686632 0.01389908 0.05959618 0.002024471 0.01376503 0.05969166 0.002041101 0.01390302 0.0597071 0.002299308 0.01423156 0.05959451 0.002391695 0.01421993 0.05972737 0.002563655 0.01456427 0.05973267 0.00267452 0.01460969 0.05961161 0.002519428 0.01495814 0.05975228 0.00264281 0.01508814 0.05966246 0.002437353 0.0152595 0.05976575 0.002492487 0.01550412 0.0597797 0.002251923 0.01548886 0.05969166 0.00197941 0.01564788 0.05979937 0.001918315 0.01563537 0.05981528 0.001410365 0.01547199 0.05972027 0.001391649 0.01539397 0.05983275 0.00100845 0.01516711 0.05974394 0.001004993 0.01509165 0.05985176 7.94266e-4 0.01473516 0.05976581 8.56379e-4 0.01460254 0.05987453 7.05679e-4 0.01428312 0.05978798 9.56134e-4 0.01409131 0.05989009 8.98959e-4 0.01397341 0.05980849 0.001252412 0.01374697 0.05991679 0.001366257 0.01385349 0.05980306 0.001682162 0.01371425 0.0599339 0.001868784 0.01395332 0.05981981 0.002088844 0.01386499 0.05995929 0.00224632 0.01412189 0.05986362 0.002319335 0.01410025 0.05996328 0.002487182 0.01441973 0.05997979 0.002643942 0.01455879 0.05988723 0.002528429 0.01489609 0.06000363 0.002667129 0.015154 0.05991613 0.002410233 0.01538783 0.06001847 0.002396941 0.01550287 0.0599457 0.001902401 0.01563805 0.06004387 0.001959621 0.015657 0.0600655 0.001510143 0.01547241 0.05994528 0.001422464 0.01548844 0.06007581 0.001123726 0.01512449 0.0599963 9.6894e-4 0.01515263 0.06009477 8.18938e-4 0.01467531 0.05999565 8.68952e-4 0.01485902 0.06011122 7.16918e-4 0.01448392 0.06012636 7.29255e-4 0.01421362 0.06004178 9.8918e-4 0.01415371 0.06013941 8.64628e-4 0.01388138 0.06015819 0.001119792 0.01400935 0.06002521 0.001210689 0.01372539 0.06017172 0.001483619 0.0138421 0.06007963 0.001679301 0.01370388 0.06018424 0.001805245 0.01381152 0.0601992 0.002145767 0.01392525 0.0600745 0.002034664 0.01400023 0.06020879 0.002402603 0.01428252 0.06012356 0.002439856 0.01429998 0.06022393 0.002603113 0.01485002 0.06012189 0.00251168 0.01461744 0.06023937 0.002675294 0.0149604 0.06025213 0.002642989 0.0151205 0.0601648 0.002415537 0.01529663 0.06027084 0.002473473 0.01546585 0.0601899 0.002020418 0.01555573 0.06028687 0.002151966 0.01566743 0.06029915 0.001801669 0.01551759 0.06017625 0.001672446 0.01562279 0.06031823 0.001389861 0.0153653 0.06023085 0.001188337 0.01543986 0.06033158 0.001063406 0.01519334 0.06034499 8.50075e-4 0.0149002 0.0602582 8.79415e-4 0.01471579 0.06036442 7.00546e-4 0.01438903 0.06025791 9.1867e-4 0.0142576 0.06038713 8.06903e-4 0.01388168 0.06040799 0.001110732 0.01395022 0.06030976 0.001268088 0.01371526 0.0604189 0.0014894 0.01385468 0.06033748 0.001848399 0.01373165 0.06043481 0.001942813 0.01407831 0.06033736 0.002257943 0.01386314 0.06045335 0.002237856 0.01413875 0.06047403 0.002521991 0.01435357 0.06034976 0.002458453 0.01463383 0.06048458 0.002685427 0.01482731 0.06037664 0.002515137 0.01509732 0.06050974 0.002593994 0.01533544 0.06042784 0.002242207 0.01545888 0.0605309 0.002309978 0.01564514 0.06054794 0.001928031 0.01553475 0.06045842 0.001613676 0.0156663 0.06055408 0.001596033 0.01554679 0.06057637 0.001215696 0.0152406 0.06048959 0.00105679 0.01527458 0.06059378 8.995e-4 0.01489686 0.06060796 7.31154e-4 0.01479429 0.06051284 8.63575e-4 0.01452124 0.06062275 7.18076e-4 0.01434653 0.06053429 9.23222e-4 0.01403903 0.06064248 9.41563e-4 0.01396447 0.06053715 0.001279413 0.01372736 0.06067138 0.001427531 0.0138477 0.06058359 0.001757621 0.01373374 0.06068462 0.001966118 0.01398408 0.06057786 0.002139747 0.0138908 0.06070995 0.002282738 0.01414334 0.06071811 0.002511739 0.01441609 0.06063055 0.002501785 0.01444351 0.06073421 0.00265336 0.0148127 0.06074655 0.002674698 0.01493656 0.06065511 0.002494215 0.01530778 0.06076765 0.0024724 0.01523452 0.06064587 0.002317905 0.01562929 0.06079089 0.001998841 0.01543819 0.06066071 0.002046883 0.01551324 0.06068122 0.00164628 0.01565724 0.06080907 0.001528739 0.01534861 0.06073212 0.001174867 0.0155006 0.06083089 0.001128554 0.01505804 0.06085306 7.74679e-4 0.0148313 0.06076097 8.52392e-4 0.01457184 0.06086939 7.13916e-4 0.01422274 0.06079089 9.88007e-4 0.01416951 0.06088691 8.54163e-4 0.01393651 0.06090319 0.001052439 0.01392859 0.06081348 0.001337587 0.01373177 0.06092041 0.00143516 0.01386171 0.06079703 0.001596391 0.0137251 0.06093484 0.001951277 0.01393485 0.06084942 0.002075433 0.01387023 0.06095713 0.002256929 0.0142349 0.06087046 0.002402424 0.01422792 0.06097358 0.002572238 0.01461237 0.06088954 0.002529859 0.01472514 0.06099468 0.00268644 0.01511693 0.06091499 0.002426683 0.01525008 0.0610134 0.002511322 0.01544988 0.06091427 0.002022147 0.01556742 0.06104052 0.002139747 0.01567584 0.06105053 0.001697182 0.0155096 0.0609318 0.001583695 0.01554924 0.06107878 0.001211583 0.01535147 0.06098216 0.001171112 0.01522594 0.06108909 8.65666e-4 0.01491969 0.06100672 8.88582e-4 0.01478976 0.06111222 7.11823e-4 0.01444095 0.06099981 9.01312e-4 0.01438665 0.06112843 7.53225e-4 0.01422077 0.06104159 9.95497e-4 0.01404345 0.0611447 9.36632e-4 0.0138812 0.06106764 0.001417398 0.01380074 0.06116098 0.001243174 0.01369583 0.06117844 0.00165534 0.0139054 0.06106775 0.001979649 0.01377421 0.06120359 0.002081692 0.01405417 0.06110894 0.002249419 0.013996 0.06120878 0.002403795 0.01435542 0.06122964 0.002625107 0.01445472 0.06113243 0.002506196 0.01472109 0.06124275 0.002679109 0.01497906 0.06115704 0.002486944 0.0151003 0.06126177 0.002595603 0.01540398 0.06125885 0.002369999 0.01538574 0.0611822 0.002162337 0.01565289 0.06129574 0.001901924 0.01553219 0.06120866 0.001611232 0.01564085 0.06131678 0.001421689 0.01548218 0.06131368 0.00111413 0.01523888 0.06123989 0.001051664 0.0152778 0.06134539 9.00105e-4 0.01473909 0.06136393 7.00323e-4 0.01475208 0.06126487 8.5807e-4 0.01424372 0.06128925 9.70141e-4 0.01425594 0.06138378 8.07758e-4 0.01388669 0.06140303 0.001100122 0.01388722 0.0613175 0.001418828 0.01370143 0.06142508 0.001580238 0.0138756 0.0613414 0.001920938 0.01376223 0.06144344 0.00206393 0.01409679 0.06136232 0.00229305 0.01397418 0.06146043 0.002384066 0.01423048 0.06147557 0.002572357 0.01460897 0.06138968 0.002547144 0.01472359 0.06149774 0.002687811 0.01523196 0.06151413 0.00252211 0.01516872 0.06141757 0.002381861 0.01557213 0.06153124 0.002136409 0.0154156 0.06140732 0.002083361 0.01551556 0.06142717 0.001725852 0.01567703 0.06155449 0.001682996 0.0154764 0.06144344 0.001459002 0.01559126 0.06157189 0.001299858 0.01531714 0.06145793 0.001156806 0.01534801 0.0615884 9.59208e-4 0.01500082 0.06150287 9.13565e-4 0.01498347 0.06160461 7.55635e-4 0.01460981 0.06152188 8.63903e-4 0.01465719 0.06161737 7.08589e-4 0.01420235 0.06154239 0.001002192 0.01425743 0.0616343 8.00136e-4 0.01388317 0.06166046 0.001107335 0.01394939 0.06156128 0.001303672 0.0137037 0.06167274 0.001589238 0.0138424 0.06158035 0.001690566 0.01373398 0.06169027 0.001946985 0.01389312 0.06156116 0.001961886 0.01387798 0.06170243 0.002261042 0.01416516 0.06159007 0.002340555 0.01422303 0.0617268 0.002572953 0.01446759 0.06160634 0.002490341 0.01464176 0.0617429 0.002680599 0.01486927 0.06165152 0.00251758 0.01498788 0.06175315 0.002638578 0.01533067 0.06176614 0.002445042 0.01532417 0.06165051 0.002229511 0.01561564 0.06178855 0.002033889 0.01548367 0.06166768 0.001922309 0.015527 0.06171017 0.001601755 0.01566469 0.06181228 0.001532316 0.01530945 0.06170767 0.001146733 0.01548457 0.06183111 0.001121103 0.01525372 0.06184232 8.92427e-4 0.01499885 0.06172567 9.30351e-4 0.0149635 0.06185895 7.48565e-4 0.01463693 0.0617454 8.66303e-4 0.0145266 0.06187194 7.15018e-4 0.01425313 0.06176358 9.889e-4 0.01412636 0.06188946 8.8232e-4 0.01381224 0.06190681 0.001226067 0.01391828 0.06181335 0.00134021 0.01369738 0.06192719 0.001663386 0.01385313 0.06183475 0.00178039 0.01373678 0.06194156 0.001963019 0.01397579 0.06185263 0.002138733 0.01390683 0.06196099 0.002302289 0.01428467 0.06187349 0.00243622 0.01418197 0.06196922 0.002543151 0.01456284 0.06198793 0.002673268 0.01483583 0.06190043 0.002530634 0.01500785 0.0620014 0.002631604 0.01530754 0.06192636 0.002260684 0.01537913 0.06202811 0.002396583 0.01561588 0.06203424 0.002029955 0.01549988 0.06192284 0.001860916 0.01567196 0.06205999 0.001639366 0.01546859 0.06196987 0.001397132 0.01550883 0.06208008 0.00113976 0.01517522 0.06195998 0.001019001 0.01516115 0.0620948 8.2974e-4 0.01498204 0.06200385 9.10976e-4 0.01478248 0.06211149 7.16618e-4 0.01442015 0.06203043 8.81881e-4 0.01440918 0.062128 7.44421e-4 0.01401799 0.06215173 9.67063e-4 0.01394623 0.06206059 0.001285612 0.01376825 0.06216055 0.001318991 0.01386028 0.0620622 0.001800239 0.01370263 0.06217938 0.001769423 0.01396852 0.06210225 0.002130687 0.01377946 0.06219732 0.002086281 0.01401644 0.06221055 0.002423226 0.01425701 0.06212192 0.002415657 0.01454216 0.06223297 0.002678692 0.01473581 0.0621457 0.002540409 0.01506757 0.06225687 0.002611041 0.01521384 0.06216996 0.002347528 0.01543211 0.06227451 0.002335906 0.01542627 0.06215715 0.002070188 0.01561802 0.0622887 0.002020299 0.01551383 0.06218111 0.001664996 0.01567286 0.06230705 0.001600801 0.01541793 0.06219977 0.001308262 0.01557582 0.06232255 0.001257061 0.01520889 0.06234365 8.56827e-4 0.01511007 0.06224709 9.69084e-4 0.0148136 0.06236118 7.09483e-4 0.01469552 0.06226766 8.56611e-4 0.01443177 0.06237506 7.44398e-4 0.01427084 0.06226491 9.76351e-4 0.01410239 0.06239253 9.01433e-4 0.01383578 0.06240987 0.001187562 0.01395171 0.06227886 0.001299679 0.01386314 0.06232291 0.001531183 0.01371705 0.06242281 0.001519262 0.0137223 0.06243276 0.001946687 0.0139085 0.06234729 0.002036869 0.01396453 0.06246644 0.00236994 0.01432001 0.06237506 0.002458333 0.01428592 0.06247097 0.002597689 0.01462322 0.06248897 0.002676904 0.01489084 0.06240236 0.002516269 0.01498162 0.06250685 0.002635419 0.01531898 0.06252032 0.002450525 0.01531475 0.06240093 0.002234041 0.01556676 0.06253629 0.002145349 0.01552611 0.06245082 0.001806139 0.01567202 0.06255006 0.001714766 0.01560997 0.06256836 0.001356065 0.01540076 0.06247752 0.001245737 0.01538532 0.0625869 9.95217e-4 0.01510125 0.06247019 9.77942e-4 0.01499271 0.0626077 7.56391e-4 0.01474934 0.06248819 8.65638e-4 0.01462262 0.06261903 7.0945e-4 0.01427352 0.06251519 9.69724e-4 0.01420861 0.06263256 8.28849e-4 0.01386463 0.06265586 0.001141548 0.01392477 0.06254321 0.001357436 0.0137152 0.06267023 0.001523673 0.01384228 0.0625835 0.00175327 0.0137096 0.06269603 0.001885712 0.01388663 0.06270116 0.002273023 0.0140419 0.06257796 0.002218544 0.01426488 0.06259912 0.00241357 0.01416349 0.06272065 0.00253123 0.01459592 0.06273508 0.002684652 0.01468408 0.06261539 0.002523481 0.01505243 0.06266117 0.002456784 0.01508343 0.06276082 0.002599477 0.01546263 0.06277936 0.002309024 0.01544362 0.06265598 0.002044975 0.0155217 0.06270003 0.001815557 0.01565027 0.06279468 0.001899659 0.01564997 0.06281101 0.001479983 0.01544016 0.06272369 0.001327693 0.01547884 0.06282866 0.00111103 0.01517337 0.06274336 0.001013219 0.01521134 0.06284379 8.54129e-4 0.01482558 0.06273418 8.79268e-4 0.01467424 0.06286239 7.07951e-4 0.01445168 0.062779 8.86331e-4 0.01417344 0.0628913 8.41187e-4 0.01411694 0.06279814 0.001084744 0.01381599 0.06290519 0.001226544 0.01386177 0.06282079 0.001480281 0.01369959 0.0629329 0.00161755 0.01376146 0.06294351 0.002048313 0.01391458 0.0628466 0.002029359 0.01397359 0.0629611 0.002381205 0.0141412 0.06284016 0.002318501 0.01431643 0.06297194 0.002616941 0.01453125 0.06288611 0.002521157 0.01480072 0.06299465 0.002675294 0.01488655 0.06287461 0.002496302 0.01509183 0.0630095 0.002592563 0.01522934 0.06292128 0.002334177 0.01540321 0.06302917 0.002373695 0.0154851 0.06292116 0.001923441 0.01561629 0.06303763 0.002024769 0.01566684 0.06305593 0.001693248 0.01546972 0.06297105 0.001377224 0.01560699 0.06307196 0.001343429 0.0154345 0.06308203 0.001050591 0.01524537 0.06296223 0.001080691 0.0151624 0.06309539 8.37244e-4 0.01475483 0.06301462 8.50997e-4 0.0148161 0.06311005 7.15221e-4 0.01431661 0.06313204 7.73129e-4 0.01422739 0.06304097 9.87291e-4 0.01391279 0.06315213 0.001078367 0.01399874 0.06303191 0.001224875 0.01372724 0.06316787 0.001455724 0.01387494 0.06304293 0.001496434 0.01370906 0.06319338 0.001889526 0.01391422 0.06309735 0.002037942 0.01395249 0.06320768 0.002360105 0.01427662 0.06312304 0.00243473 0.0143668 0.06323081 0.002631306 0.01472908 0.06324106 0.002681195 0.0148378 0.06314986 0.00252819 0.01507514 0.06325697 0.002595603 0.01532489 0.0631774 0.002247214 0.01537328 0.06327605 0.002404987 0.01559472 0.06328535 0.002077221 0.01550459 0.0631746 0.001808404 0.01566916 0.06330621 0.001697421 0.01549029 0.06321692 0.001454412 0.01561313 0.0633164 0.00136137 0.01524746 0.06321603 0.001085102 0.01537543 0.06333327 9.83895e-4 0.01498538 0.06325352 9.11709e-4 0.0148521 0.06336164 7.17194e-4 0.01458734 0.06327295 8.62885e-4 0.01459497 0.06335514 7.17957e-4 0.014279 0.06338495 7.92362e-4 0.01433312 0.06325626 9.45584e-4 0.0139063 0.06340181 0.00108236 0.01396286 0.06330937 0.001259148 0.01369214 0.06342566 0.001660525 0.01384454 0.06333351 0.001761436 0.01378685 0.06344479 0.002109527 0.01392859 0.06332004 0.002036154 0.01421141 0.06336891 0.002388358 0.01411324 0.06347048 0.002503931 0.01437973 0.06346398 0.002630114 0.01472872 0.06339478 0.002544879 0.01463371 0.06349247 0.00268197 0.01507383 0.06350827 0.002604424 0.01510989 0.0633884 0.00241065 0.01538801 0.0635246 0.00238502 0.01545047 0.06343823 0.00204432 0.01560622 0.06353658 0.00205022 0.01551103 0.06346458 0.001494944 0.01567322 0.06355327 0.001751124 0.01561647 0.06356787 0.001364588 0.01538449 0.06359457 9.87287e-4 0.01517069 0.06349402 0.00100094 0.01496607 0.06360638 7.41016e-4 0.01466917 0.06349104 8.65164e-4 0.01450806 0.06361711 7.22897e-4 0.01431488 0.0635128 9.51141e-4 0.01412737 0.06364077 8.79347e-4 0.01390278 0.06356459 0.001356899 0.0138607 0.06366091 0.001155436 0.01370447 0.06366854 0.001560449 0.01385223 0.06355714 0.001744687 0.01373666 0.06369262 0.001979112 0.01401686 0.06360632 0.002200901 0.01395392 0.06370836 0.002357304 0.01430034 0.06359583 0.002430438 0.01426291 0.0637232 0.002589344 0.01474899 0.06364679 0.002543807 0.01456922 0.06374245 0.00267595 0.01503515 0.06375908 0.002621293 0.01520651 0.06364661 0.002337098 0.01544773 0.06376975 0.002333045 0.0154429 0.06365883 0.002034366 0.01564109 0.06379473 0.001940786 0.01551532 0.06368255 0.001666843 0.01566749 0.06380969 0.001616656 0.01543372 0.06369698 0.001348733 0.01553267 0.06382554 0.001180887 0.01520508 0.0637418 0.001027166 0.01519012 0.06384813 8.44773e-4 0.01471149 0.06374228 8.63844e-4 0.01474827 0.06386035 7.09773e-4 0.01443302 0.06387865 7.41458e-4 0.0143094 0.06378686 9.50373e-4 0.0140115 0.06389456 9.64075e-4 0.01401758 0.06380462 0.001185834 0.01370567 0.063923 0.001542508 0.0138458 0.06382673 0.001619219 0.01373767 0.06393975 0.001961767 0.0139302 0.06384861 0.002058088 0.01388138 0.06395375 0.002270162 0.01418823 0.06386804 0.00237137 0.01426601 0.06397616 0.002594888 0.01466494 0.063892 0.002541601 0.01476794 0.06399691 0.00268501 0.015154 0.06401097 0.002565979 0.01515865 0.06391698 0.002388715 0.01549994 0.06403052 0.002267718 0.01542913 0.06393665 0.002080798 0.01566433 0.0640465 0.001866102 0.01552617 0.06396198 0.001564502 0.015625 0.06406521 0.001384258 0.01545846 0.06407827 0.00108999 0.01527816 0.06398701 0.001102983 0.0152195 0.06409674 8.67514e-4 0.01485037 0.06401014 8.6432e-4 0.01487493 0.06410789 7.26419e-4 0.01446783 0.06412649 7.32627e-4 0.01426959 0.06403821 9.56232e-4 0.01411938 0.06414073 8.9008e-4 0.01384967 0.06415867 0.001164495 0.01387196 0.06406855 0.001442193 0.01371473 0.0641697 0.001541018 0.01371622 0.06418985 0.001880884 0.01391839 0.06409764 0.002051949 0.01387536 0.06420743 0.002262115 0.01410067 0.06421333 0.002493441 0.01427507 0.06412279 0.002429485 0.0144751 0.064233 0.002658665 0.01465892 0.06412178 0.0025267 0.01497966 0.06425428 0.002645313 0.01515638 0.06414222 0.002381801 0.01542991 0.06427884 0.002347648 0.01542228 0.06418627 0.002094507 0.01564288 0.06429046 0.001953482 0.01552069 0.06420379 0.001731574 0.01562565 0.06431937 0.001366376 0.01542049 0.06422579 0.00127089 0.01530653 0.06434005 9.26822e-4 0.01501184 0.06425231 9.19712e-4 0.014997 0.06435495 7.61089e-4 0.01457816 0.0643686 7.09479e-4 0.01447129 0.06427836 8.73769e-4 0.01411467 0.06439089 8.86826e-4 0.01399886 0.06430584 0.001202821 0.01381331 0.06440669 0.001228034 0.01384574 0.06432896 0.001665651 0.0137372 0.06442421 0.001947164 0.01396816 0.06432396 0.002115786 0.01386898 0.06445235 0.002245545 0.01426839 0.06437242 0.002422153 0.01477801 0.06439936 0.002540647 0.01523303 0.05869555 0.001045286 0.01478892 0.05870306 8.6138e-4 0.01442462 0.05871087 8.8634e-4 0.01385724 0.05877178 0.001568436 0.01403862 0.05880618 0.002233803 0.01451897 0.05883371 0.002529203 0.01534885 0.05887717 0.002202212 0.01549738 0.05891197 0.001510322 0.01528936 0.05893486 0.001093864 0.01478117 0.05896109 8.60373e-4 0.01429402 0.05898493 9.45946e-4 0.01397407 0.05900633 0.001256167 0.01384478 0.05902594 0.001638472 0.01395684 0.05904912 0.002116382 0.01434075 0.05907458 0.002468228 0.01485329 0.05909883 0.002518832 0.01527917 0.05918431 0.001107394 0.01491433 0.05920475 8.83999e-4 0.01390844 0.05926316 0.00138396 0.01385486 0.05928587 0.001859903 0.01408779 0.05930906 0.002282083 0.0144459 0.05932933 0.002500295 0.01489436 0.05935132 0.002508819 0.01388674 0.05951541 0.001429438 0.01388049 0.05954092 0.001959145 0.01493149 0.05960267 0.002493858 0.01535427 0.05962759 0.002224266 0.01552706 0.05965477 0.00166434 0.01535505 0.0596795 0.001182138 0.01501995 0.05969947 9.29414e-4 0.01452898 0.05972278 8.5872e-4 0.01401174 0.05975282 0.001181483 0.01432681 0.05982351 0.002461791 0.01482748 0.05984759 0.002522885 0.01524114 0.0598697 0.00232619 0.01549506 0.05989265 0.00192523 0.01533621 0.05993062 0.001164674 0.01500767 0.05994993 9.22934e-4 0.01434725 0.05998218 9.28486e-4 0.01385992 0.06002098 0.001542747 0.01406449 0.06005764 0.002260208 0.01447147 0.06008052 0.002510488 0.0153529 0.06012725 0.002220928 0.01530408 0.06018447 0.001107811 0.01477992 0.06021171 8.58741e-4 0.01403188 0.06025117 0.00116378 0.0138607 0.06027162 0.001556754 0.01387935 0.06028968 0.001929104 0.01514106 0.06036335 0.002406358 0.01545655 0.06038731 0.002026915 0.01551556 0.06041085 0.001534998 0.01524394 0.06043726 0.001062214 0.0147379 0.06046342 8.50077e-4 0.01422458 0.06048917 9.89979e-4 0.01384186 0.06052672 0.001654744 0.01419609 0.06056612 0.002375483 0.01470178 0.06059187 0.002547144 0.01539814 0.06067585 0.001234352 0.0149399 0.06070363 8.8946e-4 0.01446187 0.06072658 8.86126e-4 0.01405066 0.06074988 0.001138627 0.01387929 0.06078922 0.001923382 0.01407992 0.06080883 0.002277374 0.01456224 0.06083464 0.002536833 0.01512342 0.06086248 0.00241506 0.01525974 0.06093645 0.001070439 0.01476955 0.06096184 8.58039e-4 0.01401442 0.06100207 0.001179158 0.01384776 0.06102591 0.001648128 0.01425176 0.06106972 0.002426564 0.01473516 0.06109338 0.002529263 0.01522237 0.06111741 0.002357542 0.01550716 0.06114482 0.001870036 0.01546216 0.06116998 0.001358091 0.01502782 0.06119942 9.14999e-4 0.01448398 0.06122529 8.80474e-4 0.01406824 0.06124871 0.001117885 0.01383513 0.06127643 0.001663088 0.01405799 0.0613085 0.002271294 0.0145266 0.06133311 0.002517461 0.01505869 0.06135839 0.002461493 0.01484805 0.06145828 8.61771e-4 0.01427251 0.06148648 9.57794e-4 0.01389461 0.06151372 0.00138837 0.0149129 0.06160187 0.002515852 0.01549935 0.06166243 0.001502752 0.01397407 0.06175595 0.001245975 0.01384091 0.06178045 0.001743495 0.014072 0.06180924 0.002281367 0.0146659 0.06184071 0.002548038 0.01525253 0.0618698 0.002323687 0.01550048 0.0619145 0.001453042 0.01463383 0.06196922 8.48812e-4 0.01415741 0.06199294 0.001041829 0.01387602 0.06201654 0.001450598 0.01408058 0.06205922 0.002282857 0.01449316 0.06208157 0.002512216 0.01503592 0.06210768 0.002470195 0.01515716 0.0621922 9.96799e-4 0.01464545 0.06221753 8.50046e-4 0.0138517 0.06228655 0.001849591 0.01406979 0.06230807 0.002261161 0.01441943 0.06232804 0.002494633 0.01495033 0.06235337 0.002498269 0.0155189 0.06239783 0.001817107 0.01543784 0.06242179 0.001314818 0.01403504 0.06250125 0.001161754 0.01386153 0.06253659 0.001872003 0.01518303 0.06261605 0.002380788 0.01551175 0.06266117 0.001527726 0.01525568 0.06268668 0.001071989 0.01433593 0.06273263 9.24734e-4 0.01389825 0.06276351 0.0013659 0.01388287 0.06279057 0.00195074 0.0144329 0.06282907 0.002501785 0.01528066 0.06287187 0.002295076 0.0155071 0.06291192 0.001513183 0.01487797 0.0629568 8.68503e-4 0.01435679 0.06298184 9.21774e-4 0.01386797 0.06303864 0.001904785 0.01408708 0.06305915 0.00227952 0.01438856 0.06307631 0.00247842 0.01485985 0.06309896 0.002521693 0.0153535 0.06312733 0.00221914 0.01544451 0.06317138 0.001321375 0.01479279 0.0632106 8.57699e-4 0.0140165 0.06325244 0.00118041 0.01385223 0.06327402 0.001605749 0.01412004 0.06331151 0.002320408 0.01460117 0.06333673 0.0025357 0.01539343 0.0633803 0.002168953 0.01552128 0.06340986 0.001551628 0.01518648 0.06344175 0.001004397 0.01398336 0.06350505 0.001229763 0.01392889 0.06354671 0.002072572 0.01480817 0.06359666 0.002530455 0.01517987 0.06369113 0.001010894 0.01429736 0.06373423 9.37704e-4 0.01393604 0.06375962 0.001319289 0.01384532 0.06378066 0.001736938 0.01401203 0.06380426 0.002202689 0.01447641 0.06383109 0.002517461 0.01496458 0.06385439 0.00248456 0.01531404 0.0638743 0.002253293 0.01552927 0.06390041 0.001770675 0.0153948 0.06392586 0.001240432 0.01507848 0.06394636 9.5649e-4 0.01462906 0.0639683 8.52124e-4 0.01417922 0.06399142 0.001025438 0.01390546 0.06401336 0.001379787 0.01386618 0.06403946 0.001919209 0.01418054 0.06406521 0.002367973 0.0148794 0.06410014 0.002511262 0.01549994 0.06414258 0.001927495 0.01547604 0.06416696 0.001411914 0.01519393 0.06419008 0.001020848 0.01470482 0.06421482 8.52306e-4 0.01415205 0.06424343 0.001030862 0.01383918 0.06427437 0.00160408 0.01432687 0.0643236 0.002461612 0.01488953 0.06435102 0.002515614 0.01531022 0.06437426 0.002255797 0.01550829 0.06439518 0.001861214 0.0137192 0.05869776 0.001865506 0.01381999 0.05869632 0.001266717 0.01383596 0.05871599 0.002186715 0.01542633 0.05884897 0.001048743 0.01502877 0.05886822 7.71024e-4 0.01469486 0.05925816 0.002675712 0.01552236 0.06129771 0.002214908 0.01429039 0.06224095 0.002596318 0.01541906 0.06234955 0.001038253 0.01497089 0.06287097 7.57181e-4 0.01511955 0.06336414 8.13028e-4 0.01375216 0.06343245 0.001387596 0.0138089 0.06392651 0.001254737 0.01553201 0.06467103 0.001688897 0.01531976 0.06469327 0.002154946 0.0156303 0.06456822 0.001824796 0.01547539 0.0646587 0.002052664 0.01549845 0.06455278 0.002203285 0.01559078 0.06444597 0.002072989 0.01525706 0.06463176 0.002389729 0.01507097 0.06468546 0.002408146 0.01532435 0.06455945 0.00240606 0.01475894 0.064691 0.002489864 0.01505327 0.0645464 0.002583801 0.01492714 0.06462919 0.002561748 0.01466608 0.06461995 0.002606391 0.01482486 0.06445693 0.002668917 0.01460039 0.06453102 0.002656042 0.01447498 0.06468015 0.002489805 0.01406949 0.06469351 0.002172946 0.0143696 0.06457608 0.002585828 0.01422065 0.06467664 0.002385377 0.01408618 0.06456053 0.002438366 0.01393926 0.0646227 0.002221763 0.01394283 0.06469523 0.001489818 0.01384848 0.06466948 0.001859247 0.01372826 0.06453323 0.001861155 0.01374846 0.06457597 0.001546382 0.01384794 0.0646454 0.001401066 0.01427358 0.06469178 0.00102669 0.01405143 0.06464922 0.001074314 0.01384478 0.0645371 0.001221716 0.01398998 0.06445229 9.95688e-4 0.0147013 0.06468939 8.89157e-4 0.0143041 0.06454741 8.09185e-4 0.01438766 0.06464743 8.63028e-4 0.01470029 0.06457448 7.50503e-4 0.014638 0.06444662 7.11496e-4 0.01494127 0.06467163 8.95089e-4 0.01534211 0.06469357 0.001241564 0.01502287 0.06456017 7.96745e-4 0.01524806 0.06463819 9.9731e-4 0.01513856 0.06444758 8.2285e-4 0.01536041 0.06451869 9.99161e-4 0.01550549 0.06456315 0.001211166 0.01549601 0.06465691 0.001388967 0.01562464 0.06454205 0.001480042 0.01509636 0.05752581 9.82965e-4 0.01552206 0.05752605 0.001717925 0.01427471 0.05752521 9.81269e-4 0.01386129 0.0575245 0.001693665 0.01427292 0.05752623 0.002406954 0.01512217 0.05752265 0.002410471 0.01512581 0.05680674 9.31263e-4 0.01424515 0.05680632 9.29357e-4 0.01512497 0.05680638 0.002460598 0.0155664 0.05680686 0.001692116 0.01424217 0.05680608 0.002459108 0.01380228 0.05680656 0.001693308 0.01314085 0.05679512 6.42084e-4 0.01389509 0.05679512 -1.87187e-5 0.0151056 0.05679512 -1.46443e-4 0.01286107 0.05679512 0.001311182 0.01283979 0.05679512 0.00195825 0.01592975 0.05679512 3.07068e-4 0.01377934 0.05679512 0.003327488 0.01312506 0.05679512 0.002740204 0.01635342 0.05679512 8.56547e-4 0.01439356 0.05679512 0.003533661 0.01655209 0.05679512 0.001601815 0.01513296 0.05679512 0.003514647 0.01642417 0.05679512 0.00237745 0.01594871 0.05679512 0.003078937 0.01297324 0.05869513 0.002432584 0.01352077 0.05869513 0.003179967 0.01460677 0.05869513 0.003575682 0.01555186 0.05869513 0.003352344 0.01624548 0.05869513 0.002740204 0.01654517 0.05869513 0.001881122 0.01641708 0.05869513 9.65006e-4 0.01585072 0.05869513 2.33637e-4 0.01514625 0.05869513 -1.15291e-4 0.01426768 0.05869513 -1.34522e-4 0.01349663 0.05869513 2.55253e-4 0.01297599 0.05869513 9.23755e-4 0.01281929 0.05869513 0.001756429 + + + + + + + + + + 0.1735908 0.003589153 -0.9848114 0.142266 -0.004988253 -0.9898159 -0.009249567 0.005992293 -0.9999393 -0.04267972 -0.005973875 -0.9990711 -0.2071213 0.005982339 -0.9782971 -0.2396173 -0.005956709 -0.9708492 -0.3968114 0.005964159 -0.9178808 -0.4270723 -0.005937337 -0.9041981 -0.5707714 0.00594598 -0.8210876 -0.5976186 -0.005919039 -0.8017587 -0.7221108 0.00592786 -0.6917521 -0.7445117 -0.005901038 -0.6675834 -0.8448314 0.00590837 -0.535 -0.8619365 -0.00588274 -0.5069821 -0.9340685 0.005889892 -0.3570455 -0.9452436 -0.005865454 -0.3263131 -0.9862853 0.005871951 -0.1649451 -0.9911355 -0.005848288 -0.1327263 -0.999415 0.005854368 0.03369837 -0.9977954 -0.005828678 0.06610888 -0.9729351 0.005834758 0.2310047 -0.964961 -0.00581032 0.2623293 -0.9078948 0.005816459 0.4191576 -0.8939297 -0.00579214 0.4481697 -0.8068767 0.005798459 0.5906915 -0.7875163 -0.005774974 0.6162669 -0.6738758 0.005781352 0.7388221 -0.6499296 -0.005755841 0.7599727 -0.5141713 0.00576204 0.8576682 -0.4866176 -0.005738079 0.8735963 -0.3340902 0.005744695 0.9425237 -0.3040417 -0.005720674 0.9526417 -0.1407641 0.00572586 0.9900266 -0.1094343 -0.005702197 0.9939778 0.05813771 0.005707681 0.9982923 0.08950901 -0.005684554 0.9959698 0.2547371 0.005690276 0.9669936 0.2849078 -0.005666494 0.9585382 0.4412387 0.005671262 0.897372 0.4690283 -0.005648612 0.8831651 0.6102494 0.005652904 0.7921893 0.634581 -0.005631089 0.7728359 0.7550832 0.005635619 0.6556049 0.7750208 -0.005612075 0.6319109 0.8699883 0.005616962 0.4930405 0.8847808 -0.005594432 0.465974 0.9504138 0.005598545 0.3109377 0.9595174 -0.00557661 0.2815939 0.9931737 0.005580663 0.1165112 0.9962741 -0.005558729 0.08606576 0.996573 0.005562424 -0.08253198 0.9935946 -0.005540847 -0.1128684 0.9604769 0.005544424 -0.2783049 0.9515854 -0.005522966 -0.307335 0.8863159 0.005526125 -0.4630482 0.8719093 -0.005505025 -0.4896365 0.7770291 0.005508244 -0.6294405 0.7577183 -0.005487442 -0.6525587 0.6369476 0.00549066 -0.7708876 0.6135335 -0.005469024 -0.7896498 0.4716258 0.005471885 -0.8817819 0.4464736 -0.004877924 -0.8947836 0.3035731 0.003667116 -0.9528011 0.2807367 -0.00269556 -0.9597811 1.81898e-6 1 -2.09368e-5 -5.09634e-6 1 -6.55752e-5 -1.01791e-5 1 -1.06335e-5 0 1 0 0 1 2.78545e-6 5.51001e-4 0.9999998 -4.11666e-4 -2.75352e-4 0.9999999 -5.16584e-4 -0.001901447 0.999998 7.14349e-4 2.19446e-4 1 6.86764e-5 0.003588855 0.9999932 -9.23976e-4 1.84193e-5 1 6.06617e-5 1.2435e-4 1 -3.14257e-5 0 1 -2.98143e-6 -7.67102e-4 0.9999997 2.17498e-5 -8.25734e-5 0.9999996 -9.16532e-4 0 1 0 1.86833e-4 1 2.79901e-5 1.13162e-5 1 -1.02449e-4 -3.23487e-4 1 6.73158e-5 -8.156e-5 1 1.47256e-5 0 1 6.87892e-7 1.882e-5 1 7.03878e-5 -1.08002e-5 1 3.36415e-5 0.003273487 0.9999946 1.62475e-4 0 1 -2.98146e-6 0 1 1.3758e-6 -0.001329123 0.9999954 -0.002739548 2.64137e-5 1 -4.11236e-5 0 1 1.49073e-6 -3.97526e-5 1 -4.59536e-5 0 1 -2.7516e-6 0 1 -3.04712e-6 0 1 4.4721e-6 0 1 -2.7517e-6 0 1 -1.31308e-6 0 1 -1.11807e-6 0 1 -2.75166e-6 0 1 3.04821e-6 0 1 -5.82645e-7 0 1 -2.74943e-6 0 1 2.70446e-6 0 1 -1.54219e-6 0 1 -1.83438e-6 0 1 3.08556e-6 0 1 7.71102e-7 0 1 2.66843e-6 0 1 -3.08533e-6 0 1 -1.33434e-6 0.04354488 0.9680243 -0.2470487 0.003025949 0.9718341 -0.2356465 -0.002196967 0.9707442 -0.2401062 -0.05138123 0.9687435 -0.2426851 -0.07503074 0.9722326 -0.2216627 -0.09812301 0.9689469 -0.2269669 -0.1411801 0.9689283 -0.2030917 -0.1504695 0.9728124 -0.1760543 -0.1786097 0.9689298 -0.171096 -0.206933 0.9728125 -0.1039935 -0.2089053 0.9689466 -0.1322922 -0.2310982 0.968912 -0.08833646 -0.231063 0.9728125 -0.01568341 -0.2438107 0.9689655 -0.04076951 -0.2473325 0.9688948 0.008339762 -0.2404375 0.9689843 0.05709165 -0.2190859 0.9728125 0.07508063 -0.2247425 0.9688779 0.1037623 -0.1728746 0.9728128 0.1541092 -0.1993396 0.9690034 0.1459323 -0.1668564 0.9688621 0.1829352 -0.1269853 0.9690228 0.2118243 -0.09965294 0.972812 0.2090601 -0.08274394 0.9688446 0.233439 -0.0347529 0.9690419 0.2444383 -0.01085525 0.9728117 0.2313429 0.01440405 0.968829 0.2473114 0.07963794 0.9728118 0.2174745 0.06287562 0.9690616 0.2386766 0.1093409 0.9688117 0.2223705 0.1571841 0.9725667 0.1714853 0.1505778 0.9690821 0.1954644 0.1874153 0.9687086 0.1627241 0.2092372 0.9724203 0.1030462 0.2121078 0.9698249 0.1202079 0.2377769 0.9682003 0.07778501 0.2321355 0.9725613 0.01541817 0.2409171 0.9701341 0.02826166 0.2493658 0.9681892 -0.0206511 0.2328927 0.9701581 -0.06748622 0.2200157 0.9725505 -0.07575452 0.221813 0.9681785 -0.1158857 0.1883364 0.9701821 -0.152565 0.1735049 0.9725393 -0.1551243 0.1594299 0.968168 -0.192958 0.09667241 0.973012 -0.2095285 0.114267 0.970206 -0.2136437 0.07520091 0.9688508 -0.2359515 -0.7404622 -0.02765923 0.6715286 -0.9226496 0.02231299 0.3849934 -0.992567 -0.02374237 0.1193609 -0.9769808 0.02921611 -0.2113174 -0.842355 -0.0306344 -0.5380516 -0.6138048 0.02797549 -0.788962 -0.3692412 -0.02295535 -0.9290501 -0.02117043 0.0203768 -0.9995683 0.2516653 -0.02569025 -0.9674734 0.5040686 0.02486991 -0.8633056 0.8212521 -0.02097129 -0.5701802 0.903667 0.01473194 -0.4279825 0.9991017 -0.01547116 -0.03945225 0.9966285 0.01032513 0.08139467 0.8402045 -0.002059757 0.542266 0.8486668 0.002816855 0.5289205 0.4741179 -0.01251339 0.8803725 0.313354 0.03067064 0.949141 -0.1370612 -0.03460741 0.9899579 -0.4587701 0.03683888 0.8877912 -0.7401828 0.03142237 0.6716711 -0.9343908 -0.02928805 0.355044 -0.9948766 0.0274195 0.09730768 -0.9233429 -0.0337243 -0.3824927 -0.7924586 0.03591686 -0.6088673 -0.3799344 -0.03592365 -0.9243156 -0.1197839 0.03583836 -0.992153 0.3953483 -0.03584444 -0.9178317 0.6247831 0.0357595 -0.7799791 0.9063902 -0.02670067 -0.421597 0.9907404 0.02340161 -0.1337382 0.9956023 -0.0181533 0.09190565 0.8901164 0.0224511 0.4551799 0.7309234 -0.02154052 0.6821195 0.5566769 0.0173121 0.8305488 0.2083213 -0.02305382 0.9777888 -0.06355011 0.03359454 0.9974131 -0.453251 -0.03758674 0.8905903 -0.003204643 -0.9999924 -0.002249836 -1.89197e-4 -1 3.29546e-4 -0.001459777 -0.9999988 6.97225e-4 0.001293659 -0.9999977 0.001721084 -2.09285e-4 -0.9999967 0.002575874 -0.001371622 -0.9999986 9.63886e-4 1.44799e-5 -0.9999998 6.86402e-4 -2.68526e-4 -1 0 -3.16967e-4 -0.9999997 -8.22466e-4 -7.97438e-4 -0.9999994 8.11964e-4 -3.13378e-4 -1 -7.19405e-5 -3.98683e-4 -0.9999995 9.70823e-4 -7.13268e-4 -0.9999997 4.29079e-4 8.90304e-5 -1 5.89904e-5 2.13112e-4 -1 -7.53901e-6 0 -1 0 0 -1 8.36267e-7 0 -1 6.75682e-6 4.57707e-6 -1 3.83912e-4 0 -1 1.50454e-6 -1.0474e-4 -1 3.77998e-4 0 -1 -8.67093e-6 2.2124e-4 -1 -2.04547e-5 4.43085e-4 -0.9999998 4.31439e-4 0 -1 7.07444e-7 1.20357e-4 -1 5.61603e-4 0 -1 5.20567e-6 0 -1 -1.56157e-6 2.45242e-4 -1 -1.3291e-4 7.05484e-4 -0.9999997 3.57074e-4 5.25875e-4 -0.9999997 6.07246e-4 7.27992e-4 -0.9999998 3.60661e-4 9.50354e-4 -0.9999996 7.74336e-5 0 -1 3.62206e-7 0 -1 -1.16567e-6 0 -1 7.30979e-6 0 -1 -1.80626e-5 -3.29804e-6 -1 -3.99401e-5 0 -1 -7.29542e-7 -1.45584e-5 -0.9999999 6.10288e-4 0.001498281 -0.9999794 0.006243526 -1.15298e-4 -1 -1.30145e-6 9.90752e-4 -0.9999995 -8.1762e-5 -1.85101e-4 -1 -9.79488e-5 4.51813e-4 -0.9999986 0.001605391 -1.01511e-4 -1 1.42091e-7 -3.30707e-5 -1 2.70551e-5 3.38699e-4 -1 1.19676e-4 0.002163827 -0.9999952 -0.002200841 6.48248e-4 -0.9999984 0.001672863 3.59654e-4 -1 3.58696e-4 0.001550793 -0.9999933 -0.003333628 -0.7670763 0.03632301 0.6405269 -0.9593206 -0.03347766 0.2803272 -0.9993907 0.024374 0.02498787 -0.8957169 -0.02597928 -0.4438652 -0.82112 0.01426577 -0.5705775 -0.4098958 -0.001283288 -0.9121315 -0.3234387 -0.02604275 -0.9458907 0.01948922 0.02101206 -0.9995893 0.4055047 -0.01580423 -0.9139564 0.495988 0.007838189 -0.8682941 0.8316395 -0.01150709 -0.5551967 0.8851984 0.01261603 -0.4650425 0.9998712 -0.01214236 0.01049488 0.9990504 -0.002663612 0.04348826 0.853426 0.01392507 0.5210281 0.7732371 -0.01672053 0.6338967 0.4819692 0.01432865 0.876071 0.3118281 -0.02211248 0.9498812 -0.1243125 0.03375703 0.9916688 -0.4428651 -0.04489439 0.8954636 9.47237e-4 -0.7029242 0.7112642 -0.00232762 -0.7207304 0.6932116 3.89054e-4 -0.822683 0.5685002 3.27777e-4 -0.8230323 0.5679945 3.79298e-5 -0.8916765 0.4526732 4.4182e-4 -0.8938472 0.4483717 3.72854e-4 -0.9450665 0.3268778 2.04865e-4 -0.9444756 0.3285816 -1.88901e-4 -0.977558 0.2106665 -9.5803e-4 -0.979229 0.2027553 -8.8413e-4 -0.9974108 0.07190972 0.007014989 -0.9993374 0.03571754 -0.006489217 -0.9972826 0.0733866 7.52107e-5 -0.9976636 0.06831884 1.99039e-4 -0.9978053 0.06621575 -1.35993e-4 -0.99962 0.02756756 3.71841e-4 -0.9999597 0.008975505 -0.8124426 1.42564e-4 0.5830414 -0.8335707 -0.01040023 0.5523148 -0.9981147 -0.002286374 0.06133508 -0.9975039 -0.005093574 0.07042807 -0.9027852 0.01218026 -0.4299192 -0.8211953 -0.01917308 -0.5703252 -0.6516602 0.01357817 -0.7583896 -0.4103026 -0.0140658 -0.911841 -0.2103988 0.01319873 -0.9775266 0.001722157 -0.01264709 -0.9999186 0.2672869 0.01649796 -0.9634758 0.518193 -0.02251321 -0.8549674 0.7476606 0.02894455 -0.6634501 0.9286449 -0.02949804 -0.3697953 0.9991133 0.030366 0.02916365 0.9774399 -0.01635771 0.2105795 0.7138404 0.009589016 0.7002428 0.6584114 -0.01166158 0.752568 0.1839373 0.01941645 0.9827462 0.08278518 -0.009346425 0.9965236 -0.3826611 -0.01342958 0.9237912 -0.494624 0.01701009 0.8689406 -0.9723694 -0.2312484 -0.03196805 -0.9240377 -0.3656437 -0.1116198 -0.9037569 -0.3533194 -0.2416385 -0.9858303 -0.1407828 0.09120833 -0.9917635 -0.07899373 -0.1008228 -0.9329648 -0.3426001 0.1104621 -0.9365173 -0.1001275 -0.3360206 -0.9288274 -0.2177261 -0.2997915 -0.7717131 -0.634294 0.04615432 -0.8493843 -0.5083702 -0.141796 -0.7216166 -0.6737328 0.1592282 -0.7770214 -0.6282086 0.03989577 -0.9849501 -0.1678909 0.0410614 -0.958163 -0.2630892 0.1127289 -0.9420024 -0.3305675 0.05793696 -0.9745123 -0.2015399 -0.09852606 -0.8901848 -0.4384228 0.1239214 -0.8901321 -0.4384325 0.1242659 -0.9652904 -0.2322554 -0.1194653 -0.9172458 -0.396144 -0.04159528 -0.7686738 -0.6383974 0.03986585 -0.8476069 -0.5223383 0.09341031 -0.8208581 -0.5425941 0.1782805 -0.7519671 -0.6410934 0.1534427 -0.8795095 -0.2260223 -0.4187806 0.9877598 -0.1548767 0.01854407 0.9853774 -0.1669569 -0.03401291 0.9765356 -0.09282606 -0.1943231 0.9156383 -0.2859867 -0.2825209 0.9434069 -0.3284166 0.04610943 0.9478884 -0.2044904 -0.2443178 0.9405143 -0.2420203 -0.2384515 0.8599907 -0.1725929 -0.4802371 0.8887397 -0.3567136 -0.2879189 0.7940894 -0.5966757 0.1157591 0.8031215 -0.5894322 0.08698046 0.8310686 -0.5508512 -0.07673454 0.7270337 -0.6813308 0.08491414 0.9662204 -0.2013946 -0.1608052 0.9431294 -0.3289622 0.04786419 0.8904073 -0.4533832 0.04023176 0.9250978 -0.1150702 -0.3618742 0.9056036 -0.423725 0.01842337 0.8416737 -0.5129913 0.1685985 0.935557 -0.2368386 -0.2619935 0.8848572 -0.454934 -0.1003138 0.8556606 -0.2766791 -0.4373713 0.8326177 -0.5386312 -0.1289356 0.789542 -0.1704207 -0.5895594 0.8437787 -0.3472678 -0.4091975 0.8164817 -0.4446896 -0.3682511 0.7261047 -0.6861553 0.04430645 0.6441165 -0.6057758 -0.4670649 0.6180645 -0.6440141 -0.450824 0.8026372 -0.3051627 -0.5124933 0.5566321 -0.7332604 -0.3904995 0.466445 -0.8162915 -0.3407306 0.3832747 -0.8879809 -0.2541462 0.2328338 -0.9576442 -0.1694289 0.7974666 -0.3821479 -0.4669156 0.723353 -0.5425296 -0.4271091 0.6932895 -0.6059404 -0.3901102 0.5932499 -0.7263126 -0.3471667 0.8413353 -0.3205054 -0.4352369 0.1492452 -0.9849067 -0.08766281 0.5135883 -0.8121019 -0.2769799 0.4183143 -0.8750294 -0.2435914 0.8321744 -0.420614 -0.3613445 0.7301665 -0.5963318 -0.3335345 0.9175173 -0.1971056 -0.3454149 0.658256 -0.6994764 -0.2782659 0.8211244 -0.4363312 -0.3679267 0.5495071 -0.7970815 -0.2504059 0.9229254 -0.2400795 -0.3009497 0.2529637 -0.9613279 -0.1088947 0.3082616 -0.9419635 -0.1329646 0.8485594 -0.4508365 -0.2769356 0.9466483 -0.1783148 -0.2684414 0.4038314 -0.9019938 -0.1527336 0.8077113 -0.5435999 -0.228258 0.7481224 -0.6294895 -0.2098952 0.6923237 -0.6900158 -0.2111071 0.919571 -0.3427553 -0.1921151 0.5058565 -0.8512538 -0.1395571 0.9260992 -0.3338545 -0.1757314 0.9218441 -0.351148 -0.1640086 0.7008438 -0.7050988 -0.1079524 0.1418277 -0.9892862 -0.034608 0.4831156 -0.8695191 -0.1026439 0.7838608 -0.6134904 -0.09587365 0.4024224 -0.912791 -0.06977778 0.9750388 -0.2121464 -0.06552422 0.7182368 -0.68894 -0.09745657 0.9387359 -0.3326582 -0.09007549 0.1555779 -0.987179 -0.03568273 0.8639966 -0.5003394 -0.05630588 0.4129577 -0.9096189 -0.045381 0.9632156 -0.2687211 -0.002182304 0.6017341 -0.7981123 -0.03054696 0.8660565 -0.4988803 -0.0326299 0.9704813 -0.2404968 0.01809602 0.6135492 -0.7896118 -0.008403599 0.7691845 -0.6382977 0.03051638 0.3270004 -0.9448304 -0.01913833 0.9418227 -0.3277999 0.0742799 0.8301917 -0.553431 0.06705063 0.7705793 -0.6364958 0.03287434 0.9538581 -0.2784764 0.1122748 0.4296651 -0.9023945 0.03274214 0.2921899 -0.9562491 0.01459151 0.2198068 -0.9753903 0.01728421 0.8959745 -0.4095296 0.1717998 0.8258832 -0.5494241 0.1266897 0.9040625 -0.3740621 0.2067578 0.6610609 -0.7398301 0.1250997 0.6113914 -0.7846688 0.1024473 0.8991118 -0.3881948 0.2022451 0.5341927 -0.840801 0.08770358 0.7768891 -0.5899083 0.2201173 0.4322521 -0.8955993 0.1051672 0.685029 -0.7060506 0.1795212 0.9096341 -0.2761827 0.3103048 0.8766428 -0.3465461 0.3337712 0.1615215 -0.9860408 0.04042899 0.5917077 -0.7838675 0.1882387 0.2029771 -0.9775249 0.05696713 0.803014 -0.5076473 0.3121904 0.4716362 -0.86947 0.1469056 0.7774084 -0.5579805 0.2903348 0.8838219 -0.2650396 0.3855037 0.637923 -0.7272403 0.25333 0.8675826 -0.1766875 0.4648461 0.3856199 -0.9102579 0.1507579 0.2963689 -0.9476968 0.1184746 0.8515557 -0.3083795 0.4239753 0.6015944 -0.7540248 0.263687 0.7941236 -0.4469443 0.4118355 0.7661836 -0.5140377 0.3856528 0.4833151 -0.8466777 0.222584 0.6604716 -0.6647579 0.349105 0.8352344 -0.1808524 0.5193035 0.6288341 -0.6918886 0.3547644 0.7694926 -0.389665 0.5060061 0.4435795 -0.858821 0.2562493 0.22531 -0.9654501 0.1309257 0.1763173 -0.9780519 0.1110261 0.7399504 -0.43387 0.5140333 0.4165778 -0.8738831 0.2505819 0.6315663 -0.6403343 0.4371455 0.746658 -0.2806237 0.6031188 0.583529 -0.6894575 0.429118 0.7319802 -0.3807229 0.5650267 0.4248306 -0.8517215 0.3067402 0.7276245 -0.2463162 0.6402273 0.6253457 -0.5472142 0.5563268 0.3511523 -0.8912097 0.2871193 0.5725151 -0.6602603 0.4860893 0.2452199 -0.9481196 0.2023276 0.6863858 -0.3113369 0.6572244 0.6234472 -0.5189831 0.5847822 0.6657662 -0.2441905 0.7050719 0.469539 -0.7615724 0.4466997 0.3988113 -0.8353563 0.3783246 0.5434802 -0.5973435 0.5897544 0.5035959 -0.6635082 0.5533065 0.6178053 -0.3221663 0.7173044 0.5753263 -0.4483676 0.6840806 0.5956447 -0.1741009 0.7841532 0.4392867 -0.7253393 0.5300096 0.3067557 -0.8815014 0.3589653 0.3197433 -0.8639475 0.3890488 0.5590947 -0.2357526 0.7948797 0.1386538 -0.9781772 0.1547402 0.5014159 -0.4972692 0.7080293 0.09336805 -0.9890072 0.1146616 0.4870882 -0.5201097 0.7015919 0.5283458 -0.1999971 0.8251376 0.494383 -0.2627546 0.8285804 0.4312793 -0.6616987 0.6133132 0.4560397 -0.4873389 0.7446668 0.4736443 -0.2385826 0.8477851 0.3493382 -0.7488942 0.5631344 0.4049354 -0.5473993 0.7323806 0.2772355 -0.8611151 0.4261704 0.3442015 -0.702386 0.6230404 0.3789369 -0.434337 0.8171648 0.1748489 -0.9327083 0.3154098 0.3690935 -0.2813967 0.8857687 0.3708519 -0.4338706 0.8211123 0.3390775 -0.4946181 0.8002371 0.1671277 -0.9322616 0.3208687 0.2694957 -0.7077676 0.6530216 0.2652753 -0.7566987 0.5975248 0.2039887 -0.8554249 0.476064 0.295237 -0.2475231 0.9228041 0.2663535 -0.3423163 0.9010413 0.2671769 -0.4999137 0.8238343 0.2210568 -0.6252042 0.748501 0.2196177 -0.6838278 0.6958072 0.1381835 -0.8838579 0.4468787 0.1895839 -0.2382081 0.9525308 0.2056348 -0.3379181 0.9184366 0.05865806 -0.9826033 0.1762104 0.1674503 -0.5035446 0.8475868 0.1399036 -0.8540422 0.5010381 0.1706709 -0.6044065 0.7781801 0.06740748 -0.9688541 0.2382816 0.1253652 -0.2406637 0.9624783 0.1061487 -0.7305961 0.6745086 0.09267854 -0.3418585 0.9351703 0.1003298 -0.7616614 0.6401607 0.09812927 -0.4958465 0.8628482 0.09628075 -0.8460927 0.5242683 0.07404631 -0.5895329 0.8043435 0.05870842 -0.9088817 0.4129014 0.03637206 -0.2752557 0.9606828 0.04755711 -0.947115 0.317351 -0.003779053 -0.323284 0.9462945 0.008971035 -0.8416209 0.5399944 0.003502786 -0.6183232 0.7859162 0.009998202 -0.6294631 0.7769661 -0.02363252 -0.3015401 0.9531606 0.0137366 -0.8434568 0.5370214 -0.112184 -0.2422647 0.9637026 -0.07437759 -0.3488755 0.934213 0.006511986 -0.9792022 0.2027831 -0.08304113 -0.5391273 0.8381205 -0.06637513 -0.6110731 0.7887865 -0.01427561 -0.8810157 0.4728716 -0.02268046 -0.9342226 0.355969 -0.08240509 -0.7230973 0.6858132 -0.1618598 -0.2419927 0.9566823 -0.1927223 -0.3552954 0.9146713 -0.1629201 -0.4834658 0.8600686 -0.2452667 -0.2734926 0.9300785 -0.1126753 -0.7431601 0.6595585 -0.0434212 -0.9397884 0.3389873 -0.21581 -0.3415346 0.9147569 -0.09775441 -0.8889788 0.4473932 -0.1833446 -0.6493146 0.738089 -0.1726455 -0.6780542 0.7144482 -0.2397256 -0.5876672 0.7727736 -0.3002628 -0.2816061 0.9113399 -0.3249587 -0.4170814 0.8487904 -0.03856098 -0.989265 0.1409533 -0.1520526 -0.862365 0.4829148 -0.2465791 -0.5846027 0.7729414 -0.1292547 -0.8911672 0.4348729 -0.3906345 -0.2422593 0.8880963 -0.09464287 -0.9571378 0.2737333 -0.3200614 -0.4189698 0.8497207 -0.2462281 -0.7721213 0.5858332 -0.3586546 -0.5364301 0.7639435 -0.4465894 -0.2368888 0.8628103 -0.4515501 -0.3468899 0.8220523 -0.2628914 -0.768844 0.5828954 -0.4002509 -0.4986938 0.7688328 -0.2693986 -0.7935905 0.5455626 -0.5546627 -0.191395 0.8097638 -0.4038084 -0.6224681 0.670427 -0.1708096 -0.9357603 0.3085076 -0.335041 -0.7432926 0.5790196 -0.5057801 -0.3596276 0.7841268 -0.4898783 -0.5138432 0.7042617 -0.1701498 -0.9378657 0.3024185 -0.4772395 -0.5010844 0.7219121 -0.3172502 -0.8497481 0.4210469 -0.6033738 -0.1952905 0.7731765 -0.5661439 -0.4352284 0.700041 -0.5998376 -0.3558256 0.7166472 -0.4287757 -0.7389727 0.5196834 -0.08945268 -0.9873006 0.1312855 -0.2812215 -0.8576893 0.4304458 -0.5271375 -0.6041514 0.5976013 -0.6760807 -0.1972741 0.7099281 -0.4070154 -0.7458562 0.5272921 -0.6297897 -0.3352495 0.7006946 -0.2442407 -0.9250873 0.2907923 -0.1737229 -0.9641537 0.2005692 -0.6205478 -0.4836515 0.6172534 -0.5644111 -0.5945901 0.572628 -0.3685682 -0.8452917 0.3868328 -0.7115027 -0.1916064 0.6760553 -0.546068 -0.6492556 0.5294119 -0.6956013 -0.3774542 0.6112832 -0.3839084 -0.838855 0.3859234 -0.7766455 -0.1939132 0.5993492 -0.6971773 -0.3789638 0.6085478 -0.6832678 -0.4824354 0.5480887 -0.3744999 -0.8648183 0.3344238 -0.782751 -0.2527163 0.5687139 -0.5825992 -0.6555178 0.4804943 -0.5673634 -0.6867443 0.4544019 -0.2570206 -0.9419671 0.2159591 -0.1679325 -0.9730765 0.1578638 -0.4830076 -0.7883988 0.3809607 -0.7226561 -0.449909 0.5247381 -0.7203046 -0.5001119 0.480676 -0.6713919 -0.5974223 0.4385426 -0.8345535 -0.2000393 0.5133274 -0.8160692 -0.3335732 0.4719746 -0.6387946 -0.6703185 0.3776437 -0.2907328 -0.9386934 0.1852816 -0.8204295 -0.351735 0.4507527 -0.4748923 -0.833467 0.2825066 -0.4898197 -0.8200241 0.2960357 -0.7254315 -0.5811309 0.3688308 -0.3629149 -0.9062827 0.2166666 -0.8654286 -0.2736136 0.4197249 -0.8719752 -0.3376774 0.354448 -0.8557094 -0.3977903 0.3309449 -0.7326296 -0.5996472 0.3219891 -0.6489771 -0.7160354 0.2571424 -0.10326 -0.9934511 0.04891139 -0.5297934 -0.816726 0.2286429 -0.3413723 -0.9292367 0.1413655 -0.3912119 -0.9073498 0.1538501 -0.9099293 -0.31948 0.2645022 -0.1827228 -0.9804894 0.07247728 -0.8696301 -0.4002288 0.2890681 -0.7600103 -0.6139141 0.2132931 -0.6622607 -0.7154868 0.2224622 -0.9061564 -0.3667635 0.2106303 -0.5577568 -0.8151232 0.1564666 -0.4474732 -0.8846772 0.13082 -0.7882916 -0.5895657 0.1760926 -0.7694891 -0.6127375 0.1801096 -0.9412591 -0.2917371 0.1700615 -0.6413018 -0.7540827 0.1417442 -0.9349867 -0.3244513 0.1432881 -0.823308 -0.5538108 0.1243289 -0.3478974 -0.9346759 0.07313305 -0.9517356 -0.2896451 0.1015149 -0.2710325 -0.961056 0.05396968 -0.9395204 -0.3346348 0.0729447 -0.576732 -0.8142351 0.06634354 -0.8316565 -0.5515431 0.06440395 -0.7930521 -0.6037799 0.08073508 -0.9540889 -0.2985974 0.02353745 -0.6836984 -0.7273074 0.05983853 -0.5766544 -0.8142858 0.06639677 -0.9422291 -0.3349686 -5.56713e-4 -0.1937611 -0.9807574 0.02390724 -0.8406265 -0.541598 0.004331648 -0.7874121 -0.615999 -0.02297008 -0.9524285 -0.3011001 -0.04710382 -0.6933202 -0.7205864 -0.007892191 -0.9266053 -0.3685757 -0.07453018 -0.5900607 -0.8071244 -0.01946294 -0.4707102 -0.8822461 0.008583009 -0.8128797 -0.5798957 -0.05429136 -0.3205285 -0.9472349 -0.002763271 -0.311544 -0.9501859 -0.00933659 -0.9459837 -0.2825661 -0.1589698 -0.9242781 -0.3552685 -0.1396215 -0.5594619 -0.8263828 -0.06398421 -0.8594077 -0.4895235 -0.1475986 -0.4106651 -0.9100817 -0.05572611 -0.7698482 -0.6288453 -0.1090303 -0.6749177 -0.7290576 -0.1138471 -0.9331372 -0.2714473 -0.2357355 -0.6691574 -0.7324464 -0.1255014 -0.8871249 -0.3874486 -0.2507847 -0.1090986 -0.9938453 -0.019212 -0.832219 -0.5099738 -0.2175737 -0.7711539 -0.6010721 -0.2098426 -0.3463941 -0.9346612 -0.08012306 -0.5260632 -0.8375633 -0.1474632 -0.1633616 -0.9858713 -0.03702634 -0.908351 -0.2230383 -0.353769 -0.7204155 -0.6567962 -0.2227561 -0.3845727 -0.9175851 -0.1007044 -0.8803569 -0.3510559 -0.3189539 -0.5870288 -0.7864468 -0.1920904 -0.7749719 -0.5391804 -0.3297017 -0.7533238 -0.5766929 -0.3161147 -0.8782225 -0.2227098 -0.4232322 -0.8590365 -0.2788859 -0.4292773 -0.6149958 -0.7379426 -0.2778866 -0.5674765 -0.7862326 -0.2445585 -0.7907316 -0.4719161 -0.3899219 -0.8228639 -0.2419901 -0.514136 -0.8197502 -0.268029 -0.5061324 -0.7659863 -0.4286547 -0.4790825 -0.76108 -0.4440566 -0.472833 -0.7419683 -0.5310211 -0.4092673 -0.3696398 -0.9108653 -0.1835506 -0.2966043 -0.9456736 -0.1331444 -0.6314309 -0.6880123 -0.3576789 -0.5856639 -0.7256402 -0.3611705 -0.168203 -0.9828152 -0.0760414 -0.4290502 -0.8621439 -0.2694882 -0.3666059 -0.9064583 -0.2096033 -0.2093345 -0.9684035 -0.1355504 -0.1191555 -0.9910933 -0.05946612 0.5983552 -0.7712337 -0.2171861 0.7195789 -0.3263103 -0.6129663 0.5185124 -0.8547451 -0.02357101 0.7387887 -0.3024165 -0.6022753 0.6947263 -0.2015421 -0.6904609 0.6969397 -0.4704089 -0.5412861 0.6714406 -0.6053367 -0.4274753 0.5760775 -0.7938182 -0.1949041 0.7442956 -0.2710626 -0.6103681 0.4178261 -0.907602 0.04098933 0.7283878 -0.395057 -0.5598047 0.4160316 -0.9038283 -0.1000612 0.70068 -0.4744162 -0.5328947 0.2895818 -0.955378 -0.05826932 0.2943078 -0.9426193 -0.1576446 0.6876859 -0.5696101 -0.4501474 0.643682 -0.5696212 -0.5110824 0.5284836 -0.7908192 -0.3087236 0.4988458 -0.8141633 -0.297138 0.6412523 -0.6207463 -0.451076 0.7447476 -0.6389148 -0.1927142 0.7129742 -0.6962091 -0.083431 0.6225513 -0.7817878 0.03518581 0.7262367 -0.1793068 -0.6636486 0.7591081 -0.4195312 -0.4977435 0.817403 -0.4555334 -0.3526214 0.7533354 -0.4134185 -0.5114401 0.6150854 -0.785198 0.07165348 0.7196152 -0.6232501 -0.3061265 0.7793903 -0.2264334 -0.5841906 -0.7327659 -0.1728953 -0.65815 -0.476185 -0.8737916 0.09867125 -0.6888122 -0.5529841 -0.4687712 -0.5363022 -0.7989556 -0.2721211 -0.7318996 -0.4669008 -0.4963129 -0.642604 -0.6758288 -0.3609926 -0.6268685 -0.7023631 -0.337227 -0.7524568 -0.4001364 -0.5231632 -0.5524111 -0.8335204 -0.009270608 -0.6315041 -0.6890978 -0.355453 -0.5966662 -0.7868131 -0.1578435 -0.7960919 -0.2033278 -0.5699962 -0.7576149 -0.3296762 -0.5633236 -0.7543109 -0.2344102 -0.6132431 -0.7358702 -0.441644 -0.5132697 -0.4922058 -0.8436509 -0.2144449 -0.3167777 -0.9450878 -0.08038061 -0.2812288 -0.9595316 -0.01447594 -0.4565529 -0.8805161 -0.1274787 -0.6895623 -0.660532 -0.2969874 -0.4119531 -0.911057 0.01642572 -0.5479637 -0.8242822 -0.1424595 -0.4095184 -0.9120588 0.02106195 -0.8819206 -0.2176356 -0.4181516 -0.8622792 -0.2121456 -0.4598575 -0.6253838 -0.7802044 -0.01328516 -0.5653793 -0.8155265 0.1235429 -0.7182827 -0.6891438 0.09565955 -0.830774 -0.3422236 -0.4389734 -0.7790455 -0.06391859 -0.6237006 -0.786938 -0.6129155 -0.07115805 -0.8121704 -0.3213236 -0.4869604 -0.6905836 -0.649089 -0.3190264 -0.7771593 -0.528348 -0.3418653 -0.7848081 -0.5640336 -0.2567925 -0.6544861 -0.7549084 -0.04196912 -0.848426 -0.4783778 -0.2265573 -0.09650331 -0.9920772 0.0804364 -0.1351454 -0.980036 0.1458264 -0.1954122 -0.9717178 0.1325839 -0.2259828 -0.9580065 0.1765087 -0.3582192 -0.8930546 0.2722728 -0.3173472 -0.9225463 0.2195433 -0.01856368 -0.9989141 0.04273211 -0.4725811 -0.8261451 0.3068414 -0.4873105 -0.8064554 0.3349002 -0.3287504 -0.8620833 0.3856627 -0.1381106 -0.9637456 0.2282977 -0.1281002 -0.9714198 0.1998348 -0.4638573 -0.7782449 0.4232863 -0.195444 -0.9385716 0.2844027 -0.3164218 -0.8445826 0.4319232 -0.2047503 -0.9281728 0.3107614 -0.4870624 -0.7065166 0.5134243 -0.04481172 -0.9852212 0.1653216 -0.2266884 -0.8882557 0.3995175 -0.6208171 -0.5868864 0.5197602 -0.09316295 -0.940631 0.3263957 -0.09424358 -0.9433271 0.3182016 -0.3266572 -0.7744745 0.5417421 -0.3235956 -0.8050502 0.4971722 -0.4705809 -0.6459006 0.6011373 -0.126784 -0.8831097 0.4517115 -0.1300884 -0.8933498 0.4301201 -0.394164 -0.6238541 0.6748635 -0.412913 -0.6787022 0.6073436 -0.1664541 -0.8218443 0.5448531 -0.1597471 -0.8113876 0.5622555 -0.2316344 -0.692712 0.6830049 -0.2182533 -0.6848958 0.6951858 -0.1239207 -0.7164176 0.6865782 -0.6844086 -0.5487011 0.4801168 -0.5959742 -0.7345471 0.3244308 -0.6088891 -0.6794548 0.4093843 -0.6181988 -0.5817442 0.5285868 -0.7189626 -0.6398249 0.2715086 -0.8858501 -0.3754328 0.2726166 -0.8848576 -0.4212008 0.1990405 -0.8105503 -0.4419719 0.3842773 -0.73207 -0.5985662 0.3252569 -0.8068778 -0.3965833 0.4378013 -0.9790055 -0.00134176 -0.2038295 -0.9956139 0.004904448 -0.09342956 -0.971647 5.08501e-4 -0.2364363 -0.9468426 -0.009998261 -0.3215419 -0.948563 -0.007795393 -0.3164922 -0.8712182 -0.006951689 -0.4908467 -0.8575099 -0.009959161 -0.5143712 -0.8173156 -0.04833823 -0.574159 -0.66115 0.001756727 -0.7502518 -0.6993895 -3.70222e-4 -0.7147406 -0.7406409 -0.002809166 -0.6718953 -0.7237145 0.002738714 -0.6900941 -0.7955971 -0.005871295 -0.6057977 -0.8518478 -9.71424e-4 -0.5237885 -0.8372392 0.00611633 -0.5468028 -0.8962394 -0.005715668 -0.4435338 -0.9395334 -0.002004086 -0.3424515 -0.928664 0.006500363 -0.3708652 -0.9656274 -0.007037401 -0.2598348 -0.9885282 -0.001949489 -0.1510237 -0.9836887 0.005951523 -0.179781 -0.9980511 -0.006830692 -0.06202912 -0.9998145 0.005650579 0.01841247 -0.999387 0.001122117 0.03499156 -0.9954833 -0.005831599 0.09475672 -0.9815583 -9.51963e-4 0.1911609 -0.9764057 0.005294919 0.2158794 -0.9591159 -0.00699383 0.2829272 -0.9306851 -0.003294229 0.3658066 -0.9143859 0.00521332 0.4048105 -0.9025906 -0.001137495 0.4304984 -0.8568443 -0.006353557 0.5155363 -0.8161899 0.008468329 0.5777218 -0.7804647 -0.005413711 0.6251765 -0.7449312 -0.006042003 0.6671141 -0.6857487 0.006607592 0.7278084 -0.6702753 5.89317e-4 0.7421123 -0.6350803 -0.004935085 0.7724305 -0.5474385 -2.92595e-4 0.8368459 -0.5281857 0.005352079 0.8491121 -0.4741551 -0.00574702 0.8804227 -0.3746815 -6.72835e-4 0.9271534 -0.34973 0.004546403 0.9368395 -0.335971 0.001195192 0.9418716 -0.2443151 -0.006207704 0.9696761 -0.1891538 -0.001065373 0.981947 -0.1574388 0.007058858 0.9875035 -0.09218204 -0.00480163 0.9957306 -0.04074907 -0.005767345 0.9991528 0.05137974 0.002196252 0.9986768 0.04107296 0.005237579 0.9991425 0.1075713 -0.004921913 0.9941852 0.210747 -0.001204788 0.9775399 0.2379676 0.005709469 0.9712564 0.3021598 -0.006208002 0.9532371 0.400048 -0.001611351 0.9164929 0.4254449 0.004880666 0.9049713 0.4638969 -0.003266096 0.8858833 0.5307064 -0.004887104 0.8475417 0.5960998 0.006314218 0.8028856 0.6125376 2.75863e-4 0.7904415 0.6865009 -0.006312251 0.7271017 0.7431914 0.005634307 0.6690552 0.7472672 0.003914356 0.6645122 0.7965785 -0.0063771 0.6045017 0.8352003 -0.004060208 0.5499309 0.8608766 0.007645368 0.5087563 0.8899976 -0.004071831 0.4559471 0.9160908 -0.005569219 0.4009323 0.9499168 2.33501e-4 0.3125026 0.9445397 0.005108952 0.3283579 0.9749344 -0.007429897 0.2223683 0.9914662 0.002459645 0.1303414 0.9908441 0.003846168 0.1349563 0.9995841 -0.006421685 0.0281139 0.9964092 -5.04461e-4 -0.0846675 0.9979469 0.005775749 -0.06378531 0.9856901 -0.006655693 -0.1684368 0.9655967 0.004709362 -0.2600014 0.9645504 0.003473937 -0.2638763 0.9281917 -0.006692826 -0.3720422 0.8919904 0.005833923 -0.4520169 0.8907399 0.004840791 -0.4544877 0.8383756 -0.01011049 -0.5449994 0.804288 -0.005502641 -0.5942142 0.7356892 -0.003584027 -0.6773098 0.7635069 0.007149755 -0.6457601 0.6746497 -0.00471723 -0.7381229 0.6079801 -6.69923e-4 -0.7939521 0.647509 0.002190351 -0.7620548 0.5735082 0.01167011 -0.8191167 0.002923786 -0.9976763 0.06807065 -0.00268346 -0.9981209 0.06121838 0.003178894 -0.9977312 0.06724864 0.0821681 -0.9126431 0.4004135 0.09106284 -0.9674363 0.2361664 0.01944279 -0.9834978 0.1798729 0.1164033 -0.9117667 0.3938678 0.07599687 -0.8857431 0.4579123 0.1052758 -0.9764946 0.1880835 0.06627178 -0.9926878 0.1008919 0.06927806 -0.8430196 0.5334028 0.1702143 -0.6930588 0.7004973 0.1838152 -0.6823899 0.7074999 0.2137226 -0.7820413 0.585435 0.06371897 -0.9970816 0.04204899 0.05469226 -0.9982547 0.02228367 0.1841038 -0.9606384 0.2080376 0.187123 -0.9756461 0.1144548 0.1683609 -0.6733526 0.7198964 0.2068215 -0.7394493 0.6406556 0.3154305 -0.6070056 0.7294161 0.2653224 -0.9204595 0.2869819 0.3779972 -0.6556202 0.6536667 0.3452402 -0.9126479 0.2188223 0.4155094 -0.6188032 0.6666593 0.3888505 -0.7031658 0.5952757 0.5038765 -0.5598717 0.6577631 0.4664393 -0.8289712 0.3086119 0.4394519 -0.8643351 0.2445545 0.7293106 -0.5446442 0.4140879 0.8170748 -0.4102774 0.4050449 0.8221383 -0.4042488 0.4008386 0.1513914 -0.9711653 0.1841703 0.0510317 -0.9977934 0.04247474 0.2637841 -0.882904 0.3884567 0.1537676 -0.9362349 0.3159428 0.2177279 -0.9369482 0.2733545 0.3651348 -0.8506742 0.3781932 0.2649133 -0.8836877 0.3858978 0.3449764 -0.6936282 0.6323538 0.2827486 -0.8216503 0.4949185 0.3362 -0.9204282 0.1994531 0.1950386 -0.9740582 0.1147643 0.3764851 -0.8335677 0.4042572 0.3624181 -0.7833187 0.5050396 0.3702281 -0.7126088 0.5959194 0.4225291 -0.8056124 0.4152806 0.6185033 -0.623516 0.4782066 0.4717046 -0.6918329 0.5466829 0.6107673 -0.6086255 0.5064962 0.6364314 -0.5366616 0.5540302 0.5618585 -0.7937908 0.232833 0.7134098 -0.6170455 0.3321165 0.6452932 -0.6730772 0.361336 0.5742762 -0.7190731 0.3913321 0.4274312 -0.7990185 0.422933 0.7511484 -0.4262833 0.5040423 0.6425902 -0.5040439 0.5770768 0.9932466 -0.1159137 -0.005047082 0.6798751 -0.6916801 0.2436156 0.9688938 -0.1760707 0.1739077 0.9144499 -0.3477893 0.2069401 0.9113764 -0.3943667 0.1177636 0.8951865 -0.3519647 0.2734266 0.7937999 -0.5654319 0.2239835 0.8500239 -0.4149387 0.3244768 0.7700321 -0.5267591 0.359966 0.9999904 5.91833e-4 -0.004354417 0.9999916 -0.003576517 0.002048611 0.9999994 -5.77169e-4 0.00101906 0.9999094 0.01242655 -0.005199909 0.9999914 -0.002738833 0.003129482 0.99999 -0.003011345 0.0033288 0.9999722 0.007447123 -6.37536e-4 0.9995503 -0.01793199 0.0240364 0.9956322 -0.05540645 0.07514488 0.9774245 -0.1277487 0.1682906 0.9462823 -0.1942892 0.2584604 0.9274368 -0.2255746 0.2982903 0.8706732 -0.2947136 0.3937917 0.857075 -0.3092449 0.4120558 0.7409459 -0.4032212 0.5370399 0.7078245 -0.4231056 0.5656555 0.5766173 -0.4913694 0.6527394 0.484957 -0.5243796 0.6998878 0.3641418 -0.5600478 0.744142 0.2616522 -0.5789668 0.7722277 0.146241 -0.5947515 0.7904962 0.9864823 3.30965e-4 -0.1638674 0.9821801 -0.006706774 -0.1878224 0.944453 -4.4203e-4 -0.3286464 0.9159812 -0.0158807 -0.4009068 0.9330922 0.009492754 -0.3595122 0.8709468 6.40781e-4 -0.491377 0.8226846 -0.02600055 -0.5679031 0.4163295 0.4993619 -0.7598076 0.3734545 0.551954 -0.7455726 0.1948049 0.5195399 -0.8319432 0.7473706 -0.003926336 -0.6643958 0.6962639 -0.03059762 -0.7171335 0.8736835 0.02630227 -0.4857833 0.7636663 0.05798721 -0.6430018 0.6747723 0.01517522 -0.73787 0.9394236 3.59845e-4 -0.3427583 0.7968214 0.05721628 -0.6014998 0.8489251 0.08673161 -0.5213482 0.7188224 0.1071639 -0.6868845 0.673633 0.09817087 -0.732517 0.9356521 0.1358559 -0.3257275 0.8580943 0.1611146 -0.4875617 0.8629678 0.08260154 -0.4984612 0.6299304 0.08423036 -0.7720705 0.7155296 0.2034601 -0.6682975 0.8702626 0.2881742 -0.3994981 0.7969061 0.2157331 -0.5642695 0.7665337 0.3317046 -0.5499074 0.7389486 0.2179594 -0.6375334 0.7146717 0.3397109 -0.6114253 0.6376237 0.4436853 -0.6297456 0.5790256 0.4332103 -0.690694 0.5730657 0.3515605 -0.7402709 0.9822387 0.06066828 -0.1775577 0.9317415 0.1395501 -0.3352367 0.02792483 0.6003426 -0.7992553 0.03890103 0.6014232 -0.7979831 0.1148995 0.5965539 -0.7943059 0.1137928 0.5960558 -0.7948389 0.1773059 0.591462 -0.7865974 0.1001598 0.5978221 -0.795347 0.2045911 0.5898774 -0.7811449 0.2225952 0.5854695 -0.7795363 0.3017107 0.5723823 -0.7624626 0.2905897 0.5728958 -0.7663864 0.3218222 0.569007 -0.7567442 0.413558 0.5472381 -0.7276677 0.4248611 0.5439341 -0.7236221 0.4351213 0.5423321 -0.718711 0.4684078 0.5299857 -0.7069013 0.5134208 0.5153146 -0.6861851 0.5552879 0.4994505 -0.6649847 0.5454121 0.5042767 -0.6695003 0.5361948 0.5067784 -0.6750341 0.602022 0.4798631 -0.6382014 0.593782 0.4828349 -0.6436563 0.5925222 0.4832945 -0.6444718 0.6044182 0.4787501 -0.6367708 0.7489833 0.3982015 -0.5295845 0.7536844 0.3950811 -0.5252341 0.8651536 0.301351 -0.4008703 0.8809557 0.2846538 -0.3780072 0.938463 0.2071083 -0.2763936 0.9750801 0.1340761 -0.1767555 0.9917111 0.07675021 -0.1030465 0.9998804 -0.009739816 0.01201117 -0.6519392 0.009421467 -0.7582128 -0.7074595 0.2667902 -0.6544649 -0.7228614 0.1083257 -0.6824493 -0.7255342 0.4224046 -0.5432997 -0.7690581 0.122891 -0.6272541 -0.7840962 0.1953349 -0.589099 -0.7772873 0.3184868 -0.5425779 -0.7334951 0.00354743 -0.6796856 -0.8694988 0.2588847 -0.4206549 -0.8509719 0.01601999 -0.5249668 -0.8867504 0.1776596 -0.4267444 -0.8406078 0.02452957 -0.5410887 -0.9458116 0.02740478 -0.3235576 -0.9286467 0.05269378 -0.3672038 -0.9171774 0.1474966 -0.3701761 -0.988946 0.02946609 -0.1453191 -0.7820387 0.01847708 -0.6229561 -0.7248218 0.02625876 -0.6884358 -0.9124894 0.1294595 -0.3880766 -0.8263738 0.08936464 -0.5559859 -0.8356357 0.08631622 -0.5424596 -0.9441171 0.155015 -0.2908836 -0.9999898 0.004339337 0.001309454 -0.9999688 -0.007056653 0.003569066 -0.9999992 -3.28306e-4 0.001312673 -0.9999706 0.007374107 -0.002146005 -0.999989 -0.003083825 0.003523647 -0.9999922 -0.002495169 0.003091514 -0.9999995 -6.7856e-4 -8.06152e-4 -0.9944855 0.06279218 -0.08399903 -0.9862092 0.09986573 -0.1319793 -0.9473577 0.192036 -0.2561946 -0.9210091 0.234182 -0.3112895 -0.9188514 0.2371884 -0.3153631 -0.8303918 0.3350098 -0.4452167 -0.8256731 0.339074 -0.45088 -0.6857735 0.4370558 -0.5819768 -0.7143708 0.419683 -0.559947 -0.5323825 0.5088222 -0.6765124 -0.5294346 0.5099737 -0.6779573 -0.5255001 0.5113396 -0.6799865 -0.5136156 0.5149779 -0.6862921 -0.5066447 0.5169865 -0.6899538 -0.4545524 0.5360212 -0.7113813 -0.4593289 0.5334008 -0.710282 -0.3824653 0.5548242 -0.738844 -0.3824806 0.556149 -0.7378394 -0.3617076 0.5597733 -0.7455344 -0.2997907 0.5735521 -0.7623408 -0.2671099 0.5789016 -0.770406 -0.2553862 0.5826215 -0.7715765 -0.2126588 0.5867839 -0.78132 -0.1520631 0.5932626 -0.7905166 -0.01178073 0.6032958 -0.7974306 -0.0820598 0.5984323 -0.7969599 -0.04773807 0.600796 -0.7979757 -0.1399447 0.5978921 -0.7892658 0.6589065 0.4523963 -0.6009826 0.5196404 0.5137041 -0.682702 0.5973014 0.4816107 -0.641313 0.2958306 0.5945268 -0.7476779 0.3951178 0.5513347 -0.7347871 0.4007549 0.5497922 -0.7328876 0.1079373 0.5974071 -0.7946411 0.09010601 0.5989239 -0.7957205 -0.2113441 0.5863431 -0.7820073 -0.2854298 0.5761919 -0.7658544 -0.4250005 0.5507068 -0.7183987 -0.4735083 0.5287809 -0.704401 -0.4574238 0.5340516 -0.7110221 -0.5522913 0.5011576 -0.6661949 -0.6198235 0.4713189 -0.6274371 -0.6420141 0.4606842 -0.6128523 -0.9988817 0.02636671 -0.0392459 -0.9808891 -0.1168607 0.155564 -0.9771745 -0.1270874 0.1702322 -0.9210289 -0.2350724 0.3105589 -0.8981875 -0.2638567 0.3516233 -0.839727 -0.3262818 0.4340493 -0.8989638 -0.2652081 0.3486101 -0.7352588 -0.4067499 0.5421708 -0.6690328 -0.4475021 0.5934113 -0.606066 -0.4775164 0.6361306 -0.4698882 -0.5302264 0.7057372 -0.4314179 -0.542706 0.7206586 -0.3070831 -0.5713287 0.7611069 -0.1960427 -0.589479 0.7836337 -0.1603794 -0.5928637 0.7891712 0.02647691 0.6359698 -0.7712597 0.003696739 0.6006986 -0.799467 0.007777094 0.5990599 -0.8006665 0.01672732 0.5966234 -0.8023471 -0.007523119 0.5982123 -0.8013024 -0.001688361 0.6010938 -0.7991767 -2.32643e-4 0.601584 -0.7988097 1.63755e-4 0.6006785 -0.7994908 0.027709 0.6010192 -0.7987542 -0.6802155 0.5800422 -0.4481718 -0.4991845 0.8623825 -0.08432883 -0.4411884 0.8871245 -0.13551 -0.5224602 0.7062287 -0.4777827 -0.4313322 0.7761142 -0.4599994 -0.5491634 0.7062819 -0.44675 -0.4092742 0.7787071 -0.4755102 0.5953182 0.6400078 -0.4857842 0.426235 0.8659242 -0.2617232 0.3410086 0.8837702 -0.3204113 0.3100056 0.9495922 -0.04659718 0.368993 0.9293969 0.00810033 0.480874 0.7000124 -0.527961 0.5044204 0.6669379 -0.5484104 0.4098876 0.7401481 -0.5330789 0.6308204 0.7256887 -0.2746664 0.2935037 0.8703696 -0.3953635 0.5158818 0.7940709 -0.3214303 -0.01565659 0.6009645 -0.7991225 -0.008368074 0.600834 -0.7993301 0.01247853 0.6029551 -0.7976775 0.0020141 0.6009796 -0.7992618 0.00234884 0.6010764 -0.7991881 0.001186668 0.6015249 -0.7988533 0.005071699 0.5984548 -0.8011406 -0.002337813 0.6006809 -0.7994856 0.02667325 0.6000752 -0.7994989 -4.89592e-4 0.6007014 -0.7994734 0.9999768 -0.006542026 0.001907944 1 1.62467e-4 1.78877e-6 1 2.71678e-4 4.34411e-5 0.9999994 -9.84716e-4 -6.11042e-4 0.9999975 0.001900017 -0.001209259 1 -2.81294e-5 5.95785e-5 1 8.79951e-5 2.1887e-4 1 -1.67802e-5 -1.184e-5 0.9999887 -0.004667699 -9.59696e-4 0.9999668 -0.006907641 -0.004342555 -7.01943e-7 -0.7994946 -0.6006734 -3.48654e-6 -0.7994943 -0.6006737 1.80428e-6 -0.7994946 -0.6006734 0 -0.7994946 -0.6006733 -0.6563301 -0.7543275 -0.01486307 -0.5457572 -0.8378534 0.01228451 -0.2767397 -0.9609051 -0.00875318 -0.3098701 -0.950774 0.003101766 0.01760035 -0.9998243 -0.006449222 0.07645124 -0.9970419 0.007919192 0.3483015 -0.9373637 -0.00595504 0.374989 -0.9270289 8.18111e-4 0.6055273 -0.7958207 0.002491533 0.6609252 -0.7503296 -0.01354479 0.8177925 -0.5752411 0.01769769 0.923792 -0.3824766 -0.01789414 0.9714206 -0.2370061 0.01305204 0.9998683 0.007013678 -0.01464003 0.9948063 0.101485 0.007835984 0.9291459 0.3696942 0.003763079 0.8953175 0.4451026 -0.01703518 0.7829169 0.6220033 0.01238089 0.5829949 0.812461 -0.004917979 0.6023368 0.7981496 -0.01215583 0.2777312 0.9605843 0.01196759 0.1885774 0.9819804 -0.0123803 -0.09211635 0.99572 0.007518112 -0.1346428 0.9908922 -0.001992464 -0.4199765 0.9075009 0.007873296 -0.3904272 0.9206338 1.77561e-4 -0.6378913 0.7700356 -0.01183015 -0.7447802 0.667158 0.01423794 -0.8410472 0.5408467 -0.01116019 -0.9280098 0.372416 0.01020842 -0.9714938 0.2368733 -0.009534776 -0.9939461 0.1095942 0.007771968 -0.9955772 -0.09335047 -0.01057422 -0.9802891 -0.1971462 0.01291972 -0.8801292 -0.4745291 -0.01395767 -0.8143593 -0.5801734 0.01476681 0 0 1 -3.39842e-6 0 1 3.86476e-6 0 1 2.70535e-6 0 1 8.94868e-7 0 1 5.14617e-5 0 1 -1.11674e-5 0 1 -1.73607e-5 0 1 -3.44168e-6 0 -1 0 0 -1 1.39736e-5 0 -1 -6.23106e-6 0 -1 1.41391e-5 0 -1 4.62414e-6 0 -1 -1.51223e-6 0 -1 -5.86794e-6 0 -1 -3.06979e-6 0 -1 4.61669e-6 0 -1 -6.56048e-6 0 -1 5.11917e-6 0 -1 -1.24244e-5 0 -1 -5.20003e-6 0 -1 0.8409072 0.5411784 -0.001166045 0.8421536 0.5392378 -1.17933e-4 0.989734 0.1428778 0.003547728 0.9920632 0.1257133 -0.002626597 0.9802967 -0.1975303 4.41913e-4 0.9757795 -0.2186108 0.007980823 0.8108698 -0.5850362 -0.01493227 0.7795083 -0.6263573 0.006591677 0.4889948 -0.8722617 0.006608605 0.4530256 -0.8914455 -0.009632468 0.07057136 -0.9975067 2.29803e-5 0.06005942 -0.9981844 0.004558622 -0.3587986 -0.9333934 0.006363153 -0.3693279 -0.9292985 0.001138031 -0.6935608 -0.7202152 -0.01623159 -0.7666442 -0.6416559 0.02311682 -0.9435707 -0.3306849 -0.01794022 -0.9763073 -0.215271 0.02196425 -0.9963959 0.08124959 -0.02436727 -0.9605389 0.2772168 0.02271121 -0.8917982 0.4521625 -0.01566135 -0.7910719 0.6115764 0.01341074 -0.6952388 0.7186927 -0.01112776 -0.5482988 0.8361992 0.01181572 -0.4473744 0.8942416 -0.0137248 -0.2290388 0.9733065 0.01468479 -0.08158564 0.9965766 -0.01337474 0.08249258 0.9964852 0.01456677 0.2402909 0.9705579 -0.01666665 0.5083186 0.8610548 0.01403141 0.5438008 0.8392136 -0.001175522 -0.6051031 -0.796 -0.0153042 -0.2753009 -0.9612635 0.0134902 -0.0345155 -0.9993254 -0.01254582 0.3147925 -0.9490681 0.01324343 0.5316224 -0.8469068 -0.01125389 0.7994784 -0.6006252 0.009146928 0.8806172 -0.4737558 -0.008307874 0.9980293 -0.06167966 0.01154088 0.9892643 0.1452984 -0.01563751 0.8543859 0.5194618 0.01357811 0.6501567 0.7596558 -0.01480978 0.5299607 0.848016 0.00327003 0.1772352 0.9841499 0.006049156 0.04685425 0.9988617 -0.008939564 -0.2586464 0.9659582 0.005182087 -0.4079983 0.9129611 -0.006286561 -0.6299864 0.7765402 0.01013344 -0.8029198 0.5959448 -0.01302897 -0.9669793 0.2546527 0.01015871 -0.9890372 0.1476362 -0.003008484 -0.9514945 -0.307662 0.001506805 -0.967424 -0.2530413 -0.007813572 -0.7783943 -0.627686 0.01061987 1.03652e-6 0 -1 -1.77017e-5 0 -1 8.91702e-6 0 -1 5.60555e-6 0 -1 -1.34336e-5 0 -1 -1.50352e-5 0 -1 7.18877e-6 0 -1 -5.11074e-6 0 -1 -1.35628e-6 0 -1 1.06778e-5 0 -1 -5.00422e-6 0 -1 -1.40534e-5 0 -1 1.9683e-5 0 -1 -2.91272e-6 0 -1 0.8772971 0.479947 8.87627e-4 0.8980591 0.4396919 -0.01268613 0.9857511 0.1672563 0.01789295 0.9997648 0.009729266 -0.01938551 0.9773874 -0.2104691 0.02041172 0.9399134 -0.3411307 -0.0138852 0.8025237 -0.5966178 -0.001749753 0.7578045 -0.6520493 0.02375084 0.5482484 -0.8360893 -0.01945471 0.3541046 -0.9350349 0.01788532 0.277526 -0.9607083 -0.004372 -0.029042 -0.9995779 7.7025e-4 -0.03953093 -0.9992104 0.004008173 -0.3383197 -0.9410139 -0.005719184 -0.3637293 -0.9314979 0.00354582 -0.7073217 -0.7068829 0.003558993 -0.7026911 -0.7114638 0.006680607 -0.9206948 -0.3898196 -0.01902401 -0.9689147 -0.2454965 0.03059202 -0.9994984 0.02045094 -0.02417993 -0.975089 0.2211611 0.01701164 -0.919817 0.392153 -0.01235884 -0.8578822 0.5137085 0.01190698 -0.7415499 0.6707254 -0.01520663 -0.6242926 0.7810501 0.01481837 -0.4599476 0.887808 -0.01565814 -0.348213 0.9373372 0.01210999 -0.04821133 0.9987832 -0.01038098 -0.01228058 0.9999191 0.003332853 0.3971121 0.9177642 -0.003332734 0.416984 0.9089003 0.004967749 0.6871876 0.7264591 -0.005516827 0.7085263 0.7056784 0.002955198 -0.6883056 -0.7253344 0.01120561 -0.5362705 -0.8439576 -0.01223582 -0.1241222 -0.9922242 0.009220719 0.0143674 -0.9998774 -0.006237685 0.3045372 -0.9524868 0.005098044 0.4478807 -0.8940669 -0.00688219 0.7119956 -0.7021053 0.01051121 0.8255445 -0.5642259 -0.01120215 0.9945028 -0.1043054 0.009198129 0.9999581 -0.006803631 -0.006123781 0.875177 0.4837626 0.006238341 0.8321359 0.5545532 -0.00457257 0.5624697 0.8268131 0.002881705 0.5103923 0.8599347 -0.003504276 0.1722816 0.9850335 0.005299568 0.02253675 0.999689 -0.01068133 -0.2795837 0.9600676 0.01015973 -0.5660681 0.8243237 -0.007579147 -0.6506782 0.7593403 0.004505872 -0.8992165 0.4374238 -0.008375823 -0.9605228 0.2779794 0.01110672 -0.9989238 -0.04556405 -0.008673846 -0.9630356 -0.269244 0.008375346 -0.8838629 -0.4676839 -0.007626593 -1.05469e-5 0 -1 1.28281e-5 0 -1 -1.00225e-5 0 -1 3.61047e-6 0 -1 5.44244e-6 0 -1 -1.64341e-5 0 -1 5.9077e-6 0 -1 6.11899e-6 0 -1 3.6374e-6 0 -1 3.3365e-6 0 -1 4.36176e-6 0 -1 1.09925e-5 0 -1 5.54488e-6 0 -1 -8.03174e-6 0 -1 -1.53424e-5 0 -1 -3.00887e-6 0 -1 1.60429e-5 0 -1 -1.1713e-5 0 -1 0.8029276 0.5958538 -0.01630318 0.8989924 0.4375768 0.0184201 0.9621884 0.2717186 -0.01904648 0.9989057 0.04361224 0.01689738 0.9958562 -0.09024 -0.01128911 0.9608575 -0.2768959 0.009034574 0.9270499 -0.3748003 -0.01016438 0.8223406 -0.5687958 0.01507663 0.7318193 -0.6811661 -0.02129101 0.5179325 -0.8550898 0.02382206 0.379495 -0.9250209 -0.01788896 0.1311672 -0.9912927 0.01158088 0.03400754 -0.9993477 -0.01215255 -0.1891313 -0.981835 0.01515382 -0.3509593 -0.9362912 -0.01365417 -0.4920436 -0.8704567 0.01408076 -0.6200149 -0.78445 -0.01482546 -0.8112016 -0.5845316 0.01658564 -0.8524267 -0.5227622 -0.009404242 -0.9909074 -0.1345165 -0.002817153 -0.9873141 -0.1586543 0.006304204 -0.9771836 0.2123114 0.006006598 -0.9751378 0.2215831 0.002689898 -0.8709032 0.4913232 -0.011366 -0.8123824 0.5827993 0.01949679 -0.6118449 0.7907639 -0.01840186 -0.5010269 0.8652787 0.01627707 -0.2586147 0.9658107 -0.01812303 -0.1333469 0.9908612 0.02031302 0.2017313 0.9792718 -0.01820081 0.317123 0.9482186 0.01773589 0.5366554 0.8436498 -0.01600474 0.6688905 0.7431491 0.01774895 -0.6952925 -0.7187212 0.002845883 -0.6632973 -0.7483499 -0.003050744 -0.2930526 -0.9560943 0.002020537 -0.2857625 -0.9582999 0.001065373 0.159496 -0.9871929 -0.003330707 0.2081794 -0.9780822 0.004084587 0.6809332 -0.7323446 -0.001174807 0.6985511 -0.7155444 -0.004758775 0.9167402 -0.3994471 0.005425572 0.9605765 -0.2779407 -0.006457209 0.9983444 0.05714136 0.006585657 0.9859044 0.1671922 -0.006265997 0.8258751 0.5638183 0.006261169 0.7619227 0.6476408 -0.005962014 0.4764863 0.8791576 0.006536006 0.3660312 0.930569 -0.007908403 -0.08370685 0.996461 0.007665574 -0.2187893 0.9757158 -0.01048851 -0.5549626 0.8318145 0.01006054 -0.7684888 0.6397704 -0.01090574 -0.8513976 0.5244948 0.00522238 -0.9974781 0.07094746 0.001979112 -0.99236 0.1233079 -0.004114866 -0.9515248 -0.3075677 -0.001660108 -0.9490977 -0.3149813 -6.44437e-4 3.06188e-6 0 -1 5.58206e-6 0 -1 -1.33277e-5 0 -1 6.60792e-6 0 -1 -7.31501e-6 0 -1 6.0465e-6 0 -1 9.16387e-6 0 -1 2.74706e-6 0 -1 -4.98828e-6 0 -1 9.674e-6 0 -1 -3.69203e-6 0 -1 1.28591e-5 0 -1 -1.6162e-5 0 -1 1.14692e-5 0 -1 -1.6669e-5 0 -1 7.04792e-6 0 -1 -1.53384e-6 0 -1 0.9189177 0.3944475 0.001286923 0.917534 0.3976574 -1.886e-5 0.9996352 0.0268079 0.003305435 0.9999825 0.001265048 -0.00579673 0.9430623 -0.3325706 0.005518436 0.9205607 -0.3903099 -0.01504582 0.7525736 -0.6581629 0.02131968 0.6337593 -0.7732924 -0.01918643 0.4669806 -0.8841137 0.01650208 0.3146012 -0.9490405 -0.0186609 0.05698984 -0.9981768 0.01988196 -0.0620464 -0.9980003 -0.01207381 -0.3612609 -0.9324574 -0.003717362 -0.3223259 -0.9466001 0.007367789 -0.6180636 -0.7861069 0.005780994 -0.64126 -0.7673161 -0.003440737 -0.8567855 -0.5156722 -9.18771e-4 -0.8626303 -0.5058239 0.003353297 -0.9882985 -0.151227 0.01991677 -0.9940821 -0.1086314 -3.18687e-4 -0.9862561 0.163802 -0.02163118 -0.9271452 0.3738895 0.02466779 -0.8543733 0.5194768 -0.01379603 -0.7131285 0.7009572 0.01033675 -0.6631284 0.7484776 -0.006483912 -0.4203998 0.9073064 0.007692456 -0.3746469 0.9271323 -0.008096992 -0.03484779 0.9993529 0.008906424 0.02346974 0.9996477 -0.01240277 0.3867176 0.922077 0.01496082 0.4617326 0.8869192 -0.01333045 0.7145234 0.699544 0.009722113 0.7467753 0.665064 -0.004073262 -0.703792 -0.710371 -0.007071375 -0.4743077 -0.8803386 0.00601989 -0.3483111 -0.9373574 -0.006365656 -0.04011332 -0.9991735 0.006593525 0.1333617 -0.9910464 -0.006474614 0.3445418 -0.938744 0.007122635 0.5626282 -0.8266318 -0.01137793 0.7770811 -0.6293103 0.01065707 0.917428 -0.3978122 -0.008442938 0.9638324 -0.2664795 0.003976106 0.9915568 0.129588 -0.004690527 0.9849184 0.1730082 0.001990854 0.7268913 0.6867524 5.91779e-4 0.7194381 0.6945555 -0.001228332 0.2527816 0.9674955 0.007354557 0.3090733 0.9510383 6.62711e-6 -0.1349859 0.9907801 -0.01156294 -0.3814795 0.924252 0.0152207 -0.6771814 0.7356701 -0.01466012 -0.8312581 0.5557838 0.01069664 -0.9779775 0.2086016 -0.00673443 -0.9979129 0.0639314 0.00910139 -0.9642952 -0.2645254 -0.01269471 -0.8368976 -0.5472211 0.01232135 0 0.80019 0.5997466 -0.005770981 0.7993009 0.6009033 0.01084452 0.7991354 0.6010534 -1 1.40934e-4 1.67576e-4 -1 -1.79053e-6 -5.55391e-5 -0.9999999 -4.89935e-4 -3.17986e-4 -0.9999999 5.57161e-4 2.52004e-4 -1 -3.46327e-4 -4.25067e-4 -1 0 -8.84016e-5 -1 2.47659e-4 9.36318e-6 -0.9999992 -0.001252055 5.27157e-4 -1 -2.18589e-4 -7.6583e-5 -1 7.16949e-5 1.20479e-4 -1 -3.90546e-4 -3.35757e-4 0.08687126 0.128056 -0.987955 0.1361908 0.2081168 -0.968576 0.3641737 0.4898151 -0.792123 0.1562858 0.2645404 -0.9516265 0.4202157 0.5780733 -0.6994641 0.229113 0.3540537 -0.9067266 0.1915801 0.3171166 -0.9288349 0.291215 0.468862 -0.833884 0.5232291 0.7243021 -0.4490187 0.04996788 0.09621417 -0.9941056 0.1055552 0.2428013 -0.9643162 0.3972924 0.6447536 -0.6530326 0.6003006 0.7745719 -0.1991927 0.2845198 0.512639 -0.8100926 0.5417999 0.792573 -0.2797873 0.3222591 0.6077746 -0.7257818 0.4432667 0.7266606 -0.5248609 0.103502 0.2699615 -0.9572921 0.2131366 0.4547918 -0.864718 0.3054854 0.6420418 -0.7031794 0.1864506 0.4686232 -0.8634979 0.1790512 0.4596597 -0.8698583 0.3095375 0.6985034 -0.6451973 0.2099508 0.5633847 -0.7990735 0.07800477 0.2670348 -0.9605247 0.26391 0.7368622 -0.6224032 0.1251818 0.4681776 -0.8747224 0.1931501 0.6391357 -0.7444451 0.096551 0.4205424 -0.902121 0.03028702 0.1716397 -0.9846941 0.2171239 0.7042513 -0.6759344 0.1510054 0.6057493 -0.7811948 0.1886821 0.7694637 -0.6101841 0.02270483 0.1908297 -0.9813606 0.1209735 0.6449264 -0.7546096 0.1339579 0.7449422 -0.6535415 0.142466 0.7588239 -0.6355233 0.03714609 0.413502 -0.9097452 0.05201017 0.4451215 -0.8939586 0.1390519 0.8408935 -0.5230323 0.06336146 0.5847181 -0.8087584 -0.001057028 0.170642 -0.9853326 -0.00481981 0.1318992 -0.9912515 0.02173537 0.6717609 -0.7404492 0.05381977 0.768706 -0.637334 -0.02468156 0.3397826 -0.9401802 0.009134531 0.4098916 -0.9120886 -0.0251578 0.6552737 -0.7549726 -0.01370483 0.6495164 -0.7602241 -0.04971593 0.3702375 -0.9276059 -0.0583145 0.3967891 -0.9160556 -0.04298138 0.7144583 -0.6983567 -0.07519739 0.5543354 -0.8288896 -0.03906315 0.1309062 -0.9906249 -0.1043978 0.7475493 -0.6559506 -0.1104769 0.5944526 -0.7965056 -0.04424625 0.143341 -0.9886838 -0.1032136 0.8720705 -0.4783722 -0.1291285 0.7170873 -0.6849173 -0.1289193 0.4580409 -0.8795331 -0.06547051 0.2320282 -0.9705032 -0.1440563 0.5545707 -0.8195725 -0.1368569 0.4203315 -0.8969904 -0.1247283 0.3499827 -0.9284154 -0.2004925 0.75376 -0.6258185 -0.1914613 0.7356568 -0.6497319 -0.1992731 0.6307853 -0.7499335 -0.1533085 0.3262807 -0.932758 -0.2393613 0.6094292 -0.7558454 -0.2266659 0.5233608 -0.821411 -0.08680695 0.174727 -0.9807829 -0.1859967 0.3559133 -0.9158226 -0.09184783 0.1434904 -0.9853804 -0.3034858 0.6842191 -0.6631295 -0.2473933 0.471067 -0.8466951 -0.2280959 0.4571943 -0.8596194 -0.1895747 0.2947505 -0.9365808 -0.3531818 0.6838827 -0.63841 -0.3429177 0.5925379 -0.7289077 -0.3550839 0.6812127 -0.6402068 -0.1511489 0.2158439 -0.9646582 -0.04808193 0.06014239 -0.9970311 -0.3636561 0.57585 -0.7322234 -0.4240376 0.7054271 -0.5679478 -0.3235786 0.4550319 -0.8296041 -0.4663002 0.7786017 -0.419933 -0.3042578 0.3911173 -0.8685935 -0.3272128 0.4341804 -0.8392969 -0.4531171 0.6256781 -0.6349897 -0.2104488 0.2355438 -0.9488048 -0.2975414 0.3467866 -0.8894989 -0.4220527 0.5025243 -0.7545468 -0.4593487 0.6241071 -0.6320516 -0.4406954 0.5252835 -0.7279182 -0.5359112 0.7533878 -0.381059 -0.0180816 0.01869243 -0.9996619 -0.5223498 0.6607903 -0.5389869 -0.5616266 0.8021377 -0.2028565 -0.5486721 0.7163201 -0.431097 -0.3434005 0.3450732 -0.873499 -0.2018201 0.1919336 -0.9604322 -0.2239603 0.1966969 -0.9545428 -0.5200034 0.5511232 -0.6525793 -0.2926687 0.2484255 -0.9233796 -0.4204086 0.3993086 -0.814745 -0.56316 0.5980876 -0.5702124 -0.620952 0.7721107 -0.1351436 -0.4525169 0.4049774 -0.7944947 -0.5961067 0.5997172 -0.5338503 -0.646856 0.7024581 -0.2968672 -0.6583669 0.717445 -0.2276529 -0.4195109 0.2973256 -0.857676 -0.5263128 0.4641737 -0.7124167 -0.6533133 0.6508804 -0.3866995 -0.564754 0.4759879 -0.6741576 -0.4057496 0.301929 -0.8626738 -0.6156846 0.5513097 -0.5630187 -0.1700237 0.1068552 -0.9796296 -0.1808968 0.1147089 -0.9767898 -0.6803503 0.7112314 -0.1768431 -0.6857658 0.5528048 -0.473426 -0.4053634 0.2554339 -0.8777437 -0.6024374 0.4514826 -0.6582041 -0.7343577 0.66023 -0.1575285 -0.6927222 0.5207099 -0.4989963 -0.5985982 0.4016636 -0.6930704 -0.7167783 0.6065356 -0.3440111 -0.7400997 0.6098065 -0.2835287 -0.4903262 0.255586 -0.8332204 -0.6378138 0.3783456 -0.6708564 -0.2646256 0.131911 -0.9552868 -0.3212124 0.1650362 -0.9325157 -0.7758591 0.5812758 -0.2452777 -0.1138322 0.04736542 -0.9923703 -0.7439526 0.4952567 -0.4486149 -0.6322895 0.3619987 -0.6849578 -0.7919771 0.5119552 -0.3326777 -0.492986 0.2434406 -0.8352853 -0.7156777 0.4214011 -0.55698 -0.7946414 0.5273483 -0.3007472 -0.4144303 0.1833859 -0.891413 -0.5648677 0.2399079 -0.789537 -0.6445433 0.2722535 -0.7144523 -0.2656241 0.08679908 -0.9601613 -0.2359029 0.07231515 -0.9690822 -0.667366 0.2935431 -0.6844378 -0.8320001 0.4498316 -0.3246958 -0.8047463 0.3973043 -0.4410586 -0.5141881 0.1693502 -0.840792 -0.4765452 0.1556392 -0.8652637 -0.8778355 0.4403255 -0.1884637 -0.8099973 0.3633767 -0.4602847 -0.7552946 0.3133035 -0.5756485 -0.5711318 0.1694004 -0.8031887 -0.4226748 0.120868 -0.8981854 -0.8618777 0.3339127 -0.3816661 -0.9029377 0.3927201 -0.1745699 -0.669172 0.2092038 -0.7130516 -0.7988111 0.2586388 -0.5431453 -0.2389874 0.04103797 -0.9701551 -0.8961777 0.3294404 -0.2972117 -0.7375829 0.1980273 -0.6455669 -0.6170808 0.1161097 -0.7782866 -0.7971667 0.2327693 -0.5570851 -0.1824533 0.01491588 -0.9831014 -0.4517812 0.07355546 -0.8890913 -0.4118244 0.0582413 -0.9094002 -0.9089933 0.3117976 -0.276611 -0.7281497 0.1678097 -0.6645584 -0.5578256 0.08386808 -0.82571 -0.6036877 0.1015768 -0.7907233 -0.8751869 0.2086199 -0.4364925 -0.9205357 0.2610837 -0.2906022 -0.8791936 0.1900125 -0.436937 -0.8054639 0.1239911 -0.5795294 -0.2256983 0.002503633 -0.9741941 -0.9565092 0.2279745 -0.1819832 -0.8592628 0.145366 -0.490445 -0.7223451 0.07117843 -0.68786 -0.5994052 0.02148199 -0.8001575 -0.3927221 -0.002215325 -0.9196547 -0.7915312 0.09325492 -0.603972 -0.9474514 0.1568698 -0.2787969 -0.9051166 0.1032514 -0.4124357 -0.9654353 0.1609011 -0.20505 -0.4133117 -0.00883764 -0.9105467 -0.8450503 0.04769116 -0.5325556 -0.7094697 0.03988087 -0.7036067 -0.9757196 0.1443938 -0.1646866 -0.9082997 0.05995672 -0.4140013 -0.5612561 -0.01423025 -0.8275198 -0.5430252 -0.02004569 -0.8394773 -0.9110886 0.05812126 -0.4080925 -0.7691971 0.002256453 -0.6390077 -0.8164269 0.01484936 -0.5772581 -0.9800356 0.06781327 -0.1869006 -0.7463729 -0.03018724 -0.6648429 -0.9862042 0.05332934 -0.1567079 -0.3581105 -0.06921517 -0.9311102 -0.7620684 -0.06115329 -0.6446024 -0.5806468 -0.08176648 -0.8100392 -0.9855419 0.006700813 -0.1692993 -0.8738293 -0.04795706 -0.4838622 -0.3786167 -0.08034634 -0.9220597 -0.9357947 -0.03309738 -0.3509885 -0.8425806 -0.07684159 -0.5330604 -0.1983073 -0.03199011 -0.9796178 -0.9421264 -0.03692466 -0.3332183 -0.6905563 -0.1035713 -0.7158247 -0.7066411 -0.1022641 -0.7001431 -0.5152398 -0.1036831 -0.8507513 -0.1148794 -0.03090512 -0.9928986 -0.996505 -0.03941249 -0.07365226 -0.8572004 -0.1169581 -0.501526 -0.9616734 -0.08555865 -0.2605072 -0.9133691 -0.1432008 -0.3811173 -0.8095337 -0.1558 -0.5660227 -0.9587499 -0.1200894 -0.2576377 -0.9699777 -0.1436782 -0.1962143 -0.5892899 -0.17968 -0.7876883 -0.3473121 -0.1176254 -0.9303433 -0.8160583 -0.1956503 -0.5438475 -0.1963145 -0.0825271 -0.9770619 -0.669802 -0.1911795 -0.7175067 -0.7327565 -0.218793 -0.6443582 -0.8941875 -0.2112677 -0.3947083 -0.9100122 -0.2349868 -0.3415539 -0.7798777 -0.2217455 -0.5853375 -0.1959813 -0.08342385 -0.9770526 -0.4646108 -0.1942248 -0.8639523 -0.9548556 -0.2310764 -0.1866943 -0.5312775 -0.2064115 -0.8216682 -0.9565926 -0.2351024 -0.172214 -0.8468456 -0.3061333 -0.4348967 -0.1253396 -0.07823944 -0.9890241 -0.875142 -0.3028175 -0.3773968 -0.4308277 -0.2211938 -0.8749062 -0.6584754 -0.311782 -0.6849834 -0.3261235 -0.1967363 -0.9246287 -0.6972829 -0.3120473 -0.6453085 -0.9364275 -0.3280757 -0.1243784 -0.3436579 -0.204077 -0.9166525 -0.7996085 -0.3549428 -0.4843985 -0.6392658 -0.3409973 -0.6892461 -0.8040595 -0.3798463 -0.4573895 -0.9141757 -0.3505664 -0.2034358 -0.281796 -0.1893311 -0.9406087 -0.5528423 -0.3357174 -0.7626659 -0.183679 -0.1320534 -0.974076 -0.1783617 -0.1467532 -0.9729598 -0.8743355 -0.4270448 -0.2305865 -0.8939764 -0.4086684 -0.183838 -0.7164239 -0.4294226 -0.5498481 -0.5352715 -0.3618007 -0.7632725 -0.7599167 -0.4381129 -0.4801913 -0.8695522 -0.4373938 -0.2292724 -0.7814459 -0.473078 -0.4068655 -0.4993016 -0.3598248 -0.7881777 -0.01155704 -0.01098096 -0.9998729 -0.4780536 -0.372794 -0.795292 -0.8525232 -0.5083312 -0.1216712 -0.7794207 -0.5134358 -0.3590086 -0.3235107 -0.3000577 -0.8973885 -0.6548604 -0.4803128 -0.5834873 -0.6690725 -0.4821211 -0.5655983 -0.4171777 -0.3599361 -0.8345112 -0.7267246 -0.5417299 -0.4223743 -0.8142134 -0.544448 -0.2015762 -0.3024426 -0.2952622 -0.906283 -0.09687769 -0.1125352 -0.9889139 -0.5474683 -0.4995401 -0.6713704 -0.06651604 -0.08554399 -0.9941117 -0.799434 -0.5800287 -0.1564349 -0.718353 -0.5883876 -0.3711727 -0.2851063 -0.305986 -0.908343 -0.6129083 -0.5249865 -0.5905359 -0.7376564 -0.6130861 -0.2828227 -0.4896687 -0.5123885 -0.7054663 -0.6510996 -0.602127 -0.4620741 -0.2349995 -0.2817232 -0.9302726 -0.4943798 -0.504543 -0.7078313 -0.7229779 -0.6535401 -0.2240275 -0.6427912 -0.6193733 -0.450773 -0.2187824 -0.3124069 -0.9244112 -0.3917215 -0.4784327 -0.7859112 -0.08578848 -0.1313283 -0.98762 -0.5388585 -0.6161197 -0.5744808 -0.656562 -0.6841307 -0.3176342 -0.3803655 -0.50285 -0.7761857 -0.6510896 -0.6929351 -0.3097149 -0.5367599 -0.6213597 -0.5707898 -0.4369515 -0.6066608 -0.6641055 -0.646098 -0.7257977 -0.2361679 -0.5567392 -0.6936624 -0.4570274 -0.1797975 -0.2979583 -0.9374934 -0.3351522 -0.48697 -0.8065565 -0.6288775 -0.7490015 -0.2085907 -0.4304831 -0.6411629 -0.6352909 -0.5386186 -0.7298847 -0.4209019 -0.1744523 -0.3231852 -0.930117 -0.5856342 -0.7720458 -0.2469373 -0.4946284 -0.7392522 -0.4569999 -0.2436965 -0.485139 -0.8397929 -0.5657206 -0.8067491 -0.1706346 -0.3081547 -0.5300192 -0.790013 -0.3608657 -0.6422114 -0.6762696 -0.1219397 -0.2903742 -0.9491121 -0.4692087 -0.7754431 -0.4225295 -0.3522908 -0.682886 -0.6399672 -0.09609287 -0.2386121 -0.9663491 -0.4935871 -0.8422443 -0.2167862 -0.4326094 -0.7802628 -0.4517068 -0.2231631 -0.5383599 -0.8126297 -0.3455449 -0.6861772 -0.6401247 -0.5106177 -0.8416789 -0.1756309 -0.2554336 -0.6311246 -0.7324175 -0.4063658 -0.8157258 -0.4116531 -0.04084217 -0.1578359 -0.9866204 -0.1310251 -0.4385076 -0.8891252 -0.32174 -0.7779892 -0.5396445 -0.4076536 -0.8838654 -0.2293478 -0.1543392 -0.4876843 -0.8592692 -0.4206258 -0.869803 -0.2579084 -0.2372481 -0.7112585 -0.6616833 -0.3050895 -0.7857368 -0.5380874 -0.2352164 -0.7114033 -0.6622526 -0.2936466 -0.8528092 -0.4318428 -0.3377799 -0.9006001 -0.2735403 -0.1619679 -0.6441986 -0.7475122 -0.32537 -0.9172503 -0.2297527 -0.005136013 -0.05478715 -0.9984849 -0.05318516 -0.3333897 -0.9412878 -0.08084273 -0.4066536 -0.9099985 -0.1952874 -0.8082646 -0.5554919 -0.1300652 -0.6704689 -0.7304482 -0.2744092 -0.9408921 -0.1985489 -0.06754159 -0.5186297 -0.8523271 -0.2324039 -0.8716363 -0.4315536 8.26246e-5 -0.1105068 -0.9938754 -0.2168053 -0.9094637 -0.3547837 -0.1478711 -0.7904711 -0.5943818 -0.1104384 -0.650955 -0.7510401 -0.02355295 -0.3245112 -0.9455887 -0.231019 -0.9401801 -0.2503831 -0.1271706 -0.8230144 -0.5536019 7.94114e-4 -0.261588 -0.9651793 -0.02449423 -0.523286 -0.8518051 -0.2032798 -0.9630203 -0.1768308 -0.01866966 -0.5377852 -0.8428752 -0.128762 -0.8937692 -0.4296479 -0.03306311 -0.6875718 -0.7253634 -0.02337479 -0.7270714 -0.6861639 -0.09891963 -0.9181735 -0.3836306 -0.1304135 -0.9784771 -0.1599218 -0.0538904 -0.8082734 -0.5863361 -0.09206348 -0.9666281 -0.2390701 -0.03881359 -0.886408 -0.4612749 0.03155934 -0.5303357 -0.8472001 0.0359649 -0.3340489 -0.9418694 0.03719478 -0.744251 -0.6668636 -0.04401606 -0.9806353 -0.1908325 0.002641797 -0.9059571 -0.4233615 0.06713092 -0.5916286 -0.803411 0.05275446 -0.78166 -0.6214697 9.07736e-4 -0.9688916 -0.2474842 0.03517222 -0.889768 -0.455056 0.06255108 -0.3319791 -0.9412106 0.06774097 -0.5914803 -0.8034689 0.09640949 -0.4266334 -0.8992714 0.06023925 -0.2605447 -0.9635807 0.04579424 -0.9789093 -0.1990967 0.09848833 -0.9188435 -0.3821343 0.1286141 -0.8111934 -0.5704594 0.1492828 -0.6811425 -0.7167704 0.09480226 -0.9685451 -0.2300714 0.1356214 -0.8908621 -0.4335569 0.1159295 -0.9759024 -0.1848646 0.1493676 -0.7844986 -0.6018732 0.1765564 -0.6551747 -0.734557 0.1289734 -0.4586735 -0.8791955 0.07165092 -0.2074162 -0.9756253 0.03980225 -0.09236878 -0.9949291 0.1980214 -0.9078263 -0.369647 0.2263167 -0.8325495 -0.5056107 0.2061268 -0.6711719 -0.7120676 0.2198833 -0.8962768 -0.3851484 0.1743764 -0.968075 -0.1800657 0.1286869 -0.2969941 -0.9461682 0.1711757 -0.4251251 -0.8888013 0.2583135 -0.7944238 -0.5496954 0.2113161 -0.4746311 -0.8544419 0.2996241 -0.7956692 -0.5264372 0.2537136 -0.6259655 -0.7374258 0.298902 -0.9211685 -0.2492114 0.312914 -0.6883664 -0.654398 0.3156443 -0.781273 -0.5384991 0.1611312 -0.271027 -0.9489895 0.3261857 -0.9134038 -0.2435089 0.3416465 -0.9140051 -0.2187978 0.1096289 -0.163405 -0.980449 0.1461768 -0.2101789 -0.9666733 0.2759447 -0.4534575 -0.847485 0.284162 -0.4588048 -0.841873 0.4049695 -0.8105016 -0.4231865 0.3633418 -0.6740647 -0.6431326 0.3841231 -0.6113098 -0.6919175 0.4127353 -0.8794786 -0.236996 0.4128139 -0.8793991 -0.2371541 0.423316 -0.7882879 -0.4465489 0.3087044 -0.4065009 -0.8599178 0.3983639 -0.6149852 -0.6805141 0.4876278 -0.8528739 -0.1866157 0.2142959 -0.2447791 -0.9456006 0.4874541 -0.7809154 -0.3905887 0.478643 -0.6757862 -0.5605479 0.2165538 -0.2425748 -0.9456542 0.5021407 -0.8387923 -0.2104338 0.5011438 -0.7616999 -0.4106924 0.4646418 -0.5380232 -0.7033059 0.416871 -0.4569616 -0.7857512 0.5748197 -0.8114685 -0.1053631 0.5665177 -0.7490343 -0.3435192 0.5246422 -0.6483873 -0.5516743 0.3287509 -0.3015464 -0.894982 0.458988 -0.4969244 -0.7364756 0.5964739 -0.7652568 -0.2420762 0.5779738 -0.6710718 -0.4643371 0.5175693 -0.5003841 -0.6940733 0.6198534 -0.6568105 -0.4293969 0.1323788 -0.1022882 -0.9859072 0.348963 -0.2900943 -0.8911061 0.6691018 -0.7097523 -0.2203509 0.5328398 -0.4844322 -0.6938351 0.6590027 -0.7108895 -0.2456657 0.6277925 -0.6187536 -0.4722505 0.1918015 -0.1284598 -0.9729904 0.01623815 -0.01025694 -0.9998155 0.6735606 -0.5827333 -0.4546847 0.2966293 -0.2040792 -0.9329324 0.4931579 -0.3638423 -0.7901988 0.6466199 -0.500328 -0.5758079 0.503857 -0.3617656 -0.7843812 0.7366238 -0.6449123 -0.2036508 0.6330869 -0.4345216 -0.6406186 0.3975011 -0.2157327 -0.8918814 0.6569218 -0.4812099 -0.580423 0.746666 -0.5995413 -0.2881672 0.51806 -0.2955812 -0.8026492 0.5384647 -0.2997769 -0.7875212 0.3687754 -0.1708061 -0.9136903 0.2049046 -0.09528529 -0.974133 0.7732379 -0.572564 -0.2725319 0.6508699 -0.3947702 -0.6484789 0.7552654 -0.4855179 -0.4402803 0.1658388 -0.06424361 -0.9840582 0.7897089 -0.5279127 -0.3125188 0.7614421 -0.3998961 -0.5101854 0.8287758 -0.506123 -0.2386848 0.6151026 -0.2678022 -0.7415732 0.7433704 -0.416602 -0.5233004 0.7552888 -0.3469377 -0.5560332 0.219095 -0.05699789 -0.9740373 0.4469816 -0.1524922 -0.8814498 0.8633678 -0.4268139 -0.2691209 0.8643907 -0.4395478 -0.2441852 0.7812927 -0.3324471 -0.5282619 0.5804921 -0.1931397 -0.7910284 0.6090371 -0.2214246 -0.7616068 0.877096 -0.3829596 -0.2899048 0.3818433 -0.09511125 -0.9193202 0.7974035 -0.2665857 -0.5413684 0.9017189 -0.3515136 -0.251677 0.8067309 -0.2603267 -0.5304861 0.6261688 -0.149299 -0.7652598 0.9064705 -0.2825471 -0.3138127 0.4862067 -0.06728553 -0.8712497 0.6042879 -0.1112452 -0.7889618 0.1716645 -0.02038449 -0.9849446 0.7960259 -0.1785755 -0.5783198 0.926544 -0.2569522 -0.2747579 0.2600937 -0.004715323 -0.9655719 0.8016943 -0.1725569 -0.5722852 0.472016 -0.03497868 -0.8808959 0.5021308 -0.04942047 -0.8633785 0.9369574 -0.2185297 -0.2726824 0.736205 -0.07929497 -0.6720972 0.9171441 -0.1467524 -0.3705543 0.7487366 -0.05601018 -0.6604972 0.9157938 -0.1505209 -0.3723776 0.8357336 -0.04526638 -0.5472664 0.6906527 -0.01651054 -0.7229982 0.277383 0.01364523 -0.9606625 0.9621115 -0.0978021 -0.2545117 0.376336 0.03701949 -0.9257434 0.4491698 0.02428072 -0.8931165 0.8641581 -0.01866143 -0.5028744 0.6327342 0.06329888 -0.7717777 0.944754 -0.001485228 -0.3277773 0.9642111 -0.02978068 -0.2634581 0.6969471 0.03452497 -0.716291 0.3814842 0.05410176 -0.9227908 0.8073077 0.06543046 -0.5864923 0.5777224 0.1263924 -0.8063881 0.107765 0.02849316 -0.993768 0.9474378 0.07580107 -0.3108308 0.1265176 0.03647273 -0.9912936 0.8230724 0.08675467 -0.5612714 0.6350299 0.1129174 -0.7641903 0.9609113 0.09025174 -0.2617331 0.7192274 0.1348191 -0.6815686 0.3184201 0.08755064 -0.943898 0.3053193 0.08623641 -0.9483373 0.8718825 0.1091009 -0.4774075 0.4824053 0.1566689 -0.8618236 0.5582462 0.1539687 -0.8152636 0.7968044 0.2119002 -0.565863 0.9627453 0.1790189 -0.202667 0.8767589 0.1848241 -0.4439978 0.2129714 0.1042113 -0.9714851 0.9316611 0.2201231 -0.2890563 0.6828898 0.2437252 -0.6886651 0.2788233 0.1288303 -0.9516619 0.7779065 0.2519854 -0.575643 0.7657222 0.2588112 -0.5888007 0.9305755 0.2586022 -0.2591415 0.4776437 0.2132861 -0.8522708 0.7822358 0.3227753 -0.5328447 0.8991811 0.3096545 -0.3091725 0.4116494 0.2140209 -0.8858554 0.6086888 0.2796003 -0.7425103 0.8908227 0.3510388 -0.288456 0.6250612 0.316663 -0.7134585 0.8918097 0.3581758 -0.2763795 0.4200073 0.2437403 -0.8741765 0.1483594 0.1054805 -0.9832921 0.7434066 0.3745607 -0.5541218 0.5620013 0.3442326 -0.7521027 0.7485743 0.3878066 -0.5378128 0.1512714 0.1095897 -0.9823986 0.3366419 0.2545869 -0.9065637 0.8398397 0.444958 -0.3109369 0.5740458 0.3797121 -0.7254585 0.857608 0.4343196 -0.2754545 0.6768813 0.4531899 -0.5800438 0.7054271 0.4558926 -0.5427105 0.3471658 0.2791554 -0.8952923 0.4608647 0.389537 -0.7974112 0.1257141 0.121887 -0.9845504 0.7882732 0.5282934 -0.3154865 0.7884299 0.5223571 -0.3248406 0.5036209 0.4096966 -0.7606017 0.07048201 0.08095413 -0.9942228 0.7778559 0.5418027 -0.3184181 0.2023496 0.2242702 -0.9532877 0.57699 0.5158315 -0.633246 0.2661573 0.2886248 -0.9197044 0.6273108 0.5323658 -0.5683907 0.2924093 0.3414292 -0.8932654 0.7542278 0.6151177 -0.2297189 0.3575853 0.4206465 -0.8337801 0.6712073 0.5852092 -0.4549847 0.4249883 0.4438644 -0.7889039 0.6785591 0.6453309 -0.3508642 0.7325744 0.6354034 -0.2441257 0.5322744 0.5565919 -0.6378789 0.6797719 0.6441744 -0.3506418 0.5334923 0.6200659 -0.575243 0.5361534 0.6165701 -0.5765249 0.5431147 0.6930623 -0.4740161 0.6377215 0.7286477 -0.2497676 0.6429439 0.725373 -0.2458803 0.2098026 0.8217547 -0.5298133 0.03684067 0.647583 -0.7611039 0.07761549 0.7784479 -0.6228922 0.1455982 0.8535968 -0.5001738 0.1234153 0.8908958 -0.4371196 0.1119416 0.8095939 -0.5762178 -0.2034547 -0.9790784 0.003404617 -0.2297828 -0.9732075 -0.008193075 -0.3820081 -0.9241318 -0.007088601 -0.3562029 -0.9343892 0.006035089 -0.5038748 -0.8637086 0.01086205 -0.5648025 -0.8249087 -0.0228911 -0.6642448 -0.7470244 0.02708214 -0.7614634 -0.6477068 -0.02548682 -0.8186145 -0.5740186 0.01931744 -0.89037 -0.4547148 -0.02181601 -0.9255926 -0.3776071 0.02629405 -0.9800439 -0.1966891 -0.02876555 -0.9932017 -0.1133488 0.02650737 -0.998481 0.05071014 -0.02154654 -0.9906042 0.1353896 0.01931631 -0.9689554 0.2468265 -0.01422178 -0.943465 0.3312336 0.01257967 -0.9077074 0.4192159 -0.01804006 -0.8678771 0.496308 0.02163332 -0.7709625 0.6366289 -0.01790332 -0.7463774 0.6654974 0.005842983 -0.6129859 0.7900926 -0.001484155 -0.6034606 0.7973245 -0.0104469 -0.4155212 0.9094715 0.0142728 -0.365043 0.9307317 -0.02196079 -0.2184122 0.9756173 0.02160918 -0.1161191 0.9928787 -0.02661305 0.003909647 0.9997717 0.02101361 0.1061522 0.9942824 -0.01159197 0.2012746 0.9794246 0.01469689 0.2532333 0.9673305 -0.01203477 0.4517893 0.8920471 0.01176798 0.4554883 0.8902052 0.008077085 0.640174 0.7680003 -0.01878303 0.6822804 0.7307768 0.0214219 0.8198085 0.5724488 -0.01472038 0.822835 0.5681801 -0.0106731 0.9022736 0.430842 0.01666402 0.9381736 0.3455327 -0.02091771 0.9690346 0.2461156 0.01997834 0.9883605 0.1511942 -0.01684623 0.9997846 0.01626956 0.01288855 0.9997612 -0.020509 -0.007553279 0.9718495 -0.2352542 -0.01281267 0.9800528 -0.1983617 0.0122168 0.8916295 -0.4524869 -0.01589578 0.9080305 -0.4188085 0.008951246 0.8066417 -0.5906897 0.02036899 0.7458994 -0.6658523 -0.01657837 0.6979584 -0.7160646 0.01028132 0.6127502 -0.7901583 -0.01367777 0.5562742 -0.8308864 0.01367819 0.4436315 -0.8961009 -0.01394045 0.411238 -0.9115065 0.006264448 0.2207916 -0.9753206 -9.46255e-4 0.2193892 -0.9756351 -0.002147078 -0.09035277 -0.9959016 0.00406742 0.02796375 -0.9996063 -0.002311766 0.02537137 -0.999677 -0.00151813 0.172451 -0.9850172 0.001319885 0.07896333 -0.9968776 -1.62401e-4 0.1880396 -0.9821598 -0.001799404 0.3549857 -0.9348698 0.001912295 0.3699771 -0.9290393 -0.001742184 0.5342566 -0.8453207 0.001738846 0.5423294 -0.8401659 -5.39509e-4 0.6973966 -0.7166828 0.001951992 0.689026 -0.7247362 -7.89856e-4 0.8264428 -0.563017 0.002101838 0.816183 -0.5777904 -0.00194168 0.9134284 -0.4069939 -0.002136468 0.9213442 -0.3887413 0.002288699 0.9799597 -0.1991811 0.002466917 0.9753958 -0.2204491 -0.002321064 0.9994422 -0.03331834 -0.002272486 0.9998304 -0.01840806 5.31514e-4 0.9934387 0.1143639 7.46107e-4 0.9912846 0.1317147 -0.002503335 0.9560208 0.293286 0.002761781 0.9483322 0.3172674 -0.002723455 0.8788756 0.4770436 0.002715766 0.8668293 0.4985979 -0.00267744 0.7668226 0.6418536 0.002669513 0.7510662 0.6602218 -0.002631068 0.6243122 0.7811707 0.00262314 0.6056184 0.7957511 -0.002584278 0.4570012 0.8894624 0.002576053 0.4362366 0.8998285 -0.002536177 0.2715423 0.9624232 0.002527415 0.2496132 0.9683425 -0.002489507 0.07530122 0.9971578 0.002481639 0.05312192 0.9985851 -0.002441287 -0.1239417 0.9922866 0.002432465 -0.1454657 0.9893604 -0.002392411 -0.3182545 0.9480024 0.002382934 -0.3383 0.9410355 -0.002343714 -0.499927 0.8660646 0.002335131 -0.5177704 0.8555167 -0.002294778 -0.6617487 0.7497223 0.002285003 -0.6767693 0.7361919 -0.00224328 -0.7972883 0.6035946 0.00223416 -0.8090248 0.5877707 -0.002191543 -0.9011533 0.4334952 0.002182126 -0.909305 0.4161249 -0.0021407 -0.9692242 0.2461705 0.002130389 -0.9736511 0.2280337 -0.002087116 -0.9987934 0.04906547 0.002077996 -0.9995197 0.03092831 -0.002034068 -0.9886854 -0.14999 0.002024292 -0.9858889 -0.1673892 -0.001979708 -0.9393001 -0.343091 0.001970171 -0.9333013 -0.3590892 -0.001923739 -0.8525988 -0.5225626 0.00191456 -0.843833 -0.5366026 -0.001868963 -0.7320244 -0.6812759 0.001858294 -0.7210276 -0.6929041 -0.001810908 -0.5823643 -0.812926 0.001800477 -0.5697364 -0.8218257 -0.00175178 -0.4095633 -0.9122801 0.001741945 -0.3880714 -0.9216222 -0.003662824 -0.2263772 -0.9740277 0.004836857 -0.1854757 -0.9826455 -0.002583622 -0.1669489 -0.9859339 -0.007909476 -2.04257e-7 0 1 -4.11254e-6 0 1 -7.44995e-7 0 1 5.12499e-6 0 1 -8.21179e-6 0 1 -8.06667e-6 0 1 7.78903e-6 0 1 -2.12042e-6 0 1 5.2153e-6 0 1 -4.90634e-6 0 1 4.41931e-6 0 1 2.13562e-6 0 1 7.36176e-6 0 1 -3.86677e-6 0 1 -6.67287e-6 0 1 -4.32946e-6 0 1 8.46384e-6 0 1 -4.88601e-6 0 1 -5.50864e-6 0 1 2.24956e-6 0 1 5.33758e-6 0 1 0 3.13171e-6 1 -1.09183e-6 0 1 -1.05018e-6 0 1 -3.10159e-6 0 1 -0.00125283 -0.600232 0.799825 0.001487672 -0.6007983 0.7993993 2.21889e-6 0 1 -1.37742e-6 0 1 3.97205e-6 0 1 -1.94235e-6 0 1 1.42105e-6 0 1 -2.34132e-6 0 1 8.12001e-6 0 1 -1.85095e-6 0 1 -1.93157e-6 0 1 9.65149e-6 0 1 -9.32829e-6 0 1 3.03092e-6 0 1 -3.70419e-6 0 1 9.2962e-7 0 1 2.16502e-7 0 1 3.87392e-6 0 1 -8.60922e-6 0 1 -4.53748e-6 0 1 5.81299e-6 0 1 5.17119e-7 0 1 -1.65046e-6 0 1 -3.21535e-6 0 1 8.50968e-7 0 1 -1.98105e-6 0 1 -4.29942e-6 0 1 -7.01943e-6 0 1 2.77523e-6 0 1 -2.43711e-6 0 1 2.11484e-6 0 1 1.24927e-6 0 1 -1.21163e-5 0 1 -4.13145e-6 0 1 9.28625e-6 0 1 -1.37996e-6 0 1 1.48155e-5 0 1 2.66116e-7 0 1 -6.28305e-7 0 1 1.94537e-6 0 1 0 -3.05874e-7 1 0 -5.69434e-7 1 0 -7.75995e-7 1 0 -5.62965e-7 1 -2.38507e-6 0 1 -9.16548e-7 1.46226e-6 1 -1.86002e-6 0 1 5.12527e-6 0 1 -5.5872e-6 0 1 5.40787e-6 0 1 -2.79997e-6 0 1 1.40913e-6 0 1 0 -2.78995e-7 1 0 -4.80066e-7 1 0 -5.38823e-7 1 1.42415e-6 0 1 -3.57392e-6 0 1 1.23792e-6 1.37408e-6 1 -1.11512e-6 0 1 1.37064e-6 0 1 2.87211e-6 0 1 -1.7776e-6 0 1 -6.8547e-6 0 1 -1.46692e-6 0 1 1.56387e-4 -0.2315406 0.9728252 -2.95449e-4 -0.2366035 0.9716063 0.001214265 -0.4614905 0.8871444 0.001151621 -0.4606834 0.8875638 -0.5635156 -0.4194005 0.7117258 -0.4587078 -0.2844143 0.8418407 -0.4926887 -0.4035431 0.7709805 -0.3453761 -0.4677913 0.8135643 -0.2787051 -0.4453169 0.8508915 -0.1614717 -0.03338617 0.9863125 -0.167771 -0.2862621 0.9433488 -0.139233 -0.481936 0.8650734 -0.1200399 -0.213457 0.9695497 -0.1486576 -0.4416381 0.884792 -0.1421692 -0.4319149 0.8906388 -0.07031202 -0.17647 0.9817916 -0.8250475 -0.2490462 0.5072206 -0.7780165 -0.3413473 0.5274206 -0.6890345 -0.2464326 0.6815441 -0.686226 -0.268853 0.6758787 -0.3118626 -0.2641535 0.912669 -0.3177446 -0.3295969 0.8890469 -0.1964083 -0.1978299 0.9603579 0.004500746 6.64793e-4 -0.9999897 0.002233684 -0.00172466 -0.999996 2.40732e-4 -3.6217e-4 -0.9999999 0.003381907 -9.78083e-4 -0.9999939 9.77901e-5 -4.35022e-4 -1 -4.19963e-5 -5.64235e-4 -1 0.001423597 -0.001752674 -0.9999975 4.83604e-4 1.06451e-4 -1 -7.72383e-4 -0.001422882 -0.9999987 -8.33736e-4 -0.001407504 -0.9999988 4.19254e-4 3.49173e-4 -0.9999999 7.62944e-4 -0.001467585 -0.9999986 -1.80322e-5 -1.36797e-5 -1 0.001083791 -0.001069426 -0.9999989 0.002505064 0.001350104 -0.999996 0.002547442 7.25892e-4 -0.9999966 1.59099e-4 -3.4371e-4 -1 0.003974735 -0.001607 -0.9999909 4.56915e-4 -7.28243e-5 -1 1.68664e-6 0 -1 0.003531157 -1.48104e-4 -0.9999938 0.001966297 2.13001e-4 -0.999998 -4.51578e-6 0 -1 3.43e-5 -5.76514e-5 -1 1.37905e-6 -4.48432e-5 -1 9.71987e-5 -6.63789e-5 -1 1.63707e-5 -5.80206e-5 -1 -6.25405e-7 0 -1 0.001020848 5.9828e-4 -0.9999994 1.242e-5 -6.22945e-5 -1 -1.89973e-6 0 -1 -9.32944e-6 0 -1 7.20711e-4 9.18589e-4 -0.9999994 -3.37782e-5 -8.01297e-5 -1 -0.001613557 -0.001110136 -0.9999982 -0.002358675 -0.002370536 -0.9999944 5.15234e-4 0.001503884 -0.9999988 -0.001563727 -8.52723e-4 -0.9999985 -3.7687e-5 7.00046e-4 -0.9999998 6.38858e-4 6.92776e-4 -0.9999996 -0.001329362 -2.24842e-4 -0.9999992 -0.001298367 2.78795e-4 -0.9999992 -4.3804e-4 8.47972e-4 -0.9999996 6.3093e-6 0 -1 -3.65128e-6 0 -1 1.3201e-6 0 -1 -6.90258e-6 0 -1 -1.02691e-6 0 -1 2.03944e-6 0 -1 -2.23438e-6 0 -1 -0.004425406 0.003104925 -0.9999855 -0.001342058 4.30821e-4 -0.9999991 -1.4607e-6 0 -1 -9.7984e-4 8.38903e-4 -0.9999992 -0.003655433 0.003198206 -0.9999882 -4.57651e-5 9.38835e-4 -0.9999996 0.004116356 0.003205358 -0.9999864 7.39126e-4 5.3048e-4 -0.9999997 1.9704e-4 9.2938e-4 -0.9999997 -0.00111562 1.70824e-4 -0.9999995 -5.89306e-4 0.001547574 -0.9999986 -6.05957e-4 -6.78402e-4 -0.9999996 -0.001337528 2.76086e-4 -0.9999992 4.91338e-4 8.69068e-4 -0.9999995 7.67464e-4 7.61323e-4 -0.9999995 -0.001200139 -5.83561e-4 -0.9999991 8.20018e-5 4.41839e-4 -1 -4.31399e-5 4.02314e-4 -1 -0.001080334 -4.72334e-5 -0.9999994 -0.00124067 -4.59297e-4 -0.9999992 -0.001029014 2.96016e-4 -0.9999994 -2.43243e-4 3.9506e-4 -1 -6.9665e-4 4.76264e-4 -0.9999997 -0.001030504 5.64528e-4 -0.9999994 -0.6256209 0.7800529 -0.01078212 -0.6416524 0.7669774 -0.005301654 -0.6983417 0.7157641 -9.02454e-4 -0.6978759 0.7162173 0.00141251 -0.7020035 0.7121731 7.54567e-4 -0.7488077 0.6627872 3.16985e-4 -0.7465551 0.6653236 9.90108e-5 -0.7920969 0.6103954 4.26647e-4 -0.8050104 0.5932601 -8.56044e-4 -0.8429561 0.5379825 2.52632e-4 -0.8558375 0.5172433 -0.001305401 -0.8749814 0.4841536 -0.001742839 -0.8971143 0.4417963 0.001484513 -0.9269852 0.3750956 -0.001345753 -0.9467869 0.3218613 2.46567e-4 -0.9500349 0.3121418 0.001123189 -0.9672371 0.253875 -3.26986e-4 -0.9768788 0.2137863 0.001881897 -0.9892669 0.1461203 -5.98165e-5 -0.9927573 0.1201295 0.001408457 -0.9968442 0.07937312 0.001228928 -0.9982041 0.05990546 -7.39871e-5 -0.9996376 -0.02691584 4.89794e-4 -0.9989638 -0.0455085 -6.00449e-4 -0.9960494 -0.08879816 8.62142e-4 -0.9904933 -0.1375604 -4.69702e-4 -0.9854614 -0.1698958 0.001207709 -0.9713917 -0.2374833 2.68831e-4 -0.9722126 -0.2340993 5.29429e-4 -0.9501212 -0.3118784 0.001317203 -0.9436738 -0.3308772 -2.04737e-4 -0.9112284 -0.4119014 5.24202e-4 -0.9060313 -0.4232106 -4.3321e-4 -0.8616285 -0.5075395 -9.24841e-5 -0.8627933 -0.505557 8.12395e-5 -0.7983748 -0.6021605 -7.31193e-4 -0.8165175 -0.5773202 8.95694e-4 -0.7807547 -0.6248378 2.4849e-4 -0.736531 -0.6764023 -0.001486837 -0.7028545 -0.7113338 -7.31482e-5 -0.7136229 -0.70053 4.1567e-4 -0.6445386 -0.7645714 8.10075e-4 -0.6336885 -0.7735884 -2.01392e-4 -0.5931497 -0.805092 -6.37942e-4 -0.5619135 -0.8271951 0.001365005 -0.5084066 -0.861117 -6.35749e-4 -0.4848283 -0.8746092 7.10668e-4 -0.42246 -0.9063805 -0.001472115 -0.38508 -0.922883 7.30377e-4 -0.3508226 -0.9364414 -0.00112456 -0.2851017 -0.9584971 -6.096e-4 -0.2547715 -0.9669998 0.001677095 -0.2014843 -0.9794917 -4.48281e-4 -0.1551871 -0.987885 6.23186e-4 -0.1357266 -0.9907463 -4.32265e-4 -0.04163992 -0.9991326 -2.71988e-4 -0.06108093 -0.9981325 7.26448e-4 -0.001550257 -0.9999984 9.43408e-4 0.04440736 -0.9990134 -5.87596e-4 0.1084688 -0.9940999 -1.84571e-4 0.08673256 -0.9962316 5.50479e-4 0.1463213 -0.9892366 0.001031577 0.2260264 -0.9741204 -0.001322567 0.2331055 -0.972451 -0.001006007 0.2330224 -0.9724709 -0.00100255 0.3465141 -0.9380446 -5.09695e-4 0.3375926 -0.9412924 2.14769e-4 0.4317606 -0.9019883 3.34314e-4 0.4308893 -0.9024049 4.05826e-4 0.4852865 -0.8743551 -5.4973e-4 0.5106698 -0.8597764 9.52121e-4 0.5809383 -0.8139463 -0.001529574 0.5971162 -0.8021548 1.96036e-4 0.6330566 -0.7741045 0.001201868 0.683425 -0.7300196 -0.001306295 0.7132171 -0.7009421 0.001241445 0.7548148 -0.655938 -2.14481e-4 0.769338 -0.6388412 0.001073777 0.8123305 -0.5831967 -9.82704e-4 0.8445939 -0.5354066 -0.001041173 0.8311331 -0.5560737 9.43931e-5 0.8933616 -0.4493376 -8.43872e-4 0.8851087 -0.465384 6.34465e-4 0.9339406 -0.3574275 -8.28688e-4 0.9383801 -0.3456047 2.61885e-4 0.9608938 -0.2769144 -0.001309871 0.979996 -0.1990165 -4.9612e-4 0.9744296 -0.224692 7.31244e-4 0.9920742 -0.1256514 -7.97652e-4 0.9892609 -0.14616 5.47185e-4 0.9999613 -0.008759081 -8.17212e-4 0.9992936 -0.03757125 8.97644e-4 0.9971389 0.07558268 -0.001106798 0.9992469 0.03880327 3.67077e-4 0.993699 0.1120822 4.04818e-4 0.9837108 0.1797536 -0.001259744 0.978704 0.2052764 3.53974e-4 0.9600213 0.2799246 -0.00121802 0.9544824 0.2982671 -1.09947e-4 0.9312599 0.3643513 -0.001805484 0.9178336 0.3969652 4.20467e-4 0.8844348 0.466662 -0.001313984 0.8966207 0.4427995 3.77617e-4 0.8379705 0.5457152 -7.1931e-4 0.8514949 0.5243631 2.61881e-4 0.8259922 0.5636816 1.79293e-4 0.7893151 0.6139879 -8.5171e-4 0.7350391 0.6780244 -7.42352e-4 0.7643784 0.6447672 9.96758e-4 0.6799525 0.7331112 -0.01458513 0.6798965 0.7331619 -0.0146448 0.7139897 0.7001563 -1.30227e-5 0.7097124 0.7044912 7.34696e-4 -0.9882121 0.1530913 1.25924e-4 -0.9795123 0.2013741 0.002008378 -0.9480889 0.3179966 -0.002395272 -0.8808088 0.4734691 0.001678526 -0.8804137 0.4742037 0.001627683 -0.7504708 0.6609017 -0.00166589 -0.787243 0.6166422 0.001071929 -0.6866838 0.7241824 -0.06344425 -0.9472506 0.1387922 -0.2888825 -0.8601508 0.4676954 -0.2034741 -0.8649705 0.4417539 -0.2380751 -0.7624189 0.6330633 -0.133971 -0.8472305 0.5176013 -0.1195386 -0.6758071 0.7362625 -0.03467649 -0.933639 0.3521904 -0.06542372 -0.8394951 0.5341173 -0.09983384 -0.9665487 0.2163777 -0.1377109 -0.7688973 0.6392053 -0.0146178 -0.5862751 0.7622683 -0.2742785 -0.6204463 0.7808614 -0.07281368 -0.7209921 0.6573319 -0.2192836 -0.7645109 0.5403733 -0.351454 -0.7177991 0.6255265 -0.3057469 -0.8022959 0.4780043 -0.3575378 -0.5213246 0.8002133 -0.2964446 -0.4734917 0.7629544 -0.440121 -0.6238819 0.5617926 -0.5432868 -0.5432482 0.7140317 -0.4416336 -0.3743256 0.7646703 -0.5245568 -0.4075081 0.7835431 -0.4690387 -0.411498 0.6727381 -0.6148927 -0.4765771 0.6536096 -0.5879361 -0.2997216 0.7729954 -0.5591467 -0.3595839 0.6040063 -0.7112495 -0.2447248 0.7748141 -0.5829005 -0.312008 0.7606586 -0.5692536 -0.1954277 0.8151314 -0.5453155 -0.2170045 0.6760169 -0.7042089 -0.1313687 0.6427466 -0.7547311 -0.6356516 0.5923361 -0.4950608 -0.03620386 0.6717076 -0.7399312 -0.04183727 0.6751621 -0.7364822 -0.04892981 0.735839 -0.6753865 -0.1015375 0.8709359 -0.4807921 -0.108969 0.7939382 -0.598154 -0.1963301 0.8152132 -0.544869 -0.03729194 0.8521374 -0.5219879 0.5640735 0.6092048 -0.5573964 0.5687983 0.6039393 -0.5583242 0.4489095 0.650334 -0.6128182 0.5084658 0.7851718 -0.3535079 0.4377596 0.7475609 -0.499519 0.3609639 0.6039277 -0.710617 0.3195422 0.6739699 -0.6660761 0.3892328 0.7715588 -0.5031847 0.3353016 0.7444849 -0.5773345 0.1484694 0.6428065 -0.7515029 0.272267 0.7590726 -0.5913372 0.1513375 0.6820686 -0.7154575 0.2405768 0.8272024 -0.5077983 0.701044 0.5500147 -0.4538955 0.7099174 0.5707418 -0.4126393 0.6015008 0.788099 -0.1307553 0.6303433 0.7626622 -0.1449621 0.6596868 0.6621613 -0.3554657 0.5716935 0.7522274 -0.3275983 0.9309448 0.3486848 -0.1084477 0.9114443 0.4032129 -0.081784 0.8413274 0.5342746 -0.08196789 0.8168184 0.4928101 -0.2999103 0.867371 0.4750148 -0.1484208 0.8609128 0.4284373 -0.2743552 0.7494598 0.6509954 -0.1204791 0.6647434 0.7469176 -0.01517844 0.9820749 0.1417605 -0.1242296 0.9450771 0.3118708 -0.09780609 0.9127224 0.3126813 -0.2629986 0.7970274 0.6029688 -0.03429567 0.7532351 0.6465253 -0.1210043 0.8132119 0.5819676 2.37535e-4 0.848126 0.5297867 0.002893567 0.9088072 0.4172157 -7.97427e-4 0.9443114 0.3290466 0.002058029 0.9772334 0.2121571 -0.002085268 0.9918164 0.1276708 8.09149e-4 0.04755979 -0.4262096 0.9033734 0.1130315 -0.233655 0.9657273 0.1382612 -0.4509318 0.8817847 0.329535 -0.5299226 0.7814018 0.2513111 -0.3195183 0.9136471 0.06817179 -0.1815431 0.9810172 0.2459595 -0.3172912 0.9158768 0.1132388 -0.139073 0.9837864 0.09705185 -0.04114621 0.9944285 0.3417775 -0.2476149 0.9065732 0.7152206 -0.2381869 0.6570591 0.5394157 -0.2919276 0.7898158 0.5148066 -0.3866703 0.7651538 0.6346868 -0.3947556 0.6643348 0.7717054 -0.3343232 0.5410166 0.8399326 -0.2376565 0.4878857 0.3881149 -0.4003797 0.8300983 0.3218522 -0.1996312 0.9255045 -0.01350826 -0.01297664 0.9998246 -0.009354829 -0.008226871 0.9999225 -0.009940147 -0.01305758 0.9998654 -0.01086395 -0.01585489 0.9998154 -0.007622778 -0.004387021 0.9999613 -0.01048392 -0.004738867 0.9999339 -0.005241513 -0.01081395 0.9999279 -0.005076825 -0.01158332 0.9999201 -0.008478164 -0.002836346 0.9999601 -0.01631438 -0.001385867 0.999866 -0.001133799 -0.004387438 0.9999898 -5.09548e-4 -0.004885673 0.999988 -0.01764518 -0.00234431 0.9998416 -0.02047359 -6.69843e-4 0.9997902 -1.85619e-4 -0.003457963 0.9999941 -0.009528994 3.18074e-4 0.9999547 4.45017e-4 -0.003042042 0.9999954 -0.005962193 0.001350104 0.9999814 0.003169536 -0.009672462 0.9999483 -0.006965756 0.002225577 0.9999734 0.003047049 -0.008474051 0.9999595 -0.004491686 0.001998722 0.999988 0.004707336 -0.007786154 0.9999586 -0.005268514 0.00372523 0.9999792 -0.008193314 0.006501436 0.9999454 0.0161072 -0.01933258 0.9996834 0.01604503 -0.01744872 0.999719 -0.01027566 0.01081764 0.9998888 -0.009179592 0.009345531 0.9999142 0.02306044 -0.02036398 0.9995267 0.01261788 -0.009164571 0.9998784 -0.006815075 0.01056176 0.9999211 -0.003982067 5.56759e-4 0.999992 0.01233786 -0.005645394 0.999908 0.01547604 -0.006042063 0.999862 -0.009087324 -1.06911e-4 0.9999588 -0.006592333 -0.002301394 0.9999757 0.001399934 -0.0035187 0.9999929 0.01272004 -0.002980291 0.9999147 7.54328e-4 -0.00393176 0.9999921 0.01259762 -0.003004491 0.9999161 1.25429e-4 -0.004979968 0.9999876 0.002198398 -6.80609e-5 0.9999976 0.002418994 4.10685e-4 0.999997 0.004867613 0.001282989 0.9999874 0.003731966 0.001436769 0.9999921 0.006056487 0.003850102 0.9999743 0.008993089 0.00610435 0.9999409 0.007389724 0.007094979 0.9999476 0.007779896 0.007741153 0.9999398 0.01022809 0.006482541 0.9999268 0.003269612 0.004714429 0.9999836 1.81783e-4 -0.00483781 0.9999883 -5.8257e-4 -0.003427028 0.999994 0.00383383 0.00178349 0.9999911 0.003568768 -0.005667209 0.9999777 0.001404166 0.003333687 0.9999935 0.006065785 -0.002289593 0.9999791 -0.9746508 -0.08968162 0.2049707 -0.6667283 -0.277516 0.6917069 -0.9459927 -0.144533 0.2901862 -0.8549654 -0.183702 0.4850648 -0.6811798 -0.2682569 0.6811993 -0.8772252 -0.1802877 0.4449408 -0.9137893 -0.03304791 0.4048418 -0.9355829 -0.1549118 0.3173121 -0.9458727 -0.1280229 0.29822 -0.8275781 -0.2269376 0.5134333 -0.9204979 -0.1364107 0.3661636 -0.9718648 -0.07388174 0.2236523 -0.9663666 -0.07629489 0.2455908 -0.6819675 -0.2482286 0.6879702 -0.9103788 -0.1347422 0.3912226 -0.8574584 -0.1407812 0.4949203 -0.7563625 -0.1934055 0.624908 -0.5632677 -0.1910188 0.8038915 -0.9805833 -0.03155535 0.1935475 -0.9092091 -0.09048229 0.4063887 -0.8838113 -0.08938908 0.4592245 -0.5911252 -0.1626936 0.7900011 -0.7849752 -0.075598 0.6148975 -0.9152852 -0.05882489 0.3984879 -0.7543882 -0.03772944 0.6553435 -0.9009536 -0.03689068 0.4323445 -0.7232735 -0.1473878 0.6746499 -0.5554096 -0.145998 0.8186603 -0.6088447 -0.06874847 0.7903049 -0.3163565 -0.1352396 0.938951 -0.3616799 0.05564934 0.9306401 -0.6356725 -0.09889888 0.7655977 -0.9027749 0.002435624 0.4301066 -0.9107204 0.006722927 0.4129688 -0.6672633 -1.66608e-4 0.7448219 -0.6735734 0.001442015 0.739119 -0.3949036 0.002351582 0.9187196 -0.3423238 -0.003247976 0.9395765 -0.2895845 3.53235e-4 0.9571524 -0.4358686 0.1656484 0.8846352 -0.2384267 0.108796 0.9650472 -0.3946999 0.2337321 0.8885838 -0.5849076 0.4908079 0.6457483 -0.7157035 0.5876721 0.3773727 -0.3056219 0.1289488 0.943381 -0.7756731 0.5528608 0.304428 -0.5685681 0.4929321 0.6585958 -0.4687575 0.2317674 0.8523792 -0.4328643 0.1756706 0.8841768 -0.5815536 0.3578305 0.7305839 -0.7582008 0.3490034 0.5507526 -0.7054634 0.2853196 0.6487791 -0.8420469 0.4059376 0.3552067 -0.8243434 0.4097703 0.3905718 -0.493027 0.07143336 0.8670765 -0.2480122 0.08589053 0.9649419 -0.8705533 0.4821841 0.0981608 -0.6974955 0.1696391 0.6962202 -0.8280192 0.2627598 0.4953199 -0.702823 0.163702 0.6922728 -0.8774281 0.2366116 0.417295 -0.9467306 0.2680346 0.1784898 -0.664874 0.09865832 0.7404115 -0.9241588 0.2870259 0.2520847 -0.88405 0.1267005 0.4498917 -0.8911253 0.1502181 0.4281709 -0.9581293 0.1085927 0.2649452 0.1873354 0.1786823 0.9659079 0.1924359 0.1868113 0.9633639 0.3420284 0.3506538 0.8718134 0.4384983 0.4221118 0.7934361 0.5148925 0.5243036 0.6782267 0.5663961 0.5621687 0.6026293 0.6168947 0.6375463 0.4614928 0.6639847 0.6568678 0.3572804 0.6801328 0.6971844 0.2266129 0.4581257 0.3957592 0.7959245 0.2456932 0.1946493 0.9496034 0.6416208 0.5392282 0.5454868 0.3387761 0.2530623 0.9061955 0.7069075 0.60882 0.360028 0.5614347 0.4320358 0.7057877 0.7336373 0.6098225 0.2998215 0.6247183 0.4903425 0.6076934 0.3834396 0.2647849 0.8847955 0.5411391 0.37841 0.7509822 0.1267967 0.07309782 0.9892318 0.7489216 0.5000974 0.4347633 0.7681499 0.5541826 0.3206675 0.1758956 0.09307754 0.9799987 0.6327076 0.3710313 0.6797183 0.374772 0.2141045 0.9020561 0.7581369 0.4753872 0.4463582 0.4895273 0.2499399 0.8354 0.8027036 0.469728 0.3674542 0.6252021 0.3529402 0.6961003 0.8393235 0.4253482 0.3385486 0.2742905 0.09364986 0.957076 0.7451696 0.3314313 0.5786845 0.5285823 0.2107464 0.8223057 0.8139194 0.3531238 0.4613447 0.8319264 0.3691889 0.4142442 0.5970299 0.218348 0.7719324 0.9106827 0.362127 0.198799 0.6122512 0.2097662 0.7623298 0.2507415 0.06346845 0.9659713 0.3337248 0.07739877 0.9394878 0.837225 0.2480767 0.4873523 0.8111866 0.2565934 0.5254869 0.5539088 0.1378528 0.8210858 0.158461 0.03172475 0.9868555 0.9245744 0.2814176 0.2568393 0.9352092 0.3007255 0.1869437 0.6225115 0.1207997 0.7732315 0.819719 0.1660441 0.5481699 0.8360599 0.1804315 0.5181201 0.9391909 0.1917064 0.2849022 0.9481584 0.2033384 0.2442318 0.5724552 0.0608592 0.8176743 0.6050668 0.07344371 0.7927801 0.2365879 0.008125185 0.9715762 0.7967212 0.07469582 0.599713 0.8363791 0.09475445 0.5398997 0.9296833 0.08971232 0.3572684 0.9547533 0.1193239 0.2724115 0.4844049 0.002676963 0.87484 0.5144596 0.008984148 0.8574677 0.941709 0.05651468 0.3316479 0.7304589 -0.006258964 0.682928 0.8047932 0.01234382 0.5934271 0.8924847 -0.002538204 0.4510706 0.4588915 -0.03444194 0.8878247 0.9219341 -0.04918295 0.3842117 0.1272587 -0.01260614 0.9917895 0.2687995 -0.0421015 0.9622756 0.7734116 -0.08498406 0.6281817 0.5953302 -0.09229332 0.7981629 0.9037436 -0.08499252 0.4195518 0.7152225 -0.1053099 0.6909173 0.9291018 -0.1207067 0.3495708 0.3307752 -0.07790601 0.9404885 0.5024796 -0.1228032 0.8558234 0.8033751 -0.1951766 0.5625786 0.8849532 -0.1922485 0.4241443 0.5815821 -0.178868 0.7935796 0.945167 -0.2468836 0.2137944 0.7800005 -0.2157864 0.5873972 0.8180844 -0.2657312 0.5100244 0.2279513 -0.08804881 0.9696834 0.9250165 -0.2846528 0.2516295 0.2831295 -0.1215575 0.9513473 0.5384075 -0.2181808 0.8139501 0.5327898 -0.2131121 0.818974 0.9296074 -0.3386334 0.1454561 0.74332 -0.3229834 0.5857962 0.804319 -0.308008 0.5081358 0.8880309 -0.361211 0.2844781 0.7483384 -0.3459318 0.565969 0.8559545 -0.422432 0.2981494 0.3150324 -0.1964532 0.9285262 0.4997774 -0.2891039 0.8164813 0.5324989 -0.3154063 0.7854706 0.858915 -0.4503365 0.2438489 0.6602144 -0.3902 0.641764 0.2945977 -0.1917706 0.9361818 0.6816001 -0.4184803 0.6002462 0.8017481 -0.4923983 0.3387387 0.07269406 -0.05906748 0.9956037 0.803417 -0.528339 0.2745524 0.3680842 -0.3061671 0.8779384 0.5055258 -0.4114178 0.7584058 0.4819976 -0.4003643 0.7793503 0.6247695 -0.4965949 0.6025418 0.6776331 -0.5686327 0.4663373 0.7364365 -0.5848637 0.3399938 0.2870894 -0.2843919 0.9147137 0.3074827 -0.3373419 0.88975 0.6538527 -0.6063251 0.4526 0.46222 -0.490789 0.7385653 0.6738062 -0.6937868 0.2542543 0.5045704 -0.5598505 0.657249 0.5606938 -0.5997266 0.5709208 0.1101925 -0.1697669 0.9793043 0.6177015 -0.7194044 0.3176512 0.2794488 -0.3422785 0.8970807 0.31928 -0.4588142 0.8291863 0.6192929 -0.7163968 0.3213286 0.4593021 -0.600382 0.6546626 0.4866319 -0.6790382 0.5496331 0.5583313 -0.7389332 0.3771525 0.5580642 -0.7932657 0.2435036 0.1663148 -0.3068015 0.9371298 0.3031476 -0.4615162 0.8337292 0.4356332 -0.7308734 0.5254027 0.4681206 -0.8118687 0.3489014 0.5061091 -0.8278688 0.2418407 0.3303896 -0.6063393 0.7233225 0.1593382 -0.3462523 0.9245111 0.3881692 -0.6929606 0.6075609 0.2562945 -0.5716329 0.7794544 0.2534525 -0.59693 0.7612074 0.4101929 -0.8727717 0.2645967 0.1127522 -0.3057639 0.9454075 0.3190336 -0.7908428 0.5222884 0.3188857 -0.7883608 0.5261169 0.3679518 -0.8659049 0.3388515 0.1247844 -0.4127323 0.9022644 0.1737145 -0.5690441 0.8037488 0.02331197 -0.09297335 0.9953957 0.174203 -0.6118699 0.7715366 0.3264339 -0.9250833 0.1940662 0.2256613 -0.7906583 0.5691542 0.2447448 -0.8132705 0.5279121 0.2663946 -0.9166703 0.2979089 0.03319233 -0.2611778 0.9647199 0.2379382 -0.9462352 0.2191446 0.05614107 -0.3635545 0.9298798 0.04313182 -0.3309198 0.9426727 0.1051362 -0.621104 0.7766442 0.09274661 -0.7044195 0.7036983 0.1482372 -0.8286636 0.5397616 0.1403191 -0.9231499 0.3579174 0.1407569 -0.9227386 0.3588051 0.07335317 -0.7104368 0.6999278 0.04991471 -0.8053215 0.5907332 0.01221388 -0.514464 0.857425 0.09206533 -0.927181 0.3631245 0.07700616 -0.9451161 0.3175309 -0.007403194 -0.1472325 0.9890743 -0.005490601 -0.8354855 0.5494851 -0.02208465 -0.5249287 0.8508598 -0.0116353 -0.9238755 0.3825163 0.01222789 -0.9500237 0.3119384 -0.02660208 -0.2396416 0.970497 -0.05004858 -0.7513353 0.6580201 -0.04359602 -0.4342585 0.8997328 -0.0702511 -0.9501098 0.3039016 -0.1018303 -0.7933096 0.6002422 -0.1059707 -0.9293293 0.353719 -0.1103962 -0.7835978 0.6113815 -0.1185528 -0.5585723 0.82094 -0.1461494 -0.9562633 0.2533795 -0.1226811 -0.5718845 0.8111088 -0.05382645 -0.1816375 0.9818913 -0.1794304 -0.6531959 0.7356222 -0.2151536 -0.8223641 0.5267128 -0.2235324 -0.8364294 0.5004189 -0.226886 -0.9185568 0.3236915 -0.2556949 -0.9522476 0.1668673 -0.1045969 -0.2990509 0.9484873 -0.2246751 -0.5985746 0.7689147 -0.1088607 -0.30449 0.9462743 -0.1812579 -0.4322493 0.8833494 -0.3079912 -0.8411815 0.4444717 -0.3296024 -0.8879286 0.3208507 -0.2926746 -0.6908732 0.6610868 -0.3249356 -0.7827949 0.5307063 -0.384188 -0.9098136 0.1569681 -0.227929 -0.4412528 0.8679541 -0.3803448 -0.8003033 0.4635218 -0.3011402 -0.5373453 0.7877658 -0.1082134 -0.1724925 0.9790486 -0.1521868 -0.2316605 0.9608187 -0.3344327 -0.6285236 0.70222 -0.4278885 -0.8585844 0.2823902 -0.3910271 -0.701527 0.5957832 -0.4586433 -0.8554767 0.2404289 -0.188668 -0.2648863 0.9456425 -0.4420363 -0.7169027 0.539124 -0.3533064 -0.5122166 0.7828211 -0.4926456 -0.7978416 0.3474898 -0.3539917 -0.5163524 0.7797886 -0.4521728 -0.6696229 0.5891901 -0.5459551 -0.7957804 0.2620434 -0.2506734 -0.2874831 0.9244005 -0.5200486 -0.6804705 0.5162457 -0.3875672 -0.4514454 0.8037343 -0.4071968 -0.4889579 0.7714344 -0.5706251 -0.7452267 0.344999 -0.5050665 -0.5874649 0.6322917 -0.09095263 -0.07768636 0.9928205 -0.6147605 -0.7448533 0.2593513 -0.2392092 -0.2481935 0.9387114 -0.6050599 -0.5930612 0.5312071 -0.3815055 -0.3176149 0.8680866 -0.665267 -0.6550623 0.3582086 -0.4448773 -0.4012612 0.8006709 -0.688671 -0.6611763 0.2976211 -0.5870327 -0.5237442 0.6173206 -0.3816871 -0.3125263 0.869852 -0.2541678 -0.1778064 0.9506754 -0.4946315 -0.3469743 0.7968366 -0.7477527 -0.6130601 0.2549966 -0.634508 -0.4491304 0.6290323 -0.6560023 -0.4915286 0.5727658 -0.7489578 -0.5488415 0.3712618 -0.7738455 -0.5427621 0.3264544 -0.2956665 -0.17699 0.9387524 -0.4679734 -0.2755687 0.8396801 -0.7016299 -0.4128815 0.5807276 -0.7624141 -0.4330556 0.4808197 -0.8075651 -0.4808257 0.3415337 -0.5648801 -0.287496 0.7734705 -0.2353178 -0.1049547 0.966235 -0.2394377 -0.1075776 0.9649336 -0.6042534 -0.3087956 0.7345224 -0.8497447 -0.4802322 0.2175109 -0.5076296 -0.2187847 0.833334 -0.7594155 -0.3348033 0.5578485 -0.7972614 -0.3694164 0.4773949 -0.8783197 -0.3878014 0.2795796 -0.888282 -0.4084665 0.2100247 -0.604369 -0.2024075 0.7705644 -0.6742049 -0.2241086 0.7037209 -0.7611243 -0.2735142 0.5881155 -0.8625307 -0.2736213 0.4256435 -0.9061161 -0.3217657 0.2746279 -0.2722498 -0.06602424 0.9599589 -0.3070376 -0.0695945 0.9491495 -0.5012421 -0.1205485 0.856869 -0.7993798 -0.1754145 0.5746493 -0.8787825 -0.2142853 0.4264073 -0.5919882 -0.1078777 0.7986941 -0.8988595 -0.2080408 0.3857083 -0.7679219 -0.1426172 0.6244648 -0.9316784 -0.1569632 0.3276246 -0.3720248 -0.02610135 0.9278557 -0.8088073 -0.1094185 0.5778049 -0.57343 -0.06157577 0.8169372 -0.9101343 -0.1093574 0.3996205 -0.1402397 0.006205856 0.9900982 -0.7122373 -0.04239857 0.7006572 -0.3520327 -0.01575362 0.9358552 -0.934128 -0.07705891 0.3485209 -0.7392233 -0.01117569 0.6733678 -0.4723091 0.01755863 0.8812581 -0.9301718 -0.04662698 0.3641517 -0.214179 0.02483671 0.9764787 -0.6745308 0.01978719 0.7379816 -0.7368198 -0.007219731 0.6760507 -0.9620434 -0.007686972 0.2727884 -0.4264335 0.05784499 0.9026675 -0.8934648 0.07435935 0.4429349 -0.7085485 0.08589214 0.7004153 -0.9582731 0.03301686 0.2839413 -0.4553433 0.0723353 0.8873726 -0.8779668 0.1079503 0.4663916 -0.8923686 0.1242592 0.4338642 -0.6760382 0.09459733 0.7307693 -0.6934819 0.1712584 0.6998239 -0.3258317 0.09047073 0.9410892 -0.4228184 0.1100885 0.8995027 -0.4850425 0.1387772 0.8634088 -0.8962508 0.1906179 0.4004991 -0.7544041 0.203837 0.6239593 -0.8701646 0.2104122 0.4455788 -0.2079332 0.07787144 0.9750384 -0.5351868 0.191247 0.8228 -0.9096286 0.3145356 0.2713728 -0.7073733 0.261534 0.6566757 -0.7356529 0.2942851 0.6100911 -0.8810534 0.3330932 0.3358481 -0.2815815 0.1377741 0.9495947 -0.4204701 0.2001866 0.8849464 -0.5111054 0.2738327 0.8147312 -0.2363055 0.1353771 0.962202 -0.698335 0.3513078 0.6236274 -0.7120512 0.3501613 0.6085805 -0.8624739 0.4331544 0.2617561 -0.8609212 0.4294053 0.2728111 -0.4826792 0.3069617 0.820241 -0.2920275 0.2059581 0.9339706 -0.691164 0.4418933 0.571859 -0.3663053 0.2680012 0.8910644 -0.7816949 0.511938 0.3561917 -0.8141349 0.5071867 0.2827473 -0.6490184 0.4336577 0.6250729 -0.3796511 0.3000938 0.875105 -0.1262987 0.1173049 0.9850321 -0.7577826 0.5763658 0.3058891 -0.5495995 0.4776461 0.6854158 -0.5950514 0.4997573 0.6294096 -0.1836677 0.1838593 0.9656407 -0.3043843 0.296761 0.9051426 -0.6816508 0.5919278 0.4300857 -0.3951108 0.420991 0.816489 -0.7056291 0.5971468 0.381449 -0.5492407 0.5739723 0.6073636 -0.5012525 0.4979767 0.7076476 -0.6359541 0.6499412 0.4160996 -0.6395753 0.6754827 0.3669697 0.3142749 0.05940335 0.9474717 0.3557404 0.0593568 0.932698 0.3823667 0.07849699 0.9206705 0.6101205 0.1005024 0.7859085 0.6507083 0.1331921 0.7475551 0.8355733 0.1638411 0.5243791 0.8333902 0.1625624 0.528237 0.3287368 0.1351043 0.934708 0.8624663 0.1499779 0.4833824 0.6273123 0.2079538 0.7504895 0.2661262 0.06143027 0.9619789 0.9666758 0.1824712 0.1795613 0.5508639 0.2516779 0.7957434 0.929202 0.2252283 0.2930119 0.2489868 0.1681701 0.9537947 0.2144532 0.1324783 0.9677083 0.4610555 0.2693161 0.8455157 0.8608359 0.1378741 0.4898493 0.531744 0.3371407 0.7769071 0.7115192 0.2848712 0.6423308 0.6243678 0.3635968 0.6913481 0.7808157 0.3908181 0.4874303 0.7184709 0.4613661 0.5205199 0.8618106 0.4067859 0.302998 0.8710354 0.4274072 0.2421166 0.5345289 0.3980442 0.7455466 0.689606 0.4863904 0.5365334 0.8033357 0.4899961 0.3384609 0.6758757 0.5818697 0.4523493 0.7539826 0.6353476 0.1668646 0.3336305 -0.005916178 0.9426854 0.2626243 0.002045035 0.964896 0.482963 0.007313668 0.8756104 0.6690178 -0.002566337 0.743242 0.7548992 0.01032382 0.6557596 0.849541 -0.003541946 0.5275109 0.9404976 0.009628713 0.3396639 0.9735435 -2.33433e-4 0.2285019 0.9654947 -0.08039277 0.2477034 0.9750903 -0.06447172 0.2122323 0.9405224 -0.1489437 0.3053414 0.9385132 -0.1518954 0.3100337 0.8201164 -0.2343125 0.5220218 0.9300618 -0.1361126 0.3412603 0.9651902 -0.08063364 0.2488095 0.4382345 -0.2309179 0.868693 0.8436338 -0.1671087 0.5102518 0.6721187 -0.1684279 0.721033 0.8056892 -0.1533263 0.5721504 0.9575534 -0.03316378 0.2863418 0.9475968 -0.1214786 0.2954716 0.9637168 -0.110598 0.2429361 0.8236469 -0.2288395 0.5188819 0.7902043 -0.1627237 0.5908454 0.6834039 -0.2529285 0.6848258 0.6263421 -0.196356 0.7544137 0.920896 -0.0683133 0.383776 0.4520605 -0.1399297 0.8809432 0.6506145 -0.1150805 0.750638 0.4740658 -0.0796324 0.8768811 0.4126734 -0.04899328 0.9095606 0.2590683 -0.1044619 0.9601934 0.9385614 -0.07775688 0.3362385 0.8170428 -0.04062855 0.5751439 0.7806501 -0.1906564 0.5951768 0.9378309 -0.08754849 0.33587 0.430164 -0.1527401 0.8897356 0.966191 -0.04369056 0.2540986 0.8384245 -0.05376958 0.542359 0.6916548 -0.03046298 0.7215856 0.6727463 -0.1275029 0.7288041 0.7415315 -0.07857078 0.6663015 -0.6274362 -0.7751736 0.07368814 -0.6501939 -0.7371284 0.1840916 -0.7220721 -0.658119 0.2132869 -0.5200564 -0.8535931 0.03033649 -0.7159712 -0.5018146 0.4853528 -0.6516033 -0.6740574 0.3479365 -0.7306091 -0.2475545 0.6363388 -0.4719607 -0.8604058 0.1922366 -0.712606 -0.5085135 0.4833289 -0.5671619 -0.7615959 0.3135271 -0.7013021 -0.002339184 0.7128604 -0.4547018 0.4489827 0.769195 -0.6307961 0.06938594 0.7728401 -0.7028943 -0.2142533 0.6782589 -0.6420122 -0.5682992 0.514642 -0.5991144 0.2406587 0.7636395 -0.6135663 -0.4432575 0.6534976 -0.2399786 0.654361 0.7170928 -0.2766663 0.6389963 0.7177323 -0.3862949 0.4723258 0.7922656 -0.413908 -0.9016177 0.1255623 -0.6520251 -0.3349756 0.6801873 -0.6029072 -0.1249387 0.7879678 -0.4766947 0.2161234 0.8520873 -0.520895 -0.7319564 0.4392133 0.05699574 0.8245397 0.562926 -0.5989248 0.05395448 0.7989856 -0.4112982 -0.8029776 0.4313475 -0.6242651 -0.3190977 0.7130706 0.4436278 0.8275363 0.3440613 -0.4928712 -0.6591277 0.5680041 -0.5003848 -0.7546613 0.4243834 -0.5228307 -0.4102843 0.7472047 0.247225 0.878317 0.4091933 -0.5592002 -0.4544095 0.6934026 -0.520909 -0.05932688 0.8515481 -0.3662523 -0.7911345 0.4898627 -0.3899161 -0.8396013 0.3781999 0.07992249 0.8380768 0.5396662 -0.3904868 0.431472 0.8132354 -0.2663296 0.6295629 0.7298762 -0.4755251 0.2475541 0.8441523 -0.2454895 0.5832744 0.7742906 0.4854861 0.850373 0.202902 0.6890541 0.7247075 0.001863837 0.4282523 0.8739663 0.2297453 -0.4013238 -0.5655928 0.7204471 0.2587684 0.8814917 0.3949826 -0.5430014 -0.1985834 0.8159132 -0.2607 0.5195041 0.8137267 -0.4513799 -0.6506667 0.6106466 0.7187851 0.6896705 -0.08776521 -0.3689345 0.0584172 0.9276179 -0.1284213 0.7203248 0.6816453 0.5768253 0.8123277 0.0860027 -0.3881931 -0.1866087 0.9024874 -0.3520085 0.3150268 0.88139 0.8267351 0.4899511 -0.2765085 0.8300924 0.4829996 -0.2786719 -0.1190024 -0.992606 0.02391237 -0.4625911 -0.3322483 0.8219614 -0.2402824 -0.8975541 0.3696769 0.8548682 0.1617117 -0.4930008 -0.2361413 -0.8921398 0.3851285 -0.2975382 -0.7087886 0.6396013 0.5998156 0.7987777 -0.04664349 0.4007709 0.9034508 0.1521822 -0.3040128 -0.7163494 0.6280285 0.6819326 0.7118385 -0.1680887 -0.3915647 -0.1803904 0.9022951 -0.3400178 0.2418521 0.9087879 0.8346332 0.2926309 -0.4666417 0.4154421 0.9014852 0.1213778 0.7017267 0.6692345 -0.2443457 0.2996671 0.9133998 0.2755005 -0.334605 -0.4323924 0.8373031 -0.3322355 -0.4299868 0.8394825 0.771731 0.02394264 -0.6354984 -0.2692006 0.147165 0.9517739 -0.215901 0.4796203 0.8505006 0.5345534 0.8445913 -0.03030186 -0.07153618 -0.9692222 0.2355653 -0.353026 0.03663462 0.9348961 -0.2060074 0.5094341 0.8354866 0.7604519 0.5559462 -0.335614 0.7168273 -0.2351577 -0.656399 -0.1823831 -0.840449 0.5102764 0.7920651 0.3087426 -0.5266033 -0.1446056 -0.7647365 0.627907 0.09964507 0.8759891 0.471926 -0.3027229 -0.09993612 0.9478247 0.7635893 0.3851523 -0.5182559 0.7488719 0.02695333 -0.6621665 0.6610655 -0.256444 -0.7051447 -0.1760842 -0.527687 0.8309879 0.18764 0.9176844 0.3502097 0.6397724 0.6967757 -0.3243377 0.5599631 0.8090199 -0.1786847 -0.09192067 0.6723501 0.7345039 -0.2581216 -0.3437958 0.9028719 0.4531759 -0.5401103 -0.7091633 0.07634252 0.8680627 0.4905496 -0.2049776 -0.6866683 0.6974745 -0.1906927 -0.1605221 0.9684364 -0.2332758 0.3272066 0.9157064 0.7210916 -0.008950531 -0.6927819 0.6505954 -0.1855938 -0.736397 -0.01429313 -0.9629551 0.2692826 0.4873375 -0.4644979 -0.7394213 0.6284727 0.7120267 -0.3131136 -0.03626215 0.7753248 0.6305209 -0.02626329 -0.8959328 0.4434127 -0.04171407 -0.9376183 0.3451551 0.7266111 0.3811091 -0.5716575 0.3742011 0.9273465 0.001411497 -0.2192501 -0.08212578 0.9722061 0.3640196 0.9307856 0.03358471 -0.06341505 -0.8242743 0.5626283 -0.1056457 -0.4487913 0.8873699 0.6727557 0.5176993 -0.528571 -0.2635501 0.1295326 0.9559093 -0.1809437 0.2695714 0.945828 -0.03983157 -0.7059605 0.7071303 0.2263444 0.9496402 0.2166836 0.6693278 0.1971036 -0.7163453 0.487584 0.8513333 -0.193633 0.2402428 -0.653523 -0.7177682 0.5386132 -0.2846271 -0.7930217 -0.08921158 -0.6001499 0.7948971 0.1185451 -0.9521682 0.2816433 0.4899731 0.8361762 -0.2464463 -0.04177993 -0.4051805 0.9132816 0.6689921 0.061737 -0.7407011 0.5463078 0.7396662 -0.3929909 -0.0864908 0.5813644 0.8090333 0.2022251 0.9585547 0.2006936 0.1064823 -0.7694353 -0.6297864 -0.1250817 -0.06037259 0.9903079 0.07017207 0.9054893 0.4185271 0.4506472 -0.4307103 -0.7819244 0.3538808 0.9271709 -0.1229742 -0.1235569 0.2740467 0.9537464 0.6211624 0.508427 -0.5963718 0.5438402 0.6680213 -0.5079228 -0.08230465 -0.1130995 0.9901689 0.6258721 0.2081025 -0.7516499 0.42909 0.8618167 -0.2704697 0.5387117 -0.1841358 -0.8221216 0.6016329 0.1726257 -0.7798963 0.6061863 0.4169853 -0.6772454 0.1118438 -0.8585116 0.5004486 -0.02364099 -0.4270375 0.9039248 0.08783489 -0.6320172 0.7699607 0.0491383 -0.6703119 0.7404509 0.01934379 -0.7899433 -0.6128748 0.3509865 -0.5143053 -0.782495 0.5499385 0.6680898 -0.5012223 0.07311707 0.910288 0.4074674 0.07257574 -0.9130967 0.4012321 -0.05987268 0.2315068 0.9709891 0.2130324 0.9759422 0.04641193 0.4300603 0.7726809 -0.4669178 0.2091092 0.9758536 0.06311255 -0.04885369 0.252214 0.9664375 0.2470634 -0.6242327 -0.7411432 0.1780119 -0.727846 0.6622326 0.2053143 -0.9006232 0.3830458 0.4923005 -0.1236329 -0.8616004 0.2826787 0.9533212 -0.1061671 -0.06546205 0.4937087 0.86716 0.5017176 0.4666566 -0.7283619 0.4243597 0.7706039 -0.4754877 0.4840084 -0.1816317 -0.8560058 0.1911374 -0.8908903 0.4120451 0.01362252 -0.3916671 0.9200062 0.1989262 -0.6520929 -0.7315759 0.5341787 0.3886084 -0.7507575 0.2821537 0.9319804 -0.2276002 0.01723545 -0.03424119 0.999265 -0.1728383 -0.8630608 -0.4746081 -0.1969357 -0.8752783 -0.4417061 0.2203981 -0.7141945 0.6643425 0.4316965 0.601185 -0.6724691 -0.05762726 0.3490099 0.9353456 0.3812054 -0.344493 -0.8579086 0.513751 0.1913173 -0.8363359 0.002487003 0.8183597 0.574701 -0.00151813 0.6184911 0.7857905 0.06064921 -0.4009236 0.9141018 0.4710153 0.1100968 -0.8752277 0.4815477 0.4760998 -0.7358266 0.3602107 0.8210652 -0.4428322 0.06770688 0.9535304 0.2935909 -0.01605421 0.7197918 0.6940044 -0.5309984 -0.8465414 -0.03753143 0.2398312 -0.9586188 0.1533989 -0.01229876 0.7500117 0.6613104 -0.3759095 -0.890356 -0.2568236 0.3570535 -0.3906825 -0.8484576 0.2179558 -0.7110576 0.6685002 0.4497784 2.64661e-4 -0.8931402 0.01251757 0.1612394 0.986836 0.09279221 -0.7307467 -0.6763128 0.4217295 0.349847 -0.8365116 0.1547895 0.9862624 -0.05767792 0.07688981 0.9683178 0.2375892 0.2435635 -0.5329723 0.8103193 0.3173372 -0.8539802 0.4123287 -0.4223034 -0.878694 -0.2226135 0.1238704 -0.02474933 0.9919897 0.2159202 0.9329758 -0.2879836 0.01460981 -0.7989838 -0.6011753 0.1920935 -0.4441378 0.8751239 0.08830064 -0.09017181 0.992004 0.1264511 -0.09565198 0.9873505 0.1758343 0.9563394 -0.2334467 0.3620907 0.5672042 -0.7397093 0.2559502 0.8224688 -0.5079711 0.3122001 -0.930865 0.1897936 0.2814083 0.7948693 -0.5375799 0.4226187 0.1850884 -0.8872067 0.07448583 0.990952 0.111652 -0.02772527 -0.8223201 -0.5683494 0.02621859 0.4812785 0.8761756 0.326898 -0.8651342 0.380369 0.0770983 0.3143978 0.9461554 0.3504989 -0.6880963 0.6353535 0.3498778 -0.9342441 0.0690906 0.05872035 0.99517 0.07866889 0.253664 -0.5034101 -0.8259741 0.339565 -0.1530526 -0.9280467 0.3680678 0.3775337 -0.8497025 0.3057271 0.6301189 -0.7137796 0.3655494 -0.6686683 0.6475 -0.1459932 -0.903044 -0.4039772 0.1289921 0.9546029 -0.2685042 -0.1422858 -0.9006437 -0.4106041 0.3515486 -0.4512899 0.8202141 0.3211135 -0.2243621 -0.9200804 0.3343163 0.0905286 -0.938103 0.220613 -0.03348815 0.9747864 0.08986073 -0.7024231 -0.7060643 -0.3304776 -0.9315541 -0.1516292 0.2979499 0.2556971 -0.9196983 0.09077787 0.3586966 0.9290298 -0.001008689 0.8993599 0.4372079 0.3478295 -0.4592912 0.8173533 -0.3460325 -0.9307521 -0.1181613 0.03619492 0.9942659 -0.1006252 0.3003515 -0.07661473 -0.9507467 0.05431735 0.6071045 0.7927634 0.1834275 -0.5323384 -0.8264202 0.2688741 -0.1100562 -0.956867 0.432094 -0.8174706 0.3808368 0.3133898 -0.1964111 0.9290907 0.238704 0.5385194 -0.8080948 0.04584044 0.9849323 -0.1667551 0.2953256 0.2561424 -0.9204205 0.2896079 -0.3175403 0.9029372 0.4512966 -0.8357974 0.3126884 0.46396 -0.6818034 0.5655841 0.1635321 0.2414049 0.9565464 0.1406277 0.7846878 -0.6037293 0.2105477 -0.4347113 -0.8756117 0.2370967 0.3507336 -0.9059642 0.4900577 -0.649608 0.5812513 0.183758 -0.5131577 -0.8383926 0.09846884 0.8297782 -0.549338 0.2673893 0.07209056 0.9608881 0.09826683 0.486411 0.8681866 0.1667273 0.2639179 0.950026 0.0361281 0.6535009 0.7560632 -0.03436619 0.982847 0.1811926 0.4520902 -0.4056655 0.7943866 0.1608155 0.618088 -0.769484 -0.03699141 0.9437264 0.3286522 0.1994597 -0.2984333 -0.9333561 0.1074225 0.8288218 -0.5491036 0.2078752 -0.02863818 -0.977736 0.4573915 -0.8770838 0.1466874 -0.4120485 -0.9091385 -0.06069099 0.5584227 -0.6737895 0.4839132 0.1772937 0.2935209 -0.9393682 2.48294e-4 0.922203 -0.386706 0.009055793 0.7955367 0.6058377 -0.03983759 0.9987363 -0.03064095 -0.04177629 0.9732201 0.2260471 0.5896209 -0.7372108 0.3299509 0.4958122 -0.4468594 0.7446388 0.3521493 -0.01024919 0.9358877 -0.01720315 0.916887 -0.3987762 0.08378738 0.4916953 -0.8667269 0.1045398 -0.563838 -0.8192425 0.1751691 0.4861635 0.8561314 -0.05425739 0.9303334 0.3626789 -0.1868391 -0.9343131 -0.3035627 0.158889 -0.05783146 -0.9856013 -0.0316798 0.8497186 0.5262839 0.1325307 0.3128114 -0.9405236 0.1392518 -0.3267202 -0.9348064 0.2543551 0.2741684 0.9274348 -0.0858618 0.9883502 -0.125665 -0.002587378 0.7064982 -0.7077102 -0.3106872 -0.9504552 0.01041638 -0.292465 -0.956263 -0.005041658 0.4495726 -0.1872868 0.873389 0.4540228 -0.1587434 0.8767348 0.5652163 -0.8209071 0.08149969 0.1475733 -0.07863456 -0.9859203 0.2511555 0.2783603 0.9270581 0.5432269 -0.410624 0.73232 0.1040652 -0.4151219 -0.9037943 -0.03554439 0.7325096 -0.6798283 0.60611 -0.6271332 0.4892185 0.3940995 0.09879904 0.913742 -0.07756447 0.9323928 -0.3530262 0.03828483 0.5095453 -0.8595917 -0.0612201 -0.9086957 -0.4129459 -0.1398494 0.9901696 -0.002559721 0.05762749 0.07192522 -0.9957439 0.004466295 0.4530457 -0.8914762 0.6167241 -0.4547028 0.6425705 -0.1211469 0.9013659 -0.415768 0.2437911 0.4085001 0.8795986 0.08867985 0.6991554 0.7094488 -0.1298739 0.9868259 -0.096475 0.09412974 -0.0647282 -0.9934536 0.5691875 -0.1615421 0.8061822 0.6800305 -0.3578106 0.6399453 0.5712888 -0.09897136 0.81476 -0.1503673 -0.9523913 -0.2652179 0.6629808 -0.7371766 0.1304883 0.6301659 -0.6373147 0.4435324 0.3688685 0.2613619 0.8919788 0.4139099 0.07768148 0.9069973 0.01874059 -0.7678936 -0.6403034 -0.07593113 -0.9253745 -0.3713711 -0.1121151 0.7067643 -0.6985087 -0.1150683 0.7024811 -0.7023388 0.02885282 -0.7084814 -0.7051395 -0.06878119 -0.9079315 -0.4134364 -0.2208378 0.8909198 -0.3968537 -0.1553356 0.962318 0.2231931 -0.02381002 0.1481771 -0.9886742 0.05845928 -0.441933 -0.8951412 0.242317 0.4190029 0.8750538 -0.1306123 0.5614594 -0.8171314 0.1397324 0.5795788 0.802847 0.7138453 -0.5873534 0.3813671 0.4424236 0.1098337 0.890055 -0.2157145 -0.9688422 0.121705 0.02738612 -0.2673625 -0.9632068 -0.1465788 -0.979826 -0.1358522 0.004131734 0.09001266 -0.9959321 -0.1975491 0.9072255 -0.3713707 -0.1915968 0.9803099 0.04778319 0.7409449 -0.5382378 0.4016225 0.7362385 -0.3676371 0.5681512 -0.09457755 0.4416912 -0.8921681 0.5706703 0.05559498 0.8192954 -0.03916817 0.84803 0.5284988 0.02068382 -0.5571568 -0.8301498 0.6951494 -0.1958095 0.6916835 0.7302164 -0.3900938 0.5609019 -0.1214333 0.2675276 -0.9558677 0.3898029 0.3689752 0.8437482 0.4121608 0.3064857 0.8580153 -0.2821611 0.9077197 -0.310532 -0.02255916 -0.2553262 -0.9665918 -0.07668018 0.1622626 -0.9837638 -0.2467522 0.9680912 -0.04373574 -0.246529 0.7235786 -0.644715 -0.2482162 0.7210424 -0.6469054 -0.09111934 0.8812978 0.4636934 0.01331037 -0.6575006 -0.7533365 0.6951116 -0.1811316 0.6957092 -0.2227618 0.4893241 -0.8431721 -0.1645525 0.9483588 0.2711792 0.2967462 0.4713718 0.8305122 0.211568 0.6117942 0.7621988 0.5768777 0.1449723 0.8038628 -0.2681391 0.5385153 -0.7988134 0.00254631 -0.8729497 -0.4878036 -0.04034465 -0.2786012 -0.9595592 -0.1200306 -0.1126915 -0.9863536 -0.1747289 0.2678231 -0.9474918 -0.3510919 0.8463115 -0.4006137 -0.04612725 -0.3941729 -0.917878 -0.03689312 -0.9789305 -0.2008336 -0.2161715 0.1558946 -0.9638293 0.04363417 0.7449336 0.6657103 0.3119965 0.5849465 0.7486627 -0.3629434 0.7471218 -0.5568494 0.105974 0.7086955 0.69751 0.5873944 0.2407911 0.7726497 -0.1153685 -0.9907795 0.07103604 -0.03916305 -0.9714074 -0.2341669 0.6522746 0.09879362 0.751517 -0.3391727 0.9389997 -0.05693477 0.03444641 0.7820927 0.6222094 -0.3363299 0.4504787 -0.8270135 -0.1155665 0.8845425 0.4519171 -0.4075369 0.8484753 -0.3376439 -0.3142552 0.9428714 0.1106219 -0.1499173 -0.1076209 -0.9828239 0.4137212 0.4134915 0.8110855 0.03025442 -0.8915608 -0.4518894 -0.395033 0.9005974 -0.1813098 -0.2762361 0.1501532 -0.949288 -0.4153009 0.635694 -0.6507061 0.5238072 0.3899314 0.7573505 -0.3642336 0.4607464 -0.8093495 -0.3157029 0.9421277 0.1128149 -0.01201075 -0.9969669 -0.07689458 -0.2438293 0.918568 0.3110955 0.02505278 -0.9446301 -0.3271795 -0.4679306 0.7664415 -0.4400098 -0.07514345 -0.4644221 -0.8824204 -0.2943658 0.06703329 -0.9533391 -0.02187621 -0.7083536 -0.7055187 -0.1867514 -0.1958152 -0.9626943 -0.06533026 -0.6152483 -0.7856217 -0.1842091 -0.2803745 -0.9420495 0.001372456 -0.8306023 -0.5568645 -0.4790968 0.6200245 -0.6213179 0.3261455 0.5829709 0.74416 -0.5060924 0.5735358 -0.6441485 0.04314112 -0.9990282 -0.009040653 0.2975429 0.5963002 0.7455833 -0.1002722 0.850453 0.5164061 -0.2100608 -0.3381723 -0.9173406 -0.5555554 0.7279264 -0.4018476 -0.4323916 0.9013209 0.02565878 -0.4441283 0.2851694 -0.8493695 -0.5288724 0.8163749 -0.2320045 -0.3450682 0.03450191 -0.9379432 -0.5005999 0.3369891 -0.7973945 0.3454868 0.5939691 0.7265257 0.1704061 0.7187029 0.6741127 -0.518596 0.8450951 -0.1298945 -0.296878 0.8993123 0.3210932 -0.3835697 0.06431728 -0.9212697 -0.5636473 0.7546712 -0.3358173 -0.1992095 0.8732669 0.4446578 -0.5727977 0.5718863 -0.5872384 0.02946937 -0.9470557 -0.3197143 -0.09183597 -0.5974596 -0.7966231 -0.2708279 -0.2820277 -0.9203873 0.1156834 -0.9858214 -0.1215465 -0.3730992 0.8924869 0.253504 -0.2363855 -0.3273715 -0.9148496 0.06955671 -0.9835857 0.1664963 -0.0109564 0.8042631 0.5941725 -0.4417557 0.8843221 0.1510841 0.03203159 -0.9461861 -0.3220342 -0.6110022 0.4933598 -0.6190901 -0.543066 0.2824853 -0.7907475 -0.4166477 -0.06594252 -0.9066733 -0.6089217 0.3988378 -0.6856697 -0.5358821 0.8425086 0.05486172 -0.3425797 -0.2436 -0.9073579 0.09403944 -0.9233678 -0.3722211 -0.5458083 0.1594938 -0.8225905 -0.4615181 -0.0348497 -0.8864461 -0.6667236 0.6180914 -0.4164645 -0.6060181 0.7892599 -0.09905099 -0.6746259 0.5377476 -0.5056751 -0.6304472 0.7655055 -0.1285988 0.1314605 -0.9889093 0.06911206 0.002624571 -0.8070929 -0.5904186 -0.384482 0.8387488 0.3855831 -0.4125373 0.8570463 0.3086826 0.1197636 -0.9471239 -0.2976795 -0.6541548 0.2330784 -0.7195526 0.252794 -0.9643363 0.07842707 -0.7010399 0.6508275 -0.2914907 -0.6039709 0.1174585 -0.7883037 0.2019211 -0.9793906 0.004696071 0.147446 -0.9546695 -0.2585844 -0.7393522 0.5968179 -0.3117159 -0.3415539 -0.3700236 -0.8639581 -0.721361 0.3657641 -0.5880945 -0.5760183 0.8134001 0.08113735 -0.1999551 -0.5568162 -0.8062095 -0.3019588 -0.4471699 -0.8419383 -0.5052537 -0.1745539 -0.845133 -0.1452645 -0.6347733 -0.7589211 -0.6921057 0.2487678 -0.6775724 -0.1208268 -0.6569721 -0.7441698 -0.5819531 -0.04755288 -0.8118309 -0.7186258 0.694826 -0.02817595 -0.4932065 -0.2036017 -0.8457504 -0.729445 0.6832767 -0.03229677 -0.7692292 0.361136 -0.5271314 0.2442636 -0.9611022 -0.1289102 -0.7829897 0.4258968 -0.453364 -0.7735168 0.5876378 -0.2373896 -0.7038229 0.1237967 -0.6995055 0.2056592 -0.9338378 -0.2926622 0.08059 -0.8840942 -0.4603072 -0.7845712 0.1737397 -0.5951998 -0.6483565 -0.01458936 -0.7611972 -0.7728883 0.1369121 -0.6195957 -0.8403263 0.3587587 -0.4063794 -0.8542261 0.3770712 -0.3579317 -0.7587882 0.04029923 -0.6500895 0.06322818 -0.8443816 -0.531998 0.2663501 -0.9576095 -0.1097351 -0.812992 0.211241 -0.5426059 -0.1639821 -0.6698006 -0.7242079 -0.4684956 -0.3710789 -0.8017558 -0.6584158 -0.1328389 -0.7408391 -0.3065592 -0.55506 -0.7732592 -0.2644832 -0.5741833 -0.7748306 -0.4170809 -0.4423971 -0.7939323 0.2691095 -0.9391536 -0.2134726 0.1065062 -0.8686119 -0.483911 -0.6269394 -0.2249132 -0.7458962 -0.009812116 -0.7960335 -0.6051731 -0.5885955 -0.2841798 -0.7568338 0.4503149 -0.8884951 0.08827793 -0.763077 -0.1314547 -0.6327978 0.1737076 -0.8901994 -0.4211543 -0.08123904 -0.7520557 -0.6540739 -0.5632518 -0.3621979 -0.7426709 0.0377599 -0.8135148 -0.5803172 0.1925804 -0.9000316 -0.3909677 0.3938722 -0.9035679 -0.1686115 -0.4204259 -0.5236732 -0.7409511 -0.3437535 -0.6303112 -0.6960901 -0.2603043 -0.6574099 -0.7071449 0.2622942 -0.890647 -0.3714159 0.2431336 -0.8808085 -0.4062789 0.361323 -0.877958 -0.3140627 0.4894261 -0.8692519 -0.06973618 0.0630654 0.01738321 -0.9978581 0.02586013 -0.01761299 -0.9995105 -0.05708664 0.01329189 -0.9982808 -0.07484865 0.04758524 -0.996059 6.77574e-6 1 8.6051e-6 8.53834e-6 1 1.76191e-6 4.32509e-6 1 9.65517e-6 0 1 9.87362e-6 1.1054e-5 1 3.46344e-6 1.06653e-5 1 -3.23191e-6 1.31162e-5 1 4.57725e-6 -1.49412e-6 1 0 1.03558e-5 1 -6.0996e-6 1.02519e-5 1 1.38435e-6 -2.33113e-5 1 0 3.17814e-7 1 1.68296e-5 9.87491e-6 1 -4.27708e-7 0 1 9.18027e-7 8.9507e-6 1 1.18517e-6 6.54898e-6 1 1.87763e-5 0 1 7.35809e-7 1.07473e-5 1 -1.63953e-6 5.27192e-6 1 1.71539e-5 0 1 -1.30508e-5 0 1 1.49359e-5 -2.85473e-6 1 6.67804e-6 1.01262e-5 1 0 0 1 9.22108e-7 8.9784e-6 1 -5.49596e-6 0 1 6.7264e-6 0 1 -1.02196e-6 0 1 -1.13097e-6 -8.63957e-6 1 8.13569e-6 -9.01259e-6 1 0 4.60267e-6 1 -5.30427e-6 -1.10637e-5 1 1.5876e-5 2.71141e-6 1 -1.19942e-5 0 1 1.15853e-6 0 1 -8.4809e-6 0 1 -4.05416e-7 0 1 3.92507e-6 0 1 -1.19884e-6 -1.06277e-5 1 -4.02699e-7 -3.21866e-6 1 -1.0424e-5 -8.74985e-6 1 1.31514e-5 4.69596e-7 1 -9.89826e-6 -1.87856e-7 1 -8.44125e-6 -9.89173e-6 1 0 -1.03829e-5 1 -9.6387e-7 4.44118e-6 1 -1.01054e-5 -1.03389e-5 1 1.35252e-5 -2.3503e-6 1 -9.89407e-6 -7.07746e-6 1 0 -1.04038e-5 1 5.28615e-6 -2.25286e-6 1 -1.42463e-5 -4.77746e-6 1 -1.42546e-5 -1.7645e-6 1 -9.54931e-6 -0.877258 -0.2121827 -0.4305778 -0.946442 -0.1133777 -0.302313 -0.9195122 -0.1972045 -0.3400114 -0.6534963 0.03523576 -0.7561091 -0.8385482 -0.4914996 -0.2350857 -0.7972176 -0.1199121 -0.5916631 -0.8431449 -0.4878296 -0.2261173 -0.4145724 0.02291417 -0.9097279 -0.6169149 -0.205626 -0.7596934 -0.7903336 -0.3590955 -0.4964104 -0.6201533 -0.3471819 -0.7034733 -0.5436599 -0.1637144 -0.8231838 -0.6732776 -0.7166799 -0.1818439 -0.2939233 -0.1242591 -0.9477177 -0.6213453 -0.3512902 -0.7003751 -0.6897888 -0.6473795 -0.3241779 -0.4452068 -0.472769 -0.7604475 -0.5908238 -0.6468967 -0.4821328 -0.3446332 -0.1605803 -0.9249011 -0.3382478 -0.2242969 -0.9139362 -0.5060489 -0.79137 -0.3429988 -0.474603 -0.7964273 -0.3747739 -0.5412413 -0.5123557 -0.6667454 -0.4438768 -0.5015488 -0.7425781 -0.3395547 -0.8943762 -0.2911937 -0.2213534 -0.8763666 -0.4277669 -0.3706948 -0.6845908 -0.6276312 -0.4158682 -0.6978437 -0.5831534 -0.3686107 -0.3567576 -0.8583998 -0.09495157 -0.135992 -0.9861493 -0.2321272 -0.473471 -0.8496719 -0.0491724 -0.9621449 -0.2680662 -0.2190448 -0.5053023 -0.834679 -0.1171651 -0.2340326 -0.965143 -0.2805205 -0.6972929 -0.6596142 -0.1294137 -0.9111752 -0.3911674 -0.01125794 -0.007368028 -0.9999095 -0.1750884 -0.7655919 -0.619042 -0.04667639 -0.460943 -0.8862014 -0.00797522 -0.01039659 -0.9999142 0.1697561 -0.9001118 -0.4012253 0.01149922 -0.7181147 -0.6958298 -0.003773391 -0.0306372 -0.9995235 0.1519187 -0.9126967 -0.3793491 -0.03362065 -0.2426335 -0.9695354 -0.07241356 -0.04584604 0.9963206 0.1021689 -0.7513477 -0.6519497 0.001258313 -0.5165367 -0.8562642 -0.003796696 -0.5261846 -0.850362 0.09235018 -0.7642816 -0.6382359 0.3821001 -0.8395894 -0.3861207 -0.02874469 -0.3313525 -0.9430692 0.2005642 -0.5960674 -0.7774816 0.1598554 -0.7733147 -0.6135395 0.3862933 -0.8394627 -0.3822041 0.5883503 -0.8021442 -0.1020238 0.02171927 -0.3101614 -0.9504359 0.3707794 -0.6094066 -0.7008183 0.5816423 -0.6553334 -0.481903 0.5927098 -0.6203559 -0.5136669 0.7504996 -0.5596616 -0.3514676 0.2588151 -0.4421397 -0.8587942 0.4334687 -0.6255846 -0.6486515 0.2540863 -0.4149168 -0.8736615 0.1121696 -0.2458899 -0.9627856 0.4557236 -0.4991487 -0.7369984 0.7502012 -0.4493777 -0.4850338 0.7634377 -0.5531815 -0.3333966 0.6528012 -0.424526 -0.627398 0.6531516 -0.4249809 -0.6267251 0.8467927 -0.3203333 -0.4246513 0.4441101 -0.3104282 -0.8404765 0.4722933 -0.3153766 -0.8230898 0.9047234 -0.2403737 -0.3517045 0.1875914 -0.1323431 -0.9732908 0.7222242 -0.1674035 -0.6710948 0.7909454 -0.2369322 -0.564153 0.908481 -0.003891944 -0.417908 0.9820457 -0.1056839 -0.15626 0.3064271 -0.1643017 -0.9376073 0.9416555 0.09240752 -0.3236449 0.7723029 -0.07759004 -0.6304983 0.5071123 -0.1216982 -0.8532449 0.5631129 -0.09608185 -0.8207755 0.843092 0.07021087 -0.5331665 0.7329741 0.2780085 -0.6208545 0.9440916 0.1571638 -0.2898116 0.2386626 -0.02242368 -0.9708437 0.5011305 0.05296128 -0.8637496 0.8574775 0.3428922 -0.3836109 0.5336126 0.09442067 -0.8404418 0.834589 0.4456169 -0.3238629 0.3386964 0.01118451 -0.9408293 0.7697401 0.5269186 -0.3603571 0.7336011 0.3105943 -0.6044508 0.7226738 0.6180728 -0.3094004 0.6554948 0.3407787 -0.6739411 0.6118163 0.7073078 -0.3541138 0.1435514 0.0423361 -0.9887369 0.4486207 0.228554 -0.8640038 0.6729908 0.5452725 -0.4997613 0.5854806 0.742621 -0.3251562 0.4001644 0.2326532 -0.8864204 0.4810323 0.5193481 -0.7063183 0.4212859 0.5985122 -0.6813966 0.3777205 0.8434766 -0.3819352 0.5090591 0.8357235 -0.2059738 0.1211295 0.06550186 -0.9904732 0.3482076 0.3605136 -0.8653216 0.3564279 0.3907797 -0.8486758 0.2804627 0.9197332 -0.2746484 0.2651768 0.2616411 -0.9280223 0.3280427 0.9228049 -0.2020376 0.3004539 0.907102 -0.2947767 0.2889587 0.6913414 -0.662231 0.1803956 0.1950847 -0.9640536 0.2863577 0.6901108 -0.6646401 0.06923937 0.9462284 -0.316003 -0.2602079 0.7267723 -0.6356838 0.009023964 0.9672749 -0.2535706 0.03408598 0.8012718 -0.5973289 0.1818069 0.5092152 -0.8412171 0.1687881 0.4281442 -0.887808 -0.01918911 0.8551833 -0.5179703 0.0463401 0.2270314 -0.9727844 0.02321314 0.6915488 -0.7219567 -0.1733028 0.9212892 -0.348127 0.01013839 0.673817 -0.7388287 -0.03600949 0.3481134 -0.9367606 0.01562112 0.4816346 -0.876233 -0.3002796 0.9168545 -0.263078 -0.4060285 0.8390239 -0.3621877 -0.1729093 0.6973031 -0.6956082 -0.3058024 0.8263742 -0.4728538 -0.1911919 0.6646077 -0.7223174 -0.5720634 0.7534534 -0.3241166 -0.09552115 0.4100144 -0.9070634 -0.5587598 0.7710869 -0.3053075 -0.4174273 0.6454927 -0.6396045 -0.1338161 0.6118611 -0.7795637 -0.4015854 0.6752189 -0.6187155 -0.7434576 0.6265403 -0.233919 -0.1134557 0.4227484 -0.8991172 -0.7777652 0.5244616 -0.3464412 -0.6147202 0.5458858 -0.5693222 -0.6142941 0.5493271 -0.566465 -0.2310422 0.275451 -0.933138 -0.2635509 0.4937257 -0.8287195 -0.4890816 0.5182234 -0.7016009 -0.377785 0.3191812 -0.8691387 -0.7507422 0.4585565 -0.4755124 -0.7233326 0.571231 -0.3879241 -0.8695415 0.2534303 -0.4238758 -0.5807067 0.3508784 -0.7346184 -0.4670271 0.3263853 -0.821802 -0.8756251 0.3006013 -0.3780471 -0.4879733 0.3739688 -0.7886884 -0.3062092 0.3306114 -0.8927106 -0.2045149 0.1819493 -0.9618047 -0.9146472 0.1018321 -0.3912171 -0.7844099 0.263828 -0.5613341 -0.9372147 0.04420489 -0.3459401 -0.6456165 0.1606401 -0.7465749 -0.458831 0.1831998 -0.869432 -0.7157014 -0.01145225 -0.6983125 -0.2546483 0.06667721 -0.9647324 -0.5703638 -0.01990377 -0.821151 -0.5829747 0.05519187 -0.8106136 -0.9940026 -0.1093574 -1.093e-4 -0.9520161 -0.3060478 -1.73532e-4 -0.9066879 -0.4217275 -0.007951796 -0.8620474 -0.5068258 0.001437544 -0.7157134 -0.6983897 0.002523124 -0.5699994 -0.8215826 -0.01013922 -0.5461454 -0.8376615 -0.006971418 -0.3202466 -0.9473254 0.004125058 -0.09383881 -0.9954228 -0.0181024 -0.03243803 -0.9994394 -0.008297979 0.1773455 -0.9841427 0.003464758 0.3769645 -0.9262216 0.003374874 0.5695785 -0.8218442 -0.01235085 0.6097183 -0.7925922 -0.00641489 0.7690797 -0.6391403 0.004008948 0.9045488 -0.4262681 -0.009333074 0.9346867 -0.3554687 -0.001700341 0.9955934 -0.09377419 -6.03039e-4 0.9999338 0.008500099 -0.007763803 0.9915435 0.1297748 3.38177e-4 0.9410185 0.3383551 -3.20349e-4 0.9042359 0.4269366 -0.009100079 0.8038132 0.594875 0.002864837 0.676396 0.7365379 6.49494e-4 0.5972806 0.8019903 -0.008214771 0.4763313 0.8792659 1.81119e-4 0.3179491 0.9481078 -1.12956e-4 0.1967757 0.9804028 -0.00947231 0.07167381 0.9974248 0.002592206 -0.1784591 0.9839326 0.005401372 -0.4092889 0.9123347 -0.01132178 -0.3799673 0.9249766 -0.006569325 -0.6262512 0.7796201 0.001412749 -0.7791587 0.6267694 -0.008490383 -0.7979792 0.6026693 -0.004339694 -0.945906 0.324388 0.005861341 -0.9956553 0.09284538 -0.007095873 -0.9978445 0.06476151 -0.01060473 -0.003891885 -0.008318603 -0.9999579 -0.005074381 5.70988e-4 -0.999987 -0.009651422 -0.002375423 -0.9999507 -0.001527369 -0.006774306 -0.999976 -0.008908212 0.001014471 -0.9999598 -0.003889322 0.004578173 -0.999982 0.001507639 -0.007770657 -0.9999687 0.004601657 -0.004843652 -0.9999777 -0.003723025 0.002083659 -0.9999909 0.002513468 -0.004275143 -0.9999878 -0.008856356 1.26306e-4 -0.9999608 0.004043638 -0.003218352 -0.9999867 -0.00671029 0.009722232 -0.9999303 0.003988862 -0.001844465 -0.9999904 -5.03209e-4 0.01112347 -0.9999381 0.004379391 -0.001593947 -0.9999892 -0.002077698 0.008586466 -0.999961 0.004518568 -7.32094e-5 -0.9999899 5.58477e-4 0.009608328 -0.9999538 0.002748787 0.001898586 -0.9999945 0.005999386 0.006288886 -0.9999623 0.002231359 7.07066e-4 -0.9999973 0.002679705 0.005674242 -0.9999804 0.005010128 0.001657485 -0.9999861 0.001685976 0.001412987 -0.9999977 0 8.35771e-6 -1 6.62043e-6 1.15008e-5 -1 5.23029e-6 7.06809e-7 -1 0 1.52556e-5 -1 0 1.68257e-5 -1 4.80973e-5 -2.11686e-5 -1 1.23283e-6 -3.52169e-7 -1 0 8.09396e-6 -1 1.49482e-5 -1.40282e-5 -1 -3.26969e-6 -8.92778e-6 -1 0 -9.08432e-6 -1 -1.63418e-5 -3.06032e-6 -1 -7.48673e-6 -5.79755e-6 -1 -7.60341e-6 4.88764e-6 -1 -1.37734e-5 -9.4962e-6 -1 -2.27797e-5 -3.9172e-6 -1 0 9.96643e-6 -1 0 8.61878e-6 -1 -7.20513e-6 -9.64792e-7 -1 -1.26278e-5 7.6521e-6 -1 2.15015e-5 1.7727e-5 -1 6.92189e-6 -2.35861e-6 -1 -3.07447e-6 3.42056e-6 -1 -8.7471e-6 -1.74681e-6 -1 -8.61443e-6 -1.90811e-6 -1 -6.20029e-6 -6.31827e-6 -1 -1.62349e-6 -1.22871e-5 -1 -1.29075e-5 0 -1 2.32276e-6 0 -1 6.56429e-6 0 -1 -1.06806e-5 0 -1 1.7308e-5 1.4882e-5 -1 8.89178e-6 0 -1 -1.8157e-6 0 -1 -1.15854e-6 0 -1 -1.49836e-6 0 -1 1.19367e-5 0 -1 3.03457e-7 0 -1 -1.52448e-6 1.18513e-5 -1 5.81339e-6 0 -1 1.00017e-5 -3.33074e-6 -1 -4.39468e-6 6.35538e-6 -1 -2.22467e-5 -1.23077e-5 -1 -2.48117e-5 -3.47454e-5 -1 5.66606e-6 0 -1 0 4.03692e-7 -1 3.07134e-6 0 -1 -7.9663e-6 -2.29407e-7 -1 0 7.48015e-6 -1 -9.07421e-6 1.86383e-6 -1 -9.52187e-7 0 -1 -1.63857e-6 1.10528e-5 -1 -1.72564e-6 0 -1 3.08835e-5 2.23914e-5 -1 0 -1.64896e-5 -1 -3.30862e-6 0 -1 6.39908e-6 1.43579e-5 -1 2.57382e-6 0 -1 1.16988e-5 -9.44766e-6 -1 -1.1732e-5 1.33807e-5 -1 8.65282e-6 -8.64308e-6 -1 8.91621e-6 -2.12915e-6 -1 -1.20498e-6 1.55472e-5 -1 -1.30042e-5 9.64338e-6 -1 1.385e-5 2.95766e-6 -1 3.82898e-6 1.84659e-6 -1 -2.10369e-6 -1.53054e-5 -1 -4.01353e-6 -7.92734e-6 -1 -3.89674e-6 1.53314e-6 -1 -5.36105e-6 -1.37575e-5 -1 1.9856e-6 1.37499e-6 -1 -2.20203e-5 1.83957e-5 -1 8.92184e-6 8.87095e-7 -1 4.15753e-6 1.09038e-5 -1 8.1673e-6 -6.81707e-6 -1 7.06958e-7 -1.05831e-6 -1 2.45972e-5 -5.73286e-6 -1 7.20625e-6 2.36785e-6 -1 -1.5668e-5 1.91494e-5 -1 0.05649739 -0.7321555 -0.6787903 0.1723238 -0.6778635 -0.7147067 0.1720461 -0.677617 -0.7150074 0.3322725 -0.5894112 -0.7363351 0.3185873 -0.6468004 -0.6929297 0.4346838 -0.588725 -0.6815078 0.5456078 -0.4993152 -0.6730502 0.4782646 -0.4937659 -0.7262632 0.6116122 -0.3500539 -0.7095019 0.6058638 -0.3402966 -0.7191157 0.7000764 -0.2043915 -0.6841909 0.6799855 -0.2113407 -0.7021074 0.6923127 -0.05351811 -0.7196104 0.7161236 -0.03649228 -0.6970189 0.6973065 0.06927794 -0.7134174 0.7228131 0.1055121 -0.682941 0.6836032 0.2332503 -0.6915787 0.6681263 0.1883812 -0.7198054 0.6129218 0.3125883 -0.7256828 0.6147552 0.3160818 -0.7226122 0.5883529 0.4623168 -0.6634033 0.4629023 0.4695539 -0.751825 0.4641522 0.560483 -0.6858729 0.3420028 0.6219921 -0.7043863 0.3060252 0.6034592 -0.7363325 0.2141926 0.7083181 -0.6726122 0.1207858 0.6642428 -0.7376939 0.0779525 0.7199979 -0.6895843 -0.05150282 0.6925003 -0.7195768 -0.04907852 0.689597 -0.7225283 -0.1602621 0.7059586 -0.689883 -0.2195105 0.6364521 -0.7394213 -0.2573102 0.6576984 -0.707972 -0.3470839 0.6433896 -0.6823362 -0.3933634 0.5587101 -0.7301427 -0.4558404 0.5745202 -0.6798061 -0.5368096 0.4216793 -0.7307682 -0.545705 0.4534008 -0.7047226 -0.6283302 0.3568856 -0.6912552 -0.6203107 0.2838454 -0.7311953 -0.6704997 0.2621803 -0.6940402 -0.6872732 0.1259545 -0.7153958 -0.7051908 0.118747 -0.6990029 -0.672948 -0.06097173 -0.7371726 -0.7200605 -0.02113229 -0.6935895 -0.7179636 -0.1500297 -0.6797201 -0.6380796 -0.2307722 -0.7345739 -0.6607099 -0.2762511 -0.6979597 -0.5780302 -0.3788144 -0.7227592 -0.6124382 -0.370821 -0.6981485 -0.49654 -0.4778959 -0.7246127 -0.5460157 -0.4730728 -0.6914253 -0.4516216 -0.5741969 -0.682888 -0.3632509 -0.5692763 -0.7375455 -0.3370637 -0.656876 -0.6744642 -0.1946713 -0.6551837 -0.7299571 -0.1853352 -0.6821697 -0.7073157 -0.02055263 -0.7232153 -0.6903168 -0.05080628 -0.6620043 -0.7477761 -0.07544457 -0.9971441 0.00344479 -0.07956737 -0.9968082 0.006520569 -0.2608702 -0.9653518 -0.006534874 -0.2835198 -0.9589067 0.01071131 -0.4976021 -0.8671755 0.01997196 -0.4565512 -0.8896058 -0.01275926 -0.6190829 -0.7850211 -0.02187341 -0.6939546 -0.7196582 0.02278649 -0.7561433 -0.6541947 -0.0166369 -0.8246575 -0.5653932 0.01645612 -0.8545336 -0.5192888 -0.01055496 -0.9295776 -0.3681226 0.01927161 -0.9222167 -0.3866519 0.004117071 -0.9789384 -0.2026416 -0.02482151 -0.9935738 -0.1110224 0.0220285 -0.9994001 -0.03187197 -0.0135495 -0.9941602 0.1052213 0.02395981 -0.9830428 0.1818519 -0.02359443 -0.9407271 0.3387165 0.0174281 -0.9316628 0.3633242 9.77266e-5 -0.8698429 0.4932602 -0.008236765 -0.8541196 0.5199893 0.00954473 -0.7577605 0.6525183 0.004353225 -0.7691855 0.6389881 -0.006929397 -0.6190136 0.7853799 -8.94606e-4 -0.6224682 0.7826389 0.003132522 -0.4711669 0.881989 -0.009865283 -0.4222853 0.9063417 0.01483517 -0.3636392 0.9315049 -0.008090674 -0.2503743 0.9680699 0.01239049 -0.2202023 0.9754362 -0.005929529 -0.04419302 0.9989416 0.01275908 -0.07308351 0.9973083 -0.005923688 0.1434253 0.9895998 0.01102048 0.1092944 0.993969 -0.008963048 0.2844346 0.9585154 -0.0185858 0.362701 0.9314059 0.03051245 0.4874746 0.8728072 -0.02400678 0.5857589 0.8101923 0.02179759 0.634007 0.7732005 -0.01401096 0.7521649 0.6587854 0.01580756 0.7874343 0.6161794 -0.01643872 0.8540517 0.5199432 0.0159617 0.8888123 0.4580859 -0.01304721 0.9399875 0.3410033 0.01185095 0.9456637 0.3251461 2.45592e-4 0.9896778 0.1431076 -0.007628619 0.9926025 0.1211081 0.008558452 0.9974035 -0.07148593 0.008718907 0.9986982 -0.05058622 -0.006563305 0.9558829 -0.293745 0.00133872 0.9595687 -0.2812969 -0.00999242 0.8718262 -0.489809 0.002540707 0.8737376 -0.486397 -8.2285e-4 0.7460208 -0.6659178 0.002544045 0.7361057 -0.6768057 -0.009083271 0.5995851 -0.8002358 0.0109806 0.5913779 -0.8063901 0.002691566 0.4447343 -0.895419 -0.02088528 0.3681001 -0.9292178 0.03250789 0.2427338 -0.9698333 -0.02244269 0.1351931 -0.9906233 0.01970517 0.07795208 -0.9969159 -0.009066641 1.93611e-5 0 -1 -9.81538e-6 0 -1 -1.22881e-5 0 -1 1.03423e-5 0 -1 1.94011e-5 0 -1 1.01752e-5 0 -1 -4.96767e-6 0 -1 -2.07614e-5 0 -1 2.52655e-6 0 -1 -5.4948e-6 0 -1 -5.75859e-6 0 -1 -8.08825e-6 0 -1 0.9823648 0.1869711 -0.001094579 0.9747343 0.1581612 -0.1577282 0.8728165 0.4845747 0.05812793 0.8683726 0.4952393 -0.02582973 0.6513679 0.7544553 -0.08072936 0.5704947 0.7616052 0.3073982 0.3828812 0.8621461 -0.3318224 0.2183365 0.9092172 0.3544761 0.01927936 0.9655718 -0.2594216 -0.07870876 0.9779595 0.1933911 -0.2839354 0.9310234 -0.2292947 -0.4181684 0.8693361 0.2634201 -0.5178769 0.8414278 -0.1542815 -0.7185762 0.6783565 0.1532344 -0.7509081 0.6508719 -0.1118161 -0.9235098 0.36572 0.1156663 -0.9334116 0.3568568 0.03736352 -0.9860369 0.1117774 -0.123439 -0.9585422 0.01842832 0.2843543 -0.9099877 -0.1947282 -0.3660648 -0.8627837 -0.3355222 0.378192 -0.7635858 -0.5716948 -0.3001698 -0.705614 -0.6545042 0.2715387 -0.4811601 -0.8032287 -0.3511534 -0.3842666 -0.8693059 0.3108803 -0.1047672 -0.9682422 -0.2270039 -0.09122109 -0.9886777 -0.119143 0.2228121 -0.9408313 0.2553261 0.3004552 -0.9189879 -0.2553195 0.5917522 -0.8000666 -0.09860497 0.6106871 -0.7779318 0.1479305 0.830852 -0.5135268 0.2144179 0.8681161 -0.4885659 -0.08762329 0.9625591 -0.1917221 -0.1916317 0.9596419 -0.1178155 0.2553567 -0.05770897 -0.9971789 -0.04799968 -0.2945146 -0.9542631 0.05141288 -0.4255662 -0.9032616 -0.05488133 -0.5971566 -0.8010199 0.04208582 -0.7817857 -0.6222277 -0.04054647 -0.7657552 -0.6430649 -0.009302377 -0.9580875 -0.2863119 0.00968796 -0.9524217 -0.3030952 0.03203624 -0.9987345 0.01616162 -0.04762637 -0.9857217 0.1595395 0.05385273 -0.9392207 0.3412494 -0.03759878 -0.8709945 0.4898487 0.03764218 -0.7812573 0.6226383 -0.04425668 -0.6418428 0.7646735 0.05755454 -0.5070227 0.8604065 -0.05127197 -0.2709775 0.9616506 0.04242169 -0.1900677 0.9813005 -0.03039056 0.1212113 0.9918948 0.03811514 0.219304 0.9745376 -0.04671692 0.4584419 0.8875207 0.04623925 0.5745577 0.8169497 -0.04976737 0.7599977 0.6481233 0.04837268 0.8289917 0.5578863 -0.03918844 0.9430526 0.3314448 0.02821826 0.97047 0.2389846 -0.03277647 0.997023 0.06930154 0.03380286 0.9925222 -0.1130271 -0.04609376 0.9619946 -0.2677137 0.05381339 0.8706684 -0.4871684 -0.06784904 0.7615786 -0.6430273 0.08070802 0.5664568 -0.8207489 -0.07414883 0.4107491 -0.910465 0.04836326 0.2337394 -0.971851 -0.02952253 0.09869837 -0.9944558 0.03628206 -0.2633128 -0.9647093 0.001546204 -0.2246983 -0.9744133 -0.005432605 -0.6195518 -0.7849063 0.008809745 -0.7639545 -0.6451347 -0.01322418 -0.9327517 -0.3603346 0.01154637 -0.993795 -0.1106328 -0.0114811 -0.9836718 0.1795472 0.01236265 -0.9105227 0.4133322 -0.01023846 -0.7183222 0.6956772 0.006825387 -0.6509699 0.7590958 -0.003451585 -0.3235567 0.9461957 0.004997014 -0.2419354 0.9702829 -0.004282295 0.1499111 0.9886936 0.00343579 0.1908705 0.981612 -0.002527534 0.6695195 0.7427829 0.004153668 0.7132667 0.7008739 -0.005146086 0.9470734 0.3209804 0.004845917 0.9610865 0.2762454 -0.001182973 0.9872877 -0.1589106 -0.003261089 0.9773145 -0.2117274 0.0052796 0.696964 -0.7170849 -0.005520641 0.7199084 -0.6940691 -2.11795e-4 0.302042 -0.9532763 0.005903124 0.225528 -0.9742262 -0.004519701 -0.2982385 -0.9543874 0.01409327 -0.6612991 -0.7499459 -0.01626825 -0.7899864 -0.6130282 0.01085215 -0.9919078 -0.126645 -0.008952856 -0.9921023 -0.1251311 -0.008673608 -0.9483559 0.316911 0.01373243 -0.8331101 0.5528778 -0.01593101 -0.5821936 0.8129734 0.01117736 -0.4285582 0.9034764 -0.008260726 -0.09118694 0.9957917 0.009158492 0.1071671 0.9941993 -0.009108304 0.3656635 0.9307126 0.008028388 0.5563257 0.8309203 -0.008563041 0.7459753 0.6659296 0.007659137 0.8820403 0.4711114 -0.007688164 0.9565703 0.2913722 0.008692324 0.9986147 -0.05080741 -0.01368236 0.9562089 -0.29223 0.01631647 0.7777143 -0.6285143 -0.01141196 0.6088471 -0.793242 0.008503437 0.4635907 -0.8860345 -0.005165934 0.1789181 -0.9838405 0.006791889 -0.02589976 -0.9995916 -0.01207578 -0.02457171 -0.9996972 0.001307129 -0.05062705 -0.9987143 -0.002620518 -0.4908025 -0.8712635 -0.003579676 -0.5665354 -0.8239781 0.009893774 -0.8947791 -0.4463266 -0.01276522 -0.9674378 -0.2525951 0.01612275 -0.9947366 0.1018285 -0.01141077 -0.9139302 0.4057534 0.009790956 -0.858828 0.5122474 -0.004146635 -0.5422493 0.8402035 0.004909992 -0.5220754 0.8528984 0.001312315 -0.1491934 0.9887916 -0.00571227 -0.008580744 0.999926 0.008630871 0.2948123 0.9555203 -0.008169293 0.4789968 0.877752 0.01065915 0.7193235 0.694596 -0.01050311 0.9047551 0.4257555 0.01227694 0.9444473 0.3286548 -0.002293348 0.9904733 -0.1376261 -0.004669368 0.9713134 -0.2376435 0.008725881 0.8353943 -0.5496018 -0.007383644 0.7327796 -0.6804159 0.008274078 0.4565137 -0.8896788 -0.008177042 0.3497955 -0.9368152 0.004526317 0.01728439 -0.9997959 0.01046568 -0.1683185 -0.9856118 -0.01544153 -0.5295078 -0.8481455 0.01645869 -0.7707166 -0.636942 -0.01734983 -0.9476726 -0.31887 0.01544868 -0.9891654 -0.1466962 -0.005670845 -0.9696584 0.2444578 -0.001755416 -0.9470894 0.3208352 0.009297847 -0.7446567 0.6674028 -0.007750391 -0.6345504 0.7728466 0.007356941 -0.3884589 0.92144 -0.006937146 -0.2112823 0.9773862 0.008719921 0.1252963 0.9920434 -0.01228237 0.3107385 0.9504272 0.01139426 0.7150856 0.6989935 -0.00779283 0.7459336 0.6660198 -8.86319e-4 0.9618845 0.273433 0.003567814 0.9857856 0.1677039 -0.01011335 0.9715201 -0.2365902 0.01318049 0.8950892 -0.4456827 -0.01350498 0.6276531 -0.7783988 0.01212179 0.5039451 -0.8636795 -0.009869575 5.17113e-6 0 1 -2.4939e-6 0 1 -4.45466e-6 0 1 4.30537e-6 0 1 2.18241e-6 0 1 3.75112e-6 0 1 2.38628e-6 0 1 -1.02212e-5 0 1 -6.17568e-7 0 1 3.28433e-6 0 1 8.39892e-7 0 1 4.23134e-6 0 1 -6.72802e-7 0 1 -1.50532e-5 0 1 -3.66229e-7 0 1 -2.88609e-6 0 1 -2.08129e-5 0 1 4.81331e-7 0 1 -1.62491e-6 0 1 2.13745e-5 0 1 -6.45211e-6 0 1 6.29196e-7 0 1 -1.4322e-5 0 1 -1.26604e-6 0 1 1.43165e-5 0 1 8.15883e-7 0 1 -1.45043e-5 0 1 2.45805e-6 0 1 -5.62814e-7 0 1 4.71789e-7 0 1 4.67909e-6 0 1 -9.36426e-6 0 1 2.27991e-6 0 1 1.57181e-6 0 1 -7.44601e-6 0 1 2.53282e-6 0 1 -1.06125e-5 0 1 1.44503e-6 0 1 -1.32098e-5 0 1 8.66785e-7 0 1 0.06568974 -0.6631792 -0.7455724 0.1106395 -0.837592 -0.5349753 0.5530596 -0.2199171 -0.803593 0.7715638 -0.3441274 -0.5350379 0.4863746 0.3586679 -0.7967417 0.5378592 0.4093357 -0.7369884 -0.06712555 0.6712395 -0.738195 -0.1103451 0.8376837 -0.5348926 -0.772652 0.3296971 -0.5425022 -0.7782903 0.3336858 -0.5319004 -0.5287649 -0.4119647 -0.7420868 -0.6773146 -0.4950652 -0.5442017 -0.9192609 0.3931558 -0.01970225 -0.9189447 0.3938556 -0.0204578 -0.7970271 -0.6036278 -0.0195254 -0.8008095 -0.5983654 -0.02575504 0.1137318 -0.9931924 -0.02517575 0.1180087 -0.9927922 -0.02092045 -0.009427845 0.00383991 -0.9999482 0.008167982 0.006123542 -0.999948 -0.01277983 -0.00659722 -0.9998967 -0.007968127 -0.005975484 -0.9999504 0.008211553 6.62567e-4 -0.9999662 0.007854402 0.0010944 -0.9999686 0.004438757 -0.001903116 -0.9999884 0.001888155 -0.008082807 -0.9999656 0.004051983 4.85978e-4 -0.9999918 0.01662296 -0.003944933 -0.9998542 0.003819346 -0.003017187 -0.9999882 -0.002295613 0.009162485 -0.9999554 0.004170477 0.003118872 -0.9999865 0.001204371 0.007631897 -0.9999701 -7.83177e-6 3.34205e-4 -1 -0.005815804 -0.006123602 -0.9999644 9.49421e-4 -0.006646931 -0.9999775 0.00163865 0.004756331 -0.9999874 -8.07474e-4 0.006937861 -0.9999756 -0.006998836 1.13975e-4 -0.9999755 -0.002139866 -0.001725316 -0.9999963 -0.001941382 -0.001074552 -0.9999976 -0.003185212 0.008200824 -0.9999613 -8.98342e-4 5.09044e-4 -0.9999995 -5.67283e-4 -0.003786027 -0.9999927 0.001825928 0.003086686 -0.9999936 -0.02850049 0.03370618 -0.9990254 8.33824e-4 -0.006932795 -0.9999756 -0.04918664 0.02030539 -0.9985833 0.01950162 -0.03927272 -0.9990383 -0.1006981 0.01505273 -0.9948033 -0.02536308 0.04778051 -0.9985359 -0.1296908 -0.07415682 -0.9887776 -0.07351589 -0.08547151 -0.9936247 -0.04210096 -0.01590907 -0.9989868 -0.03056621 0.04839646 -0.9983604 -0.01965379 0.03989177 -0.9990108 -0.0687018 0.2143202 -0.9743444 -0.01898545 -0.04025697 -0.9990091 0.001226961 -0.02146822 -0.9997688 0.003795444 -0.0291925 -0.9995666 0.006768345 -0.02256262 -0.9997225 -0.003356575 -0.007889628 -0.9999634 0.004755496 0.01188915 -0.9999181 0.04414135 -0.04786556 -0.997878 0.05540639 -0.04671418 -0.9973706 0.4030638 -0.4695815 -0.7855143 0.5784521 -0.3421273 -0.7405012 0.4310879 -0.1903905 -0.8819947 0.6722856 -0.05489283 -0.738254 0.4575785 0.09467059 -0.8841151 0.5309748 0.1598118 -0.8321815 0.3611536 0.299557 -0.883082 0.4028474 0.4290977 -0.8084487 0.2818161 0.4897882 -0.8250378 0.2742993 0.5568122 -0.7840409 0.128034 0.6268676 -0.768534 -0.007215261 0.514636 -0.8573785 -0.1018149 0.6080636 -0.7873325 -0.2604684 0.4464304 -0.8560702 -0.2605207 0.4763414 -0.8397784 -0.4719608 0.3618003 -0.8039613 -0.4561024 0.2883654 -0.8419122 -0.5472424 0.2251684 -0.8061172 -0.4876052 0.06929671 -0.8703098 -0.5986284 0.01502734 -0.800886 -0.4923879 -0.2065067 -0.8455231 -0.4844786 -0.2076727 -0.8497957 -0.4122549 -0.3932755 -0.8218153 -0.3513086 -0.382794 -0.8544302 -0.2549877 -0.5188782 -0.8159331 -0.2129362 -0.5016128 -0.8384766 -0.04281884 -0.6581672 -0.7516533 0.09526932 -0.5349131 -0.8395189 0.1709213 -0.5864429 -0.7917518 0.2798995 -0.4025582 -0.8715522 0.3784226 -0.4513411 -0.8081384 0.5054571 -0.3091055 -0.8055848 0.4472709 -0.1789854 -0.8763065 0.5489544 -0.1333292 -0.82515 0.5228415 0.00938642 -0.8523783 0.6146863 0.0756244 -0.785138 0.5372052 0.3471588 -0.7686946 0.4564291 0.2521932 -0.8532708 0.415402 0.4788463 -0.7733999 0.1709427 0.384631 -0.907104 0.0943436 0.5998949 -0.7944971 -0.00128591 0.5124658 -0.8587067 -0.1174338 0.5697399 -0.8133916 -0.1975141 0.4352772 -0.8783633 -0.3530042 0.5163348 -0.7802477 -0.4471782 0.3942894 -0.8028497 -0.404724 0.2464695 -0.8805971 -0.4817412 0.2302408 -0.8455262 -0.5057843 0.02210891 -0.8623767 -0.4982098 0.01428931 -0.8669387 -0.5834861 -0.1395248 -0.800048 -0.4795418 -0.1816481 -0.8585124 -0.4926697 -0.3408849 -0.8006711 -0.3125697 -0.3627514 -0.8779019 -0.3255919 -0.4762013 -0.8168367 -0.2143591 -0.5736446 -0.790558 -0.04268145 -0.4677912 -0.882808 7.25839e-4 -0.5750403 -0.8181248 0.2450252 -0.5549014 -0.7950139 0.2706478 -0.4285303 -0.8620393 0.3655866 -0.4462468 -0.8168295 0.4322484 -0.2366662 -0.8701439 0.4489316 -0.2709718 -0.8514897 0.6231851 -0.1228221 -0.7723699 0.4862405 0.06864196 -0.8711249 0.5405073 0.1049991 -0.8347617 0.4895699 0.3206591 -0.8108632 0.420233 0.3167111 -0.8503519 0.2810171 0.5033695 -0.8170977 0.2244237 0.471171 -0.8530135 0.06524848 0.6131012 -0.7873053 -0.03443056 0.4906463 -0.8706784 -0.1805271 0.571523 -0.800482 -0.2595648 0.3614332 -0.8955402 -0.3794159 0.4189533 -0.8249374 -0.5020021 0.2889174 -0.8151814 -0.4582398 0.1738707 -0.8716566 -0.5559736 0.1292191 -0.8210943 -0.5206429 -0.03190737 -0.8531782 -0.5834084 -0.07568812 -0.8086446 -0.4469233 -0.2593963 -0.8561387 -0.5003623 -0.3306182 -0.8002058 -0.3560026 -0.490495 -0.7954099 -0.2139649 -0.4392585 -0.8725085 -0.1646279 -0.5546627 -0.8156268 -0.01465642 -0.4976243 -0.8672689 0.06484729 -0.5987414 -0.798313 0.1946302 -0.5233236 -0.8296093 0.2146139 -0.4323988 -0.8757694 0.3904367 -0.4772281 -0.7872818 0.4599126 -0.2567226 -0.8500435 0.4539315 -0.2466083 -0.8562306 0.5346967 -0.04120385 -0.8440389 0.5737789 -0.08070385 -0.8150244 0.5757458 0.08936703 -0.8127302 0.4411292 0.1731458 -0.8805825 0.5178194 0.2996494 -0.8012948 0.4489865 0.4120759 -0.792846 0.3598648 0.4072884 -0.8394126 0.3173536 0.5818586 -0.7488172 0.07958263 0.5443141 -0.8350981 0.05380362 0.596206 -0.8010267 -0.1306909 0.5066034 -0.8522165 -0.1836116 0.5664426 -0.8033864 -0.3673455 0.4105399 -0.8345745 -0.3673776 0.4107814 -0.8344414 -0.5158737 0.2078732 -0.8310614 -0.4835665 0.1645947 -0.859693 -0.5855647 0.03342443 -0.8099363 -0.4786018 -0.08676433 -0.8737348 -0.5664193 -0.1909011 -0.801702 -0.463776 -0.2797017 -0.8406419 -0.3740136 -0.2788079 -0.8845225 -0.3391801 -0.4517875 -0.8251333 -0.1769778 -0.3970534 -0.9005706 -0.120649 -0.5785263 -0.8066915 0.04030996 -0.5209386 -0.8526419 0.07663744 -0.5796002 -0.8112894 0.282678 -0.410843 -0.8667764 0.3121296 -0.4319409 -0.8461691 0.4849588 -0.2390847 -0.8412215 0.4394901 -0.1488627 -0.8858263 0.6135203 -0.09612172 -0.783807 0.4300613 0.1223461 -0.8944713 0.5121844 0.2060788 -0.8337858 0.4253757 0.3573359 -0.8314846 0.4261679 0.3587414 -0.8304731 0.2647654 0.5408076 -0.7983899 0.1905852 0.4981587 -0.8458814 0.03197157 0.6801552 -0.7323707 -0.1216477 0.5328336 -0.8374307 -0.2187365 0.5981051 -0.7709894 -0.2986515 0.4183142 -0.8577998 -0.4785777 0.4544937 -0.7512649 -0.5408567 0.2112659 -0.8141503 -0.5201225 0.2121904 -0.8273137 -0.5781933 -0.01910752 -0.8156761 -0.4960287 -0.05211013 -0.8667412 -0.4202824 -0.2377642 -0.8756889 -0.4520624 -0.2781446 -0.8475112 -0.3652206 -0.4350299 -0.8230207 -0.3551927 -0.3961973 -0.8466793 -0.2826932 -0.5819489 -0.7625092 -0.07879513 -0.5655266 -0.8209574 -0.04348653 -0.630722 -0.7747896 0.1178746 -0.3962105 -0.9105619 0.3267792 -0.5756222 -0.749583 0.3764515 -0.2768369 -0.8841074 0.4852675 -0.3021555 -0.8204984 0.5725368 -0.07328587 -0.8165971 0.5347076 -0.03807127 -0.8441791 0.585036 0.08036243 -0.807016 0.4684278 0.1714889 -0.8666989 0.5167607 0.2640863 -0.8143813 0.3406382 0.3901776 -0.8554105 0.4650011 0.4217096 -0.7784184 0.2504104 0.5796446 -0.7754397 0.1452363 0.5230211 -0.8398544 0.02126371 0.5657464 -0.8243051 -0.03511631 0.4906325 -0.8706588 -0.1925907 0.5966196 -0.7790725 -0.3177299 0.4218702 -0.8491604 -0.3062247 0.3276099 -0.8938111 -0.5346317 0.3490982 -0.7696099 -0.4970795 0.06617563 -0.8651779 -0.5356202 0.05712056 -0.842525 -0.5786424 -0.152687 -0.8011615 -0.4177864 -0.2114221 -0.8836035 -0.4893464 -0.3523628 -0.7977348 -0.304767 -0.4745523 -0.8257828 -0.2284682 -0.4434234 -0.8667054 -0.1662786 -0.5765001 -0.7999995 -0.0268628 -0.5023221 -0.8642632 0.07982945 -0.598035 -0.7974844 0.1926604 -0.4996398 -0.8445366 0.2023919 -0.5071216 -0.837774 0.3843117 -0.4417746 -0.8106415 0.3780602 -0.3801281 -0.8441406 0.5852319 -0.2987388 -0.7538294 0.5753272 -0.1268472 -0.8080275 0.5717533 -0.1284914 -0.8103013 0.5384634 0.06624561 -0.8400409 0.5253012 0.0726546 -0.847809 0.4919359 0.2652174 -0.8292521 0.4667672 0.2684574 -0.84265 0.3751847 0.4495073 -0.8106663 0.2598646 0.4140672 -0.872364 0.1950891 0.6186928 -0.7610253 -0.007890522 0.4852359 -0.8743478 -0.1085835 0.6045311 -0.7891464 -0.2179171 0.4663301 -0.8573497 -0.3077956 0.5005931 -0.8091159 -0.3669357 0.3417205 -0.8652083 -0.4578434 0.3466252 -0.8186761 -0.5205618 0.2288044 -0.822596 -0.4703438 0.1326226 -0.8724609 -0.6126789 0.06268513 -0.7878421 -0.5070011 -0.1447154 -0.8497102 -0.5027578 -0.1457979 -0.8520432 -0.4282212 -0.4119964 -0.804292 -0.3407395 -0.2762135 -0.8986672 -0.3380447 -0.564926 -0.752718 -0.03893762 -0.4052866 -0.9133601 0.02688938 -0.6185229 -0.7853066 0.2522884 -0.5062775 -0.8246416 0.2554354 -0.3762383 -0.8906163 0.4013788 -0.3925995 -0.8275027 0.4781526 -0.1915336 -0.8571376 0.4519923 -0.1453377 -0.8801023 0.6069571 -0.07844585 -0.7908536 0.551185 0.09563386 -0.8288844 0.4766764 0.1266489 -0.8699079 0.5316727 0.3232861 -0.7828221 0.339889 0.3579986 -0.8696623 0.3601761 0.478807 -0.8006354 0.1024395 0.494311 -0.8632282 0.0956518 0.5396567 -0.8364338 -0.124051 0.6240234 -0.7714961 -0.1734465 0.5102332 -0.8423649 -0.38422 0.5590214 -0.7347587 -0.4193718 0.3038774 -0.8554449 -0.5263229 0.2749848 -0.8045915 -0.4564603 0.126279 -0.880737 -0.6234816 0.05151581 -0.7801392 -0.4238201 -0.1628789 -0.890981 -0.4699357 -0.2032653 -0.8589783 -0.4690799 -0.3959221 -0.7894365 -0.2878059 -0.3515179 -0.890844 -0.1669859 -0.5338217 -0.8289452 -0.1301641 -0.5073029 -0.8518809 0.01199686 -0.5854209 -0.8106409 0.06826674 -0.5093761 -0.857832 0.2449151 -0.5593723 -0.7919086 0.258164 -0.5182975 -0.8153031 0.4580339 -0.4787244 -0.749018 0.4545946 -0.2656537 -0.8501599 0.5544162 -0.2534295 -0.7927144 0.5263683 -0.01907104 -0.8500428 0.5284604 -0.02046066 -0.8487114 0.5506497 0.1707852 -0.8170786 0.4329696 0.2124458 -0.8760161 0.5019066 0.3855299 -0.7742458 0.2313597 0.4545254 -0.8601624 0.2708526 0.4808271 -0.8339329 0.06761699 0.5591139 -0.8263291 0.04940629 0.5382745 -0.8413202 -0.1368733 0.5553567 -0.8202711 -0.1772705 0.4583135 -0.8709328 -0.340851 0.5122736 -0.7882871 -0.4144938 0.3261573 -0.8495977 -0.4202858 0.3405422 -0.8410653 -0.4865053 0.07970887 -0.8700339 -0.5488851 0.161135 -0.8202199 -0.6465697 -0.05642038 -0.7607657 -0.4977357 -0.1826494 -0.8478788 -0.5643485 -0.2874394 -0.7738795 -0.3586547 -0.4851247 -0.7975091 -0.3570134 -0.4738414 -0.8049942 -0.1404487 -0.5064609 -0.8507477 -0.1405053 -0.5059372 -0.85105 0.03990542 -0.6118706 -0.7899507 0.1482713 -0.4023572 -0.9033961 0.3326382 -0.5121856 -0.7918446 0.3407491 -0.3486202 -0.8731289 0.5123904 -0.2841616 -0.8103755 0.4826822 -0.2163094 -0.8486626 0.5800801 -0.07974344 -0.8106468 0.4833777 0.01574492 -0.8752703 0.6164966 0.1370404 -0.7753399 0.3435088 0.27416 -0.8982417 0.4107986 0.4025248 -0.8180577 0.2369593 0.495689 -0.8355494 0.2392823 0.4971323 -0.8340286 0.05071061 0.5583744 -0.8280378 0.02761387 0.5341627 -0.8449306 -0.1275614 0.5675392 -0.8134049 -0.178186 0.4717001 -0.8635675 -0.3274313 0.5212291 -0.7881048 -0.3690865 0.3495859 -0.8611418 -0.4904721 0.3474113 -0.7992138 -0.4903365 0.1740455 -0.853978 -0.5416096 0.1617324 -0.8249254 -0.5646299 -0.04492712 -0.8241206 -0.4911038 -0.08042091 -0.867381 -0.5242205 -0.2819136 -0.8035656 -0.3526777 -0.3051373 -0.8845958 -0.3702007 -0.4835822 -0.7931582 -0.1494359 -0.4498537 -0.8805116 -0.1406082 -0.5199312 -0.8425562 0.05673485 -0.6203245 -0.7822906 0.1548194 -0.4394679 -0.8848159 0.2642636 -0.5235008 -0.8100073 0.404683 -0.4416962 -0.8007099 0.3787645 -0.254267 -0.8898797 0.5123902 -0.2582344 -0.8190063 0.6090865 -0.08351093 -0.788695 0.4644181 0.02205914 -0.8853414 0.5715696 0.2092221 -0.793432 0.35305 0.2453078 -0.9028731 0.4185097 0.4357959 -0.796826 0.2353659 0.5151004 -0.8241811 0.1850509 0.4781287 -0.858574 0.01507151 0.5850101 -0.8108861 -0.03817379 0.5156289 -0.8559613 -0.2219232 0.5790226 -0.7845272 -0.2593579 0.4535735 -0.8526456 -0.3187356 0.449528 -0.8344653 -0.378654 0.2715398 -0.8848092 -0.4616224 0.2838485 -0.8404372 -0.562412 0.1702716 -0.8091355 -0.4830743 0.0520969 -0.8740282 -0.6017241 -0.02005773 -0.7984522 -0.5117796 -0.2132943 -0.8322183 -0.4200376 -0.2314472 -0.8774968 -0.4601383 -0.3900692 -0.7975706 -0.2850846 -0.4599584 -0.8409311 -0.2859153 -0.484308 -0.8268605 -0.07593369 -0.5491664 -0.8322563 -0.08192372 -0.5250014 -0.8471495 0.1311904 -0.594519 -0.7933073 0.1828185 -0.4440845 -0.8771353 0.4012231 -0.4924415 -0.772348 0.3994029 -0.2806767 -0.8727532 0.5218641 -0.2837513 -0.8044521 0.5452586 -0.055579 -0.8364234 0.54388 -0.05449056 -0.8373921 0.5538999 0.1356672 -0.8214556 0.4785649 0.166068 -0.8622049 0.512501 0.3315131 -0.7921122 0.3905866 0.3607553 -0.8469343 0.3796061 0.525117 -0.7616767 0.1446626 0.5531406 -0.8204318 0.1414616 0.5672 -0.8113402 -0.07749623 0.5168183 -0.8525804 -0.07835018 0.5148219 -0.8537094 -0.3074876 0.4709772 -0.8268204 -0.307178 0.4526951 -0.8370835 -0.4532436 0.325911 -0.82967 -0.4422555 0.2957087 -0.8467388 -0.5430414 0.167802 -0.822769 -0.4366171 0.04427355 -0.8985574 -0.6081154 -0.120502 -0.7846497 -0.4395739 -0.1784317 -0.8803051 -0.4638912 -0.3883894 -0.7962152 -0.3096351 -0.3810181 -0.8711783 -0.2982927 -0.5350891 -0.7903805 -0.07378518 -0.522454 -0.8494691 -0.07447648 -0.5234325 -0.8488062 0.1895464 -0.5208113 -0.8323628 0.20366 -0.5394996 -0.816984 0.4263641 -0.4095724 -0.8065136 0.3879522 -0.2870582 -0.8758372 0.5140136 -0.2272826 -0.8271232 0.4647421 -0.04736828 -0.8841783 0.5317512 -0.01920551 -0.8466828 0.5537746 0.1776188 -0.8135018 0.4654605 0.1183095 -0.8771256 0.5543231 0.3819235 -0.7395001 0.2938078 0.3911081 -0.8721877 0.2987208 0.4864652 -0.8210467 0.07323408 0.5026276 -0.8613956 0.04515004 0.5844485 -0.8101738 -0.1460265 0.504992 -0.8506817 -0.1840877 0.542158 -0.8198637 -0.3614341 0.4089881 -0.8379105 -0.3023955 0.3752811 -0.876197 -0.4818145 0.3704464 -0.7941187 -0.5030679 0.1252558 -0.855122 -0.4892113 0.1268312 -0.8628941 -0.5929086 -0.04692327 -0.8039016 -0.5038442 -0.117309 -0.8557919 -0.5577402 -0.2468499 -0.7924588 -0.394003 -0.3151893 -0.8633756 -0.422758 -0.4257955 -0.7999837 -0.2141461 -0.4916365 -0.8440586 -0.2305591 -0.5038926 -0.832427 -0.003327548 -0.5352156 -0.844709 0.006876885 -0.5573359 -0.8302587 0.2164053 -0.4896865 -0.8446159 0.2081083 -0.5308818 -0.821496 0.4057017 -0.4220867 -0.8107091 0.3866366 -0.3199995 -0.864935 0.5763967 -0.2481383 -0.7785848 0.4925761 -0.0719223 -0.8672924 0.5877982 -0.02219492 -0.8087031 0.5477631 0.1240857 -0.8273804 0.4786627 0.1548956 -0.8642277 0.4919524 0.3151175 -0.8115934 0.3776974 0.3394431 -0.8614658 0.373793 0.4632404 -0.8035466 0.2291871 0.4699904 -0.852398 0.2068992 0.5515167 -0.8080978 -0.01419979 0.5247131 -0.8511608 -0.001654028 0.4919411 -0.8706269 -0.1839535 0.5947365 -0.7825916 -0.3061809 0.3793568 -0.8731219 -0.3262269 0.3914986 -0.8604099 -0.5068046 0.3800131 -0.7737825 -0.518567 0.1690767 -0.8381536 -0.4329228 0.0761249 -0.898211 -0.6021077 -0.02172327 -0.7981194 -0.5430191 -0.2116961 -0.8125978 -0.3877137 -0.236114 -0.8910266 -0.4566584 -0.4062407 -0.7914744 -0.311348 -0.527401 -0.790513 -0.1636251 -0.4525186 -0.876615 -0.09633433 -0.5869633 -0.8038619 0.06334084 -0.5137463 -0.8556008 0.1177153 -0.5780498 -0.8074662 0.2492268 -0.4552273 -0.8547831 0.252627 -0.4151907 -0.8739545 0.4087039 -0.3327314 -0.8498535 0.4064683 -0.3149451 -0.8576674 0.5890617 -0.2125346 -0.7796379 0.4878899 -0.1046988 -0.8666035 0.6218373 0.1164473 -0.7744408 0.4049706 0.2053172 -0.8909791 0.4714112 0.2985983 -0.8298256 0.3608501 0.4910101 -0.7929037 0.2518215 0.4532293 -0.8550844 0.1619284 0.6372496 -0.7534535 -0.04294085 0.5041266 -0.8625617 -0.131605 0.6092357 -0.7819923 -0.298921 0.4118282 -0.8608391 -0.2911655 0.4067144 -0.8659134 -0.4884266 0.3470817 -0.8006083 -0.4580187 0.1780244 -0.8709341 -0.5609529 0.1601638 -0.8122066 -0.5856833 -0.05760872 -0.8084902 -0.4978185 -0.1000418 -0.861492 -0.5338639 -0.2872462 -0.7952856 -0.4185529 -0.3062765 -0.8549902 -0.4097055 -0.3824367 -0.8281809 -0.2035118 -0.4334577 -0.8778938 -0.2050219 -0.4694697 -0.8588156 -0.09532809 -0.5771387 -0.8110633 -0.01798111 -0.5316547 -0.8467703 0.06354075 -0.5995478 -0.7978127 0.1939303 -0.455083 -0.8690745 0.2826854 -0.5199066 -0.8060932 0.461798 -0.3535834 -0.8134627 0.431806 -0.2952961 -0.852258 0.5548186 -0.07564508 -0.8285253 0.5873961 -0.1034846 -0.8026561 0.6246812 0.1185472 -0.7718291 0.4819067 0.2055783 -0.851765 0.5182703 0.3191096 -0.7934515 0.3583752 0.4015927 -0.8427873 0.3578409 0.4014051 -0.8431037 0.1287598 0.4791696 -0.8682267 0.2093666 0.5328417 -0.8199057 0.008551299 0.6356086 -0.7719642 -0.181304 0.478279 -0.8592894 -0.1815581 0.476638 -0.8601471 -0.3861207 0.4651317 -0.7965947 -0.3410447 0.2481884 -0.9066924 -0.6134467 0.2061128 -0.7623654 -0.4874547 0.02115643 -0.8728919 -0.5451719 -0.01658254 -0.8381603 -0.4932473 -0.2055 -0.8452674 -0.4984985 -0.2115646 -0.8406782 -0.4596809 -0.3664813 -0.8089407 -0.3663966 -0.3654866 -0.8556711 -0.3086221 -0.5217676 -0.7953056 -0.148913 -0.4576179 -0.8765906 -0.08069002 -0.6245107 -0.7768369 0.1277409 -0.53019 -0.8382011 0.1364852 -0.4989655 -0.8558068 0.3153133 -0.4767442 -0.8205441 0.3360337 -0.402602 -0.8514652 0.4248573 -0.4068585 -0.8086794 0.4885433 -0.1852814 -0.8526408 0.4818094 -0.1850184 -0.8565208 0.6611396 -0.006722807 -0.7502329 0.5160679 0.1186718 -0.8482872 0.5715049 0.1968682 -0.7966336 0.3541764 0.2843704 -0.8908944 0.3839334 0.3949232 -0.8346443 0.2663083 0.4931539 -0.8281782 0.1731303 0.4181787 -0.8917133 0.03377908 0.4713764 -0.881285 -0.05595928 0.3353865 -0.9404172 -0.3936875 0.6465052 -0.6534839 -0.2967134 0.4015668 -0.8664325 -0.3910868 0.1582522 -0.9066463 0.1297531 0.9897649 0.05941045 -0.3301129 0.9206038 -0.2086004 -0.3750628 0.8100996 0.4506293 -0.6846653 0.5982546 -0.4163232 -0.7823548 0.5863167 0.2101282 -0.9743441 0.2192727 0.0507242 -0.9416871 0.2412778 0.2345429 -0.8865773 -0.1279029 -0.4445467 -0.8642493 -0.2809601 0.4172945 -0.7576319 -0.5026761 -0.416306 -0.6546877 -0.5911423 0.4710996 -0.3085202 -0.7917555 -0.5271987 -0.01601088 -0.974993 0.2216584 0.5067185 -0.858133 -0.08273065 0.5116648 -0.8440287 -0.1606702 0.8803196 -0.4463033 0.1607816 0.9031499 -0.4056496 -0.1406013 0.9849621 0.05708086 0.1630696 0.8999902 0.430369 0.06928503 0.5462658 0.7579768 -0.3564618 0.4678165 0.7868245 0.4025606 0.1871846 0.9113957 -0.3664968 0.08025199 0.9225749 0.3773795 -0.3415659 0.9261693 -0.1598231 -0.3508316 0.8626102 -0.3644461 -0.7480346 0.5647076 0.3486397 -0.8315919 0.5197575 -0.1957225 -0.9897165 0.1210726 0.07617485 -0.9383752 0.03268909 -0.344069 -0.8555567 -0.233642 0.4619896 -0.7989173 -0.440455 -0.4095492 -0.6668343 -0.631597 0.3954962 -0.5762709 -0.7481294 -0.3289596 -0.1760549 -0.9283306 0.3274249 -0.1871369 -0.8625123 0.4701621 0.2011576 -0.8107826 -0.5496975 0.3807621 -0.7684993 0.5142267 0.600705 -0.7319831 -0.3214876 0.7394276 -0.5039616 0.4463962 0.7576451 -0.29912 -0.5800873 0.8145787 0.02418535 0.5795487 0.9026746 0.2076149 -0.376928 0.817107 0.5173076 0.2544192 0.778653 0.6011843 -0.1796582 0.5065792 0.8599196 0.06257706 0.4928112 0.8535158 0.1692563 0.03740233 0.9923344 -0.1177855 0.01411992 0.9889531 0.1475548 -0.3882206 0.8795312 -0.2751541 -0.4075184 0.7368667 0.5394036 -0.655869 0.4134076 -0.6316092 -0.8192127 0.4061455 0.4048907 -0.9963645 0.0150001 0.08386272 -0.9356625 -0.05802041 -0.3480938 -0.8535729 -0.4016159 0.3318406 -0.8202452 -0.5034607 -0.2715236 -0.5118423 -0.8585723 0.02951413 -0.5092569 -0.8582822 0.06331914 -0.1099553 -0.9867801 0.1190592 0.01894479 -0.8718116 -0.4894749 0.2719832 -0.7518076 0.6006751 0.4889644 -0.7411161 -0.460066 0.8317164 -0.5551323 -0.008725285 0.8282466 -0.5401098 0.1492951 0.9819759 -0.1479787 0.1175832 0.9690078 -0.07873874 -0.2341458 0.9206753 0.2650195 0.2865692 0.8932991 0.3584926 -0.2711086 0.643614 0.7648194 0.02850174 0.3269221 0.9036952 0.2765086 -0.07418531 0.9443036 -0.3206045 -0.1479216 0.9014253 0.4068805 -0.5622932 0.7369271 -0.3751864 -0.613585 0.7773708 -0.1385937 -0.8393191 0.3740898 0.3944623 -0.8831722 0.2484838 -0.3978226 -0.9620993 -0.08496546 0.2591257 -0.8581843 -0.2214291 -0.4631294 -0.7168104 -0.41804 0.5580551 -0.5888194 -0.6549835 -0.4735909 -0.4643921 -0.7905178 0.3992767 -0.2415999 -0.8408962 -0.4842758 -0.01975232 -0.8152312 0.5787989 0.2420841 -0.8713397 -0.4268051 0.4371439 -0.7922167 0.4257909 0.5819762 -0.7148192 -0.3877336 0.8200709 -0.3760683 0.4313427 0.9232476 -0.3652616 0.1191547 0.9011951 0.07982391 -0.4259998 0.9121767 0.1560775 0.3789113 0.803541 0.5924392 -0.05777227 0.7379478 0.5925796 -0.3229284 0.3284047 0.9021258 0.2798563 -0.08207094 0.985095 -0.15117 -0.5933638 0.7909352 -0.1494692 -0.782401 0.4868759 0.3883308 -0.850308 0.08816111 -0.5188487 -0.9000352 -0.00482589 0.4357907 -0.90663 -0.4188283 0.05103874 -0.8303048 -0.4513199 -0.3269625 -0.5915316 -0.7626743 0.261569 -0.268625 -0.9325667 -0.2411641 0.1751389 -0.9475677 0.2672863 0.2006274 -0.9700714 0.1367853 0.5314549 -0.6916553 -0.4890487 0.5346074 -0.5065608 0.6764549 0.7558025 -0.2745143 -0.5944783 0.8983302 -0.1465672 0.4141509 0.898412 0.1647717 -0.4070704 0.9237342 0.2467193 0.2929927 0.7146965 0.6800361 -0.1635844 0.4202699 0.8909379 -0.172055 0.01650661 0.9578116 0.2869228 -0.04418772 0.9957991 -0.08019691 -0.4203136 0.8050016 -0.4186991 -0.4020113 0.5656067 0.7200528 -0.6614621 0.3729466 -0.6506757 -0.7967522 0.1953079 0.5718749 -0.9549844 0.03333079 -0.2947776 -0.8906996 -0.3477016 0.2928447 -0.8867874 -0.3431571 0.3095988 -0.5735074 -0.6131922 -0.543217 -0.4485881 -0.6820102 0.5776078 -0.2034778 -0.9073166 -0.3679312 -0.1335018 -0.9805359 0.1439677 0.2161331 -0.9249038 -0.312793 0.2679772 -0.9149799 0.3016625 0.7262485 -0.6869277 0.02633738 0.902878 -0.3270388 -0.2790287 0.9455919 0.05142575 0.3212654 0.7812361 0.2278463 -0.5811682 0.8419805 0.3892532 0.373565 0.5792765 0.7957561 -0.1766668 0.6159989 0.7567799 0.2186996 0.1494634 0.9107279 -0.3850135 0.07617032 0.9264625 0.3685992 -0.3357232 0.8906277 -0.3067122 -0.358393 0.9186459 -0.1662657 -0.5973476 0.674864 0.4332835 -0.7081914 0.4644439 -0.5317489 -0.7914754 0.3172378 0.5224242 -0.902316 0.09977239 -0.4193705 -0.9121354 -0.2440486 0.3293165 -0.920397 -0.2109504 -0.3291949 -0.6782069 -0.554012 0.4828107 -0.6371445 -0.7015714 -0.319131 -0.2834756 -0.9295998 -0.2355548 -0.1758328 -0.7559865 0.6305294 0.241055 -0.830709 -0.5018119 0.367689 -0.716003 0.5934177 0.5927125 -0.7054562 -0.3886175 0.8305174 -0.3639583 0.421634 0.8273383 -0.2085795 -0.5215418 0.8220105 0.1277081 0.554968 0.7841327 0.3298973 -0.525646 0.675434 0.5825974 0.4520722 0.6279609 0.7384374 -0.245714 0.2911685 0.954693 0.06149953 0.2769958 0.9379737 0.2085155 -0.3339864 0.9306526 -0.1494621 -0.6752232 0.7371852 0.02513295 -0.9005907 0.3441886 0.2654631 -0.9493343 0.3057178 -0.07280731 -0.9051886 -0.08869427 -0.4156526 -0.8010281 -0.2074257 0.5615414 -0.8427302 -0.4536413 -0.2898544 -0.6838774 -0.6864224 0.2472569 -0.5918473 -0.7506665 -0.2936269 -0.3161644 -0.901443 0.2957034 -0.1335328 -0.8836078 -0.4487832 0.03388619 -0.8947669 0.445246 0.3984413 -0.7525525 -0.524318 0.6824983 -0.6116 0.400177 0.8660675 -0.1830697 -0.4652016 0.9299029 -0.1168997 0.3487336 0.9158849 0.3381172 -0.2164069 0.9273093 0.3632816 0.09013253 0.5272706 0.8280827 -0.1904328 0.5240308 0.8187738 -0.2345234 0.1632829 0.9045418 0.3938817 -0.03384035 0.8983354 -0.438005 -0.2482224 0.8877714 0.387618 -0.4134588 0.7982038 -0.4380897 -0.6295349 0.599882 0.493789 -0.7694597 0.4684701 -0.4341285 -0.8867183 0.233556 0.3989768 -0.9005417 0.06869328 -0.4293089 -0.787026 -0.3057051 0.5358493 -0.5663246 -0.6335675 -0.5271326 -0.3013015 -0.7653695 0.5687064 -0.1097609 -0.8568989 -0.5036635 0.2668813 -0.9404457 0.2105619 0.2605941 -0.9654121 -0.008387088 0.5999804 -0.7385922 0.3074169 0.6803369 -0.5926697 -0.4311432 0.8411521 -0.4656091 0.275084 0.8843984 -0.2234135 -0.409788 0.8001044 -0.06259357 0.5965862 0.7215875 0.2534204 -0.6442745 0.716423 0.4418838 0.5398861 0.5598893 0.6611736 -0.4993731 0.4530871 0.7691755 0.4506454 0.09899663 0.9293047 -0.3557984 0.09506255 0.922811 -0.3733405 -0.2365718 0.8654149 0.4416909 -0.414457 0.8304879 -0.3721767 -0.6460755 0.7264491 0.2342182 -0.7215355 0.5999008 -0.3456959 -0.8112783 0.3767901 0.4470535 -0.9022099 0.1923534 -0.3860278 -0.9342635 -0.06512975 0.3505851 -0.9164826 -0.1994416 -0.3468179 -0.7453141 -0.5181812 0.4195179 -0.6672357 -0.641899 -0.3778389 -0.3744421 -0.8361954 0.4007124 -0.250491 -0.8804927 -0.4024761 0.223493 -0.9124101 0.3428681 0.2466924 -0.9383985 0.2419732 0.6018204 -0.6649051 -0.4423952 0.576706 -0.4978421 0.6477373 0.7267324 -0.1342262 -0.673679 0.859516 -0.05562824 0.5080727 0.8763371 0.4161586 0.2425803 0.7835522 0.4621329 -0.4153062 0.4482495 0.8214553 -0.3525388 0.4245268 0.8759536 0.2290905 -0.01560741 0.9904718 -0.136829 -0.01089936 0.9792589 -0.20232 -0.3824498 0.8374976 0.3902946 -0.4892228 0.5685536 -0.6613682 -0.685128 0.6063317 0.4036849 -0.9797466 0.1822232 -0.0830143 -0.8860216 0.1128475 -0.4497014 -0.8167399 -0.3457734 0.4619274 -0.8135681 -0.484493 -0.3215176 -0.5828167 -0.8015471 0.1335927 -0.5193138 -0.8298026 -0.204306 -0.2044726 -0.930036 0.3053264 -0.05754554 -0.9094879 -0.4117286 0.244935 -0.8352385 0.4923247 0.3966912 -0.6364837 -0.6614564 0.5522775 -0.4950204 0.670779 0.7651908 -0.2624599 -0.5878757 0.9334113 -0.1747751 0.3133642 0.9309169 0.159272 -0.3286735 0.9046968 0.227244 0.3603941 0.6612837 0.6432912 -0.3858503 0.4060692 0.834754 0.3718784 0.02051579 0.9609614 -0.275921 -0.06232875 0.9527792 0.2971988 -0.3535805 0.8316248 -0.4282304 -0.44926 0.8044278 0.3886663 -0.7876024 0.6136298 0.05604439 -0.7764788 0.5162068 -0.3614019 -0.9498723 0.1955969 0.2438948 -0.9882935 0.1507896 -0.0232076 -0.9604396 -0.2580047 -0.1048312 -0.9284438 -0.2824488 0.2412778 -0.6772453 -0.6859627 -0.2660714 -0.6893672 -0.7240399 0.02322322 -0.214437 -0.955187 0.2040453 -0.07471102 -0.8466935 -0.5268099 0.2134923 -0.8198466 0.5312932 0.4247215 -0.7620226 -0.4888079 0.6870433 -0.6218367 0.3758866 0.7678392 -0.5117305 -0.3854286 0.8499652 -0.1797463 0.4952276 0.8860442 0.03073447 -0.4625809 0.8800026 0.2050728 0.4284164 0.7314053 0.4213001 -0.5362392 0.5961087 0.6439304 0.4795916 0.5956853 0.802688 -0.02917259 0.2018745 0.9714211 -0.1248511 0.2043291 0.9576417 -0.2029092 -0.164648 0.8763729 0.4526165 -0.3615055 0.7827048 -0.5066429 -0.5203541 0.7096598 0.474989 -0.656047 0.455783 -0.6015516 -0.7671074 0.2762834 0.5789766 -0.9140761 0.07153278 -0.3991842 -0.9419104 -0.1344169 0.307794 -0.8189841 -0.3315073 -0.4683672 -0.7154657 -0.4610896 0.524886 -0.4430193 -0.6967155 -0.5641998 -0.4760318 -0.869214 0.1336439 -0.0869776 -0.9556159 0.2814843 0.05818879 -0.8879697 -0.4562059 0.3003855 -0.8767326 0.3756443 0.4768675 -0.8128753 -0.3344117 0.6720674 -0.665247 0.3252261 0.7436439 -0.5324369 -0.4043573 0.8432517 -0.2127335 0.4936306 0.9130405 -0.04558724 -0.4053134 0.9421966 0.2152734 0.2567549 0.8253114 0.3608048 -0.4343742 0.685551 0.5005736 0.5286266 0.4237768 0.7730171 -0.4720783 0.3976787 0.7487872 -0.5302541 0.06435614 0.771309 0.6331989 -0.1702156 0.7559331 -0.6321329 -0.448515 0.692252 0.5653509 -0.6375827 0.6889613 -0.3447037 -0.9054624 0.2616123 0.334211 -0.8715998 0.2644448 0.4127746 -0.7992837 -0.1682257 -0.5769278 -0.601982 -0.2615886 0.7544462 -0.5428022 -0.5725817 -0.6144235 -0.4002307 -0.8306351 0.3871188 -0.3095547 -0.9253623 -0.2188163 0.02968376 -0.8984762 0.4380178 0.2303794 -0.8128638 -0.534956 0.4157911 -0.8569966 0.3044251 0.682177 -0.6689465 -0.2952038 0.738322 -0.6685241 0.08919781 0.9418951 -0.2853172 0.1772788 0.9653623 -0.2585153 -0.03529423 0.8996868 0.1623182 -0.4052366 0.6746661 0.2343329 0.6999384 0.6266801 0.5173006 -0.582814 0.4287579 0.7878596 0.4420905 0.1031076 0.918215 0.3824266 -0.3389593 0.7767376 -0.5308346 -0.4093648 0.7102358 0.5727002 -0.7611285 0.5143731 -0.3950996 -0.7933807 0.4037261 0.4555791 -0.8332818 0.1182596 -0.5400519 -0.8124507 -0.07459264 0.5782387 -0.7826063 -0.3847295 -0.4893984 -0.8347318 -0.5080871 0.2122982 -0.5065634 -0.7954016 -0.3327611 -0.4922344 -0.8503929 0.185842 -0.109139 -0.9814971 0.157328 0.03871554 -0.8446024 -0.5339924 0.2487916 -0.8051499 0.5383646 0.485724 -0.6981936 -0.5259259 0.6994652 -0.5808004 0.4164366 0.8226701 -0.4891598 -0.2897185 0.9169987 -0.1334797 0.3758943 0.9464517 0.2408719 -0.2149649 0.7108694 0.6833562 -0.1664003 0.7136452 0.7004956 0.004081249 0.3136142 0.8301272 0.4610153 0.1403821 0.8312013 -0.5379568 -0.2679015 0.9385794 0.2174801 -0.2677444 0.9341461 0.2359748 -0.7490484 0.6543322 -0.1038071 -0.6562139 0.6588974 0.3677467 -0.8338486 0.275548 -0.4782988 -0.8155025 0.1282423 0.5643666 -0.8960246 -0.1582928 -0.4148293 -0.9241157 -0.3028524 0.2330036 -0.7565336 -0.5397667 -0.3692004 -0.7274441 -0.609645 0.3148941 -0.3859554 -0.9155789 0.112933 -0.2281743 -0.7881174 -0.571671 0.1417367 -0.8424598 0.5197811 0.3356527 -0.8073197 -0.4853579 0.5345509 -0.767619 0.3535768 0.7041317 -0.5674826 -0.4268047 0.7499182 -0.3768606 0.54369 0.8322754 -0.1690545 -0.5279567 0.87379 0.1181837 0.4717242 0.8541913 0.3096341 -0.4177131 0.7602557 0.5022888 0.4119677 0.6516692 0.6713414 -0.3530272 0.4578487 0.8224695 0.337518 0.337934 0.8852438 -0.3196 -0.02496439 0.9442271 0.3283474 -0.1483078 0.9033184 -0.4025182 -0.4481776 0.7513123 0.4844242 -0.6073204 0.6086375 -0.5106098 -0.729282 0.435429 0.5277778 -0.8720198 0.2689425 -0.4089638 -0.9783799 -0.1388678 0.1532602 -0.1974311 0.256044 0.9462888 -0.752694 0.3495528 0.5579112 -0.4318091 0.1463896 0.8900062 -0.4230713 -0.01008927 0.9060403 -0.770147 -0.2357264 0.5927113 -0.4150767 -0.2095955 0.8853141 -0.3065213 -0.4831007 0.8201577 -0.3026413 -0.4806513 0.8230325 -0.1692215 -0.6253993 0.7617349 0.007129311 -0.561782 0.8272548 0.04123073 -0.5985596 0.8000165 0.279654 -0.4644884 0.8402643 0.1974971 -0.4086526 0.8910657 0.4971973 -0.3416417 0.7975437 0.433597 -0.2397629 0.8686239 0.6076255 -0.1120492 0.7862801 0.6221699 0.06545048 0.7801415 0.5554486 -0.05406308 0.8297916 0.4478555 0.2327744 0.8632738 0.5114096 0.3659176 0.7775376 0.3280399 0.377074 0.8661439 0.3148793 0.4582838 0.8311601 0.1478324 0.489448 0.8594104 0.1365384 0.5291422 0.8374759 -0.03014111 0.6152008 0.7877941 -0.1336282 0.4545115 0.8806605 -0.2187719 0.5202158 0.8255389 -0.4169268 0.4320616 0.7996842 -0.368703 0.2808269 0.8861119 -0.5148611 0.2441479 0.8217725 -0.5268955 0.06424909 0.8474983 -0.5156248 0.06893956 0.8540366 -0.5775357 -0.1653474 0.7994453 -0.4546547 -0.1964173 0.8687401 -0.4676683 -0.3628262 0.8060047 -0.3341215 -0.3597804 0.8711606 -0.3027405 -0.5154719 0.8016464 -0.1368902 -0.5118036 0.8481263 -0.1093458 -0.5711845 0.813506 0.07537508 -0.5220551 0.8495747 0.108319 -0.5563105 0.8238845 0.2992762 -0.4737657 0.828239 0.2930115 -0.4289618 0.85448 0.4609777 -0.3360612 0.8213175 0.4213336 -0.2240566 0.8787928 0.5826147 -0.1754715 0.7935805 0.6273843 -0.01312804 0.7785992 0.4735559 0.06114757 0.8786386 0.5541861 0.2435888 0.7959538 0.4331156 0.2827842 0.8558295 0.433741 0.4146809 0.7999428 0.2530696 0.352049 0.90112 0.1246988 0.5671899 0.814092 0.05878961 0.4965955 0.8659889 -0.07877826 0.5953389 0.7996034 -0.166356 0.4879086 0.8568961 -0.2336895 0.5226185 0.8199142 -0.3856782 0.3787007 0.8413311 -0.3609976 0.2932932 0.8852456 -0.6467873 0.24996 0.7205458 -0.4652101 0.01649153 0.8850467 -0.5905473 -0.09026461 0.8019391 -0.454737 -0.2466288 0.8557971 -0.4918211 -0.2499845 0.8340382 -0.3881964 -0.4182361 0.8212077 -0.2806332 -0.3969043 0.8739062 -0.2472139 -0.5323615 0.8096151 -0.05805349 -0.5416629 0.8385888 -0.0393818 -0.5063537 0.8614261 0.1671363 -0.5891301 0.790564 0.2225031 -0.4262765 0.8768015 0.3292647 -0.4521927 0.8289189 0.4158857 -0.3228633 0.8501756 0.4377976 -0.3244391 0.8384943 0.5791265 -0.1833511 0.7943519 0.489768 -0.08257687 0.8679335 0.6066561 0.05279219 0.7932096 0.4804435 0.1443719 0.8650611 0.5496655 0.2810743 0.7866798 0.3952828 0.3271094 0.8583421 0.3793265 0.5550479 0.7402928 0.1654609 0.5384633 0.8262445 0.1283347 0.5938321 0.7942882 0.01040029 0.4792186 0.8776341 -0.1711103 0.614946 0.7697809 -0.2735668 0.4428231 0.8538554 -0.2710188 0.4316572 0.8603609 -0.4901478 0.3612927 0.7932358 -0.4600561 0.1685417 0.8717465 -0.4746313 0.1816854 0.8612291 -0.5828387 -0.01228505 0.8124951 -0.4655322 -0.06832736 0.8823895 -0.5734975 -0.2914316 0.7656163 -0.3517506 -0.3184255 0.8802708 -0.3571737 -0.4349724 0.8265749 -0.1965851 -0.4951366 0.8462826 -0.1953648 -0.5030993 0.8418573 -0.03790616 -0.6255232 0.7792843 0.08384877 -0.4768198 0.8749928 0.1620341 -0.5289441 0.8330446 0.2979668 -0.4389858 0.8476482 0.3016842 -0.4406802 0.8454513 0.5026637 -0.3716767 0.7805035 0.4458689 -0.2152937 0.8688208 0.5743056 -0.1505323 0.8046821 0.4982682 -0.004714012 0.8670101 0.5747961 0.05641067 0.8163501 0.5654317 0.2175472 0.795588 0.3979795 0.2604154 0.8796568 0.4226242 0.3290615 0.8444569 0.3502931 0.5257341 0.7751765 0.2550665 0.4846545 0.8366906 0.1267417 0.6554127 0.7445608 -0.06323397 0.5432751 0.83717 -0.1164043 0.5937541 0.7961823 -0.2198464 0.4583118 0.8611725 -0.3872256 0.5105246 0.7677376 -0.4976962 0.2824455 0.820075 -0.5221185 0.2780475 0.8062766 -0.4830514 0.101858 0.8696473 -0.5476902 0.07349491 0.8334472 -0.6245911 -0.1184889 0.7719108 -0.4346121 -0.1843866 0.8815408 -0.4941211 -0.3419113 0.7993379 -0.3796329 -0.3398346 0.8604599 -0.2586186 -0.6054505 0.7526926 -0.1246917 -0.5043266 0.8544629 0.04391711 -0.6087915 0.7921138 0.07577311 -0.5287824 0.8453683 0.2044566 -0.5251033 0.8261138 0.2230957 -0.3749176 0.899814 0.5036811 -0.3921176 0.7697723 0.4316295 -0.213881 0.8763281 0.5007257 -0.1894472 0.8446204 0.487946 0.06165635 0.8706935 0.5427611 0.05060929 0.838361 0.46865 0.333987 0.8178141 0.4908507 0.3389375 0.8026127 0.3433684 0.550055 0.7612737 0.2056971 0.4882906 0.8480927 0.0909624 0.6014362 0.7937257 0.01679384 0.4964267 0.8679162 -0.1692565 0.5599554 0.8110501 -0.1916044 0.473339 0.8597896 -0.41675 0.491393 0.7647564 -0.3950448 0.286288 0.872914 -0.522288 0.2728319 0.8079468 -0.5370922 0.09741151 0.8378801 -0.4786028 0.06368148 0.8757191 -0.5139865 -0.1840652 0.8378174 -0.5462923 -0.1828126 0.8174009 -0.3952057 -0.3354513 0.855152 -0.3819842 -0.3328592 0.8621443 -0.3150874 -0.511039 0.7997244 -0.1531324 -0.4672709 0.8707517 -0.140516 -0.4970887 0.8562467 0.06831824 -0.4929432 0.8673753 0.0473113 -0.4615303 0.885862 0.3179832 -0.5089481 0.7999116 0.3318566 -0.4269707 0.8411703 0.5340763 -0.4230354 0.731986 0.516704 -0.1734765 0.838405 0.5554679 -0.1589521 0.8162046 0.5383056 0.04271656 0.8416664 0.4591598 0.07887482 0.8848452 0.5598073 0.2306933 0.7958621 0.4559661 0.385869 0.8019976 0.3266934 0.3489796 0.878342 0.2782868 0.5248975 0.8043875 0.1286523 0.4883553 0.8631094 0.08770984 0.5704976 0.8166025 -0.1477718 0.518496 0.8422145 -0.08573484 0.4484433 0.8896899 -0.3395895 0.5272853 0.778877 -0.423308 0.3563863 0.8329461 -0.4069364 0.329795 0.8518439 -0.5660244 0.1266899 0.8145956 -0.5398674 0.1063504 0.8350047 -0.5544826 -0.08870077 0.8274548 -0.5049119 -0.1048948 0.8567736 -0.5401316 -0.3229869 0.7771341 -0.3738471 -0.3430789 0.8617049 -0.3730402 -0.4270653 0.8236845 -0.1925644 -0.5045423 0.841639 -0.1945928 -0.4903445 0.8495269 -0.01523804 -0.6129275 0.7899923 0.08556067 -0.4729095 0.8769471 0.1818625 -0.5320744 0.8269358 0.3035898 -0.4376139 0.8463613 0.3321632 -0.449945 0.8289857 0.4960172 -0.3693737 0.7858308 0.4271838 -0.1606562 0.8897773 0.4994288 -0.1444189 0.854233 0.6354043 0.02708411 0.7717046 0.4687956 0.1670413 0.8673685 0.5282048 0.1681067 0.83231 0.402684 0.3938 0.8262973 0.3861809 0.3881326 0.83679 0.2281787 0.5208801 0.8225682 0.1825932 0.4760934 0.8602295 -0.05446064 0.6257049 0.7781565 -0.09393459 0.522836 0.847242 -0.3060328 0.5887342 0.7481551 -0.3957803 0.4086238 0.822426 -0.4052934 0.4094532 0.817365 -0.5121552 0.2926175 0.8075097 -0.463598 0.1894189 0.865562 -0.5864121 0.112123 0.8022153 -0.5176859 -0.002645432 0.8555667 -0.5916424 -0.09675288 0.8003738 -0.4699129 -0.2018461 0.8593254 -0.5064998 -0.3083547 0.8052176 -0.3504176 -0.3739202 0.858715 -0.3502281 -0.3720083 0.8596221 -0.1683803 -0.4889247 0.855921 -0.1150383 -0.4281951 0.8963342 0.03990805 -0.586893 0.8086804 0.1416355 -0.516815 0.8442995 0.2111015 -0.5655125 0.7972652 0.4777955 -0.4086582 0.7776312 0.4965396 -0.412557 0.7637048 0.4693485 -0.148946 0.8703604 0.5244181 -0.1315269 0.841241 0.5787313 0.05525052 0.8136446 0.4579958 0.1213883 0.8806275 0.5509743 0.2652289 0.7912529 0.3957925 0.4298701 0.8115171 0.2888813 0.375387 0.8806999 0.1798515 0.613722 0.7687646 0.02912658 0.499104 0.8660525 -0.05303162 0.5862609 0.8083847 -0.1831577 0.4612109 0.8681807 -0.3229084 0.5382559 0.7784669 -0.435415 0.3011369 0.8483693 -0.4601313 0.3350244 0.8222152 -0.5202569 0.1776891 0.8353199 -0.4261986 0.08245843 0.9008638 -0.6249727 -0.1232727 0.7708521 -0.5382422 -0.154398 0.8285269 -0.5510114 -0.3485514 0.7582206 -0.2969608 -0.346617 0.889759 -0.2767313 -0.574435 0.7703534 -0.1125843 -0.4867169 0.8662746 -0.04516988 -0.5866584 0.8085739 0.1090353 -0.5032491 0.857235 0.1512027 -0.5404615 0.827671 0.3609082 -0.4302691 0.827414 0.3444435 -0.3648439 0.8650132 0.5146216 -0.3012384 0.8027577 0.4605396 -0.1664265 0.8718977 0.5991108 -0.09328955 0.7952128 0.5263468 0.1080662 0.8433747 0.4941591 0.1148691 0.8617493 0.5188346 0.3247208 0.7908015 0.3483538 0.329333 0.8776044 0.3488541 0.5216028 0.7786086 0.1215654 0.5247457 0.8425343 0.0952385 0.4865238 0.8684609 -0.0898959 0.6135768 0.7845013 -0.1857823 0.4784484 0.8582378 -0.2466012 0.5055181 0.8268249 -0.3953624 0.380055 0.8362098 -0.3811461 0.3768029 0.8442437 -0.551502 0.2332682 0.8008943 -0.4904143 0.1525305 0.8580374 -0.5937644 0.02216643 0.8043337 -0.4715536 -0.05490756 0.8801264 -0.5744696 -0.2527636 0.7785212 -0.3878512 -0.3079452 0.8687584 -0.40952 -0.4286848 0.8053091 -0.2065272 -0.499041 0.8416084 -0.1838342 -0.4761446 0.8599368 0.01652824 -0.6280352 0.7780094 0.07769858 -0.4339823 0.8975646 0.3015624 -0.4650726 0.8323267 0.3015997 -0.4062986 0.8625307 0.5274265 -0.3882536 0.7556988 0.5173999 -0.1254413 0.8464998 0.4535059 -0.1424297 0.879799 0.627282 0.06277453 0.7762582 0.3742273 0.137102 0.9171462 0.4919936 0.3825915 0.782027 0.2753113 0.4354223 0.8570946 0.295882 0.4507256 0.8421998 0.1165171 0.5656927 0.8163428 0.0351991 0.4846581 0.8739953 -0.07105064 0.6006324 0.7963622 -0.259391 0.5254544 0.8103172 -0.2483133 0.3722885 0.8942828 -0.4491675 0.4048582 0.7964537 -0.5282679 0.2073721 0.823365 -0.4336886 0.1067011 0.8947229 -0.5964982 0.01603585 0.8024542 -0.5083611 -0.2199477 0.8325816 -0.4551065 -0.2197068 0.8629062 -0.418833 -0.4544075 0.7861887 -0.3132233 -0.4219344 0.8508012 -0.2401446 -0.5511728 0.7990864 -0.07941031 -0.4774681 0.8750534 -0.001991212 -0.6004089 0.7996908 0.1768879 -0.5276347 0.8308504 0.1875492 -0.4047222 0.8950001 0.4044361 -0.4700862 0.7845064 0.5062136 -0.3491966 0.7885491 0.4287875 -0.2056043 0.8796977 0.5942032 -0.1345553 0.7929802 0.4867308 0.03694659 0.8727705 0.4870486 0.03686547 0.8725965 0.4494845 0.3221332 0.8331831 0.4923258 0.3332094 0.8041063 0.3260856 0.5572286 0.7636521 0.218571 0.5013975 0.8371543 0.0721786 0.5648909 0.8220028 0.05443185 0.5380622 0.8411459 -0.1300253 0.5554214 0.8213407 -0.1462128 0.4660145 0.8726124 -0.4442472 0.4694483 0.7630615 -0.3804348 0.3102762 0.871205 -0.5344281 0.2362667 0.8115199 -0.4864009 0.1130719 0.8663885 -0.5959201 0.02438682 0.8026734 -0.5074196 -0.09583717 0.8563531 -0.5503275 -0.153117 0.8207892 -0.4738857 -0.3075349 0.8251392 -0.3553925 -0.2958186 0.8866722 -0.3603792 -0.502925 0.7856165 -0.1448026 -0.5346729 0.8325606 -0.09216904 -0.4649078 0.8805485 0.07578051 -0.633408 0.7700985 0.1895953 -0.4465445 0.8744437 0.3380252 -0.5053511 0.7939518 0.3903368 -0.3164055 0.8645951 0.4659141 -0.3226922 0.8238895 0.5945239 -0.1329076 0.7930176 0.4729523 -0.03209018 0.8805036 0.5798426 0.08575904 0.8102025 0.4696854 0.2095214 0.857611 0.4930117 0.2534652 0.8322829 0.357486 0.3919156 0.8477064 0.3622574 0.4259172 0.8290743 0.1549925 0.5567279 0.8161075 0.1699706 0.4459885 0.8787516 -0.03331243 0.6161313 0.7869388 -0.1529229 0.4554161 0.8770466 -0.2622372 0.5256222 0.8092918 -0.410874 0.3499191 0.8418666 -0.3783886 0.3431239 0.8597024 -0.5952354 0.1951737 0.7794885 -0.44152 0.08319264 0.8933864 -0.5301 -0.1191249 0.8395256 -0.4786329 -0.1399223 0.8667943 -0.5455918 -0.353631 0.759786 -0.2988079 -0.3713084 0.8791154 -0.3066155 -0.454369 0.8363825 -0.1559819 -0.627282 0.7630118 -0.01870608 -0.4799385 0.8771027 3.1073e-4 -0.4981523 0.8670895 0.2119066 -0.4888277 0.8462524 0.2193905 -0.4610155 0.8598445 0.3863794 -0.4596474 0.799647 0.3591155 -0.3151893 0.87846 0.657234 -0.2193691 0.7210553 0.4877488 -0.07264542 0.8699563 0.5742902 0.05433821 0.8168465 0.4517402 0.1451489 0.8802629 0.5444877 0.3033663 0.781986 0.2730647 0.4000613 0.8748639 0.2721908 0.3945646 0.877628 0.1282898 0.6646487 0.7360597 -0.05318814 0.48313 0.8739317 -0.1208324 0.5526509 0.8246069 -0.2938619 0.4864191 0.8228254 -0.2963669 0.3874214 0.8729671 -0.4479961 0.3971444 0.8009842 -0.5260932 0.2185381 0.8218681 -0.4850618 0.1759456 0.8565969 -0.5744357 0.02768093 0.8180816 -0.4752225 -0.0464313 0.8786397 -0.5868299 -0.2022846 0.7840356 -0.4158004 -0.3431712 0.8422254 -0.3968808 -0.3370214 0.8537577 -0.2865636 -0.5152709 0.8076988 -0.2023621 -0.4650673 0.8618365 -0.06902414 -0.6356157 0.7689138 0.1121053 -0.4581062 0.8817999 0.1047565 -0.5519124 0.8272961 0.3453976 -0.4350371 0.8315306 0.3347038 -0.3923658 0.8567512 0.5429862 -0.298823 0.7847744 0.4722905 -0.1660708 0.8656572 0.5732631 -0.09818583 0.8134673 0.4982573 0.04177188 0.8660225 0.5629776 0.1100391 0.8191141 0.5488475 0.2548791 0.7961175 0.4130179 0.2695448 0.8699206 0.4228155 0.4143868 0.8059222 0.2747203 0.5879194 0.7608414 0.3235973 0.4363602 0.8395681 0.04490709 0.6075606 0.7930029 0.0641545 0.5743674 0.8160799 -0.1122779 0.5669696 0.816051 -0.143961 0.4612594 0.8755084 -0.2933717 0.5138959 0.806129 -0.4019839 0.3385699 0.8507522 -0.3955898 0.3237935 0.8594572 -0.5479871 0.2137821 0.8087072 -0.5036212 0.1234006 0.8550661 -0.5874578 0.07132256 0.8061058 -0.5489124 -0.1527692 0.821801 -0.4560446 -0.1663984 0.8742625 -0.4911237 -0.3379436 0.8028647 -0.3045114 -0.3950098 0.8667411 -0.3068509 -0.4205171 0.8538196 -0.1502982 -0.5862419 0.7960723 -0.03061038 -0.4770697 0.8783323 0.05082684 -0.58234 0.8113549 0.2529726 -0.4536036 0.8545459 0.3631165 -0.5102102 0.7796359 0.4129713 -0.2964967 0.8611298 0.4119299 -0.2965641 0.8616052 0.5081575 -0.1184917 0.8530743 0.5321751 -0.1566214 0.8320213 0.6658576 0.06056904 0.7436162 0.5091591 0.1521377 0.8471194 0.5370532 0.2685014 0.7996756 0.3757655 0.3042382 0.8753511 0.3992779 0.4401731 0.8042542 0.184143 0.5582299 0.8089937 0.1380681 0.5018582 0.8538593 -0.05296349 0.6031423 0.7958732 -0.1039811 0.4869878 0.8671972 -0.2962179 0.5363886 0.7902799 -0.3370227 0.3158292 0.8869429 -0.3914759 0.4285503 0.8143042 -0.4780184 0.2131011 0.852107 -0.5061409 0.2082 0.8369433 -0.5880603 -0.00433588 0.8088055 -0.510306 -0.04332435 0.858901 -0.5545058 -0.20986 0.805284 -0.4040922 -0.2312195 0.8850124 -0.4307852 -0.5314235 0.7293924 -0.1608112 -0.4813998 0.861623 -0.1766345 -0.417101 0.8915308 0.02622777 -0.628633 0.7772598 0.2226535 -0.5249835 0.8214729 0.1409559 -0.4673714 0.8727517 0.3385809 -0.4589061 0.8214428 0.3200447 -0.3218896 0.8910435 0.4617751 -0.2917055 0.8376585 0.4969714 -0.1552863 0.8537597 0.5477243 -0.1428517 0.8243734 0.5980967 0.08447396 0.7969596 0.5318656 0.2013462 0.8225441 0.5005363 0.1327143 0.8554825 0.3991682 0.3445909 0.8496599 0.4077977 0.3819547 0.8293442 0.2574111 0.4965585 0.8289567 0.2306106 0.4769948 0.8481124 0.06588435 0.5952947 0.8008018 -0.03035515 0.4804034 0.8765223 -0.1452171 0.5870209 0.7964412 -0.330099 0.4798948 0.8128566 -0.2837122 0.3574084 0.8898128 -0.5000391 0.197003 0.8432976 -0.4837883 0.1978838 0.8525203 -0.5807269 0.01697647 0.8139215 -0.5444839 -0.01150566 0.8386924 -0.6223354 -0.1388 0.7703461 -0.4966604 -0.3325415 0.8017137 -0.4394469 -0.3273713 0.8364894 -0.3804529 -0.5271798 0.7598271 -0.1834479 -0.4550648 0.8713569 -0.1434552 -0.5926287 0.7925981 0.089742 -0.5603076 0.8234086 0.1071276 -0.481927 0.8696379 0.2677559 -0.5760481 0.7723182 0.3637506 -0.4046915 0.8389936 0.3540948 -0.3835996 0.8529176 0.6679441 -0.3564202 0.6533111 0.7226694 -0.4077372 0.5581212 0.9875733 -0.05803149 -0.1460525 0.1969411 -0.9077708 -0.3703597 0.5205317 -0.8432695 0.133953 0.7003138 0.2094489 -0.6824162 0.5822479 0.4186607 0.6969295 0.6549925 0.7444021 0.1298088 0.1811728 0.8574763 -0.4815711 -0.4490453 0.1901006 0.8730522 -0.5727759 -0.4136138 0.7077087 -0.4926618 -0.6218603 -0.6087482 -0.2963875 -0.7022963 0.6472514 0.3932402 -0.5539837 -0.7338013 0.5900662 -0.4570907 0.6654998 0.731965 -0.1167712 -0.6712614 0.6585337 0.09030735 0.7471131 -0.7643579 -0.0201658 -0.6444768 -0.638567 -0.2308167 0.7341361 -0.04910063 -0.7002545 -0.7122027 0.1129071 -0.7736526 0.6234692 0.3278014 -0.5779281 -0.747359 -0.3820447 -0.6357579 -0.6707115 -0.2312635 -0.756053 0.6122917 0.02232587 -0.6656076 -0.7459679 0.3387848 -0.3005176 0.8915796 -0.6975625 0.05896401 -0.7140938 -0.7268846 -0.145179 0.6712391 -0.6420435 -0.5366253 -0.5475524 -0.3967429 -0.8367115 0.3775036 0.05883198 -0.8488593 0.5253349 0.398029 -0.6480756 -0.6492849 0.9349684 0.2018809 -0.2916818 0.7834731 0.6197007 0.0462718 0.5943367 0.2169589 -0.7743985 0.6200599 0.4500948 0.6426044 -0.3794106 0.4081259 0.8303499 -0.7053722 0.2134667 0.6759306 -0.6612455 -0.1244439 -0.7397758 0.1943049 -0.5060681 -0.8403218 0.4109222 -0.1540148 0.8985669 0.2820476 -0.4112448 0.8667911 0.4715441 -0.1607602 -0.8670654 -0.3515767 -0.422402 0.8354463 0.4502828 -0.3431705 -0.8243054 -0.6272801 0.7645341 0.1483498 -0.8140963 0.3124798 -0.4894932 0.9374025 0.3377165 -0.0849958 0.5354803 0.342891 0.7718073 0.6719865 0.616774 0.4099075 0.7586651 0.6125273 0.2218959 0.5734093 0.2870072 0.7673518 0.7204042 0.2960609 0.6271889 0.8923854 0.402558 0.2039495 0.2506954 0.05293089 0.9666179 0.8116101 0.07167416 0.5797863 0.5732039 3.13327e-4 0.8194128 0.729056 0.01997351 0.6841627 0.9411848 0.08310341 0.3275138 0.9984336 -0.05529618 -0.008535563 0.4785956 -0.1015181 0.872147 0.8935803 -0.1985548 0.4026044 0.9212069 -0.2056906 0.3302564 0.6162185 -0.2559111 0.7448384 0.627815 -0.2623554 0.7328152 0.9232319 -0.383596 -0.02229553 0.7492188 -0.46862 0.4680454 0.1465941 -0.1400998 0.9792254 0.7348895 -0.4986382 0.459671 0.2014383 -0.2332211 0.951331 0.487915 -0.5408877 0.6851128 0.4487842 -0.519909 0.7268339 0.7176748 -0.6963555 0.005656898 0.6127821 -0.7417459 0.2726008 0.1940736 -0.5050732 0.8409736 0.3366469 -0.685352 0.6457256 0.2388914 -0.6317303 0.7374604 0.4519873 -0.8743147 0.1768651 0.4092081 -0.9119303 -0.03052753 0.1454834 -0.7932962 0.5911986 0.1558244 -0.8830938 0.4425656 0.02875345 -0.2636058 0.9642019 -0.01600497 -0.6008635 0.7991915 -0.08681476 -0.6648293 0.7419335 -0.0349375 -0.9993843 -0.003236114 -0.1703922 -0.5932658 0.786767 -0.1432765 -0.9280002 0.3439297 -0.1448823 -0.2814753 0.9485678 -0.3226947 -0.7022181 0.6346321 -0.3803179 -0.5375403 0.7526013 -0.3801697 -0.8773932 0.2926642 -0.03225666 -0.03881633 0.9987256 -0.451852 -0.888293 0.08225154 -0.4151353 -0.5419524 0.7307191 -0.4630112 -0.478506 0.7460916 -0.5784048 -0.7672678 0.2770344 -0.3081824 -0.213612 0.9270348 -0.7187739 -0.6907587 0.07884478 -0.7277464 -0.5471774 0.4134999 -0.7552611 -0.5044807 0.4184257 -0.601953 -0.2420341 0.7609678 -0.604757 -0.2432872 0.7583405 -0.8889089 -0.4262222 0.1678566 -0.8685773 -0.2459914 0.4301882 -0.9259592 -0.1629089 0.3406763 -0.4075661 -0.04038745 0.9122822 -0.1005544 0.01057475 0.9948754 -0.9939418 -0.1037865 0.03616744 -0.6908474 0.0270754 0.7224935 -0.7579165 0.1345907 0.6383165 -0.8950143 0.1976369 0.3998615 -0.9582211 0.1693723 0.2304894 -0.5123617 0.1989904 0.8353971 -0.5801853 0.3435704 0.7384744 -0.8660486 0.3773552 0.3279681 -0.884647 0.431021 0.1778221 -0.586335 0.3362008 0.7370077 -0.3270453 0.2960897 0.8974254 -0.6847425 0.6225113 0.3789558 -0.7516322 0.6252535 0.2100168 -0.3631922 0.4336702 0.8246343 -0.578807 0.6686789 0.4667451 -0.2026742 0.4241614 0.8826156 -0.5295087 0.7732188 0.3489319 -0.2144001 0.5953665 0.77432 -0.4075461 0.8158705 0.4101971 -0.1717861 0.6309273 0.7565846 -0.3199152 0.9401344 0.1174811 -0.1259537 0.8920465 0.4340379 0.01846534 0.1695984 0.9853403 -0.002060055 0.4369764 0.8994706 -0.04237836 0.9243625 0.3791547 -0.04802864 0.9139486 0.4029782 0.07845127 0.7088511 0.7009819 0.07379794 0.995207 0.0641635 0.2052996 0.747752 0.6314421 0.2343817 0.9009754 0.3651148 0.2652201 0.6633762 0.6997074 0.2888903 0.6611524 0.6924016 0.4714504 0.8814079 -0.02923762 0.3455743 0.5559629 0.7559654 0.2158704 0.2407979 0.9462645 0.4758712 0.8780748 -0.05031388 0.5978012 0.6728239 0.435823 0.01425617 -5.0702e-4 0.9998983 -0.01401036 -0.003149986 0.9998969 0.001997828 0.00171405 0.9999966 0.003300964 0.00317955 0.9999896 0.001918613 0.003210604 0.999993 -4.82696e-4 7.25729e-4 0.9999997 0.002802073 0.001478075 0.999995 -0.004490613 6.62234e-4 0.9999897 -0.624287 -0.578271 0.5252318 -0.2965245 -0.2840859 0.9117941 -0.3036679 -0.2882336 0.908134 -0.6155406 -0.742676 0.2637084 -0.4636865 -0.6939032 0.5509023 -0.3553521 -0.5365828 0.7653782 -0.2406463 -0.4752514 0.8463011 -0.3820744 -0.847833 0.3676932 -0.2621045 -0.7290152 0.6323275 -0.223713 -0.59788 0.769735 -0.183959 -0.8598806 0.4761979 -0.06422597 -0.3682035 0.9275243 -0.07764804 -0.7759181 0.6260367 -0.02059519 -0.8901512 0.4551997 -0.05124431 -0.5321714 0.8450845 0.119448 -0.8437028 0.5233525 0.1236423 -0.8278517 0.547151 0.08319634 -0.5592057 0.824844 0.09040045 -0.3953009 0.9140926 0.3170871 -0.8305579 0.4578532 0.201991 -0.4812684 0.8529831 0.3191305 -0.7430699 0.5882201 0.1735797 -0.2981974 0.9385886 0.5454245 -0.721823 0.426009 0.5147023 -0.6085165 0.6039779 0.3755359 -0.4339494 0.8189387 0.3118532 -0.2832363 0.9069315 0.7516368 -0.5582163 0.3513357 0.7034113 -0.4501131 0.5501008 0.6095587 -0.3910679 0.6895681 0.8438816 -0.3761498 0.3825901 0.7870993 -0.2788408 0.5502024 0.4383805 -0.1543576 0.8854357 0.9103777 -0.1864286 0.3694006 0.3507919 -0.1057861 0.9304593 0.778873 -0.07345008 0.6228659 0.5182854 -0.05583125 0.8533834 0.8629909 0.01202815 0.5050764 0.7380814 0.09235501 0.668361 0.4401003 0.008223414 0.897911 0.7581405 0.13453 0.6380633 0.1202845 0.01873344 0.9925627 0.664232 0.1909437 0.7227285 0.7036038 0.3006808 0.6438422 0.6501213 0.3255864 0.686539 0.7596963 0.5200558 0.3903889 0.3379726 0.2256033 0.9137164 0.653598 0.584367 0.4809626 0.6664825 0.644778 0.3742492 0.08155906 0.06374973 0.9946277 0.4752635 0.4395298 0.762193 0.4988918 0.7286178 0.4692794 0.3210363 0.3950906 0.8607201 0.4647072 0.6973787 0.5456283 0.3314639 0.4617153 0.8227701 0.2741889 0.6825845 0.6774207 0.1829302 0.3802378 0.9066178 0.2592328 0.7712628 0.5813367 0.1617988 0.7642233 0.6243267 0.1148897 0.9091148 0.4003883 0.02912127 0.1126347 0.9932096 0.04606533 0.4436145 0.8950331 -0.0427742 0.8534715 0.5193812 -0.06739181 0.7056987 0.7052998 -0.092835 0.6727725 0.7340019 -0.2597323 0.8442898 0.4687365 -0.3286044 0.7120099 0.6205329 -0.09953641 0.4150086 0.9043563 -0.3497008 0.7081509 0.6133772 -0.3432267 0.548855 0.7622033 -0.05487823 0.0817272 0.9951428 -0.5432498 0.583433 0.6037266 -0.5009822 0.5388984 0.6772043 -0.4543218 0.4307296 0.7797846 -0.4851961 0.3956134 0.7797915 -0.7196838 0.4361425 0.5402175 -0.3385241 0.1836726 0.9228575 -0.6995443 0.3173245 0.6402679 -0.7495068 0.303948 0.5880947 -0.1578454 0.06351786 0.9854189 -0.752061 0.1898956 0.631145 -0.6548053 0.1199147 0.7462242 -0.6825582 0.04377186 0.7295193 -0.8840182 0.01362287 0.467254 -0.5091969 -0.02533954 0.860277 -0.9226197 -0.1605578 0.3507053 -0.1548812 -0.03111529 0.9874431 -0.8200836 -0.1784241 0.5437167 -0.7327509 -0.291363 0.6149665 -0.6402925 -0.2890692 0.7116632 -0.6135691 -0.2794489 0.73854 -0.7699343 -0.5613886 0.3033876 -0.7528767 -0.6580779 -0.01049405 -0.6362336 -0.7714429 0.009094178 -0.5556539 -0.8313736 -0.00816828 -0.3570321 -0.9340844 -0.003802657 -0.3983391 -0.9172287 0.004190802 -0.2215394 -0.9751514 -4.74516e-4 -0.2045395 -0.9788556 0.002363383 -0.0547133 -0.9985019 -6.72922e-4 -0.04397153 -0.9990322 0.001073598 0.1229237 -0.9924141 -0.002034187 0.1537974 -0.9880983 0.002878487 0.2964494 -0.9550457 -0.002380073 0.4018948 -0.9156779 -0.003821194 0.3541256 -0.9351895 0.003984153 0.5181335 -0.8552745 -0.006582856 0.601076 -0.7991472 0.008453249 0.6891771 -0.7245361 -0.009079098 0.7998437 -0.6001781 0.006019294 0.8326337 -0.5538119 -0.003684878 0.9156011 -0.4020877 -2.49179e-4 0.9143432 -0.4049397 -8.22549e-4 0.9726683 -0.2320836 -0.007333755 0.9827311 -0.1850223 0.00251913 0.9998127 0.01932716 -0.001106381 0.9999105 0.01310783 -0.002660572 0.9811154 0.1932825 0.007380962 0.9570239 0.2899404 -0.00631231 0.9163171 0.4004276 0.004558801 0.9242439 0.3818026 1.59781e-4 0.8166701 0.5770827 -0.005058467 0.8444017 0.5356976 0.003726363 0.7116532 0.7025277 0.002120733 0.6787462 0.7343546 -0.005193352 0.5797129 0.8148155 -0.002997756 0.5404776 0.8413394 0.005656123 0.4030055 0.9151885 -0.004071593 0.3420482 0.9396762 0.003426611 0.2925741 0.9562405 -0.002110242 0.08549946 0.9963232 -0.00548309 0.13872 0.9903225 0.004269421 -0.03033167 0.9995278 -0.004941463 -0.09973436 0.9950001 0.005275189 -0.2004143 0.9797108 -0.001012146 -0.2667915 0.9637371 0.005763053 -0.3802849 0.9248431 -0.006974399 -0.5060008 0.8624935 0.008256077 -0.4894724 0.8720124 0.003349542 -0.6360664 0.7715923 0.008062243 -0.6835907 0.7298582 -0.003304779 -0.7794528 0.6264507 0.003593742 -0.8179773 0.5752503 6.30899e-4 -0.8338721 0.5519292 0.005618631 -0.9289026 0.3703176 -0.002201735 -0.9227105 0.3854922 0.001055359 -0.9772219 0.2122153 -0.001442909 -0.9796208 0.2008558 5.63329e-4 -0.9987282 0.05041837 1.92076e-4 -0.9987785 0.04941195 3.82962e-4 -0.984336 -0.1763032 -1.91422e-4 -0.9846569 -0.1745007 -6.46237e-4 -0.9073915 -0.4202572 -0.00497502 -0.9249266 -0.3801266 0.003797531 -0.8177123 -0.5755693 0.008158743 -0.02908241 0.003802061 0.9995698 0.002589046 0.01845693 0.9998264 0.02040207 0.004072248 0.9997836 -0.01458609 0.01629006 0.999761 0.01939773 4.04548e-4 0.9998118 -0.003255963 0.01957231 0.9998032 -0.01587027 -0.01514887 0.9997593 0.01138961 0.004327237 0.9999259 0.01157534 -0.01607328 0.9998039 -0.002384245 0.001469552 0.9999961 -0.005724012 2.48308e-4 0.9999836 0.004160106 0.005444407 0.9999766 0.001370131 5.19644e-4 0.999999 -0.00552082 0.001326143 0.999984 0.001682341 -0.01026141 0.999946 -0.007442593 0.002446293 0.9999693 0.009424149 -0.003911972 0.999948 0.01191818 0.004656374 0.9999182 0.022394 0.01127851 0.9996857 -0.004428088 -0.0109511 0.9999303 0.008312165 -0.0133804 0.999876 -0.01033085 -0.00930655 0.9999034 -0.007681131 -0.008960783 0.9999305 0.007921218 -0.0134871 0.9998778 -8.02487e-4 -0.02342927 0.9997253 -0.02526205 -0.001251459 0.9996802 -0.001945316 -0.02363479 0.9997189 -0.3281369 -0.2780834 -0.9027713 -0.5015104 -0.2609137 -0.8248705 -0.7263336 -0.3812748 -0.5718997 -0.5558415 -0.2760949 -0.7840994 -0.8516194 -0.3933681 -0.3464187 -0.5650327 -0.1540772 -0.8105544 -0.8294973 -0.1906769 -0.5249538 -0.891165 -0.1685065 -0.4212251 -0.3027278 -0.03169739 -0.9525499 -0.795143 0.02125948 -0.6060493 -0.749194 0.03326022 -0.6615151 -0.06098729 0.002173125 -0.9981362 -0.7487668 0.1706366 -0.6404932 -0.6857665 0.1967639 -0.7007199 -0.572478 0.1854207 -0.798679 -0.8471358 0.3616079 -0.3893595 -0.4958739 0.2740909 -0.8240045 -0.7370496 0.4212294 -0.5285108 -0.5261184 0.3069264 -0.7930924 -0.7800748 0.5443812 -0.3084356 -0.6093583 0.5560318 -0.5652531 -0.4781836 0.4230522 -0.769654 -0.6360542 0.7035779 -0.3168805 -0.2409844 0.285671 -0.9275336 -0.5052818 0.7394822 -0.4448106 -0.2872965 0.4403366 -0.8506259 -0.4659514 0.7125666 -0.5245363 -0.3472933 0.8455196 -0.4055663 -0.1868035 0.4393827 -0.8786622 -0.2173151 0.7064316 -0.6735937 -0.2020581 0.7176172 -0.6664819 -0.1541838 0.8607969 -0.4850321 -0.07720452 0.8601052 -0.5042405 0.001407742 0.7085393 -0.70567 0.003086686 0.3927047 -0.9196596 0.1163052 0.8910424 -0.438767 0.008236408 0.3553276 -0.9347056 0.1926552 0.8414904 -0.5047553 0.2042236 0.6412335 -0.7396705 0.2305873 0.6089186 -0.7589781 0.3926438 0.7865821 -0.4765706 0.1834894 0.3510825 -0.91819 0.4755427 0.7425433 -0.4716871 0.4320043 0.558221 -0.7083514 0.6263568 0.6336629 -0.4540357 0.4873015 0.5283772 -0.6952373 0.4119623 0.3538042 -0.8397081 0.790678 0.5574124 -0.2532187 0.670384 0.3869068 -0.6331576 0.6316586 0.3604457 -0.6863574 0.0709542 0.04920178 -0.9962654 0.5803209 0.2881564 -0.7617044 0.8700562 0.2160266 -0.443097 0.6575397 0.2089893 -0.7238543 0.8876248 0.09214186 -0.4512565 0.3874609 0.0527898 -0.9203734 0.9879496 0.02654623 -0.1524828 0.621007 0.0176652 -0.7836061 0.7143853 -0.0953297 -0.6932287 0.6983258 -0.1310046 -0.7036895 0.721143 -0.1513032 -0.6760622 0.6747899 -0.3348912 -0.6576523 0.6260399 -0.2910432 -0.7234417 0.7097874 -0.4720288 -0.5228679 0.2939888 -0.1711772 -0.9403558 0.5742952 -0.4958037 -0.6514321 0.4748358 -0.4355223 -0.7647559 0.6670709 -0.7007755 -0.2528442 0.37951 -0.4228101 -0.8229238 0.415935 -0.618113 -0.667034 0.4136443 -0.6222081 -0.664647 0.3026258 -0.5946927 -0.744821 0.2922739 -0.698177 -0.6535478 0.2017639 -0.8101915 -0.5503464 0.2014454 -0.7652545 -0.6113964 0.0287221 -0.1095212 -0.9935694 0.1199973 -0.9173361 -0.3795987 0.04308134 -0.434616 -0.899585 0.04529148 -0.448375 -0.8926974 0.007488667 -0.8141922 -0.5805472 -0.03799724 -0.8642055 -0.5017023 -0.1586977 -0.7752646 -0.6113755 -0.1760361 -0.6847841 -0.7071649 -0.1122702 -0.4474065 -0.8872558 -0.1077686 -0.4123461 -0.9046308 -0.3141891 -0.7965204 -0.516566 -0.5101997 -0.7330138 -0.4498745 -0.4171705 -0.6407354 -0.6445363 -0.3670416 -0.5331636 -0.7622448 -0.2023513 -0.3340262 -0.9205871 -0.7153143 -0.6290698 -0.304297 -0.690721 -0.5879333 -0.4209976 -0.4287131 -0.4165003 -0.8017061 -0.1138403 0.9931824 -0.02508747 -0.1180328 0.9927895 -0.02091264 0.8021213 0.5964955 -0.0281915 0.8006781 0.5985399 -0.02578228 0.9224041 -0.3857157 -0.01985812 0.9186195 -0.394107 -0.02860444 0.06765264 -0.6691933 -0.7400024 0.1096652 -0.8315433 -0.5445266 0.7766852 -0.3326975 -0.5348575 0.7725881 -0.3298375 -0.542508 0.4689942 0.3697193 -0.8020924 0.6785376 0.4926335 -0.5448844 -0.05546629 0.592069 -0.8039763 -0.1133701 0.8393825 -0.5315867 -0.772336 0.3290151 -0.5433657 -0.7802444 0.3344654 -0.5285372 -0.52503 -0.4103579 -0.7456206 -0.6800423 -0.4969499 -0.5390577 -0.9198452 0.3917365 -0.02066993 -0.9193839 0.3928807 -0.01944613 -0.7971995 -0.6034011 -0.01949894 -0.800897 -0.5982556 -0.02557718 0.1135687 -0.9932064 -0.02536547 0.1180085 -0.9927915 -0.02095037 0.006700873 0.01570302 -0.9998543 0.01216638 -0.004671335 -0.9999152 -0.01248478 0.006530761 -0.9999008 -0.002846181 -0.006679475 -0.9999737 0.003626525 -0.008873224 -0.9999541 -0.001476287 7.07373e-4 -0.9999987 0.001737713 0.008118748 -0.9999656 0.007395267 -0.003169536 -0.9999677 -0.004924535 -0.01506078 -0.9998745 0.001976251 -0.008786976 -0.9999595 -4.99431e-4 0.01365619 -0.9999067 0.001945376 0.009294986 -0.9999549 3.86702e-5 3.27382e-5 -1 0.01159822 0.01029539 -0.9998798 0.001016736 -0.008235692 -0.9999656 0.006794452 -0.003962993 -0.9999691 -0.005768179 -0.004826426 -0.9999718 -0.004164636 2.70553e-4 -0.9999914 -1.00853e-4 -0.001144349 -0.9999994 -0.00580728 -0.004764914 -0.9999718 0.002876043 0.00183171 -0.9999942 -0.004806995 -0.004850983 -0.9999768 -0.002054989 -0.006641983 -0.9999759 1.92734e-4 -0.00225979 -0.9999975 7.78514e-6 6.57787e-4 -0.9999999 -0.008248269 -0.004111826 -0.9999576 -0.00450015 0.001677811 -0.9999885 -0.05177748 -0.008360862 -0.9986237 -0.01083952 0.01902669 -0.9997602 -0.07489281 0.01388645 -0.9970949 3.13698e-4 -3.59693e-4 -1 -0.08406937 0.01002377 -0.9964095 -0.06200832 0.03753006 -0.9973698 -0.01066458 0.02033108 -0.9997364 -0.08297574 -0.05317395 -0.995132 -0.0283032 -0.05161249 -0.9982661 -0.005411148 0.00840193 -0.9999501 -0.0222848 -0.02749794 -0.9993734 0.009273111 -0.003962039 -0.9999492 -4.79313e-4 -0.02276551 -0.9997408 -9.80957e-4 -0.005865693 -0.9999824 6.45673e-4 -0.006797492 -0.9999767 0.001932919 -0.002295255 -0.9999955 -9.67214e-4 0.001236081 -0.9999989 -9.75867e-4 0.001015305 -0.9999991 0.06491112 -0.04151844 -0.997027 0.0903294 -0.08088022 -0.9926224 0.3317869 -0.3116744 -0.8903801 0.6336922 -0.3770743 -0.6754623 0.4582942 -0.1000413 -0.8831525 0.6222676 -0.0418834 -0.7816835 0.4952484 0.1256983 -0.8596097 0.5419576 0.1689675 -0.8232448 0.4066427 0.3336695 -0.8504742 0.4343857 0.4125141 -0.800713 0.2816781 0.4895712 -0.8252137 0.2760539 0.5399202 -0.7951607 0.01199573 0.6190618 -0.7852507 0.05943048 0.4381177 -0.896951 -0.1098433 0.6119695 -0.7832163 -0.2657632 0.4579168 -0.8483408 -0.2627739 0.4557035 -0.8504611 -0.4496534 0.373807 -0.8112214 -0.4410161 0.2717169 -0.8553799 -0.5220781 0.2473381 -0.8162465 -0.5268803 0.08494699 -0.8456839 -0.5708575 0.06650573 -0.8183513 -0.5085166 -0.1145645 -0.8533968 -0.5766921 -0.1848392 -0.7957768 -0.4063066 -0.3286724 -0.8525782 -0.4040547 -0.3245282 -0.8552317 -0.3094606 -0.556303 -0.7712076 -0.1202968 -0.4708092 -0.8739951 -0.07876396 -0.5728442 -0.8158712 0.1293113 -0.5228745 -0.8425444 0.1460904 -0.4578868 -0.876925 0.3978098 -0.4902163 -0.7755228 0.391398 -0.3422694 -0.854201 0.5356893 -0.321287 -0.7809044 0.5935763 -0.08503943 -0.8002722 0.5068503 -0.09998571 -0.8562159 0.6443172 0.09107059 -0.7593166 0.4187526 0.2173237 -0.8817125 0.4983379 0.3209128 -0.8054032 0.3679698 0.447461 -0.8150932 0.1789758 0.3980557 -0.8997329 0.1563857 0.5387049 -0.827853 0.05376327 0.5854831 -0.8088999 -1.68825e-4 0.5245019 -0.8514094 -0.1781695 0.5677341 -0.8037001 -0.2086167 0.4685969 -0.8584265 -0.2892243 0.4782065 -0.8292574 -0.4238992 0.3029835 -0.8535283 -0.4066498 0.2479486 -0.8792937 -0.5646756 0.2113429 -0.7977942 -0.5383859 0.02689164 -0.8422693 -0.5716513 0.008656322 -0.8204512 -0.5131805 -0.1865456 -0.8377628 -0.5218859 -0.1957258 -0.8302569 -0.425659 -0.3786697 -0.8218417 -0.3308429 -0.3591998 -0.8726504 -0.2410046 -0.579564 -0.7784744 -0.04551672 -0.4643234 -0.8844954 -0.007281363 -0.5679347 -0.8230414 0.2429238 -0.5654277 -0.788213 0.2706096 -0.4284869 -0.8620729 0.3663122 -0.4458152 -0.8167401 0.4343869 -0.3038316 -0.8479354 0.4146686 -0.2599905 -0.8720407 0.4868836 -0.06345194 -0.8711593 0.5100388 -0.1043207 -0.8538019 0.6464063 0.04459065 -0.7616893 0.4657132 0.2160915 -0.8581467 0.4867199 0.2426707 -0.8391751 0.3640306 0.434089 -0.8240441 0.3592849 0.4171915 -0.8347848 0.277064 0.51984 -0.8080855 0.1255345 0.4692361 -0.8741045 0.08466345 0.5958629 -0.798611 -0.1348688 0.5539932 -0.8215242 -0.1742044 0.4627434 -0.8692074 -0.2633748 0.5078505 -0.8201961 -0.4027642 0.3805637 -0.8324375 -0.397917 0.3614174 -0.8432316 -0.5384511 0.2108889 -0.8158409 -0.5164349 0.1728394 -0.8387024 -0.5816119 0.04848742 -0.81202 -0.5030701 -0.03253173 -0.8636332 -0.5730351 -0.1551458 -0.8047114 -0.4085006 -0.2417497 -0.8801615 -0.4754812 -0.3774114 -0.7946562 -0.3643597 -0.4527394 -0.8137993 -0.2651071 -0.4249601 -0.8655214 -0.1787642 -0.6436257 -0.7441703 0.02307212 -0.4939166 -0.8692032 0.1610441 -0.565277 -0.8090283 0.1844664 -0.4976352 -0.8475444 0.3544617 -0.4623826 -0.812748 0.3477444 -0.3721799 -0.8605557 0.526032 -0.2914661 -0.7989605 0.4643499 -0.1541274 -0.8721377 0.5517322 -0.09239959 -0.8288872 0.5242757 0.0448938 -0.8503645 0.5602733 0.06619799 -0.8256583 0.5128358 0.2960888 -0.8058108 0.3928983 0.3064311 -0.8670241 0.4135761 0.4245818 -0.80541 0.2517769 0.5146836 -0.8195788 0.1328131 0.44629 -0.8849779 0.05922871 0.5848659 -0.8089648 -0.09729647 0.5168795 -0.8505111 -0.1349566 0.5574376 -0.8191765 -0.3079009 0.4383393 -0.8444263 -0.2633011 0.407199 -0.8745636 -0.4519851 0.4116616 -0.7913559 -0.4634468 0.1556811 -0.872342 -0.5023669 0.2141377 -0.8377188 -0.6179777 0.05945134 -0.7839447 -0.4831615 -0.1140128 -0.8680761 -0.527891 -0.1526896 -0.8354741 -0.5137733 -0.3430947 -0.7863354 -0.3033675 -0.3680334 -0.8789309 -0.3229025 -0.4398291 -0.8380242 -0.1224399 -0.6108723 -0.7822043 -0.02107125 -0.4956683 -0.8682564 0.06358754 -0.5538139 -0.830209 0.2133076 -0.4082211 -0.8876122 0.2518189 -0.4422855 -0.8607967 0.430229 -0.4404657 -0.7879677 0.449055 -0.2388952 -0.8609756 0.477611 -0.2404897 -0.8450164 0.592402 -0.05290687 -0.8039035 0.5098554 0.0109077 -0.860191 0.5645573 0.2112648 -0.7978987 0.466515 0.2358317 -0.8524947 0.4343208 0.3948912 -0.8095841 0.3353033 0.3841559 -0.8602302 0.2509536 0.5394163 -0.8037739 0.1115816 0.4745742 -0.8731145 0.03400427 0.6351794 -0.7716158 -0.141838 0.407721 -0.9020231 -0.2701572 0.505046 -0.8197217 -0.3182586 0.3276934 -0.8895666 -0.4454615 0.3319414 -0.831492 -0.4669161 0.2021053 -0.8608965 -0.5101003 0.1996883 -0.8366136 -0.616398 0.0542683 -0.7855626 -0.4950024 -0.0669704 -0.8663069 -0.5666508 -0.165257 -0.8072157 -0.4419576 -0.2553988 -0.85991 -0.4839947 -0.363703 -0.7959077 -0.2599747 -0.4335687 -0.8628045 -0.2986704 -0.4523012 -0.8403688 -0.1271139 -0.6214334 -0.7730866 0.02753257 -0.4918744 -0.8702307 0.1029758 -0.581847 -0.8067528 0.2591028 -0.4158301 -0.8717517 0.379333 -0.4912386 -0.7840862 0.508305 -0.2763344 -0.815638 0.4810066 -0.2366232 -0.8441814 0.5558484 -0.02699553 -0.8308454 0.5200795 -0.002448797 -0.8541144 0.5238382 0.228657 -0.8205544 0.4341207 0.2390363 -0.8685626 0.4493496 0.4369959 -0.7791788 0.2632802 0.4821042 -0.8356191 0.1682155 0.4289355 -0.8875347 0.112208 0.604418 -0.7887258 -0.1293613 0.499579 -0.8565551 -0.1327678 0.5042604 -0.8532844 -0.3316512 0.4866758 -0.8081796 -0.3367971 0.3338617 -0.8804001 -0.5524174 0.3572841 -0.7531156 -0.480541 0.07346403 -0.8738898 -0.5592457 0.048078 -0.8276066 -0.5160467 -0.1538042 -0.8426389 -0.5404893 -0.1457356 -0.828633 -0.4635043 -0.3401354 -0.8182126 -0.4118464 -0.3455774 -0.8431838 -0.3739175 -0.4531309 -0.8092331 -0.2185631 -0.4465957 -0.8676304 -0.2026013 -0.563921 -0.8005911 0.05274331 -0.5218214 -0.8514227 0.04322785 -0.5423393 -0.8390467 0.2506858 -0.5126696 -0.821174 0.2677428 -0.4061746 -0.873691 0.4541127 -0.4430246 -0.7729883 0.4492017 -0.1630613 -0.8784241 0.5856018 -0.1545886 -0.7957217 0.5230836 0.07277566 -0.8491686 0.4608644 0.1014787 -0.8816496 0.5594347 0.2911963 -0.7760397 0.3441791 0.3918235 -0.8532381 0.3423534 0.3912336 -0.8542426 0.246682 0.5383337 -0.8058193 0.09357845 0.4746845 -0.8751673 0.03412038 0.6048715 -0.7955918 -0.146639 0.5556553 -0.8183791 -0.175575 0.4664193 -0.8669641 -0.3122668 0.4800508 -0.819781 -0.3488906 0.3188872 -0.8812413 -0.4905179 0.3466982 -0.7994953 -0.5787082 0.1442454 -0.8026769 -0.4978629 0.06771606 -0.8646081 -0.6015681 -0.0825001 -0.79455 -0.459939 -0.1706438 -0.8713994 -0.5233756 -0.3279631 -0.7864593 -0.3257088 -0.3892518 -0.8616245 -0.3251473 -0.3890672 -0.8619199 -0.2276021 -0.5222598 -0.8218529 -0.01783591 -0.429901 -0.9027 0.01109498 -0.5224283 -0.852611 0.2124207 -0.6400904 -0.7383508 0.2560294 -0.4745277 -0.8421831 0.4827851 -0.4896851 -0.7260352 0.4911231 -0.3096575 -0.8141931 0.6042894 -0.2477585 -0.7572649 0.4979224 -0.03109997 -0.8666638 0.6335198 0.06235367 -0.77121 0.4366091 0.206439 -0.8756459 0.4995311 0.2893569 -0.8165423 0.3845883 0.4440437 -0.8092695 0.2510753 0.4120327 -0.875894 0.2222025 0.5243349 -0.8220092 0.04684007 0.5400322 -0.8403401 0.04194974 0.5518892 -0.8328618 -0.1764531 0.5250813 -0.8325587 -0.149533 0.490546 -0.8584896 -0.3670631 0.5187387 -0.7721237 -0.3898367 0.3013164 -0.870193 -0.4797651 0.3119164 -0.8200815 -0.5500488 0.1190857 -0.8265985 -0.4741928 0.04975658 -0.8790139 -0.6244335 -0.1300972 -0.7701672 -0.4078607 -0.2621285 -0.8746076 -0.4098473 -0.2647876 -0.8728762 -0.3810651 -0.5136417 -0.7687402 -0.1632984 -0.4698917 -0.8674882 -0.133615 -0.5813204 -0.8026292 0.06862741 -0.50868 -0.8582162 0.09193348 -0.5470646 -0.8320269 0.3473991 -0.4963082 -0.7956081 0.3379254 -0.3161964 -0.8864685 0.5244211 -0.3444848 -0.7786609 0.5231574 -0.05557513 -0.8504222 0.5173794 -0.05130714 -0.8542168 0.5702467 0.1385077 -0.8097126 0.4477436 0.1914728 -0.8734208 0.5161846 0.3443276 -0.7842144 0.2750297 0.4154852 -0.867024 0.2873035 0.5397673 -0.79127 0.08488225 0.5050831 -0.8588865 0.07864362 0.5180428 -0.8517317 -0.132265 0.4881097 -0.8627023 -0.1347325 0.484646 -0.8642717 -0.2918782 0.5346705 -0.7930541 -0.3134707 0.3933725 -0.8642884 -0.4845649 0.3866321 -0.7846735 -0.4577621 0.195722 -0.8672641 -0.560964 0.1705867 -0.8100739 -0.5255032 -0.05070227 -0.8492797 -0.5247764 -0.050354 -0.8497496 -0.4008221 -0.2672396 -0.8763132 -0.4252839 -0.3015822 -0.8533357 -0.350688 -0.4740184 -0.8076661 -0.2357791 -0.4335941 -0.8697152 -0.1665437 -0.5913671 -0.7890173 0.04421734 -0.5105174 -0.8587298 0.03130364 -0.4826242 -0.8752679 0.2508886 -0.5658237 -0.7854288 0.3476226 -0.38895 -0.8531568 0.3628231 -0.3959977 -0.8435314 0.5399867 -0.2646095 -0.7989971 0.4910394 -0.1754704 -0.8532822 0.5911054 -0.04239505 -0.8054794 0.5773861 -0.0294944 -0.8159385 0.6221497 0.1772039 -0.7625802 0.3956078 0.2431052 -0.8856604 0.340364 0.4243223 -0.8391084 0.3440957 0.4318815 -0.8337126 0.1948293 0.5664834 -0.8007111 0.0518074 0.4804922 -0.8754675 0.009986042 0.5564582 -0.8308156 -0.1486995 0.573181 -0.8058239 -0.2100695 0.4305011 -0.8778039 -0.3083136 0.4827053 -0.8197185 -0.4618425 0.3056861 -0.8326209 -0.4729917 0.330965 -0.8165422 -0.6567348 0.1380143 -0.7413849 -0.5364688 0.003925383 -0.8439111 -0.6258627 -0.131426 -0.7687804 -0.4048133 -0.2437407 -0.8813154 -0.4521941 -0.334497 -0.8268206 -0.3034241 -0.4595715 -0.8347022 -0.2899343 -0.4537629 -0.8426372 -0.1331841 -0.547461 -0.8261649 -0.0613662 -0.484678 -0.8725374 0.07736444 -0.6020647 -0.7946904 0.2034 -0.4564285 -0.8661995 0.2538536 -0.4969262 -0.829833 0.4040824 -0.4417223 -0.8009986 0.3900318 -0.2549687 -0.8847972 0.5121915 -0.2586119 -0.8190115 0.6080781 -0.08658069 -0.7891419 0.4976361 0.0173791 -0.8672117 0.5760576 0.1036181 -0.8108151 0.4449985 0.2540693 -0.8587346 0.4652593 0.2851758 -0.837979 0.3774297 0.438551 -0.8156101 0.2622547 0.4181265 -0.8697084 0.2310781 0.5658959 -0.7914321 0.004752099 0.5272513 -0.8496962 0.005524575 0.5253579 -0.8508635 -0.2072813 0.564928 -0.7986808 -0.2211076 0.403882 -0.8876885 -0.4474713 0.3013891 -0.8419823 -0.3978808 0.2815888 -0.8731545 -0.6054283 0.1905457 -0.7727541 -0.4451594 -0.01846736 -0.8952609 -0.6791812 -0.1657586 -0.7150084 -0.3579514 -0.3216707 -0.8765836 -0.3616108 -0.3226134 -0.8747332 -0.254014 -0.564021 -0.7857208 -0.08619201 -0.4688088 -0.8790844 -0.02906048 -0.5851377 -0.8104131 0.1784754 -0.4574446 -0.8711436 0.2301167 -0.5143352 -0.826139 0.448231 -0.4197584 -0.789235 0.4084032 -0.2595047 -0.8751367 0.5505346 -0.2289817 -0.8027946 0.5128696 -0.05769538 -0.8565257 0.6163985 0.011994 -0.7873432 0.4922034 0.1457673 -0.8581888 0.5564342 0.2375481 -0.796211 0.3367787 0.3390447 -0.8784242 0.3709638 0.462136 -0.8054913 0.1541944 0.5185912 -0.8410038 0.15665 0.4937013 -0.8554063 -0.05698782 0.6049792 -0.7941993 -0.1137912 0.4735834 -0.8733674 -0.3393448 0.5219264 -0.7825843 -0.3531703 0.3329676 -0.8743016 -0.4360074 0.3412122 -0.8327496 -0.5122984 0.1571333 -0.8443101 -0.5090361 0.1525685 -0.8471158 -0.4947985 -0.07223254 -0.8660005 -0.5765544 -0.01302438 -0.816955 -0.5913394 -0.2186877 -0.7762046 -0.3827463 -0.3378952 -0.8598443 -0.3892697 -0.3530843 -0.8507648 -0.2749599 -0.5066915 -0.8171051 -0.1867905 -0.470646 -0.8623234 -0.09341233 -0.5815527 -0.8081279 0.009574472 -0.4898456 -0.8717567 0.163702 -0.5803605 -0.7977365 0.24145 -0.4264151 -0.8717066 0.410546 -0.5039926 -0.759897 0.446277 -0.240644 -0.8619323 0.4705383 -0.2413304 -0.8487363 0.590337 -0.09497791 -0.8015495 0.5152629 -0.01808542 -0.8568414 0.6512133 0.1655355 -0.7406209 0.4462711 0.2823672 -0.8491824 0.4157108 0.4493474 -0.7907412 0.3306465 0.2935181 -0.8969504 0.2989938 0.5420893 -0.7853292 0.1222654 0.4794135 -0.8690305 0.0622633 0.5815595 -0.8111177 -0.09186482 0.4997041 -0.8613111 -0.158138 0.5712643 -0.8053879 -0.3487688 0.4130449 -0.8412814 -0.2860453 0.3726676 -0.882778 -0.5268135 0.3350915 -0.7811411 -0.5049176 0.1259236 -0.8539329 -0.5172683 0.1235559 -0.8468576 -0.5842155 -0.07673323 -0.8079631 -0.4623573 -0.1304355 -0.8770475 -0.5199798 -0.3465954 -0.7807002 -0.3836639 -0.3677114 -0.8471072 -0.3830053 -0.5572662 -0.7367235 -0.1284655 -0.5400113 -0.831796 -0.09007453 -0.601078 -0.7940982 0.05547744 -0.5216768 -0.8513376 0.05536121 -0.5219798 -0.8511594 0.2508645 -0.5518391 -0.7953242 0.2963793 -0.3844792 -0.8742627 0.4191504 -0.4084295 -0.8108627 0.4696858 -0.2353237 -0.8508924 0.4991132 -0.2358488 -0.8338233 0.5994654 -0.06653571 -0.7976304 0.4757177 0.03990149 -0.8786925 0.5594105 0.1540251 -0.8144546 0.4910534 0.2619645 -0.8308076 0.4397898 0.2685499 -0.8570098 0.4171649 0.4497908 -0.7897227 0.2364439 0.4199057 -0.8762269 0.1979731 0.5874973 -0.784636 -0.003145217 0.4332242 -0.9012808 -0.1189345 0.5705153 -0.8126297 -0.2293739 0.4478045 -0.8642099 -0.3272348 0.5135023 -0.7932419 -0.4642241 0.2985486 -0.8338853 -0.4439703 0.259394 -0.8576743 -0.5952633 0.114347 -0.7953531 -0.50933 0.03094637 -0.8600147 -0.5658392 -0.1644621 -0.807947 -0.4792894 -0.1913459 -0.8565444 -0.4853852 -0.3838419 -0.7855359 -0.3074223 -0.3782261 -0.8731762 -0.2853679 -0.5623932 -0.7760664 -0.08571243 -0.4737868 -0.8764586 -0.002568721 -0.600099 -0.7999216 0.1285769 -0.4725953 -0.8718496 0.2334489 -0.5618058 -0.7936474 0.4030754 -0.3666579 -0.8385061 0.394502 -0.3630983 -0.8441137 0.5681487 -0.2013797 -0.7979056 0.5111418 -0.1251801 -0.8503316 0.5538976 -0.04913395 -0.8311338 0.4579464 0.08946555 -0.8844666 0.5242039 0.1628586 -0.8358752 0.4444598 0.2983428 -0.844658 0.4398559 0.2920016 -0.8492714 0.4139717 0.4774043 -0.7750565 0.1714402 0.4523402 -0.8752124 0.1686832 0.4885005 -0.8561035 0.02619469 0.6042238 -0.796384 -0.09066486 0.4680863 -0.8790195 -0.2067704 0.5800895 -0.787872 -0.3777939 0.4388492 -0.815281 -0.3530277 0.3074175 -0.8836662 -0.5182817 0.2979686 -0.8016226 -0.5658193 0.1574579 -0.8093551 -0.4957548 0.07312828 -0.8653783 -0.5899388 -0.06242829 -0.805031 -0.4873799 -0.1335538 -0.8629162 -0.5558958 -0.2926379 -0.7780379 -0.3628228 -0.3244675 -0.8735448 -0.2270017 -0.461485 -0.8576141 -0.3352017 -0.5075656 -0.7937361 -0.01893538 -0.6098678 -0.792277 -0.05574095 -0.4198036 -0.9059017 0.09651947 -0.6135155 -0.783762 0.2931911 -0.4799414 -0.8268586 0.2814673 -0.4121254 -0.8665615 0.4240072 -0.2287768 -0.8762872 0.5680736 -0.2549915 -0.7824781 0.5352571 0.02238124 -0.8443927 0.4987976 0.04154586 -0.8657223 0.5379182 0.2234779 -0.8128356 0.3978321 0.2657985 -0.8781121 0.44394 0.4468057 -0.7767123 0.1659938 0.4311426 -0.8868835 0.1642518 0.5301876 -0.8318188 -0.0193324 0.6219114 -0.782849 -0.1242071 0.4669348 -0.8755254 -0.2461833 0.5584456 -0.7921695 -0.3471141 0.329665 -0.8779708 -0.4317359 0.356777 -0.8284409 -0.545778 0.1666876 -0.8211831 -0.4954309 0.1083137 -0.861868 -0.5017409 -0.09832423 -0.8594117 -0.5783571 -0.03294485 -0.8151182 -0.5572186 -0.2249612 -0.7993121 -0.407063 -0.2938322 -0.8648481 -0.4227927 -0.3858827 -0.8199641 -0.2682638 -0.4352924 -0.8593924 -0.2702955 -0.5141042 -0.8140254 -0.08267438 -0.584035 -0.8075073 9.61764e-4 -0.484264 -0.8749215 0.1424278 -0.6174078 -0.773642 0.2916209 -0.4450173 -0.8467095 0.2907487 -0.3654171 -0.8842712 0.4504811 -0.3873525 -0.8043787 0.5297601 -0.1900708 -0.8265756 0.4422387 -0.1127193 -0.8897862 0.5537027 0.1388179 -0.8210622 0.4980878 0.1507872 -0.8539156 0.4134877 0.307252 -0.8571023 0.3338323 0.3093094 -0.8904402 0.3499632 0.4553205 -0.818663 0.1373924 0.4754855 -0.8689286 0.07059752 0.3966287 -0.9152605 -0.1368682 0.5355959 -0.8333091 -0.1393418 0.4073477 -0.9025807 -0.2971894 0.3080419 -0.9037637 -0.7056872 0.4995835 0.5024163 0.1248695 0.9921709 -0.00216943 -0.37177 0.9168441 -0.1455477 -0.3985078 0.8480832 0.3492085 -0.7395486 0.6196671 -0.2628319 -0.776861 0.5755935 0.2553023 -0.9733228 0.2244116 -0.04777449 -0.9559552 0.1876911 -0.2256585 -0.9578667 -0.1313927 0.2553961 -0.7825354 -0.2962216 -0.5476232 -0.6422242 -0.4157958 0.6439426 -0.4500052 -0.6516237 -0.6106407 -0.3077949 -0.82814 0.4684514 -0.2046403 -0.9659406 -0.1583706 0.2121201 -0.9493268 0.2319137 0.2632225 -0.9613727 -0.08047783 0.7584372 -0.6444238 -0.09742212 0.8657079 -0.2824359 0.4132553 0.8196399 0.1283426 -0.5583176 0.662411 0.2462623 0.7075074 0.6358069 0.5335365 -0.557753 0.4789403 0.8131317 0.3308066 0.4205049 0.8970738 -0.1357731 0.0768125 0.9738516 0.2138063 -0.072007 0.8870331 -0.4560563 -0.255391 0.7804921 0.5706205 -0.4971388 0.5612957 -0.6616647 -0.63082 0.4930406 0.599147 -0.7792734 0.1803749 -0.6001649 -0.9558578 0.1254067 0.2657237 -0.9311145 -0.2577797 0.2580222 -0.8481575 -0.3550317 -0.3931686 -0.6945075 -0.6208947 0.3635233 -0.5804695 -0.7054923 -0.406615 -0.1793338 -0.878371 0.4430621 -0.1376549 -0.9894659 0.04481416 0.3763388 -0.8238633 -0.4238142 0.4370486 -0.8530675 0.2850697 0.7623576 -0.5780567 0.2909666 0.6790362 -0.3018045 -0.6691966 0.827974 -0.1965039 0.5252098 0.8409573 0.2059704 -0.5003671 0.867618 0.3065949 0.3914572 0.6944037 0.6150317 -0.3735499 0.6837078 0.7051534 0.1878895 0.3304133 0.9426052 -0.04819244 0.3587922 0.9059939 0.2245954 -0.1298424 0.8962796 -0.4240564 -0.2229745 0.8499262 0.477397 -0.4889947 0.8172306 -0.3049895 -0.6315987 0.6788876 0.3744258 -0.7192672 0.4402573 -0.5374273 -0.8499512 0.369395 0.3756731 -0.996358 0.01505059 0.08392971 -0.9357771 -0.05793249 -0.3478005 -0.8536205 -0.4015499 0.3317977 -0.8202794 -0.5034697 -0.2714038 -0.505996 -0.8618729 0.03381389 -0.1413832 -0.9820498 -0.1248569 0.2464928 -0.9044461 0.3481647 0.3961917 -0.7969812 -0.4559091 0.5606111 -0.7218049 0.4058483 0.6969453 -0.4451469 -0.5622381 0.8202213 -0.3693637 0.4368152 0.9723569 0.02586501 -0.2320628 0.9692228 -0.04295819 0.2424082 0.8133409 0.377096 -0.4430298 0.6672427 0.4111296 0.6210955 0.4564154 0.7268793 -0.5131585 0.3454183 0.821406 0.4538486 0.1448706 0.9238987 -0.3541523 -0.09396415 0.9383243 0.332744 -0.2643346 0.9005594 -0.3451376 -0.4276963 0.7526361 0.5006145 -0.5590755 0.5071583 -0.6559154 -0.71022 0.3302777 0.6216946 -0.7781084 0.0809527 -0.6228917 -0.7736629 -0.09379726 0.6266161 -0.6386818 -0.3997827 -0.6574645 -0.5358217 -0.5062638 0.6757161 -0.3799191 -0.7631353 -0.5227677 -0.1088668 -0.9525257 0.2843288 -0.1225743 -0.9846073 0.1245957 0.3756229 -0.9158009 0.1421833 0.3883139 -0.9186645 0.07258152 0.6636971 -0.6236041 -0.4130668 0.698442 -0.4674974 0.5418718 0.8286507 -0.2472481 -0.5022017 0.8427682 -0.0681079 0.5339505 0.8002015 0.282956 -0.5287851 0.9228569 0.3837894 0.03226232 0.6846629 0.6563808 0.3168614 0.4157631 0.6482713 -0.6378756 0.263931 0.7422179 0.6159976 -0.06583416 0.8282625 -0.5564596 -0.2000186 0.891813 0.4057856 -0.4841782 0.7748047 -0.4065088 -0.594747 0.748033 0.2944872 -0.8625762 0.4610421 -0.2083329 -0.8862552 0.4608971 -0.04610514 -0.9925783 -0.05172878 0.1100568 -0.8833979 -0.140358 -0.4471104 -0.8122777 -0.3704935 0.4504882 -0.6700863 -0.5889253 -0.4518311 -0.5239571 -0.7091234 0.4718187 -0.3363265 -0.7957373 -0.5036731 -0.04540026 -0.818677 0.572457 0.1713802 -0.8663499 -0.4691129 0.4087942 -0.8194414 0.4017502 0.5505255 -0.7243303 -0.415051 0.7732677 -0.4724344 0.4229217 0.8313343 -0.3124711 -0.4596142 0.9185323 -0.08972805 0.385029 0.9075847 0.127814 -0.3999421 0.7859002 0.333507 0.5207053 0.6506505 0.4876938 -0.5820728 0.3701257 0.6859284 0.6265056 0.2990373 0.8995871 -0.3183076 -0.1778436 0.9838262 -0.02139228 -0.1793935 0.9837617 0.005580604 -0.6134835 0.7345701 0.289905 -0.6689521 0.7419729 0.04449045 -0.8163733 0.3563081 -0.4545099 -0.8441334 0.2223568 0.4878486 -0.9582432 0.01941126 -0.2852951 -0.9179798 -0.1931731 0.3464062 -0.7516661 -0.3825523 -0.5372633 -0.7597413 -0.5308994 0.3754186 -0.5087572 -0.8589299 0.0583589 -0.4666541 -0.862049 -0.1977516 -0.01574498 -0.9947051 -0.1015581 0.0051319 -0.9876319 0.1567072 0.4601759 -0.8821048 -0.1006453 0.4715004 -0.8672769 0.1597441 0.8703669 -0.4383565 -0.2242875 0.8841413 -0.4166719 0.2113735 0.9918325 0.03617805 -0.1223087 0.8783534 0.09813201 0.4678307 0.715854 0.3694499 -0.5925031 0.5836235 0.5399 0.6065407 0.4953647 0.7806026 -0.3811475 0.2674138 0.8948849 0.3573108 0.1040297 0.8891151 -0.4457042 -0.2221997 0.8423296 0.4910277 -0.4065903 0.8415313 -0.3556816 -0.6243233 0.6951383 0.356375 -0.7292417 0.6275999 -0.2726262 -0.9478579 0.2658471 -0.1757583 -0.8986726 0.2090421 0.3856019 -0.9479325 -0.2054303 -0.2433565 -0.9454954 -0.2576509 0.1991345 -0.7744311 -0.5508424 -0.3111739 -0.5962787 -0.5816229 0.5533232 -0.4522168 -0.7781901 -0.4357985 -0.131752 -0.9470162 0.2929193 -0.138009 -0.9652436 0.2219427 0.4855991 -0.8606217 -0.1533756 0.9262725 -0.2478007 0.2839264 0.9132881 0.2153702 -0.3457177 0.8032172 0.2816193 0.524912 0.6134647 0.5540129 -0.5627884 0.4989153 0.6433104 0.5807196 0.1952477 0.8447684 -0.4982417 0.1589773 0.9798189 0.1211661 -0.24358 0.9545499 0.1717653 -0.2698391 0.9624041 0.03106713 -0.5407224 0.7173756 -0.4393081 -0.580906 0.5587956 0.5918578 -0.82857 0.3782584 -0.4127861 -0.858925 0.1834121 0.4781298 -0.9170179 0.0131157 -0.3986305 -0.8785129 -0.411126 0.2432914 -0.7531015 -0.377442 0.5388654 -0.4937258 -0.6305162 -0.5989025 -0.3528372 -0.7450859 0.5659974 -0.09544295 -0.8890215 -0.4478073 0.03223198 -0.8828163 0.4686114 0.330788 -0.6911431 -0.6425734 0.4439063 -0.5377997 0.7167418 0.6999432 -0.4363713 -0.5653846 0.9100119 -0.1737987 0.3763942 0.9769344 -0.06916648 -0.2020275 0.9091902 0.2942607 0.294591 0.9093765 0.3774827 -0.1747609 0.5912218 0.8052068 -0.04581427 0.5715535 0.7559982 -0.3190506 0.2296622 0.8517356 0.4709584 -0.04789149 0.7615803 -0.6462987 -0.170405 0.9490515 0.2650725 -0.5340341 0.806315 0.2542909 -0.5926058 0.6986013 -0.4009672 -0.8463487 0.4538676 0.2787439 -0.8919719 0.3581922 -0.2758344 -0.9561748 -0.01173532 0.2925611 -0.9970805 -0.07195937 -0.02554392 -0.882334 -0.4544384 -0.1223624 -0.8674718 -0.4755577 0.1460738 -0.5580242 -0.814958 -0.1563735 -0.5454019 -0.8293266 0.1214672 0.01456618 -0.9995487 -0.02627575 0.01243627 -0.9998729 -0.009978592 0.5701597 -0.8172989 -0.08330881 0.5672497 -0.7578257 0.3223788 0.8037495 -0.464885 -0.3713067 0.8602725 -0.3960444 0.3210608 0.9786573 -0.007712543 -0.2053548 0.9461632 0.3235632 -0.009057581 0.6722542 0.7399763 -0.02257174 0.6783955 0.7339869 0.03229564 0.1886075 0.9807043 0.05144411 0.1300342 0.9473988 -0.2924494 -0.3189882 0.8572813 0.4041231 -0.4364328 0.830882 -0.3451979 -0.816637 0.5484337 0.1797906 -0.9454069 0.1843791 0.2687199 -0.7897303 -0.2312864 -0.5681837 -0.7217352 -0.3253519 0.6109375 -0.5638963 -0.7046555 -0.4306759 -0.5925441 -0.8051715 -0.02430224 -0.208359 -0.965723 0.1548089 -0.156746 -0.9755485 -0.1540641 0.2667514 -0.9601646 -0.08323436 0.2912222 -0.8649961 0.4086217 0.5777916 -0.6897447 -0.4363592 0.6279224 -0.5196367 0.5793886 0.773278 -0.3072498 -0.554652 0.884396 -0.06046593 0.4628043 0.8939915 0.1204005 -0.4316051 0.8160341 0.3688332 0.4450286 0.7573226 0.5533095 -0.346859 0.5740641 0.7477957 0.3335447 0.5175872 0.8379253 -0.173161 0.1302543 0.9896773 -0.0597732 0.08848625 0.935245 0.3427639 -0.2977107 0.9126389 -0.2801048 -0.374011 0.8788406 0.2962344 -0.6070128 0.6890388 -0.3959307 -0.6365525 0.525836 0.5641786 -0.7851498 0.2373265 -0.572028 -0.7668174 0.06429487 0.6386372 -0.7275078 -0.1996109 -0.6564205 -0.582355 -0.4004207 0.7074787 -0.5498809 -0.6639137 -0.5068033 -0.2643498 -0.9424345 0.2047842 -0.2608884 -0.9368969 0.2327261 0.2936981 -0.9510467 -0.09618604 0.2707654 -0.9590383 0.08325707 0.7209473 -0.6458299 -0.2512744 0.7149803 -0.5642177 0.4128701 0.8864148 -0.2565555 -0.3852899 0.9550828 -0.1887292 0.2284695 0.9731154 0.2151899 -0.08209633 0.9665227 0.2215225 -0.1294676 0.7518293 0.6343911 0.1797243 0.6545118 0.6684683 -0.3532201 0.3391324 0.861804 0.3772047 0.2566892 0.9494729 -0.1805877 -0.1371194 0.989662 0.04204112 -0.1458474 0.9710941 0.1889572 -0.5745296 0.7694447 -0.2790531 -0.5938017 0.6857089 0.4209545 -0.8057987 0.3631068 -0.4678054 -0.9271327 0.3558186 0.1175506 -0.9150919 -0.04520571 0.4007034 -0.851196 -0.183292 -0.4918022 -0.776291 -0.5753201 0.2576415 -0.6668504 -0.6341409 -0.3913769 -0.392173 -0.7545518 0.5261673 -0.1655165 -0.8879661 -0.4290928 -0.06648564 -0.9715233 0.2274252 0.2220254 -0.9011902 -0.3722378 0.332857 -0.7712942 0.5425049 0.577142 -0.6999763 -0.4206428 0.7909816 -0.5235517 0.3166097 0.8628516 -0.4463405 -0.2372076 0.9015756 -0.002654731 0.4326138 0.6784358 0.3354861 -0.6535855 0.6145315 0.5591694 0.5564897 0.4090414 0.7919902 -0.4532513 0.3183453 0.8973419 0.3056697 0.05662196 0.9337995 -0.3532881 -0.07785791 0.9072601 0.4133003 -0.3572138 0.8227614 -0.4421108 -0.4688063 0.6813104 0.5621715 -0.6316466 0.4760465 -0.6118842 -0.7620338 0.2752023 0.5861471 -0.8601781 0.04927676 -0.5076077 -0.8546985 -0.1467942 0.4979377 -0.7711083 -0.3805341 -0.5104762 -0.589708 -0.5917912 0.5495704 -0.3651808 -0.8899029 -0.2733423 0.02359825 -0.9758424 0.2171974 0.09538006 -0.9741458 -0.2047987 0.5198487 -0.8189339 0.243115 0.5723911 -0.6774937 -0.4619208 0.7458745 -0.4642719 0.4776221 0.8387945 -0.2783094 -0.4679399 0.938529 -0.01372951 0.3449273 0.9364439 0.1253156 -0.3276721 0.8291534 0.4077359 0.3824342 0.8068591 0.5423715 -0.2341188 0.557824 0.8223665 0.1120079 0.5607085 0.8232341 0.08883446 0.1500232 0.9751304 -0.1631368 0.09248751 0.9443675 0.3156204 -0.2354451 0.9360387 -0.2615287 -0.3310183 0.8400012 0.4299126 -0.5242597 0.6312693 -0.5715337 -0.6372337 0.4686175 0.6118258 -0.8538351 0.2688218 -0.4457585 -0.9488354 0.1412655 0.2824101 -0.8848627 -0.135553 -0.4456945 -0.8300296 -0.2399752 0.5034511 -0.6840764 -0.6512378 -0.3285253 -0.6882412 -0.7112483 0.1430036 -0.2829063 -0.914363 -0.2896628 -0.2597748 -0.9546026 0.1457774 0.1674415 -0.9423652 0.2896744 0.2719411 -0.7609215 -0.5891066 0.5692427 -0.6268414 0.5320082 0.6723119 -0.4318043 -0.6012834 0.8103541 -0.2843315 0.51233 0.8742628 0.07519024 -0.4795948 0.9808562 0.1138723 -0.1579689 0.7869321 0.4291536 0.4433568 0.7015718 0.5613582 -0.4389465 0.446887 0.8942821 0.02349233 0.4251309 0.8764699 0.2259742 -0.1032238 0.9795937 0.172456 -0.1337308 0.9904637 -0.03313422 -0.5206546 0.7520086 -0.4042301 -0.5081452 0.5644592 0.6505185 -0.746881 0.3389962 -0.5720582 -0.8840674 0.2198694 0.4124105 -0.9412502 -0.05880874 -0.3325504 -0.9170703 -0.1622186 0.3642351 -0.8006069 -0.4621794 -0.3813385 -0.7735799 -0.573113 0.2703992 -0.5654396 -0.7590744 -0.3226208 -0.4887992 -0.8076718 0.3297602 -0.07814747 -0.9808558 -0.1783675 -0.1492905 -0.9085875 0.3901041 0.2679607 -0.7742125 -0.5734038 0.3733863 -0.702779 0.6055448 0.7223371 -0.4402249 -0.533321 0.7767642 -0.597477 0.1991448 0.9184411 -0.07384669 -0.3886036 0.910264 -0.0106526 0.4138914 0.8313751 0.4767981 -0.2854456 0.8768272 0.4710806 -0.09621518 0.4775403 0.8762802 0.06393957 0.4141856 0.8138172 0.4076176 0.01890599 0.8393923 -0.5431973 -0.1120253 0.7695937 0.6286301 -0.4631639 0.6538277 -0.5983215 -0.5972641 0.6926018 0.4044485 -0.9044886 0.2734987 -0.3272598 -0.9456318 0.2757363 -0.1724824 -0.9308156 -0.0965299 0.3525115 -0.8216437 -0.267808 -0.5031705 -0.80475 -0.4746916 0.3564344 -0.6056689 -0.6728584 -0.4247668 -0.5582782 -0.7476452 0.3596557 -0.05909854 -0.9503759 -0.3054391 -0.09708178 -0.9944484 -0.04059112 0.5458267 -0.8309432 0.1077347 0.5434103 -0.8306604 0.1212795 0.8673102 -0.392567 -0.3060463 0.8145269 -0.3065659 0.4925072 0.889391 0.1272853 -0.4390696 0.9552741 0.2060022 0.2121667 0.8091984 0.5770314 -0.110601 0.7474919 0.5815082 0.3210983 0.3577476 0.79409 -0.491363 0.2692603 0.8108596 0.5196207 -0.1037965 0.8559969 -0.506454 -0.200495 0.8994711 0.3882703 -0.6234716 0.779257 -0.0635758 -0.6179912 0.6804485 -0.393798 -0.8139789 0.5442667 0.2030083 -0.8672468 0.2541197 -0.4281428 -0.934655 0.1623842 0.3163093 -0.9041371 -0.256787 -0.3414626 -0.5078394 0.4975994 0.7032027 -0.3756453 0.1193167 0.9190508 -0.7368133 0.07542353 0.6718761 -0.3711839 -0.08087712 0.9250305 -0.5838049 -0.3895527 0.7123347 -0.2987197 -0.3448396 0.8898608 -0.2731569 -0.5059506 0.8181683 -0.1723535 -0.5149732 0.8397006 -0.1439692 -0.4799898 0.8653801 0.06078571 -0.5067124 0.8599696 0.07829362 -0.4446833 0.8922595 0.3225194 -0.5299546 0.7843019 0.328943 -0.4008661 0.8550456 0.5612094 -0.3789909 0.7358056 0.5341749 -0.1518759 0.8316195 0.5977871 -0.1096631 0.7941188 0.4923512 0.02340513 0.8700819 0.6007197 0.1343395 0.7880918 0.4186869 0.3045256 0.8555498 0.4573391 0.3153128 0.831516 0.3008571 0.4678183 0.8310422 0.2525328 0.4433693 0.8600296 0.162398 0.5529087 0.8172632 0.01228696 0.47846 0.8780235 -0.04000777 0.5551187 0.8308084 -0.2526099 0.5643576 0.7859318 -0.2651508 0.3836883 0.8845781 -0.3902083 0.4077076 0.8255374 -0.5071109 0.3031248 0.8068172 -0.4474488 0.1593846 0.8799921 -0.5708054 0.1204709 0.8121996 -0.6032151 -0.103217 0.7908716 -0.4469878 -0.1360937 0.884127 -0.4767191 -0.3492911 0.8066814 -0.3588311 -0.3622089 0.8602588 -0.361508 -0.4730306 0.8034638 -0.1075307 -0.5033753 0.8573508 -0.1111349 -0.4915885 0.8637071 0.09684401 -0.5972382 0.7961958 0.1528777 -0.451139 0.8792623 0.3659746 -0.5453878 0.7540656 0.448198 -0.356563 0.8197448 0.3822926 -0.2327354 0.8942521 0.5439987 -0.1929415 0.8166022 0.5766828 0.0312305 0.8163711 0.4792988 0.06651324 0.8751279 0.5463638 0.2772229 0.790338 0.3879263 0.27963 0.8782484 0.3507921 0.521538 0.777781 0.2101401 0.4397201 0.8732053 0.09884333 0.5980406 0.7953474 -0.0259149 0.5093957 0.8601422 -0.1003537 0.5773668 0.8102942 -0.2066424 0.4374099 0.8751981 -0.4140377 0.4897828 0.7672585 -0.3803879 0.2931879 0.8771238 -0.5267956 0.2745616 0.8044268 -0.5668116 0.06263196 0.8214632 -0.4860796 0.0151335 0.8737836 -0.5828792 -0.1566008 0.7973256 -0.4495055 -0.2231228 0.864963 -0.4946523 -0.3674269 0.7876017 -0.3432155 -0.4067338 0.8466231 -0.3145332 -0.5750345 0.7552511 -0.0689066 -0.5817466 0.8104462 -0.07151192 -0.5761737 0.8141928 0.1519294 -0.550404 0.8209586 0.1660273 -0.4443062 0.8803562 0.3428059 -0.4677432 0.8146782 0.3939828 -0.3130711 0.8641552 0.5400682 -0.3247818 0.7764298 0.5790252 -0.007049262 0.8152793 0.4963388 -0.05514758 0.8663756 0.5055887 0.1863914 0.8424004 0.4974766 0.1766875 0.8492929 0.4688428 0.3913021 0.7918771 0.2946593 0.3754293 0.8787655 0.2801548 0.4864073 0.8275997 0.1360777 0.5387932 0.8313753 0.1337575 0.5454274 0.8274164 -0.05298644 0.5697261 0.8201249 -0.09642189 0.4905843 0.8660427 -0.2250478 0.5460924 0.8069304 -0.3449761 0.4058234 0.8463445 -0.3370452 0.3811028 0.8609072 -0.5374371 0.3013566 0.7876202 -0.4494529 0.104115 0.887216 -0.5089477 0.08173781 0.856908 -0.6245947 -0.1140618 0.7725746 -0.4333987 -0.2064459 0.8772376 -0.4711313 -0.2787572 0.836857 -0.3298144 -0.4795163 0.8131953 -0.273298 -0.4312727 0.8598326 -0.08534902 -0.4564452 0.8856486 -0.05699354 -0.5232124 0.8502945 0.09820234 -0.6386604 0.7631968 0.1615789 -0.4741558 0.8654875 0.3233558 -0.5124303 0.7955226 0.3379867 -0.3831671 0.8596209 0.5088798 -0.3415455 0.7901824 0.5092045 -0.1773511 0.8421742 0.4634138 -0.1930686 0.8648539 0.6231682 0.008161842 0.7820453 0.4461858 0.1040776 0.8888679 0.522723 0.2105152 0.8261018 0.4103098 0.3788118 0.8295466 0.2934274 0.3544188 0.8878558 0.2875685 0.5135111 0.808462 0.1543516 0.6200075 0.7692636 0.0141555 0.4807377 0.8767502 -0.07998728 0.5808266 0.810088 -0.2386597 0.4787635 0.8448829 -0.2389781 0.4712908 0.8489844 -0.3942131 0.4469952 0.802989 -0.4129711 0.2709134 0.8695176 -0.444761 0.2706773 0.853769 -0.6242529 0.1182083 0.7722274 -0.4651145 -0.02505069 0.884896 -0.5490409 -0.1032074 0.8293988 -0.53028 -0.2803408 0.8001327 -0.4067422 -0.2931841 0.865219 -0.4034978 -0.4458872 0.7989832 -0.2371202 -0.4290486 0.8716027 -0.1975123 -0.5970899 0.7774784 0.04857599 -0.4958203 0.8670656 0.1406966 -0.6099293 0.7798659 0.2593235 -0.4225118 0.8684672 0.3398801 -0.4475742 0.827139 0.4945913 -0.3110949 0.8115413 0.4368374 -0.2158284 0.8732647 0.6016602 -0.1209075 0.7895483 0.4844335 0.01803117 0.8746422 0.5932353 0.1617633 0.7886092 0.4232914 0.2507398 0.8706055 0.4671393 0.3532862 0.8105368 0.3198671 0.518575 0.7929471 0.1927501 0.4388512 0.8776429 0.1347845 0.5394425 0.8311649 -0.04239654 0.4596278 0.8870992 -0.08412146 0.5160408 0.8524233 -0.339192 0.401263 0.8508447 -0.3561746 0.446797 0.8206779 -0.4670625 0.258561 0.8455761 -0.4655092 0.256057 0.847193 -0.5595412 0.1024605 0.8224449 -0.5104463 0.05671656 0.8580372 -0.5882624 -0.1099302 0.8011634 -0.4511104 -0.1718065 0.8757751 -0.5127721 -0.2949515 0.8062683 -0.3578365 -0.4508768 0.8177184 -0.2671434 -0.4059382 0.8739843 -0.177353 -0.5825706 0.7931945 -0.04873996 -0.5021619 0.8633992 0.05490207 -0.6133693 0.7878858 0.192558 -0.4562683 0.8687582 0.2948873 -0.5172888 0.8034014 0.4528155 -0.2976189 0.840465 0.4273535 -0.2643505 0.8645738 0.5952724 -0.0767132 0.7998536 0.5225137 -0.01997637 0.8523969 0.5809766 0.1657761 0.7968592 0.4696702 0.1825926 0.8637533 0.4675882 0.3882014 0.7941417 0.3011144 0.4131327 0.8594484 0.3288362 0.4295799 0.8410279 0.1482799 0.5523909 0.8202911 0.1088647 0.5080926 0.8543949 -0.07738983 0.6340754 0.769389 -0.2857674 0.5115024 0.8103718 -0.1727051 0.4618685 0.8699715 -0.3507425 0.4076957 0.8430683 -0.3338109 0.3485217 0.8758441 -0.4890621 0.2411792 0.8382428 -0.4789142 0.1772693 0.8597772 -0.5929899 0.1298534 0.7946704 -0.5255922 -0.08203589 0.8467721 -0.5495101 -0.07606309 0.8320175 -0.49361 -0.2594113 0.8300933 -0.4459679 -0.2621657 0.8557931 -0.398901 -0.4159868 0.8172105 -0.294659 -0.4104538 0.8629622 -0.2504561 -0.5464842 0.7991413 -0.09838521 -0.4814499 0.8709342 -0.01706111 -0.6180784 0.7859314 0.1952084 -0.5229725 0.8296949 0.1953904 -0.5200726 0.8314729 0.4497215 -0.4997349 0.7402808 0.4472462 -0.3901321 0.8048403 0.5207929 -0.3459981 0.7804231 0.527216 -0.1195611 0.841278 0.540906 -0.114369 0.833271 0.5762439 0.03247487 0.8166323 0.5083773 0.07321095 0.8580167 0.5656767 0.2095758 0.7975513 0.3998327 0.2874573 0.870346 0.4290348 0.3810698 0.8189719 0.2914565 0.5305028 0.7960025 0.1552225 0.4546365 0.8770471 0.1101665 0.5558952 0.8239198 -0.09474968 0.5420194 0.8350076 -0.1047837 0.5121409 0.852486 -0.3063427 0.4866486 0.8181243 -0.2541938 0.4563413 0.852724 -0.4600664 0.430532 0.7765187 -0.4335134 0.2501254 0.8657388 -0.555626 0.210218 0.804418 -0.4833584 0.05401211 0.8737547 -0.5993201 -0.03779768 0.7996166 -0.4868498 -0.1923441 0.8520452 -0.5118457 -0.2360146 0.8260213 -0.3642448 -0.3780166 0.8511341 -0.3576956 -0.3520244 0.8649467 -0.1990647 -0.6237396 0.7558586 -0.1027615 -0.4832803 0.8694138 0.1412245 -0.5764859 0.8048104 0.1597824 -0.4621989 0.8722624 0.3948826 -0.4860887 0.7796062 0.361805 -0.2866997 0.8870741 0.5537554 -0.2537906 0.7930608 0.5151643 -0.07971489 0.8533765 0.6174145 -0.0156877 0.7864815 0.4798383 0.1537716 0.8637764 0.5397027 0.2430526 0.8060066 0.4029259 0.3949189 0.8256452 0.3219116 0.37213 0.87057 0.3016811 0.4932492 0.8159006 0.1022379 0.5669146 0.8174077 0.02748763 0.4593515 0.8878293 -0.09280103 0.5863519 0.8047232 -0.2875347 0.4926182 0.8213716 -0.2776331 0.3992337 0.8738033 -0.4727833 0.3751203 0.797346 -0.4470319 0.2281211 0.8649412 -0.5827971 0.1813082 0.7921333 -0.5263092 -1.30011e-5 0.8502933 -0.5829252 -0.05116677 0.8109132 -0.4816567 -0.2037692 0.8523408 -0.5125182 -0.2574972 0.8191584 -0.3881844 -0.404079 0.8282713 -0.306846 -0.3705521 0.8766622 -0.192686 -0.6093112 0.7691632 -0.03127562 -0.4751259 0.8793619 0.04163336 -0.5818688 0.8122165 0.2580232 -0.5198517 0.8143576 0.249556 -0.4286718 0.86831 0.4731569 -0.3272657 0.8179363 0.4347181 -0.3205662 0.8415805 0.590708 -0.1478638 0.7932216 0.5470854 -0.1065483 0.8302681 0.6526337 0.1015465 0.7508381 0.5125852 0.1986791 0.8353341 0.5403841 0.2985386 0.7866765 0.3974909 0.3281228 0.8569344 0.3354845 0.307828 0.8903326 0.2606526 0.5254637 0.8099064 0.1096346 0.4826616 0.8689179 0.06741887 0.5975788 0.7989708 -0.2042047 0.4703372 0.8585356 -0.2052315 0.490917 0.846688 -0.4247231 0.4229127 0.8004719 -0.4095923 0.3713642 0.8332604 -0.6189082 0.2331939 0.7500488 -0.547981 0.08434981 0.8322272 -0.5537112 0.07803136 0.8290446 -0.4362632 -0.07059735 0.8970454 -0.5946655 -0.2321486 0.7697274 -0.3368598 -0.3646437 0.8680786 -0.3634618 -0.3785154 0.8512471 -0.221655 -0.5478156 0.8067014 -0.1185684 -0.4792563 0.8696292 -0.01529818 -0.6004323 0.7995293 0.09959983 -0.5076445 0.8557902 0.1592908 -0.543144 0.8243913 0.3050589 -0.435175 0.8470903 0.3064208 -0.4414499 0.8433436 0.483071 -0.2996503 0.8227103 0.4390923 -0.2301883 0.8684534 0.5970652 -0.09401142 0.796665 0.4884772 0.01512193 0.8724458 0.5973439 0.1325132 0.7909619 0.3828898 0.2234546 0.8963613 0.4240517 0.4221532 0.8012284 0.2924564 0.3957135 0.8705631 0.2221956 0.5413672 0.8108951 0.1076212 0.5112069 0.852693 0.09246784 0.5365565 0.8387831 -0.08950221 0.5630745 0.8215451 -0.1168553 0.4983172 0.8590838 -0.2780689 0.5140229 0.8114545 -0.2987625 0.4101759 0.8616824 -0.4717848 0.4139802 0.7784854 -0.4592443 0.1960712 0.8664011 -0.5462276 0.1766572 0.8187965 -0.5132753 -0.08159369 0.8543366 -0.4751645 -0.05504924 0.8781734 -0.543451 -0.3289537 0.7723021 -0.3583563 -0.3548264 0.8635271 -0.3651741 -0.4327814 0.8242258 -0.177643 -0.5121009 0.8403546 -0.1738645 -0.5285772 0.8308895 -0.001937866 -0.617299 0.7867263 0.09493362 -0.4690852 0.8780358 0.1775826 -0.5296372 0.829427 0.3643502 -0.4261988 0.8280118 0.3579388 -0.3808361 0.8525512 0.4893966 -0.3404107 0.8028771 0.4682985 -0.1838724 0.8642266 0.5496346 -0.1537532 0.8211345 0.527635 0.0678026 0.846761 0.5081387 0.07525229 0.8579815 0.5649479 0.2537972 0.7851247 0.3707261 0.3286265 0.868658 0.3961387 0.3377314 0.8538218 0.2787523 0.5307569 0.8003715 0.1710286 0.4723357 0.8646665 0.06917971 0.5931088 0.8021448 -0.03292596 0.5027269 0.8638181 -0.125283 0.5757394 0.807978 -0.2241238 0.3783351 0.8981265 -0.430426 0.4411196 0.7874941 -0.4225769 0.2442639 0.8727909 -0.5552911 0.2282674 0.799716 -0.5649278 0.0446918 0.8239291 -0.4156121 -0.03914451 0.9086993 -0.5258725 -0.1795174 0.8314035 -0.4223843 -0.3360648 0.8418148 -0.3902773 -0.2709408 0.8799288 -0.3232995 -0.5537179 0.7673813 -0.135474 -0.4672572 0.8736805 -0.07485204 -0.584176 0.8081681 0.07512998 -0.5104885 0.8565962 0.1859706 -0.5976138 0.7799184 0.2915416 -0.4268999 0.8560139 0.3877786 -0.4457526 0.8068038 0.4366292 -0.2735343 0.8570495 0.4959438 -0.2702747 0.825222 0.5924935 -0.06637883 0.8028358 0.5822039 -0.0607317 0.8107714 0.464844 0.1745825 0.8680099 0.5740326 0.2922447 0.764905 0.4728255 0.4541179 0.7551246 0.2676113 0.4132977 0.8703845 0.230536 0.5453379 0.8058908 0.07977694 0.5199402 0.8504692 0.1025532 0.4817816 0.8702697 -0.1063915 0.524687 0.844621 -0.1523745 0.4716764 0.8685064 -0.2743928 0.5375443 0.7973425 -0.3756486 0.3506036 0.8578841 -0.4029418 0.356287 0.8430289 -0.5607678 0.2793011 0.7794424 -0.4836211 0.07962256 0.8716483 -0.5473877 0.04762202 0.8355233 -0.5679524 -0.154444 0.8084412 -0.4747412 -0.1771679 0.8621093 -0.4861766 -0.356352 0.7979007 -0.442184 -0.3616509 0.8207814 -0.3721606 -0.5426179 0.7530355 -0.183375 -0.5175596 0.8357666 -0.1522877 -0.5757237 0.8033373 0.002860546 -0.4840236 0.8750504 0.08087182 -0.5724317 0.8159546 0.2999488 -0.4472392 0.8426197 0.2921406 -0.4191357 0.8596389 0.4993138 -0.3139002 0.8075596 0.4614925 -0.2063347 0.8628157 0.5885053 -0.1444997 0.7954756 0.5967363 0.08937597 0.7974445 0.5215871 0.02396476 0.8528614 0.4307546 0.26624 0.8623033 0.4824177 0.2740649 0.8319625 0.3182265 0.4046709 0.857306 0.3221454 0.4792029 0.8164477 0.1244366 0.5258506 0.8414255 0.1213558 0.5219728 0.8442851 -0.09344208 0.5448654 0.8333008 -0.09330487 0.5453717 0.8329851 -0.281448 0.4808835 0.8303843 -0.2767452 0.4152156 0.8666073 -0.4775253 0.3867269 0.7889309 -0.4573017 0.1614 0.8745428 -0.5206208 0.2154172 0.8261656 -0.5560831 -0.02210211 0.8308328 -0.5290217 -0.03259921 0.847982 -0.5649826 -0.2720549 0.7789614 -0.3608335 -0.2780748 0.8902099 -0.3770049 -0.4868957 0.7879086 -0.1895851 -0.4613952 0.8667018 -0.1704062 -0.5283735 0.831735 0.0310685 -0.5798797 0.8141096 0.1084372 -0.4602601 0.8811368 0.1889484 -0.5263625 0.829 0.3778817 -0.4869813 0.7874356 0.3541519 -0.2939767 0.8877805 0.4949982 -0.2948821 0.8173258 0.6062796 -0.1101008 0.7875933 0.4814512 -0.008041858 0.8764361 0.5398291 0.04567253 0.8405347 0.5526745 0.2366139 0.7991025 0.4185201 0.2735762 0.8660237 0.4408042 0.3995995 0.8037488 0.2601098 0.4380763 0.8604838 0.2600621 0.4391838 0.8599333 -0.008693575 0.5690107 0.8222843 -0.02907443 0.5064013 0.8618078 -0.2606875 0.5097016 0.8199064 -0.2592507 0.4590576 0.8497383 -0.4758122 0.3787308 0.7938298 -0.4218637 0.2485647 0.8719214 -0.5940721 0.177051 0.7846855 -0.4844245 0.01770472 0.874654 -0.6101503 -0.1133285 0.7841386 -0.4646102 -0.2159048 0.8587913 -0.5007264 -0.320137 0.8042297 -0.3326342 -0.3709316 0.8670434 -0.3308244 -0.5411843 0.7730944 -0.1110073 -0.5007488 0.8584452 -0.06655871 -0.5859411 0.8076157 0.1407454 -0.5249919 0.8393892 0.1165162 -0.5014607 0.8572989 0.402038 -0.4532748 0.7955549 0.3549139 -0.3156197 0.8800117 0.5456121 -0.2659287 0.794726 0.4628086 -0.08692991 0.8821856 0.6532883 0.02950942 0.756534 0.4510999 0.1964594 0.8705817 0.4470493 0.1961973 0.8727278 0.4134024 0.4509791 0.7910223 0.2445192 0.4334494 0.8673708 0.3020073 0.4807665 0.8231981 0.08104729 0.5382605 0.8388724 0.06401079 0.5124447 0.8563312 -0.1529865 0.6097605 0.7776808 -0.2230491 0.4085835 0.8850472 -0.3219981 0.4565252 0.8293987 -0.4900269 0.3736845 0.7875491 -0.4411387 0.1681525 0.881545 -0.4637708 0.1889156 0.8655793 -0.6287799 -0.003338932 0.7775763 -0.4818227 -0.1060568 0.869827 -0.5641971 -0.2331146 0.7920476 -0.3590873 -0.3238663 0.8753097 -0.3934641 -0.4934765 0.775672 -0.1664798 -0.5407915 0.8245175 -0.08205121 -0.4425834 0.8929657 0.03706568 -0.6014453 0.7980537 0.2017325 -0.5360105 0.8197541 0.2014593 -0.377647 0.9037683 0.3996741 -0.413666 0.8180105 0.368293 -0.2183247 0.9037117 0.5093566 -0.1938986 0.8384268 0.5811617 -0.03458553 0.8130528 0.487434 0.02265727 0.8728659 0.5711568 0.1699129 0.8030627 0.4267165 0.2533396 0.8681775 0.473764 0.4177477 0.7752642 0.2598308 0.4546898 0.8519068 0.2552191 0.4970134 0.8293617 0.03321945 0.5533782 0.8322675 -0.007145047 0.4824113 0.8759158 -0.2299942 0.6233454 0.7473576 -0.3072257 0.3550003 0.8829423 -0.3525298 0.4586827 0.8156796 -0.4993694 0.2152912 0.8392139 -0.4736815 0.1873775 0.8605322 -0.5965032 0.0315898 0.8019888 -0.5047475 -0.05170631 0.8617171 -0.6012448 -0.1879284 0.7766516 -0.4909484 -0.3552805 0.7954531 -0.4226999 -0.3491659 0.8363062 -0.3642305 -0.5175996 0.7742267 -0.158601 -0.4559026 0.8757846 -0.1313138 -0.5617931 0.8167895 0.09135895 -0.5715613 0.8154578 0.1130563 -0.4853635 0.8669721 0.2886313 -0.5875382 0.7559703 0.3644506 -0.3943079 0.8436215 0.3650755 -0.3954896 0.8427977 0.6129058 -0.3362317 0.7150489 -0.1277911 -0.8689385 -0.4781374 0.1689049 -0.9617672 0.2155805 0.2429853 -0.8949136 -0.3742832 0.516244 -0.8330561 0.1987704 0.3305992 0.4854377 0.8093544 -0.3846867 0.4589415 0.8008677 0.4128862 -0.2618711 0.8723236 -0.369148 -0.5576725 0.7434589 -0.1698089 -0.6215273 -0.7647671 0.1017372 -0.4758365 0.8736299 0.04291099 0.7660468 -0.641351 -0.1358802 0.7169772 0.6837252 -0.3223664 0.6272559 -0.7089641 -0.4329491 0.507355 0.7450813 -0.5365679 0.3453756 -0.7699421 0.5401639 -0.1378338 -0.8301957 -0.1407274 -0.3722614 0.9173971 0.2804408 0.5292181 -0.8008003 0.06624835 0.5491398 0.8331007 -0.7555443 -0.06566828 -0.651798 -0.5871993 -0.2290527 0.776358 0.8373921 0.2304888 0.4956302 0.681245 0.7076569 -0.1874217 -0.3148462 0.8783492 -0.3596869 -0.5881314 0.5972795 0.545306 -0.3933112 -0.1167554 -0.9119619 -0.05697518 0.6039822 -0.7949588 0.2569787 0.7480576 -0.6118593 -0.01594549 0.7336657 0.6793236 0.5655092 0.02018827 0.8244949 0.3969611 -0.6559354 -0.6420053 0.5156689 -0.514915 0.684798 0.4747781 -0.1978816 -0.8575714 0.8769552 -0.3218156 -0.3569093 0.8291616 -0.03828012 0.5576968 0.6068369 0.1461707 -0.7812703 0.1377055 0.115198 0.9837514 0.6389036 0.4438421 0.6283364 0.8162328 0.5500908 0.176534 0.4857108 0.2277692 0.8439232 0.8092159 0.4879685 0.3271949 0.893795 0.3241862 0.3098933 0.1523582 -0.001564323 0.9883241 0.6058123 0.1263998 0.7855029 0.6186273 0.1414858 0.7728403 0.8694874 0.2480011 0.4271853 0.7626323 -0.06126528 0.6439245 0.7062939 -0.1225906 0.6972234 0.9998682 -0.01391613 -0.008360266 0.9972084 -0.03560155 0.06563401 0.5039863 -0.1238488 0.8547861 0.8796154 -0.2927437 0.3749374 0.9333202 -0.2714445 0.2350136 0.4178448 -0.2379481 0.8768047 0.8054738 -0.4131066 0.4249175 0.5407578 -0.3649019 0.7579101 0.5123972 -0.528215 0.6770806 0.7826787 -0.6101498 -0.1230099 0.395003 -0.5125417 0.762413 0.656641 -0.6837017 0.318394 0.2459589 -0.6248143 0.7410205 0.3075425 -0.6589173 0.6864734 0.4493532 -0.8912075 0.0618965 0.4059699 -0.8874036 0.2184109 0.03882437 -0.2253271 0.9735093 0.1836292 -0.9522209 0.2440404 0.1124973 -0.7767188 0.6197196 0.0466265 -0.7467511 0.6634672 -0.001667797 -0.5577942 0.8299777 0.1052842 -0.9944362 0.003476798 -0.06322276 -0.9285192 0.3658621 -0.06480503 -0.9341835 0.3508583 -0.1607196 -0.6099716 0.7759537 -0.145097 -0.3116073 0.9390675 -0.2340455 -0.9722108 0.005378782 -0.2145229 -0.5680458 0.7945464 -0.3413187 -0.8865323 0.3123494 -0.3049852 -0.6684047 0.6783947 -0.4334078 -0.6826004 0.5884 -0.5295363 -0.8117205 0.2463763 -0.3078903 -0.3108153 0.8992204 -0.4801716 -0.4706982 0.7401881 -0.5069522 -0.5319387 0.678263 -0.6191325 -0.7836108 -0.05127692 -0.6937732 -0.6615788 0.2845915 -0.1787492 -0.1193047 0.9766346 -0.6235949 -0.3376495 0.705069 -0.5677694 -0.2630465 0.7800285 -0.8321928 -0.5379993 0.1342082 -0.8343587 -0.4546143 0.3117234 -0.6791727 -0.1460101 0.7193091 -0.9571787 -0.2677017 0.1102039 -0.554269 -0.0215829 0.8320578 -0.9331992 -0.1785824 0.3118453 -0.119915 0.01836878 0.9926143 -0.7288447 0.08782291 0.6790233 -0.9811884 -0.005778193 0.192966 -0.8801931 0.1250234 0.457853 -0.3783205 0.1616805 0.9114457 -0.9179297 0.2523201 0.3061693 -0.4703307 0.1922915 0.8612857 -0.8231509 0.37095 0.4299054 -0.6917945 0.3638951 0.6236993 -0.6311116 0.5073545 0.586762 -0.3187801 0.3243316 0.8906113 -0.7963809 0.5963605 -0.1006558 -0.4491457 0.4651249 0.7628415 -0.7345694 0.6417792 0.2202892 -0.1033691 0.1687762 0.9802191 -0.447313 0.663698 0.5995132 -0.5678779 0.778906 0.2661206 -0.1402778 0.3441078 0.9283922 -0.5311021 0.8471829 0.01455569 -0.338168 0.6677724 0.6631158 -0.2965517 0.8190116 0.4911996 -0.3155927 0.8686631 0.3818714 -0.06119644 0.5123007 0.856623 -0.1180979 0.7751433 0.6206495 -0.06257164 0.673245 0.7367673 -0.1136532 0.9786785 -0.1710886 -0.08095061 0.9964617 0.02260994 0.03561991 0.2285503 0.9728804 0.07376629 0.7482284 0.6593276 0.1443066 0.4920862 0.8585026 0.1232548 0.9223123 0.3662629 0.2998416 0.9493065 0.09440511 0.2938291 0.5857934 0.7553215 0.3433197 0.9154337 0.2100302 0.344774 0.6557704 0.6716369 0.2594773 0.2852743 0.922654 0.5705571 0.7081417 0.4159328 0.6186245 0.7576294 0.2080896 0.5556768 0.4791128 0.6794662 0.6350343 0.7579085 0.1493522 0.004542469 0.003966927 0.9999818 -0.02017742 -0.002791225 0.9997926 0.00188744 -0.002725422 0.9999945 5.65282e-4 0.01007056 0.9999492 0.01451128 0.002351641 0.999892 0.01194244 -0.02521413 0.9996108 -0.003867983 0.001060605 0.999992 6.05896e-4 -0.00272262 0.9999962 -0.5635895 -0.5481517 0.6179778 -0.5994922 -0.6472537 0.4708204 -0.3577208 -0.3606224 0.8613869 -0.2611344 -0.3217901 0.910088 -0.5378927 -0.7059496 0.4607675 -0.35074 -0.599081 0.7197802 -0.3672221 -0.8360863 0.4075629 -0.3389183 -0.609825 0.7164131 -0.03336924 -0.06815737 0.9971164 -0.1534925 -0.411318 0.8984752 -0.2600228 -0.8637808 0.4315911 -0.1545616 -0.7214519 0.6749948 -0.08000248 -0.7383955 0.6696057 -0.009796142 -0.6103696 0.7920562 0.1283444 -0.7001656 0.7023503 0.120394 -0.6791892 0.7240216 0.262498 -0.8169694 0.5134743 0.1000938 -0.3335288 0.9374112 0.3453985 -0.6043287 0.7179741 0.4168578 -0.6736013 0.6103203 0.2658822 -0.4647991 0.8445523 0.1918336 -0.2677683 0.9441928 0.5852567 -0.6839137 0.4355877 0.5609169 -0.4781596 0.6758222 0.4287055 -0.3646582 0.826581 0.6494979 -0.4987893 0.5739005 0.2992268 -0.1930956 0.9344397 0.7276552 -0.4115602 0.5487588 0.6977134 -0.3571779 0.6209831 0.4636065 -0.2297921 0.8557246 0.8061696 -0.3018669 0.508888 0.7637771 -0.2003698 0.6135932 0.666754 -0.149339 0.7301623 0.4526608 -0.1312041 0.8819772 0.7139254 -0.007922112 0.700177 0.6855922 -0.02032107 0.7277022 0.1622493 -0.02453821 0.9864447 0.7308297 0.09923779 0.6753072 0.8303884 0.1448482 0.538028 0.4005112 0.1073138 0.9099861 0.8596111 0.3269502 0.3926478 0.7453677 0.3552094 0.5641395 0.4880241 0.2228739 0.8438956 0.7703072 0.4965428 0.4000903 0.5865475 0.4964875 0.6398924 0.2677498 0.1941631 0.9437218 0.5906456 0.5307784 0.6077929 0.1046218 0.09571701 0.9898953 0.4613809 0.6337642 0.6208628 0.3810934 0.6011285 0.7024332 0.3597693 0.581531 0.7296491 0.264946 0.582516 0.7684262 0.2464754 0.6625624 0.7072913 0.139596 0.7790484 0.6112257 0.1451104 0.666234 0.7314884 0.05178165 0.3968561 0.9164191 0.03206473 0.1520047 0.9878596 0.02381992 0.9137511 0.4055757 -0.04698675 0.8279907 0.5587699 -0.0386933 0.6150667 0.7875251 -0.183952 0.9225146 0.3393062 -0.108139 0.4361505 0.8933525 -0.234437 0.8543429 0.4638293 -0.3215926 0.8428624 0.4314642 -0.1074272 0.3220769 0.9405987 -0.3362734 0.6969697 0.6333668 -0.2158583 0.4614456 0.8605076 -0.471738 0.7454363 0.4709438 -0.6062534 0.6361437 0.477261 -0.5239773 0.5835421 0.6204244 -0.2689965 0.3222798 0.9076214 -0.3991718 0.4235838 0.8131658 -0.7703786 0.5504783 0.3216994 -0.4309608 0.2976589 0.8518639 -0.674724 0.418869 0.6076976 -0.27298 0.1510813 0.9500823 -0.7538558 0.3201877 0.5737434 -0.6317324 0.2131147 0.7453162 -0.8354663 0.1230642 0.535585 -0.6622437 0.1371542 0.7366288 -0.3055127 0.01082003 0.9521265 -0.8993881 0.008699595 0.4370646 -0.6624536 -0.09088814 0.7435688 -0.8189982 -0.1802349 0.5447546 -0.671538 -0.1071861 0.7331766 -0.8559521 -0.3241574 0.4028251 -0.4675375 -0.1624413 0.8689199 -0.6320632 -0.3235121 0.7041563 -0.5968515 -0.3029533 0.7429588 -0.7337504 -0.4931915 0.4673036 -0.2789465 -0.2001826 0.9392102 -0.6932384 -0.7206766 0.006767272 -0.555913 -0.8312258 -0.00496906 -0.5568289 -0.8306137 -0.004745662 -0.4497492 -0.8931453 0.004130721 -0.3764852 -0.9264077 -0.005264639 -0.230194 -0.9731445 8.00994e-4 -0.2489295 -0.9685154 -0.003490269 -0.03586006 -0.9993448 0.004927039 -0.04741042 -0.9988731 0.00222212 0.1412897 -0.9899679 -9.09561e-4 0.1023464 -0.9947338 0.005472898 0.267231 -0.9636279 -0.002986609 0.3257192 -0.9454555 0.004587292 0.4033828 -0.9150275 -0.002679288 0.4873371 -0.8732103 0.002555191 0.533119 -0.8460292 -0.004357159 0.653042 -0.7573137 -0.003485083 0.6583378 -0.7527198 -0.002028524 0.7882843 -0.6153076 -0.002119779 0.785642 -0.6186751 -0.002830862 0.8639351 -0.503597 -0.002525389 0.8719807 -0.4895403 5.04981e-4 0.9404917 -0.339787 0.004499077 0.9578653 -0.2872093 -0.002208411 0.9802017 -0.1978998 0.006361722 0.9944291 -0.1054032 0.001067519 0.9973556 -0.07246506 0.005554497 0.99619 0.08717203 -0.002593517 0.9879108 0.1548648 0.00701785 0.9583485 0.2855651 -0.004584252 0.9370008 0.3492914 0.005006432 0.8661853 0.4997057 -0.004162907 0.8378161 0.5459247 0.005529999 0.7478166 0.6638884 -0.004756331 0.6985337 0.7155637 0.004401028 0.6107289 0.7918352 0.002700924 0.6178529 0.7862926 0.001377046 0.4663974 0.8845752 -5.78105e-4 0.4645679 0.8855371 -8.90853e-4 0.3239142 0.9460751 0.004648923 0.3472784 0.9377619 -7.93536e-4 0.2398027 0.9707992 0.006610989 0.1094114 0.9939908 -0.003379523 -0.02584385 0.9996566 -0.004340827 0.0436291 0.9990408 0.003770112 -0.262222 0.9649777 -0.007604539 -0.1883287 0.9820922 0.005232632 -0.3864575 0.9222971 0.004327476 -0.463487 0.8860942 -0.004139482 -0.5497735 0.8352943 0.00572282 -0.61548 0.7881525 -3.16861e-4 -0.6551391 0.7554951 0.004474639 -0.742689 0.6696035 -0.006648242 -0.8343948 0.5511668 -7.77584e-4 -0.8216627 0.5699644 0.003320515 -0.9276813 0.373373 1.34847e-4 -0.935552 0.3531631 0.004286527 -0.9802779 0.1976103 0.002352535 -0.9760686 0.217457 -0.001618146 -0.9994804 -0.03223383 -1.6619e-4 -0.9994718 -0.0324977 -2.19068e-4 -0.9867303 -0.1623634 0.001172125 -0.979628 -0.2007815 -0.003995716 -0.932559 -0.3610153 0.001370728 -0.9313145 -0.3642154 7.05067e-4 -0.8402026 -0.5422716 0.001089155 -0.833244 -0.5528963 0.003189921 -0.7586783 -0.651445 -0.005179822 -0.02466547 0.00377506 0.9996886 0.002763688 0.01678645 0.9998553 -0.001231431 0.003730237 0.9999923 0.02131009 0.003588736 0.9997665 0.01157116 0.0203824 0.9997254 0.03312718 5.04287e-4 0.9994511 0.001349091 9.99952e-4 0.9999987 -0.01133626 0.0081954 0.9999023 -0.01811432 -0.004051685 0.9998278 -0.005441904 0.002352178 0.9999824 0.003949046 -0.005427896 0.9999775 0.005952954 0.002186119 0.9999799 0.005314946 0.005127191 0.9999728 -0.005537271 0.001614928 0.9999834 -0.004955768 9.15004e-4 0.9999874 6.63889e-4 -2.70263e-4 0.9999998 -0.004659056 -0.004836142 0.9999775 -0.008296191 9.16079e-4 0.9999652 -0.008888661 0.00110501 0.99996 1.31501e-4 -0.002727925 0.9999963 0.01501792 0.006716609 0.9998648 0.008837461 -0.01189529 0.9998902 -0.01267838 -0.02242356 0.9996683 -0.00100404 -0.0104742 0.9999447 -0.01591914 -0.01581543 0.9997482 -0.002371966 -0.009216725 0.9999548 0.008859634 -0.01432627 0.9998582 -0.00193113 -0.009144425 0.9999564 -0.7402607 -0.4505408 -0.4990263 -0.6187756 -0.427771 -0.6588846 -0.8135019 -0.3352643 -0.4751976 -0.425873 -0.2002085 -0.8823541 -0.701156 -0.2334384 -0.6737112 -0.7295398 -0.1643336 -0.6639023 -0.6530404 -0.08132779 -0.7529437 -0.2372576 -0.01176798 -0.9713756 -0.8344581 -0.003394961 -0.5510611 -0.7851098 0.1466902 -0.6017348 -0.8170992 0.1382704 -0.5596698 -0.5323007 0.1184797 -0.8382235 -0.8036036 0.3467397 -0.4837281 -0.3884605 0.1442932 -0.9100978 -0.8169716 0.3444698 -0.462491 -0.3103915 0.1329536 -0.9412654 -0.7433415 0.4558524 -0.4895325 -0.6153542 0.4307512 -0.6601459 -0.5564898 0.5393385 -0.6320072 -0.5369279 0.5103054 -0.6717864 -0.3998594 0.4191281 -0.8151344 -0.5684989 0.7510933 -0.3356606 -0.4283907 0.7708598 -0.471441 -0.2652751 0.4290236 -0.8634628 -0.355785 0.6977185 -0.6217765 -0.2834987 0.7292919 -0.6227052 -0.2439031 0.9367063 -0.2511823 -0.04889881 0.1232867 -0.9911656 -0.1086296 0.5344798 -0.8381713 -0.1289715 0.849774 -0.5111269 -0.09575027 0.4936481 -0.8643746 -0.05060225 0.9274467 -0.370516 0.1075565 0.7986146 -0.5921539 0.01829075 0.4225525 -0.9061539 0.1152603 0.7620596 -0.6371659 0.09723174 0.6572207 -0.7474002 0.2650116 0.8518593 -0.4517796 0.3465627 0.6613955 -0.6651694 0.1511898 0.3344308 -0.9302139 0.3444387 0.6514137 -0.6760343 0.1028187 0.2054826 -0.9732447 0.5267481 0.6051618 -0.5969218 0.5226952 0.6025546 -0.6030901 0.6748785 0.6025231 -0.426034 0.3672476 0.3888785 -0.8449276 0.6801297 0.4976949 -0.5382596 0.2969806 0.2305201 -0.9266408 0.820577 0.4686517 -0.3271374 0.3754966 0.2590916 -0.889873 0.7772651 0.3240365 -0.5393137 0.4385061 0.1803137 -0.880454 0.4084333 0.1559398 -0.8993694 0.9017972 0.2663493 -0.3403232 0.8369378 0.139682 -0.5291731 0.5874941 0.1035381 -0.8025775 0.9118342 0.08830517 -0.4009498 0.870884 -0.01856678 -0.491138 0.3918316 0.004222571 -0.9200273 0.9388155 -0.1012623 -0.3291981 0.5558076 -0.04526251 -0.8300778 0.822631 -0.185806 -0.5373588 0.9240857 -0.2810772 -0.2589617 0.6473549 -0.1538123 -0.7465075 0.5343361 -0.1704858 -0.8279007 0.6325554 -0.3422414 -0.6947982 0.802331 -0.4052236 -0.4382454 0.5034292 -0.360611 -0.7851871 0.5332937 -0.4221981 -0.7330393 0.475692 -0.5415261 -0.693157 0.3630272 -0.4995381 -0.7865577 0.3584836 -0.6407958 -0.6788743 0.3113589 -0.6733258 -0.6705878 0.2123309 -0.6227847 -0.7530304 0.1789811 -0.7211258 -0.6692857 0.09620881 -0.7492041 -0.6553146 0.09212809 -0.7458587 -0.6597025 -0.03466147 -0.8533428 -0.5201968 -0.006229519 -0.2951118 -0.9554424 -0.09671807 -0.773993 -0.6257638 -0.07226884 -0.4684261 -0.880542 -0.1997895 -0.8530261 -0.4821108 -0.2746132 -0.7462633 -0.6063652 -0.12849 -0.407464 -0.904137 -0.2709392 -0.6799879 -0.6813284 -0.3778775 -0.623382 -0.6845463 -0.06870615 -0.1449668 -0.9870482 -0.5248735 -0.7498196 -0.4028378 -0.2890465 -0.4179623 -0.8612548 -0.6185615 -0.5689621 -0.5419076 -0.5615031 -0.4754191 -0.6772674 -0.3399876 -0.3403814 -0.8766694 -0.110759 0.993451 -0.02806329 -0.1178756 0.9928069 -0.02097719 0.7952117 0.6060014 -0.02001792 0.8006123 0.5984901 -0.0288071 0.9191929 -0.3932936 -0.02011096 0.9187905 -0.3941829 -0.02107429 0.06509858 -0.657992 -0.7502059 0.1107769 -0.8372353 -0.5355051 0.6235039 -0.2529807 -0.7397592 0.7687831 -0.3396776 -0.541841 0.5350608 0.4017542 -0.7431713 0.5417541 0.4053494 -0.7363385 -0.07926267 0.6644626 -0.7431062 -0.08075654 0.6698898 -0.7380557 -0.6182844 0.26411 -0.7402502 -0.6203742 0.2654929 -0.7380037 -0.5318571 -0.3996347 -0.7466058 -0.5422487 -0.4052558 -0.7360259 -0.9188676 0.3937813 -0.02487397 -0.918728 0.3940864 -0.02519524 -0.7994394 -0.6002106 -0.02537888 -0.7995163 -0.600113 -0.02526074 0.1132243 -0.9932404 -0.02557098 0.1176961 -0.992825 -0.02112513 -0.003102421 -0.007979273 -0.9999634 -0.001031994 -1.5661e-4 -0.9999995 0.008949995 0.001042664 -0.9999595 3.23211e-4 3.42547e-5 -1 0.003944873 -0.001902163 -0.9999905 0.003475785 -0.00244379 -0.9999911 0.001127481 0.005588948 -0.9999838 0.002226889 -0.01518756 -0.9998822 0.003555893 -0.002063691 -0.9999915 0.004626393 -0.009853899 -0.9999408 0.009482324 7.746e-4 -0.9999548 0.006590425 0.005543828 -0.999963 -0.00420314 0.002374768 -0.9999884 0.001532554 -0.008525848 -0.9999626 0.004605948 -0.005774259 -0.9999728 0.002359211 0.006444096 -0.9999765 -3.21129e-4 0.007039248 -0.9999752 -0.003670513 0.001220345 -0.9999926 -0.003633081 -0.002230584 -0.999991 -0.01065957 -0.006483614 -0.9999222 -0.003801524 -0.002149879 -0.9999905 -0.007281899 0.00269109 -0.99997 -0.002310752 0.003848016 -0.99999 -0.004064202 0.001304566 -0.9999909 -0.02653437 -0.0262317 -0.9993037 -0.05342715 -0.01044255 -0.9985172 -0.03569728 0.01505219 -0.9992493 -0.03814476 0.009397983 -0.9992281 -0.008535087 0.01231056 -0.9998879 -0.02677214 0.00659877 -0.9996198 -0.06844097 -0.06248593 -0.9956964 -0.03793376 0.06213641 -0.9973465 -0.05180352 -0.07751893 -0.9956442 -0.01505464 -0.0519877 -0.9985343 7.61785e-5 0.02220332 -0.9997535 -0.03124856 -0.04267996 -0.9986 -5.69984e-4 -0.01502203 -0.9998871 0.00649625 -0.02688372 -0.9996175 0.0069108 -0.02361649 -0.9996972 0.03325617 -0.04509204 -0.9984292 0.03905814 -0.06560057 -0.9970813 0.3321927 -0.3118471 -0.8901682 0.6340527 -0.3764688 -0.6754617 0.4581828 -0.1000216 -0.8832126 0.6342331 -0.0368005 -0.7722657 0.4694314 0.1191478 -0.8748931 0.5432386 0.2006742 -0.8152434 0.421682 0.3480752 -0.8372741 0.4591118 0.4543322 -0.7634125 0.2302157 0.4348959 -0.8705552 0.1491662 0.6117926 -0.7768265 -0.01380276 0.5429382 -0.8396592 -0.07679814 0.6264964 -0.7756315 -0.2529726 0.4575392 -0.8524452 -0.2535651 0.4580041 -0.8520195 -0.492642 0.3596674 -0.7924287 -0.4358016 0.2181853 -0.8731966 -0.6242441 0.1521146 -0.7662771 -0.4730967 -0.07988661 -0.8773812 -0.5624978 -0.1461873 -0.8137724 -0.425278 -0.3411732 -0.8382955 -0.3940373 -0.2936169 -0.8709327 -0.3586071 -0.5220072 -0.7738924 -0.1211276 -0.4729806 -0.8727071 -0.09665977 -0.5914932 -0.8004953 0.1394054 -0.4799233 -0.866164 0.1739124 -0.5222124 -0.8348945 0.3406444 -0.3099426 -0.8876357 0.4714143 -0.3537211 -0.8078675 0.4919691 -0.1767589 -0.8524804 0.5567352 -0.1623829 -0.8146643 0.5395145 0.04269325 -0.8408933 0.57038 0.06277942 -0.8189783 0.4856743 0.2571768 -0.8354523 0.5097954 0.288093 -0.8106239 0.3756624 0.411477 -0.8304002 0.3617034 0.4077966 -0.838375 0.2006293 0.5766905 -0.7919444 0.09806251 0.5617274 -0.8214902 0.07445621 0.6015653 -0.7953462 -0.08656793 0.4980118 -0.8628385 -0.1692526 0.5923667 -0.7876898 -0.2892045 0.4923203 -0.8209637 -0.2948012 0.3419288 -0.8922876 -0.4418914 0.3314289 -0.8335988 -0.4545505 0.2289162 -0.8608027 -0.5471345 0.2144011 -0.8091205 -0.5523741 0.02444618 -0.833238 -0.5732529 0.01385045 -0.8192616 -0.5114745 -0.1901937 -0.8379859 -0.5455556 -0.2250655 -0.8072884 -0.3783327 -0.3913246 -0.8388859 -0.3446291 -0.381627 -0.8576665 -0.1653435 -0.5649169 -0.8084124 -0.08019191 -0.4777895 -0.8748065 0.01726341 -0.5710217 -0.8207535 0.2344394 -0.4333852 -0.8701814 0.2333362 -0.4369584 -0.8686896 0.3388401 -0.4819842 -0.8080092 0.4555861 -0.3047801 -0.8363912 0.4499374 -0.2924618 -0.8438142 0.5590782 -0.1310671 -0.8186898 0.4824479 -0.03974509 -0.8750225 0.6202465 0.07151138 -0.7811405 0.4950091 0.2463595 -0.8332304 0.4049941 0.2502466 -0.8794069 0.4126045 0.4488626 -0.7926413 0.2716251 0.4873021 -0.8299136 0.2037194 0.4501307 -0.869414 0.1047012 0.5920275 -0.7990878 -0.04216057 0.4833639 -0.8744037 -0.1505417 0.605817 -0.7812318 -0.2538426 0.3519557 -0.9009391 -0.4419414 0.4234075 -0.7908313 -0.3712521 0.1699591 -0.9128449 -0.6448417 0.1153792 -0.7555573 -0.5274303 -0.1005781 -0.843624 -0.4786038 -0.113025 -0.8707261 -0.4711675 -0.3595067 -0.8054541 -0.3853416 -0.3537698 -0.8522669 -0.3213374 -0.4899564 -0.8103612 -0.2884646 -0.4823418 -0.8271243 -0.1852465 -0.5937322 -0.7830492 0.02023726 -0.5061594 -0.8622025 0.07223945 -0.573518 -0.8160017 0.1732577 -0.3945076 -0.9024109 0.3167885 -0.4767174 -0.8199912 0.4220778 -0.331772 -0.8436692 0.4439214 -0.3369495 -0.8303005 0.5461603 -0.1373317 -0.8263468 0.517289 -0.1421223 -0.8439273 0.5785352 0.05921989 -0.8135048 0.5291717 0.08742117 -0.8439993 0.527561 0.2669897 -0.8064712 0.4497717 0.2807299 -0.8478776 0.3883548 0.438709 -0.8103795 0.367369 0.4347349 -0.82222 0.2562262 0.5914916 -0.7645167 0.08228749 0.5539035 -0.8285046 0.06499159 0.5823419 -0.810342 -0.1192122 0.5068978 -0.8537231 -0.1681038 0.5637825 -0.8086349 -0.3104186 0.3702379 -0.8755366 -0.4176254 0.4192771 -0.8060991 -0.4709665 0.135816 -0.8716334 -0.4703551 0.1349382 -0.8720997 -0.6108907 0.04597246 -0.7903792 -0.5026114 -0.09653598 -0.8591058 -0.5651468 -0.178708 -0.8054022 -0.4088971 -0.2993476 -0.8620872 -0.428677 -0.3408837 -0.8366807 -0.3212455 -0.4894804 -0.8106851 -0.2096076 -0.4520695 -0.8670052 -0.1377142 -0.6191614 -0.7730938 0.05185598 -0.4978528 -0.8657099 0.1038907 -0.5710671 -0.8143029 0.3125558 -0.4767179 -0.8216137 0.3100316 -0.3888961 -0.8675484 0.4864655 -0.3257409 -0.8107061 0.4328914 -0.2031021 -0.878268 0.5821273 -0.08203917 -0.8089483 0.4981443 0.027318 -0.8666638 0.5503377 0.06603991 -0.8323264 0.5207206 0.2641967 -0.8118192 0.3853772 0.2865976 -0.8771239 0.4113044 0.4373506 -0.7997207 0.2490144 0.4866213 -0.8373718 0.2429332 0.5383592 -0.8069405 0.04380291 0.5292936 -0.8473073 0.01848793 0.5768707 -0.8166263 -0.1581282 0.5079266 -0.8467621 -0.176023 0.4578738 -0.8714171 -0.3248175 0.5119386 -0.7952436 -0.4348549 0.3003548 -0.8489337 -0.3813212 0.2209752 -0.8976436 -0.5977653 0.04399359 -0.8004632 -0.4760283 -0.06255656 -0.8772023 -0.5586013 -0.1646022 -0.8129396 -0.4328622 -0.2673606 -0.8608999 -0.4689911 -0.3546075 -0.8088886 -0.3096907 -0.4574404 -0.8335707 -0.3116581 -0.4818989 -0.8189279 -0.1133686 -0.5333709 -0.83825 -0.1073957 -0.5539515 -0.8255931 0.112424 -0.48725 -0.8659957 0.07498294 -0.5480551 -0.8330745 0.2343692 -0.5530644 -0.7994942 0.3673816 -0.3783136 -0.8496527 0.3822511 -0.3842069 -0.8403982 0.5160071 -0.218879 -0.8281478 0.4891412 -0.2194138 -0.8441556 0.6131414 -0.09327733 -0.784447 0.5057784 0.01412945 -0.8625477 0.552582 0.1058387 -0.8267112 0.4140512 0.2042809 -0.887035 0.4710837 0.3182552 -0.8226748 0.4124938 0.399937 -0.8184738 0.309008 0.3816695 -0.8711157 0.25959 0.5553625 -0.7900542 0.06093341 0.5155948 -0.8546632 0.04944926 0.5501093 -0.8336274 -0.1499317 0.580555 -0.8002977 -0.172962 0.5105401 -0.8422785 -0.3554086 0.425686 -0.8321517 -0.3432731 0.3646149 -0.8655747 -0.5786334 0.2466701 -0.7773913 -0.465285 0.08401536 -0.8811647 -0.6085255 -0.004942476 -0.793519 -0.4730305 -0.1870909 -0.8609526 -0.504596 -0.2164475 -0.8357831 -0.413653 -0.4650385 -0.7827071 -0.2485561 -0.4138221 -0.8757689 -0.2018721 -0.5773193 -0.7911701 -0.008610069 -0.4804441 -0.8769831 0.07110792 -0.6175402 -0.7833184 0.2722944 -0.4963935 -0.8242872 0.2733718 -0.4346761 -0.8580936 0.4444472 -0.3796562 -0.8113741 0.3970367 -0.262137 -0.8795716 0.4796208 -0.07989573 -0.873831 0.5879139 -0.0617401 -0.806564 0.415678 0.1415165 -0.8984348 0.5123821 0.2398033 -0.8245963 0.3026918 0.3756861 -0.8759211 0.4091064 0.3999978 -0.8201425 0.2745919 0.5785337 -0.7680482 0.02139073 0.5018208 -0.8647071 0.03440874 0.5221325 -0.8521701 -0.1540218 0.5515226 -0.8198171 -0.2290667 0.4203623 -0.8779658 -0.3196956 0.4779946 -0.8181174 -0.5083867 0.4129103 -0.7556774 -0.4406178 0.2108939 -0.8725709 -0.5602573 0.1595875 -0.8127999 -0.504293 0.0113371 -0.8634583 -0.6063876 -0.06436496 -0.7925599 -0.5021371 -0.1760067 -0.8466877 -0.5708546 -0.3075837 -0.7612604 -0.3809472 -0.472976 -0.7944639 -0.3812917 -0.4763519 -0.7922788 -0.1773889 -0.4716449 -0.8637617 -0.1686978 -0.5093773 -0.8438459 0.01608341 -0.5605946 -0.8279343 0.04450923 -0.5205912 -0.8526451 0.2024463 -0.5504916 -0.8099226 0.2322549 -0.4574943 -0.8583453 0.4115434 -0.4495589 -0.7927981 0.4058004 -0.317578 -0.8570125 0.5371089 -0.2653926 -0.8006753 0.4769894 -0.1155192 -0.8712844 0.6252757 -0.05041342 -0.7787739 0.5063805 0.1715386 -0.845076 0.4380158 0.1847309 -0.8797821 0.4958235 0.3869962 -0.7774274 0.2766308 0.4432805 -0.85263 0.2258748 0.4152759 -0.8812075 0.09827858 0.6001611 -0.7938186 -0.03166049 0.4918441 -0.8701075 -0.1107703 0.584136 -0.8040617 -0.2189502 0.4926453 -0.8422359 -0.3678022 0.5485528 -0.7508738 -0.4911531 0.3234256 -0.8088044 -0.4757152 0.3212024 -0.8188554 -0.5527566 0.1099949 -0.8260517 -0.5776678 0.1306411 -0.80575 -0.5789433 -0.200859 -0.7902407 -0.5427718 -0.1673567 -0.8230374 -0.4197403 -0.3155359 -0.8510318 -0.4854478 -0.4422922 -0.7541339 -0.1904553 -0.4514148 -0.871752 -0.1661303 -0.571057 -0.8039245 7.69565e-4 -0.5126032 -0.8586254 0.06904041 -0.6059446 -0.7925053 0.206504 -0.4608578 -0.8631144 0.2149165 -0.3935347 -0.8938352 0.4240555 -0.4221443 -0.801231 0.4558688 -0.2493775 -0.8543972 0.4679052 -0.2501931 -0.8476251 0.5902758 -0.1118406 -0.7994162 0.50769 -0.02145677 -0.8612728 0.5842587 0.1542031 -0.7967831 0.5083546 0.1811124 -0.8418872 0.463795 0.3526081 -0.8127495 0.3852648 0.3471337 -0.8550259 0.2709537 0.5210635 -0.8093683 0.16209 0.463149 -0.8713322 0.07895427 0.614345 -0.7850774 -0.09763646 0.5025989 -0.8589887 -0.1331391 0.5402925 -0.830878 -0.2690632 0.5132299 -0.8149848 -0.2959253 0.4069838 -0.8641716 -0.4436275 0.4203224 -0.7915326 -0.4497297 0.2270911 -0.8638129 -0.5586908 0.2105906 -0.8021947 -0.5203261 0.006276071 -0.8539447 -0.4719096 0.03030687 -0.8811259 -0.5259941 -0.1776249 -0.831733 -0.4007112 -0.2082516 -0.8922229 -0.4064936 -0.3900283 -0.826221 -0.283077 -0.3601789 -0.8888975 -0.1652651 -0.5368535 -0.8273307 -0.07626938 -0.4579911 -0.885679 0.04893779 -0.6244481 -0.7795318 0.2377696 -0.4675351 -0.8513968 0.2375788 -0.4725423 -0.8486815 0.4092069 -0.4160841 -0.8120492 0.4120851 -0.2695423 -0.8703636 0.5136259 -0.2694123 -0.8146198 0.5765642 -0.05057358 -0.8154851 0.4770898 0.01579511 -0.8787127 0.6166067 0.195913 -0.7625052 0.3684024 0.2854875 -0.8847467 0.4056166 0.4217046 -0.8109503 0.238443 0.44802 -0.8616397 0.2303587 0.5277833 -0.8175449 0.07155233 0.5776379 -0.8131511 0.01665478 0.5150834 -0.8569782 -0.1975017 0.4579175 -0.8667784 -0.1366653 0.5553994 -0.820277 -0.3210135 0.5354952 -0.7811499 -0.4515028 0.3263044 -0.830464 -0.3966812 0.2113642 -0.8932914 -0.5714925 0.1653016 -0.8037859 -0.5748514 -0.07792484 -0.8145388 -0.5376095 -0.08870661 -0.8385149 -0.4458171 -0.3368605 -0.8293204 -0.3953216 -0.3332589 -0.8559553 -0.3217047 -0.4792094 -0.8166177 -0.2928887 -0.4717387 -0.8316723 -0.1562261 -0.637942 -0.7540712 0.01426577 -0.5331815 -0.8458807 0.09981393 -0.582059 -0.8069972 0.1518829 -0.4910427 -0.857793 0.275444 -0.509698 -0.8150696 0.3262873 -0.4031121 -0.8550072 0.3902314 -0.4139829 -0.8223976 0.4917086 -0.222362 -0.8418895 0.4533901 -0.2187147 -0.8640609 0.6181538 -0.06662559 -0.7832286 0.4740748 0.09672617 -0.8751555 0.5126744 0.08302652 -0.8545593 0.5504192 0.331271 -0.7663539 0.3224363 0.3776421 -0.8679986 0.3437506 0.4625504 -0.817241 0.2152105 0.5268809 -0.8222415 0.07992583 0.4469638 -0.8909744 -0.004474163 0.5526893 -0.8333754 -0.1117219 0.4974772 -0.8602527 -0.2327799 0.6308386 -0.7401731 -0.3271366 0.3544507 -0.8759831 -0.4721018 0.3727191 -0.7988746 -0.4616069 0.2083321 -0.8622742 -0.5356855 0.1856035 -0.8237673 -0.5174805 -6.09803e-4 -0.8556948 -0.5675336 -0.02879941 -0.8228465 -0.5142118 -0.2150562 -0.8302634 -0.5178791 -0.2190327 -0.8269377 -0.4005925 -0.4088695 -0.8199703 -0.2973813 -0.3850092 -0.8736889 -0.2793989 -0.4685361 -0.8380993 -0.08475965 -0.5400389 -0.8373612 0.004873275 -0.4616214 -0.8870638 0.1269603 -0.6633937 -0.737421 0.2801977 -0.3978928 -0.8735964 0.3999748 -0.4410841 -0.8034084 0.4369531 -0.2675384 -0.8587754 0.5528834 -0.2579066 -0.7923409 0.5003613 -0.06463825 -0.8634005 0.4907261 -0.05683559 -0.8694583 0.5011263 0.1355797 -0.8546875 0.5007895 0.1357449 -0.8548586 0.5089343 0.3049287 -0.8049873 0.383094 0.3269694 -0.863904 0.4098502 0.5012128 -0.7621079 0.1168071 0.5009329 -0.8575677 0.1422363 0.5302164 -0.8358466 -0.08753293 0.5429709 -0.8351771 -0.09536397 0.5255942 -0.8453736 -0.3136324 0.4792812 -0.81971 -0.3116196 0.3701915 -0.8751295 -0.5332231 0.3708388 -0.760363 -0.448854 0.07857584 -0.8901437 -0.51589 0.1333877 -0.8462065 -0.5478842 -0.147219 -0.8234983 -0.517672 -0.1539667 -0.8416116 -0.4169135 -0.3793112 -0.8260182 -0.3995257 -0.3762551 -0.8359494 -0.253561 -0.5194323 -0.8160252 -0.1485746 -0.4578058 -0.8765497 -0.05668884 -0.6323767 -0.772584 0.1628087 -0.4621525 -0.8717272 0.1986062 -0.5035321 -0.8408396 0.3880909 -0.4489176 -0.8048966 0.373429 -0.2940062 -0.879836 0.5183845 -0.2807711 -0.8077409 0.5205547 -0.08064168 -0.8500117 0.5513217 -0.07020711 -0.8313336 0.5575399 0.1473456 -0.8169692 0.4924395 0.1042363 -0.8640823 0.5114954 0.3630663 -0.7788166 0.3079823 0.3829398 -0.8709215 0.3590579 0.4035518 -0.8415601 0.1861298 0.5526669 -0.8123517 0.1419128 0.5207058 -0.8418588 -0.03067904 0.6592623 -0.7512871 -0.181806 0.5260823 -0.8307731 -0.2511745 0.5535321 -0.7940489 -0.2906371 0.4007304 -0.8688758 -0.4195731 0.3941267 -0.8176934 -0.4171989 0.2444325 -0.8753272 -0.5831496 0.1968107 -0.7881639 -0.5024158 0.04825353 -0.8632786 -0.5385215 0.01855146 -0.8424076 -0.4420251 -0.1377762 -0.8863586 -0.5526872 -0.2795336 -0.7851101 -0.3685488 -0.3240419 -0.8713029 -0.3780148 -0.4092925 -0.8304124 -0.1491827 -0.4256448 -0.8925083 -0.1377766 -0.5669288 -0.8121634 0.1033733 -0.5050107 -0.8569004 0.09523373 -0.4898949 -0.8665642 0.3364865 -0.5742344 -0.7463455 0.3645803 -0.3213883 -0.8739513 0.474211 -0.3338488 -0.8146588 0.5224991 -0.1382449 -0.8413578 0.5267351 -0.1424489 -0.8380087 0.5133563 0.0669502 -0.8555601 0.5835676 0.1168256 -0.8036172 0.4554014 0.2803037 -0.8450086 0.4727931 0.3123894 -0.8239415 0.3245972 0.4377316 -0.8384675 0.3283449 0.4584353 -0.8258492 0.1836116 0.5503017 -0.8145274 0.09588557 0.4920998 -0.8652421 -0.04590207 0.5919422 -0.8046723 -0.1104467 0.4618285 -0.880066 -0.3229309 0.5357386 -0.7801923 -0.3492746 0.3354061 -0.8749343 -0.4667702 0.3422059 -0.8154882 -0.4821053 0.1651684 -0.8604033 -0.5605345 0.1517173 -0.8141148 -0.6084259 -0.02276867 -0.7932842 -0.4933017 -0.09492683 -0.8646633 -0.540681 -0.2420403 -0.8056554 -0.4203435 -0.2848544 -0.8614925 -0.4330691 -0.3925757 -0.8113788 -0.2414004 -0.448772 -0.8604241 -0.2432818 -0.4653691 -0.8510262 -0.101154 -0.6370932 -0.7641206 0.04820394 -0.4867338 -0.8722193 0.1164283 -0.5550117 -0.8236544 0.2651494 -0.4852558 -0.8332002 0.2694119 -0.45173 -0.8505042 0.4519008 -0.3469921 -0.8218165 0.4037821 -0.331145 -0.8528207 0.567861 -0.1912783 -0.8005914 0.4755097 -0.06953114 -0.8769584 0.6384146 0.07086056 -0.766424 0.4543492 0.2077444 -0.8662616 0.5077905 0.2832586 -0.8135806 0.3411689 0.4252615 -0.8383058 0.3484956 0.4270434 -0.8343769 0.2401449 0.5272849 -0.8150467 0.1335113 0.4851389 -0.8641846 0.06019049 0.5985014 -0.7988576 -0.03077745 0.5338343 -0.8450289 -0.184459 0.6305726 -0.753892 -0.3325031 0.4243062 -0.8422625 -0.4002721 0.458246 -0.7935949 -0.4218326 0.1635144 -0.8918074 -0.4954802 0.1624143 -0.8533002 -0.5898378 1.74907e-4 -0.8075218 -0.4996492 -0.06126403 -0.8640587 -0.5652939 -0.2190975 -0.7952604 -0.4170899 -0.2761773 -0.8658881 -0.4344099 -0.4126465 -0.8006316 -0.2685274 -0.4151794 -0.8692061 -0.2303898 -0.5569839 -0.7979283 -0.1551479 -0.5229371 -0.8381324 0.03193128 -0.6746172 -0.7374769 0.1527034 -0.4600356 -0.8746707 0.2845648 -0.3549692 -0.8905166 0.2977467 -0.4497509 -0.8420636 0.5198991 -0.2800784 -0.8070075 0.462475 -0.1279946 -0.877345 0.6121491 -0.07717692 -0.7869671 0.5044709 0.131946 -0.8532875 0.545646 0.1638165 -0.8218483 0.4397637 0.4049947 -0.8016155 0.3198235 0.3850799 -0.8656942 0.2862713 0.3689265 -0.8842748 0.1299363 0.5336481 -0.8356652 0.05426001 0.490086 -0.8699837 -2.81794e-5 0.5916502 -0.8061948 -0.1996225 0.5296229 -0.8244093 -0.2267805 0.4306313 -0.8735716 -0.4486936 0.4712504 -0.75934 -0.4146928 0.3332937 -0.8467262 -0.5231384 0.1580884 -0.837457 -0.5147495 0.1475467 -0.844549 -0.5616479 -0.02887123 -0.8268725 -0.5052919 -0.06425839 -0.8605527 -0.5620199 -0.2426801 -0.7907212 -0.3558894 -0.2996307 -0.8851916 -0.4015558 -0.4252144 -0.8111385 -0.229373 -0.5310996 -0.8156723 -0.1533264 -0.4859853 -0.8604124 -0.06612557 -0.5943346 -0.8014948 0.08466744 -0.5063297 -0.8581735 0.131909 -0.5603476 -0.8176863 0.3027465 -0.4674133 -0.8305838 0.3089054 -0.3878938 -0.8683986 0.4496235 -0.3871424 -0.8049594 0.480872 -0.1832016 -0.8574376 0.4933831 -0.1830162 -0.85034 0.6186173 -0.02312523 -0.7853521 0.4131555 0.1052377 -0.9045593 0.5169407 0.2362754 -0.8227673 0.3051173 0.3205472 -0.8967458 0.3305901 0.3799774 -0.8639025 0.2540493 0.514813 -0.8187959 0.08877116 0.4541897 -0.8864713 0.03876978 0.3888945 -0.9204663 -0.2000811 0.5160064 -0.8328895 -0.2322439 0.8361617 -0.4968867 -0.247585 0.2605048 -0.9331876 -0.8647934 0.4605162 -0.2001433 0.08706265 0.9608122 -0.2631731 -0.3756981 0.9235995 0.07625639 -0.3787512 0.8538967 0.3569427 -0.7094035 0.6000055 -0.369784 -0.6710962 0.4338318 0.6011822 -0.7943512 0.1376938 -0.5916475 -0.8614276 -0.04924559 0.5054875 -0.7823184 -0.2962598 -0.5479126 -0.642032 -0.4157413 0.6441694 -0.4500659 -0.6515387 -0.6106866 -0.3078135 -0.8281055 0.4685002 -0.1295552 -0.8970029 -0.4226125 0.133872 -0.7638564 0.6313491 0.3780868 -0.626339 -0.6817257 0.5957165 -0.6729989 0.4383999 0.8619859 -0.447703 -0.2377864 0.8959482 -0.405229 0.1818422 0.9569238 -0.03392291 -0.2883507 0.9945116 0.006439805 0.1044284 0.9098289 0.402464 0.1011641 0.90252 0.4275808 -0.05130666 0.6233021 0.7766902 -0.09081244 0.3631489 0.8960509 0.2553738 -0.07184892 0.9793038 -0.1892137 -0.09362596 0.9911518 0.09408676 -0.5810734 0.8123142 0.04999476 -0.5886332 0.6890861 -0.4226952 -0.7583443 0.4778347 0.4433824 -0.8603103 0.2661884 -0.4347531 -0.9547919 0.1179935 0.2728556 -0.899206 -0.1316697 -0.4172432 -0.8587508 -0.2348868 0.4553848 -0.6887654 -0.6732816 -0.268876 -0.7480062 -0.6539257 0.113437 -0.3524579 -0.8899637 -0.2893754 -0.2168235 -0.7626084 0.6094391 0.1578951 -0.7660573 -0.6230775 0.308349 -0.7694258 0.5593791 0.5838869 -0.7065989 -0.3997425 0.7228578 -0.5635918 0.3998011 0.7828677 -0.3129073 -0.5377799 0.7773106 -0.1517468 0.6105418 0.773964 0.1957893 -0.6022012 0.7348716 0.3424881 0.5853765 0.66999 0.5899589 -0.4506242 0.4571406 0.7997807 0.3890674 0.3747987 0.8983198 -0.2292327 0.005191326 0.9554432 0.2951298 -0.09544247 0.9590832 -0.2665528 -0.5122565 0.8498106 0.124158 -0.5080823 0.8608916 -0.02680039 -0.8343473 0.4950069 0.2425548 -0.8540433 0.4114353 -0.3183254 -0.9955756 -0.07508128 0.05650007 -0.9212108 -0.09159749 0.3781277 -0.7729126 -0.482412 -0.412171 -0.7436619 -0.5714782 0.3469579 -0.450547 -0.8393454 -0.3041492 -0.1414875 -0.9820723 -0.1245613 0.2750927 -0.8822273 0.3820984 0.3983117 -0.8029277 -0.443458 0.7016294 -0.6508133 0.2901006 0.7444528 -0.4826489 -0.4613458 0.831478 -0.2907259 0.4734162 0.8972339 0.01781642 -0.4411962 0.9857172 0.08921641 0.1428357 0.8831004 0.4685546 -0.0242964 0.8481525 0.4888037 -0.2042261 0.5832386 0.7571787 0.2941312 0.2052535 0.8143404 -0.5428822 -0.1108691 0.8356324 0.537984 -0.3547557 0.7672138 -0.5343514 -0.4974262 0.736182 0.4589154 -0.6905334 0.4800513 -0.5410308 -0.7978674 0.3218547 0.5097228 -0.8737654 0.1078644 -0.4742355 -0.8648188 -0.07863247 0.4958884 -0.7904087 -0.4211353 -0.4448588 -0.8391424 -0.5138452 0.1783345 -0.5108205 -0.8504732 -0.1255304 -0.4903194 -0.8598074 0.1425423 -0.1016967 -0.965038 -0.2415769 0.003685593 -0.8620481 0.5068133 0.2753263 -0.8338754 -0.4783799 0.4855411 -0.7546128 0.4413723 0.6550264 -0.6573491 -0.3726024 0.7911561 -0.4699022 0.3914894 0.8284831 -0.2473925 -0.5024068 0.7878752 -0.04351049 0.614296 0.7163683 0.2550415 -0.6494385 0.7174956 0.4184308 0.5568804 0.5729746 0.7046238 -0.4185757 0.5069586 0.8244484 0.2515509 0.2186411 0.89946 -0.3783754 0.1581563 0.948319 0.2750958 -0.2647615 0.9319851 0.2475985 -0.333969 0.7577696 -0.56058 -0.6981586 0.5175373 0.4947017 -0.8226652 0.4575277 -0.3374764 -0.9720887 -0.03761184 0.2315796 -0.8953241 -0.1407374 -0.4225965 -0.8041363 -0.3959046 0.4434236 -0.5615838 -0.5693812 -0.6003572 -0.6013619 -0.7534443 0.2658675 -0.2748522 -0.9260238 0.2587206 -0.1302599 -0.8901979 -0.4365549 0.1179054 -0.9047948 0.4092002 0.3002825 -0.8245303 -0.4795626 0.5848921 -0.7184385 0.3764936 0.6788031 -0.5629276 -0.4715283 0.7876861 -0.417587 0.452959 0.8954367 -0.02388012 -0.4445481 0.9629432 -0.05711722 -0.2635869 0.8692417 0.3264888 0.3712465 0.6451491 0.4578222 -0.6117038 0.600846 0.6025542 0.5252738 0.2647852 0.824335 -0.5003607 0.1929754 0.8996748 0.3915939 -0.1604133 0.9135949 -0.3736471 -0.2428384 0.9516721 0.1880155 -0.6301119 0.7750051 -0.04823011 -0.6268009 0.7790759 -0.0127049 -0.9478586 0.2854766 -0.1416587 -0.9425826 0.2626288 0.2063111 -0.972095 -0.2031486 -0.1173121 -0.8477579 -0.2442733 0.4707838 -0.6423246 -0.4834827 -0.5946962 -0.4841183 -0.6289818 0.6082857 -0.3573876 -0.8532843 -0.3797105 -0.1050142 -0.9238286 0.3681207 -0.006294012 -0.9858333 -0.1676101 0.4209635 -0.8769816 -0.2317177 0.4480373 -0.8667257 0.2192012 0.7530518 -0.6044453 0.2599213 0.7307748 -0.3832011 -0.5649117 0.8529704 -0.2353446 0.4658911 0.8379876 0.09567832 -0.537236 0.8805338 0.1961225 0.4315047 0.7152175 0.6311581 -0.3001724 0.6261932 0.6307247 0.4583321 0.2977415 0.8080215 -0.5083812 0.1248161 0.8909673 0.4365755 -0.06494927 0.903505 -0.4236276 -0.2744368 0.6918734 0.6678292 -0.4574624 0.4520413 -0.7657589 -0.6787877 0.4224035 0.600685 -0.9090989 0.1154427 -0.4002652 -0.9929081 0.09271919 -0.07441008 -0.9228861 -0.3668344 0.1171055 -0.5644295 -0.5900368 -0.5773006 -0.3945098 -0.8014225 0.4495378 -0.1798097 -0.8846725 -0.4301432 -0.003400325 -0.9383276 0.3457307 0.2372881 -0.8859837 -0.3984062 0.3406117 -0.8581959 0.384036 0.7228735 -0.6410222 -0.2579621 0.6963441 -0.5780649 -0.4253774 0.7929649 -0.2842262 0.5389083 0.8445992 -0.07289749 -0.5304133 0.8693454 0.2894169 0.4005953 0.9315187 0.2996436 0.2061229 0.5478276 0.8228966 -0.1507524 0.5487372 0.8358063 -0.01775896 0.01807373 0.9960543 0.08688718 0.02722334 0.9888817 0.1461913 -0.4292606 0.8575433 -0.2834697 -0.7102645 0.6663729 0.2268735 -0.9654119 0.1936914 0.1745381 -0.8623031 -0.2066912 -0.4622901 -0.7447558 -0.4572939 0.4860258 -0.588847 -0.6285198 -0.5081558 -0.4498249 -0.8360249 0.3141974 -0.3199303 -0.9055671 -0.278555 -0.08367097 -0.8924058 0.4434085 0.1910484 -0.7764946 -0.6004638 0.3135542 -0.7719631 0.5529529 0.6670911 -0.553389 -0.4987486 0.7638916 -0.5158046 0.3878341 0.9118254 -0.2005419 -0.3582699 0.9615415 -0.123436 0.2453598 0.9498092 0.2344968 -0.2070597 0.9608166 0.2670593 0.07423412 0.785825 0.604254 0.1317431 0.7218156 0.6445347 -0.2521059 0.4340547 0.8958007 0.09559166 0.3950951 0.8597807 0.3235387 -0.008357822 0.9333273 -0.3589295 -0.099518 0.9479169 0.3025719 -0.385405 0.8527821 -0.3524565 -0.4591406 0.7805391 0.4242035 -0.7813069 0.5421309 -0.3092796 -0.8380845 0.5137205 0.1835916 -0.9394886 0.1450053 -0.3103783 -0.9486052 0.09325057 0.3024113 -0.9237517 -0.3801594 0.04649502 -0.7394465 -0.4068769 -0.5363489 -0.6184714 -0.6284754 0.4717117 -0.389565 -0.7836083 -0.4839393 -0.2257422 -0.7943434 0.5639673 0.05826777 -0.7634637 -0.6432169 0.2823807 -0.7418121 0.6082566 0.5302956 -0.6803323 -0.5058999 0.6763482 -0.5465394 0.4938097 0.7344979 -0.2596955 -0.626954 0.7097299 -0.06481397 0.7014861 0.6699787 0.2236073 -0.7079042 0.7143347 0.4318788 0.5506421 0.5516512 0.7342271 -0.3957164 0.527822 0.8226395 0.2113486 0.1098926 0.9478979 -0.2990205 0.1008118 0.986648 -0.1279169 -0.2755255 0.8543122 0.4407228 -0.4125277 0.8526176 -0.3207246 -0.7417869 0.6254349 -0.2420402 -0.6206811 0.436698 0.6511913 -0.7483211 0.09730863 -0.6561604 -0.7669054 -0.04257553 0.6403464 -0.7153594 -0.3980062 -0.5743274 -0.7708212 -0.5421804 0.3344778 -0.4823809 -0.8685538 -0.1136792 -0.1680014 -0.9826567 -0.0784949 0.2190154 -0.9662573 0.1355692 0.3068899 -0.8644469 -0.3981836 0.4828692 -0.7307441 0.4825458 0.7119863 -0.4970367 -0.4960142 0.7944886 -0.4466739 0.4114248 0.8669008 -0.0118919 -0.4983389 0.7900319 0.0695253 0.6091108 0.7044338 0.4536752 -0.5458498 0.6163967 0.5837295 0.5285027 0.5131605 0.7812879 -0.3553249 0.2609121 0.9182422 0.2979198 0.09101998 0.9132751 -0.3970441 -0.1065554 0.8598985 0.49922 -0.3602505 0.7903409 -0.4955611 -0.5745742 0.7565429 0.3122621 -0.6981245 0.6510921 -0.2978276 -0.7607617 0.4384307 0.4785606 -0.8752731 0.1955888 -0.4423146 -0.96451 0.07968801 0.2517344 -0.9011784 -0.2113006 -0.378457 -0.88674 -0.2882106 0.3614233 -0.6699346 -0.7407947 -0.04910188 -0.6812028 -0.702697 0.2053768 -0.2400856 -0.8400889 -0.4864253 -0.08262342 -0.7180749 0.691044 0.2164011 -0.8045877 -0.5530001 0.4639227 -0.8158314 0.3452464 0.6039718 -0.7467312 -0.2785869 0.7164588 -0.5384858 0.4435313 0.8353672 -0.3359221 -0.4351071 0.9418563 -0.1959493 0.2729662 0.925534 0.04082638 -0.3764573 0.9038002 0.1572789 0.3980059 0.7706247 0.5794242 -0.2653398 0.7806441 0.4764273 0.4044896 0.4062854 0.7122915 -0.57234 0.2829151 0.7439773 0.6053568 -0.1175323 0.8734462 -0.4725232 -0.04673922 0.9964017 0.0707038 -0.4731276 0.8520004 -0.2241554 -0.4678415 0.6974802 0.5428128 -0.6853466 0.3538359 -0.6364749 -0.7692632 0.2834399 0.5726222 -0.9177496 -0.1390178 -0.3720345 -0.9524087 -0.2024073 0.2279233 -0.7733439 -0.5723448 -0.2726919 -0.7665403 -0.6221767 0.1590978 -0.4589242 -0.8861032 -0.06488311 -0.3599695 -0.8171211 0.4502611 -0.01480633 -0.7918441 -0.6105439 0.1643834 -0.7340698 0.6588775 0.44458 -0.7188779 -0.5343813 0.6254652 -0.6080732 0.4889175 0.7319284 -0.3824949 -0.563896 0.8330582 -0.2155297 0.5094713 0.9098403 0.09548491 -0.4038234 0.9445506 0.1770937 0.2765175 0.6716174 0.5471968 -0.4995055 0.6566093 0.616417 0.4346199 0.234892 0.9685396 -0.08220076 -0.1832329 0.815899 -0.5483927 -0.4417968 0.7558195 0.4832728 -0.666254 0.579136 -0.4697949 -0.7953016 0.5695121 0.2077292 -0.9441984 0.2164124 -0.2483046 -0.9631528 0.1734067 0.2055891 -0.9762278 -0.2165426 -0.009421527 -0.897198 -0.2652643 -0.3530871 -0.7486578 -0.5402626 0.3842238 -0.7041893 -0.6699534 -0.2351167 -0.4123644 -0.9044327 0.109349 -0.4146968 -0.9056083 0.08888244 0.01545602 -0.9869157 -0.1604955 0.0873689 -0.8408513 0.5341686 0.3664588 -0.7688734 -0.5239672 0.6156957 -0.6668815 0.4197476 0.739102 -0.579836 -0.3428098 0.850655 -0.3103657 0.4243338 0.920204 -0.1172305 -0.3734725 0.963618 0.04349446 0.2637211 0.8951155 0.2510997 -0.3683983 0.8252124 0.4118421 0.3865365 0.6871741 0.6214751 -0.3762454 0.6242514 0.7103214 0.3251982 0.2477756 0.8762816 -0.4132043 0.2508303 0.946123 -0.2047812 -0.1031443 0.8292358 0.5492991 -0.3019636 0.7788823 -0.5496911 -0.650954 0.6449001 0.4004533 -0.6090596 0.6558209 -0.446033 -0.7537559 0.3474012 0.5578213 -0.743726 0.06528818 -0.6652889 -0.8955273 -0.08212012 0.4373639 -0.870936 -0.4287241 -0.2401375 -0.8561919 -0.4818296 0.186482 -0.5931727 -0.7498344 -0.2930778 -0.4970257 -0.7473537 0.4409399 -0.114239 -0.8394315 -0.5313231 -0.006537556 -0.8678171 0.4968409 0.3660216 -0.8248605 -0.4308522 0.4496054 -0.8931403 0.01246726 0.723878 -0.6455053 0.2435643 0.7848277 -0.5921256 -0.1828466 0.9724099 -0.2281535 0.04863065 0.970897 -0.2256964 0.08012694 0.9317395 0.3568288 -0.06734228 0.9198791 0.3460894 -0.1845118 0.6573159 0.6959341 0.2891569 0.4317798 0.7069205 -0.560205 0.3199105 0.831688 0.4538197 -0.08515751 0.89474 -0.4383931 -0.4283908 0.8358777 0.3432051 -0.8771421 0.4211417 -0.2307841 -0.8779944 0.4213684 -0.2271 -0.9388408 -0.02736973 0.343262 -0.9108455 -0.1572453 -0.381621 -0.8400551 -0.4550608 0.2953425 -0.6638424 -0.5616543 -0.4938197 -0.5582304 -0.6958395 0.4518697 -0.2226508 -0.8802281 -0.4190766 0.08808761 -0.989853 0.1114975 0.5558812 -0.8308346 0.02665066 0.432039 -0.7632676 0.4803799 0.6777725 -0.4357066 -0.5922704 0.7302154 -0.2978412 0.6148789 0.8780555 -8.85625e-4 -0.4785582 0.8407962 0.1329469 0.5247734 0.6663109 0.3963768 -0.6315975 0.5530984 0.5646935 0.6125385 0.4456657 0.8013727 -0.3989789 0.1874493 0.895346 0.404003 0.04342943 0.9151672 -0.4007284 -0.3514962 0.8614555 0.3665309 -0.455909 0.7050208 -0.5432243 -0.644463 0.6227126 0.4437304 -0.8673354 0.2966222 -0.3996805 -0.870361 0.2993391 -0.390983 -0.8636227 -0.02357929 0.503587 -0.7716833 -0.249095 -0.5851979 -0.6978759 -0.4673845 0.542698 -0.5643034 -0.6342059 -0.5285305 -0.3323652 -0.7640804 0.5529146 -0.04872095 -0.7598686 -0.6482484 0.06466776 -0.9010929 0.4287771 0.5540937 -0.8020654 -0.2228708 0.5537576 -0.8138451 -0.1760932 0.8936153 -0.4230274 0.1499983 0.9109011 -0.3798613 -0.1611354 0.9664858 0.1395485 0.2154794 0.8592133 0.2254719 -0.4592548 0.6258393 0.530716 0.5715468 0.592329 0.7144404 -0.3724532 0.280509 0.9470236 -0.1564007 0.2146306 0.8861199 0.4107618 -0.1710021 0.9341053 -0.3133779 -0.2315312 0.9552583 0.1840513 -0.5983986 0.8011257 -0.01081228 -0.6134144 0.7672329 -0.1872877 -0.8844506 0.4346926 0.1696756 -0.8525913 0.4497773 -0.266061 -0.9551527 0.01410549 0.2957776 -0.8445301 -0.1224484 -0.5213208 -0.649737 -0.3358983 0.6819195 -0.3080644 0.3446477 0.8867437 -0.5819855 0.1677258 0.7957141 -0.5374898 0.1487928 0.8300395 -0.3852271 -0.0859608 0.9188095 -0.6021882 -0.269639 0.7514414 -0.2862815 -0.3665194 0.8852719 -0.3336902 -0.3947188 0.8560655 -0.1747033 -0.5184483 0.8370723 -0.1116125 -0.4394599 0.8913012 0.08037197 -0.5956369 0.7992229 0.2854705 -0.4698504 0.8353127 0.1689674 -0.3925477 0.9040776 0.481184 -0.3304066 0.8119689 0.4503691 -0.2821481 0.8470893 0.5749986 -0.09507554 0.8126114 0.5260686 -0.06284195 0.8481172 0.5775777 0.13385 0.8052877 0.453211 0.1707305 0.8749006 0.4711183 0.3489488 0.8101125 0.4034462 0.3384276 0.8501164 0.2725788 0.5855707 0.7634186 0.1773966 0.5142046 0.839121 0.005916297 0.5077949 0.8614577 -0.01582247 0.5473538 0.8367518 -0.2504121 0.5787362 0.7761174 -0.2674014 0.3862691 0.8827756 -0.4377941 0.418431 0.7957712 -0.4530613 0.1901991 0.8709534 -0.5640662 0.1604434 0.8099921 -0.527104 -0.02819544 0.849333 -0.5719672 -0.06057405 0.818037 -0.5117313 -0.3102971 0.8011535 -0.396739 -0.3006044 0.8673151 -0.3794977 -0.4633384 0.8008115 -0.2297689 -0.4563224 0.8596372 -0.2345724 -0.4373144 0.8681775 -0.03661543 -0.5532453 0.8322134 0.04519546 -0.4874493 0.8719809 0.1546077 -0.6012708 0.7839451 0.2390162 -0.3675431 0.8987677 0.4477649 -0.405023 0.7971593 0.4352462 -0.2294675 0.8705776 0.5334673 -0.2152708 0.8179677 0.6156791 -0.010531 0.7879267 0.4644601 0.06289142 0.8833581 0.5587928 0.2481585 0.7913078 0.3930231 0.279478 0.876028 0.3931216 0.5011088 0.770938 0.2251483 0.4263028 0.8761132 0.1189569 0.5999328 0.7911573 -0.006729543 0.5036033 0.8639089 -0.0844869 0.5787796 0.8110958 -0.2133662 0.4268496 0.8787914 -0.4066275 0.512598 0.756239 -0.4266689 0.2457854 0.8703696 -0.4390434 0.260511 0.8598693 -0.5871748 0.06594914 0.8067692 -0.4962989 -0.001010715 0.8681512 -0.5891931 -0.1700588 0.7898933 -0.4282906 -0.2097755 0.8789547 -0.4493941 -0.3959638 0.8007857 -0.3386268 -0.3974056 0.8528779 -0.2615691 -0.6355522 0.7263987 -0.05915689 -0.5172396 0.8537937 0.07383096 -0.6538789 0.7529883 0.1619319 -0.4360641 0.8852267 0.3025889 -0.4975625 0.8129401 0.415252 -0.3485932 0.840267 0.3993223 -0.3165607 0.8604249 0.5917775 -0.1998131 0.7809445 0.5556699 -8.22124e-5 0.8314031 0.495677 -0.03985852 0.8675919 0.5479254 0.2062982 0.8106904 0.4615868 0.216898 0.8601703 0.4500501 0.36789 0.8137027 0.3992124 0.3770376 0.8357465 0.3463103 0.5495831 0.7602813 0.1509677 0.5138056 0.8445193 0.1356343 0.5715594 0.8092734 -0.01770436 0.6072091 0.7943449 -0.1332967 0.4081929 0.9031116 -0.2210026 0.4717928 0.8535628 -0.385198 0.3579067 0.8506029 -0.3609918 0.313553 0.8782765 -0.5100693 0.1148413 0.8524323 -0.4913755 0.1181069 0.8629026 -0.6449746 -0.07984983 0.760021 -0.4389343 -0.1802752 0.8802486 -0.4949175 -0.2850544 0.8208538 -0.3095337 -0.4356989 0.8451955 -0.304147 -0.3880274 0.8700169 -0.1604605 -0.588725 0.7922471 -0.09509259 -0.4891772 0.866985 0.1040881 -0.4739308 0.8743885 0.2084936 -0.5852233 0.7836098 0.3132205 -0.3800219 0.8703312 0.4209253 -0.3990492 0.8146052 0.4948079 -0.1947975 0.8468879 0.4769157 -0.1971663 0.8565494 0.6338084 -0.01046597 0.7734194 0.4503306 0.1017282 0.8870479 0.5313553 0.2094753 0.820842 0.4171332 0.3878432 0.8219353 0.3625273 0.3709062 0.8549869 0.2728807 0.5117281 0.8146598 0.1654335 0.4794785 0.8618192 0.1318582 0.5626971 0.8160794 -0.1253957 0.5976778 0.7918694 -0.144528 0.4564891 0.877912 -0.2724967 0.4864922 0.830103 -0.3795546 0.2657445 0.8861818 -0.4473117 0.2768191 0.8504608 -0.6211484 0.1068889 0.7763694 -0.4630408 -0.02459585 0.8859957 -0.5754325 -0.1362339 0.8064228 -0.5003529 -0.3005917 0.8119679 -0.3649618 -0.2927293 0.8838058 -0.3807198 -0.4541114 0.8055033 -0.1947441 -0.5517835 0.8109315 -0.1146211 -0.4549406 0.8831145 0.06664592 -0.5813111 0.8109475 0.120443 -0.4795591 0.8692045 0.2730996 -0.5374526 0.797848 0.3347744 -0.3435678 0.8774323 0.4799854 -0.3691257 0.7958394 0.57794 -0.1731066 0.7975084 0.464161 -0.07138705 0.8828695 0.5813126 0.02111434 0.8134064 0.5499559 0.2009059 0.8106697 0.4040025 0.2196202 0.8880029 0.4466857 0.3551872 0.8211662 0.2802166 0.5037127 0.8171611 0.1924554 0.4374505 0.8784065 0.07110077 0.593719 0.8015251 -0.03883588 0.4970525 0.866851 -0.1163699 0.5619119 0.8189707 -0.2667369 0.5189675 0.812111 -0.2768683 0.4063908 0.8707414 -0.4309771 0.4243241 0.7963716 -0.4199566 0.1699918 0.8914815 -0.579249 0.1411256 0.8028414 -0.5154033 -0.08849787 0.8523659 -0.5600512 -0.07753741 0.8248216 -0.4679825 -0.2601849 0.8445687 -0.4309619 -0.2578225 0.864754 -0.3752028 -0.4841322 0.7904675 -0.2336935 -0.4341531 0.8699992 -0.1689465 -0.5707139 0.8035812 -0.04487198 -0.5127924 0.8573392 0.01958078 -0.5783825 0.8155307 0.1583991 -0.5331119 0.8310845 0.1733912 -0.4611958 0.870192 0.4152929 -0.5028342 0.7580828 0.4175935 -0.2980279 0.8583676 0.3988198 -0.270248 0.876304 0.5884969 -0.1433999 0.7956808 0.4518927 -6.60474e-4 0.8920721 0.6514739 0.179648 0.7370946 0.4148101 0.377386 0.8279567 0.3855947 0.28203 0.8785077 0.3215612 0.5001208 0.8040384 0.2227899 0.4572673 0.8609712 0.136255 0.5648266 0.813883 0.0141769 0.4655113 0.8849284 -0.1044852 0.6037381 0.7903058 -0.3213654 0.4119198 0.8526701 -0.2747659 0.3860909 0.8805893 -0.5800617 0.3315938 0.7440256 -0.4648248 0.1059984 0.8790349 -0.5763075 0.05152928 0.8156068 -0.54562 -0.1587632 0.8228568 -0.5930172 -0.1538447 0.7903559 -0.4187883 -0.4512516 0.7880282 -0.3857219 -0.3532314 0.8523182 -0.2546414 -0.5630125 0.7862409 -0.1465292 -0.4785078 0.8657711 -0.001041531 -0.6049102 0.796293 0.07752645 -0.4772883 0.8753203 0.2568534 -0.5782831 0.7743483 0.3582491 -0.3830402 0.8514329 0.332076 -0.3377843 0.8806971 0.5416328 -0.1505361 0.8270265 0.4520978 -0.08928459 0.8874886 0.540323 0.1254457 0.8320544 0.492487 0.1337127 0.8599869 0.4878169 0.3957384 0.7780911 0.2940356 0.3660479 0.8829225 0.2927927 0.487264 0.8227066 0.08376467 0.5704907 0.8170213 0.04834938 0.5238086 0.8504627 -0.07935065 0.5842269 0.807702 -0.1335393 0.5149038 0.8467829 -0.2734474 0.5631429 0.7798056 -0.4426552 0.4013072 0.8018784 -0.3934562 0.3887909 0.833087 -0.5500478 0.1891666 0.813427 -0.5476419 0.1863136 0.8157056 -0.6785095 0.01112145 0.7345075 -0.4910232 -0.1329694 0.8609387 -0.5533504 -0.2484335 0.7950372 -0.3898599 -0.3427839 0.8546979 -0.4027841 -0.4053393 0.8206493 -0.2157735 -0.476108 0.852504 -0.21067 -0.5049692 0.837033 -0.06642395 -0.6180352 0.7833393 0.0598942 -0.4708092 0.8801997 0.1439427 -0.5563863 0.8183612 0.3581398 -0.5012166 0.7877297 0.327175 -0.3355028 0.8833994 0.5169321 -0.3047345 0.7999489 0.4894042 -0.1558859 0.8580112 0.5766855 -0.1150353 0.8088269 0.5011416 0.0797106 0.8616864 0.5420271 0.1195617 0.8318123 0.4815816 0.309524 0.8199232 0.4040051 0.3034815 0.8629478 0.3492084 0.4703307 0.8104583 0.259431 0.4505644 0.8542174 0.17615 0.5980235 0.7818818 0.04008233 0.5063455 0.8613988 -0.05988383 0.5984272 0.7989361 -0.164739 0.4756244 0.8640848 -0.2658531 0.530165 0.805138 -0.4117403 0.3340581 0.8478651 -0.417477 0.3445144 0.8408465 -0.5554063 0.1604031 0.8159624 -0.5127668 0.1249584 0.8493854 -0.6298878 -0.1101865 0.7688306 -0.4256197 -0.1749721 0.8878248 -0.4458195 -0.2139787 0.8691709 -0.3614422 -0.4146589 0.8351153 -0.2578456 -0.4061618 0.8766689 -0.2304307 -0.5592317 0.7963427 -0.01619637 -0.5150711 0.8569945 -0.001450896 -0.5414799 0.8407125 0.2995874 -0.5016078 0.8115646 0.2885868 -0.4544643 0.8427217 0.4739807 -0.3420436 0.8113868 0.4210947 -0.207646 0.8829284 0.5799115 -0.1587311 0.7990664 0.5588913 0.07375216 0.8259547 0.4631996 0.0916621 0.8815011 0.5262338 0.3474077 0.7761352 0.3308561 0.3616172 0.8716464 0.3328369 0.4898383 0.8057779 0.1221032 0.5270499 0.8410168 0.1020963 0.5000633 0.8599495 -0.06451588 0.6038458 0.7944861 -0.1899442 0.466132 0.8640847 -0.1886384 0.4950588 0.8481346 -0.3791225 0.4323521 0.8181309 -0.3655117 0.3652281 0.8561598 -0.5464116 0.2854849 0.7873581 -0.4431291 0.1146298 0.8890987 -0.6388103 0.0100696 0.7692984 -0.4051033 -0.1639147 0.8994573 -0.4589043 -0.2367377 0.8563657 -0.3239506 -0.4171031 0.8491649 -0.3456493 -0.4293108 0.8343973 -0.1583759 -0.5988545 0.7850416 -0.07330578 -0.5642591 0.8223369 -0.04154312 -0.5980272 0.8003984 0.1153974 -0.4722044 0.873903 0.2082169 -0.5509387 0.8081536 0.3880394 -0.4599204 0.7986857 0.3688628 -0.2802628 0.8862241 0.4192781 -0.3520615 0.8368147 0.5553737 -0.1008988 0.8254572 0.4921356 -0.05925464 0.8684995 0.6407673 0.1551136 0.7519023 0.4414328 0.2239402 0.8689004 0.4704682 0.3788402 0.7969567 0.3107889 0.3910053 0.8663285 0.2943637 0.4876773 0.8219009 0.103643 0.515945 0.8503287 0.09976047 0.5109414 0.8538073 -0.06361043 0.6018987 0.7960351 -0.1632124 0.4778008 0.8631733 -0.253194 0.5243849 0.8129659 -0.3357192 0.3751965 0.864014 -0.4651246 0.3931601 0.7931484 -0.5358755 0.236481 0.8105024 -0.4717062 0.1547216 0.8680752 -0.5402686 0.08718061 0.8369644 -0.4496626 -0.0562914 0.8914231 -0.5121065 -0.1109253 0.8517292 -0.5371834 -0.3265997 0.7776674 -0.3633393 -0.3273102 0.8722687 -0.3639533 -0.4530186 0.8138256 -0.1967327 -0.5014464 0.8425246 -0.1905362 -0.5305213 0.8259803 0.0348587 -0.6044934 0.7958471 0.07996046 -0.496541 0.8643226 0.2218027 -0.536503 0.8142287 0.3016585 -0.4120289 0.8597875 0.3091675 -0.4529195 0.8362293 0.4975687 -0.3152311 0.8081181 0.4497709 -0.2322519 0.8624183 0.5562533 -0.1410397 0.8189567 0.4828295 -0.02527898 0.8753495 0.5852496 0.06185501 0.8084906 0.5290998 0.2429692 0.813031 0.450648 0.2422237 0.8592113 0.4111105 0.4223837 0.8078245 0.2777982 0.3787707 0.8828144 0.1680612 0.6627642 0.7297254 -0.04099512 0.5294809 0.8473308 0.01356464 0.4827499 0.8756532 -0.1863588 0.4298945 0.8834371 -0.2361362 0.4615272 0.8551214 -0.4426569 0.4316481 0.7859612 -0.3873457 0.2619243 0.8839451 -0.5648224 0.2304432 0.7923836 -0.6230515 0.07907289 0.7781737 -0.4591061 -0.02304625 0.8880825 -0.5712183 -0.1930492 0.797773 -0.42957 -0.2620313 0.8641812 -0.4581603 -0.3667298 0.8096904 -0.2716732 -0.4397841 0.8560279 -0.2536792 -0.5721058 0.7799628 -0.06431174 -0.4870274 0.8710158 -0.05532491 -0.501408 0.8634404 0.1565563 -0.5398805 0.8270546 0.2048618 -0.4293703 0.8795868 0.3568077 -0.4886175 0.7962042 0.4299746 -0.2832834 0.8572471 0.4615677 -0.284545 0.8402318 0.5834615 -0.006765723 0.8121126 0.5389229 0.008014917 0.842317 0.5388445 0.2283939 0.8108533 0.3760674 0.2425583 0.8942813 0.4228336 0.4432258 0.7904193 0.2055738 0.4940497 0.8447806 0.1897598 0.5630224 0.8043612 -0.03543037 0.635764 0.77107 -0.1152663 0.4929373 0.8623958 -0.2943529 0.5679967 0.7685936 -0.3422653 0.3603145 0.8677719 -0.4322166 0.3741533 0.8204865 -0.4809703 0.155996 0.8627473 -0.517148 0.1457956 0.843387 -0.5886392 -0.09057337 0.8033059 -0.5172366 -0.1050529 0.8493705 -0.4858205 -0.3405352 0.8049933 -0.4046127 -0.3265904 0.8541824 -0.270637 -0.5114575 0.8155778 -0.2691996 -0.4376719 0.8578898 -0.1047638 -0.5941523 0.7975009 -0.03296881 -0.5112909 0.8587751 0.1501946 -0.5831737 0.7983421 0.1762158 -0.4882095 0.8547512 0.3638997 -0.4870597 0.7939458 0.3676018 -0.3462466 0.8631235 0.4654065 -0.3435838 0.815688 0.5342485 -0.1364108 0.8342486 0.5038528 -0.1115173 0.8565607 0.5783292 0.06365126 0.8133168 0.5108586 0.0942927 0.8544779 0.5253065 0.2688501 0.8073245 0.382028 0.2818497 0.8801224 0.3894456 0.4299538 0.814538 0.1912357 0.501632 0.843679 0.1975191 0.4131447 0.8889869 0.03191065 0.6271021 0.7782832 -0.1346989 0.4894455 0.861568 -0.1743447 0.5223191 0.8347376 -0.3509045 0.3871349 0.8526386 -0.3270573 0.3788959 0.8657202 -0.5849812 0.26703 0.7658278 -0.4547206 0.09621191 0.8854222 -0.597505 0.01525664 0.80172 -0.4198423 -0.1559187 0.894104 -0.4757166 -0.2474951 0.8440617 -0.3768231 -0.406508 0.8323194 -0.3748229 -0.3987872 0.8369449 -0.1058431 -0.4829052 0.8692525 -0.1192235 -0.4964041 0.8598655 0.01658517 -0.6230419 0.7820128 0.1497874 -0.4589598 0.8757396 0.2461383 -0.5252078 0.8145998 0.4014778 -0.3545085 0.8444758 0.406283 -0.3552336 0.8418689 0.5423014 -0.162653 0.8242895 0.4786934 -0.1728959 0.8607901 0.6333923 0.04954546 0.7722432 0.449706 0.1272606 0.884064 0.5364473 0.2829987 0.7950699 0.3905563 0.4158714 0.8212896 0.2841327 0.3686702 0.8850712 0.2289571 0.5471298 0.8051258 -0.003741323 0.6386826 0.7694613 0.05679208 0.5399271 0.8397938 -0.2150412 0.5022829 0.8375377 -0.2943195 0.5589343 0.7752217 -0.4550149 0.4124529 0.7892047 -0.3940592 0.2377877 0.8877919 -0.4939105 0.2207952 0.8410125 -0.5733732 0.01232075 0.8192017 -0.490623 -0.03686839 0.8705917 -0.5779532 -0.1900849 0.7936232 -0.4141902 -0.2857754 0.8641637 -0.4328315 -0.333895 0.8373596 -0.3779615 -0.486606 0.7876293 -0.2245622 -0.4474681 0.8656467 -0.1419965 -0.635549 0.7588903 0.07233399 -0.5816768 0.8101975 0.05945175 -0.5685287 0.8205125 0.2231554 -0.5338041 0.8156316 0.2337194 -0.4636992 0.85461 0.4150276 -0.430202 0.8016722 0.3900316 -0.3155496 0.8650455 0.5745221 -0.2661629 0.7740038 0.4825863 -0.05025225 0.8744056 0.5820406 0.009940445 0.813099 0.5116106 0.2102722 0.8330909 0.4603483 0.2101142 0.8625146 0.4271018 0.4154383 0.8031159 0.2828366 0.409097 0.8675501 0.2715351 0.4775589 0.8355873 0.07397502 0.5613658 0.8242549 0.09773445 0.4888971 0.8668494 -0.1318598 0.6271047 0.7676932 -0.210801 0.4299626 0.8778924 -0.2184471 0.4340841 0.8739862 -0.5125661 0.3232963 0.7954595 -0.4112725 0.1922268 0.8910129 -0.6317629 0.05713933 0.7730529 -0.4722062 -0.1238077 0.8727504 -0.5341027 -0.1181616 0.8371214 -0.4511812 -0.3474127 0.822034 -0.3633478 -0.3278117 0.8720769 -0.3005705 -0.57349 0.7620805 -0.1028435 -0.4686007 0.8774034 -0.08129376 -0.4268693 0.900652 0.1889783 -0.5879089 0.7865434 0.1930266 -0.3631692 0.9115092 0.4864378 -0.4144462 0.7691636 0.412851 -0.2178192 0.8843693 0.6019165 -0.1518886 0.7839812 0.4654958 0.07249563 0.882076 0.5189478 0.1140579 0.8471624 0.495486 0.354107 0.7931594 0.3383327 0.33365 0.8798913 0.300238 0.536508 0.7886801 0.1815867 0.4648124 0.8665885 0.03027689 0.5978428 0.8010414 -0.04712116 0.5089762 0.8594898 -0.1273751 0.5672689 0.8136226 -0.2608648 0.4889783 0.832376 -0.251356 0.3824827 0.8891159 -0.4117085 0.3467932 0.8427519 -0.4226499 0.2460879 0.872243 -0.5458149 0.2276614 0.8063848 -0.590481 0.0358048 0.806257 -0.489787 -0.01873177 0.8716409 -0.5825867 -0.1978453 0.7883211 -0.5109413 -0.2340307 0.827145 -0.5132967 -0.4336956 0.7405638 -0.3186199 -0.4364352 0.8414307 -0.2996423 -0.5058892 0.8088823 -0.144333 -0.4984258 0.8548333 -0.1202777 -0.5621279 0.8182576 0.09104532 -0.5720306 0.8151636 0.1130753 -0.4851989 0.8670617 0.2881602 -0.5876159 0.7560895 0.3646518 -0.39495 0.8432341 0.386296 -0.4374673 0.8120332 0.8722035 -0.3800395 -0.3079466 0.6290127 -0.1422836 0.7642634 -0.2426666 -0.9391599 0.2430876 0.1805924 -0.9825313 0.04493039 0.2165613 -0.8847917 -0.4126073 0.517665 -0.8329865 0.1953367 0.5844048 0.5745591 -0.5730209 0.2876651 0.6204593 0.7295747 -0.08807051 -0.5570175 -0.8258178 0.2508893 -0.8208259 0.5131272 0.7378515 -0.6586563 -0.1474692 0.3440319 0.4271462 0.8361749 -0.3427104 0.4405245 0.8297516 0.05883234 -0.5791602 0.8130882 -0.162829 0.6612653 -0.732267 -0.3506146 0.6920051 0.6310296 -0.5102193 0.5002561 -0.6995857 -0.6541082 0.5611715 0.5071775 -0.9065529 0.2125877 -0.3646481 -0.1600769 -0.585769 0.7945125 0.0768671 -0.6959497 -0.7139647 0.1826384 -0.5182085 0.8355257 -0.4437115 0.4472054 -0.7766128 -0.6122446 0.3737997 0.6967284 -0.6865199 0.488554 -0.5385214 -0.7423774 0.1777242 0.6459798 0.5382547 0.1387749 0.8312782 0.7362869 -0.6434224 0.2094976 0.9580837 -0.2168655 0.1872034 0.7797757 -0.09870684 -0.6182287 0.6984141 0.1667037 0.6960084 -0.3179014 -0.3084462 -0.8965488 0.2517096 -0.4331907 0.865441 -0.6839109 0.004962205 0.7295487 -0.7763925 -0.2372391 -0.5838941 -0.6906801 -0.3863261 0.6113209 -0.5633061 -0.5149211 -0.6461753 -0.4573273 -0.6265747 0.6310753 -0.2594543 -0.7383184 -0.6225509 -0.4347774 -0.06962299 -0.8978425 0.1432842 0.5360785 0.8319191 -0.1668885 0.4096041 -0.8968683 -0.2293332 -0.5050832 0.8320441 0.09854751 -0.4365794 -0.8942522 0.5010429 -0.01176333 0.8653426 -0.690546 0.003907799 0.723278 -0.5715187 -0.2859234 -0.7691646 -0.4375143 -0.488848 0.7547245 -0.2040555 -0.7329808 -0.6489227 -0.4779112 0.5535652 -0.6820312 -0.5344524 0.336422 0.7753586 0.03071016 -0.6265938 -0.7787408 0.2298628 -0.6858642 0.6904734 0.3834714 -0.6075878 -0.6955478 0.4808703 -0.4099057 0.775075 0.3075184 0.5521344 0.774971 -0.3101953 0.3042236 -0.9006813 0.8623851 -0.02982115 -0.5053737 0.931164 0.1607168 0.3272671 0.9164899 0.3659073 -0.1617349 0.7037914 0.7070872 -0.06859523 0.124329 0.1030044 0.9868802 0.2908797 0.1680948 0.9418776 0.5248123 0.3026793 0.7955862 0.7536476 0.6081365 0.2493699 0.8257762 0.4929597 0.2740154 0.6849296 0.3233681 0.65292 0.7853888 0.231392 0.5741273 0.9720422 0.2063702 0.1120059 0.3387607 0.009890019 0.9408207 0.6549941 0.03311794 0.754908 0.5476437 -0.001663684 0.83671 0.9358848 0.01354807 0.3520458 0.09076148 -0.01187789 0.9958019 0.6410598 -0.1792061 0.7462758 0.9756987 -0.2109751 0.05917358 0.9824084 -0.1850777 -0.02489835 0.5740423 -0.2329109 0.785002 0.5868538 -0.2747927 0.7616376 0.8621447 -0.4142814 0.2916804 0.5087109 -0.3414533 0.7903309 0.1189162 -0.1481269 0.9817929 0.6344414 -0.6152706 0.4678957 0.8117717 -0.5779078 0.08396077 0.6574971 -0.5860067 0.4735966 0.3685646 -0.6313981 0.6822731 0.2744715 -0.5363106 0.7981457 0.442549 -0.8215675 0.3594123 0.5514265 -0.8336958 0.0296694 0.1199167 -0.6538981 0.747019 0.03158396 -0.557657 0.8294705 0.1692637 -0.9634451 0.2076622 0.1045982 -0.9931894 -0.05132436 -0.05180919 -0.6301086 0.7747768 -0.1184976 -0.9041857 0.4103738 -0.1519293 -0.4922869 0.8570713 -0.05377644 -0.09309506 0.994204 -0.2801906 -0.9124168 0.2983102 -0.2946749 -0.6284242 0.7198957 -0.3536797 -0.8253433 0.4401356 -0.3351364 -0.5319132 0.777658 -0.2613153 -0.3113434 0.9136628 -0.5807932 -0.8135346 0.02899736 -0.64223 -0.6494829 0.4070783 -0.5392458 -0.3687865 0.7571069 -0.6921698 -0.5603265 0.4549014 -0.533316 -0.3344266 0.7770026 -0.3438212 -0.1475675 0.9273678 -0.8169034 -0.5445721 0.1900269 -0.7156258 -0.08995556 0.6926671 -0.791606 -0.2648663 0.5506414 -0.9025695 -0.3026638 0.3062077 -0.6081581 -0.09048175 0.7886424 -0.9688725 -0.2408658 0.05718255 -0.7387469 0.0135799 0.6738461 -0.912505 0.0364173 0.4074414 -0.9464136 0.07616525 0.3138473 -0.2060361 0.04040837 0.9777097 -0.4973593 0.1287745 0.8579342 -0.9297814 0.2559662 0.264552 -0.5769869 0.2213011 0.786201 -0.9182228 0.3920879 -0.05598324 -0.5743432 0.3283028 0.7498981 -0.6485367 0.4148765 0.6381831 -0.8063293 0.4827462 0.3417447 -0.2769849 0.2408593 0.9301968 -0.5692811 0.5788213 0.5838537 -0.4147238 0.5250845 0.7431625 -0.6680898 0.7098454 0.2231042 -0.4105228 0.5295296 0.7423406 -0.5861702 0.786349 -0.1950891 -0.4390876 0.8305388 0.3426478 -0.2033007 0.4640797 0.8621478 -0.09491503 0.3091357 0.9462698 -0.2765505 0.8439795 0.4595851 -0.2470599 0.868873 0.428977 -0.00910747 0.6437325 0.7651964 -0.151647 0.9883301 0.0143817 0.005629897 0.6514681 0.7586552 0.1018927 0.4333949 0.8954255 0.08901053 0.8907344 0.4457235 0.1873146 0.9190844 0.3466945 0.1805737 0.5139423 0.838604 0.2958301 0.8361877 0.4618167 0.3317179 0.841979 0.4254819 0.2799739 0.382351 0.8805807 0.5089197 0.6944849 0.5086174 0.4732449 0.8762232 0.09095168 0.5694024 0.787265 0.2366327 0.4812567 0.5509724 0.6817783 0.5583331 0.5281314 0.639798 0.01917266 0.003723323 0.9998093 -0.007349789 0.00377357 0.9999659 0.002666413 0.002197802 0.9999941 -0.004021883 0.002092778 0.9999898 0.002587258 -0.005405783 0.9999821 -2.59931e-4 -0.001001 0.9999995 0.001432061 -0.003176212 0.999994 -0.001573026 -6.16719e-4 0.9999986 -0.6378452 -0.6118834 0.4677096 -0.427411 -0.4946495 0.7567309 -0.3754465 -0.5350164 0.7568339 -0.3976899 -0.6598672 0.6375094 -0.3534647 -0.6953521 0.6257382 -0.2645244 -0.6658895 0.6975802 -0.2333161 -0.8885803 0.394954 -0.1137229 -0.4096537 0.9051249 -0.1199673 -0.8839027 0.4520221 -0.1101336 -0.867536 0.4850279 -0.08245629 -0.5351836 0.8407018 0.02804505 -0.8079541 0.5885776 0.06219875 -0.6641952 0.7449672 0.01974427 -0.4770609 0.8786484 0.1916651 -0.7327038 0.6530005 0.2322862 -0.6951475 0.6803037 0.2395191 -0.5958302 0.7665618 0.4095435 -0.6621801 0.6275283 0.3259431 -0.5942786 0.735251 0.5225402 -0.6790422 0.5156098 0.5334554 -0.5589343 0.6348368 0.221205 -0.2523418 0.9420149 0.7112126 -0.6152857 0.3400003 0.3585703 -0.3556953 0.8630807 0.4295967 -0.2334557 0.8723217 0.6894185 -0.3634629 0.6265755 0.585367 -0.2793487 0.7611241 0.8755733 -0.2367178 0.4211128 0.6450062 -0.2256387 0.7301056 0.8839563 -0.05804258 0.4639531 0.4493091 -0.06734234 0.8908347 0.9148536 -0.03619998 0.4021598 0.2838355 -0.01883846 0.9586879 0.8522652 0.09578067 0.5142666 0.714374 0.1195157 0.6894823 0.7208926 0.2656793 0.6401004 0.6349207 0.2097499 0.7435596 0.4085927 0.1618167 0.8982581 0.7955962 0.4233379 0.4333727 0.6705037 0.5022134 0.5460829 0.5566009 0.4606748 0.6913568 0.4386363 0.3569651 0.8247268 0.5666064 0.6768943 0.4698633 0.1371132 0.1595492 0.9776216 0.3984236 0.6474413 0.6496757 0.3248877 0.5753334 0.7506262 0.2458052 0.8114084 0.5302795 0.1999592 0.6562657 0.7275518 0.1639035 0.609386 0.7757476 0.06324619 0.6702798 0.7394086 0.02565366 0.8885811 0.4580019 -0.01408648 0.4496534 0.8930922 -0.1103271 0.9016894 0.4180721 -0.1482117 0.6635473 0.7333065 -0.1727224 0.6436128 0.7456069 -0.246288 0.7246362 0.6436185 -0.09898972 0.2148977 0.9716069 -0.3581898 0.6990092 0.6189396 -0.4180766 0.7524915 0.5088893 -0.2431622 0.4025779 0.8824983 -0.5354319 0.7263665 0.4309343 -0.5133123 0.5901204 0.623112 -0.3843474 0.4551755 0.8031766 -0.6481391 0.5850955 0.4874208 -0.6467653 0.4557305 0.611559 -0.2432937 0.1867661 0.9518018 -0.5290592 0.3238403 0.7843622 -0.6433141 0.2789955 0.7129576 -0.7864503 0.2899971 0.5453419 -0.7946503 0.1197723 0.595135 -0.7961108 0.1194553 0.5932436 -0.3581301 0.05176162 0.9322358 -0.2935526 0.03122043 0.9554331 -0.872931 -0.009404897 0.487753 -0.8063669 -0.05870962 0.5884945 -0.5587487 -0.05119502 0.8277554 -0.8905611 -0.2094678 0.4037626 -0.7675108 -0.2336147 0.5969519 -0.5585721 -0.1868181 0.8081437 -0.4856452 -0.147029 0.8617026 -0.8322081 -0.462293 0.3061292 -0.6947054 -0.4540526 0.5578716 -0.7089643 -0.5855766 0.3930265 -0.5419615 -0.3358145 0.7703937 -0.2875269 -0.2295594 0.9298554 -0.6375451 -0.7704122 0.001145601 -0.63137 -0.7754775 0.002598047 -0.5125184 -0.8586726 -0.002514004 -0.5811966 -0.8137307 0.007280707 -0.3530312 -0.9356104 -0.001452505 -0.408454 -0.9127731 0.003292322 -0.2989556 -0.9542586 0.004017293 -0.1840474 -0.9828974 -0.006282746 -0.07104712 -0.9974613 -0.00483632 -0.09683442 -0.9952995 -0.001508355 0.06610369 -0.9978126 -7.18097e-4 0.09242922 -0.9957096 0.004405438 0.1888879 -0.9819686 0.007692694 0.2897391 -0.9570974 -0.003990471 0.3717845 -0.9283186 -9.34547e-4 0.3659157 -0.9306481 -1.70452e-4 0.4780147 -0.8783389 0.004786849 0.5651121 -0.8250132 -0.001353502 0.6017295 -0.7986938 0.00316286 0.6787481 -0.7343513 -0.005421757 0.7614926 -0.6480942 0.01015031 0.8394216 -0.5434509 -0.00570321 0.8922364 -0.4514994 0.007914364 0.9485023 -0.31676 -0.002563476 0.953453 -0.3015422 -1.13642e-4 0.9917965 -0.1273227 -0.01134639 0.9991257 -0.04180526 -3.12484e-4 0.999176 -0.04058903 -5.11897e-6 0.9838581 0.1789495 5.84692e-4 0.9835025 0.1808933 8.21546e-4 0.9683179 0.2497031 -0.002998709 0.951588 0.3073407 0.004686415 0.8851751 0.4652565 -0.001258611 0.8889514 0.457994 -0.002635538 0.7907415 0.6121496 -9.65233e-4 0.7926827 0.6096343 -3.51297e-4 0.6300538 0.7765483 0.002234637 0.6389116 0.7692801 1.28759e-4 0.5340344 0.8454563 -0.00331664 0.4818193 0.8762519 0.005712628 0.3830766 0.92371 0.003522813 0.3398784 0.9404574 -0.004760503 0.1300106 0.9915081 0.003012061 0.1629069 0.9866234 -0.005976259 0.07986724 0.9967886 0.00580883 -0.07992935 0.9967905 -0.004478573 -0.1634821 0.9865267 0.006222903 -0.2453364 0.9694378 6.59842e-4 -0.2865337 0.9580555 0.005296647 -0.4414387 0.8972873 -0.002729654 -0.4447243 0.8956649 -0.002182722 -0.5890492 0.8080853 -0.004399061 -0.6100642 0.7923521 2.9197e-4 -0.7232213 0.6906102 -0.002934873 -0.7423236 0.6700378 0.002251327 -0.8497385 0.5271905 0.003825664 -0.871406 0.4905534 -0.003011405 -0.9283972 0.3714709 0.009385406 -0.9646149 0.2635843 -0.006444334 -0.9859291 0.1670476 0.006240844 -0.9999873 -0.004415035 -0.002451658 -0.9999251 -0.01152074 -0.004152357 -0.9740277 -0.2264184 0.00222826 -0.9727208 -0.2319778 7.94214e-4 -0.8961727 -0.4436735 -0.005334496 -0.8776308 -0.4793271 0.003113985 -0.77296 -0.6344512 -0.002174198 -0.7732598 -0.6340861 -0.002076923 -0.02561968 0.01725071 0.9995229 -7.82047e-4 0.00694549 0.9999756 0.004908502 0.01979804 0.999792 0.02510589 0.008564472 0.9996482 -9.58779e-4 0.00690937 0.9999757 0.01013535 0.02820223 0.9995509 0.005589783 0.01128268 0.9999207 -0.009957373 0.009066462 0.9999094 0.01262968 -0.01389646 0.9998237 -0.008276998 -0.0208137 0.9997492 0.007667422 -0.007672488 0.9999412 -0.002708256 0.001283705 0.9999956 0.008191943 0.00257045 0.9999632 0.006997942 0.00511837 0.9999625 -0.005092799 -5.92098e-4 0.9999869 0.002957582 -7.73066e-4 0.9999954 -0.004479587 -0.003980338 0.9999821 0.002479255 -0.005856037 0.9999798 -0.007888197 -8.96015e-4 0.9999686 0.004863142 -0.003487527 0.9999822 0.02592474 -0.002893507 0.9996597 -0.007412672 -0.006689488 0.9999502 -0.02183163 0.00195831 0.9997597 -0.00358504 -0.02669429 0.9996373 0.001045346 -0.01949578 0.9998094 -0.01375895 -0.01858586 0.9997327 0.01190292 -0.03547137 0.9992998 -0.01139813 -0.00237441 0.9999323 0.007311224 -0.005758702 0.9999568 -0.7387349 -0.6017531 -0.3035854 -0.8351936 -0.4235356 -0.3508122 -0.7499991 -0.4248901 -0.506922 -0.04809665 -0.02609091 -0.9985019 -0.5722548 -0.322635 -0.7539438 -0.4157958 -0.170722 -0.8932905 -0.7622891 -0.17404 -0.6233983 -0.7508919 -0.1795619 -0.6355462 -0.7287262 -0.1007196 -0.677358 -0.9111595 9.72082e-5 -0.4120541 -0.3443823 0.01382488 -0.9387277 -0.7914662 0.09975081 -0.6030182 -0.4983934 0.06541764 -0.8644794 -0.8756649 0.2338658 -0.4225139 -0.7537875 0.2637405 -0.6018683 -0.5066965 0.186392 -0.8417344 -0.4370133 0.1792696 -0.8814091 -0.8044284 0.4642825 -0.3705899 -0.6858677 0.4632502 -0.561235 -0.5489475 0.3676397 -0.7506648 -0.3652472 0.3027656 -0.8802998 -0.6833067 0.6238386 -0.3793646 -0.2993729 0.3563023 -0.8851128 -0.4465318 0.5762653 -0.6844909 -0.4331392 0.5646476 -0.7025409 -0.3242227 0.7815324 -0.5329979 -0.05567407 0.0994091 -0.993488 -0.3107433 0.717952 -0.6228833 -0.2410355 0.9095695 -0.3385043 -0.1426996 0.4355984 -0.888758 -0.0829752 0.8304602 -0.5508639 -0.0606175 0.7720382 -0.632679 -0.05423921 0.6431725 -0.7637979 0.01432216 0.4042622 -0.914531 0.1276335 0.8916755 -0.4343093 0.1672423 0.7967872 -0.580655 0.1529865 0.6990149 -0.6985509 0.3271149 0.8942026 -0.3056104 0.1759055 0.4700585 -0.8649291 0.01943188 0.07942563 -0.9966515 0.3890074 0.7301775 -0.5617065 0.3646155 0.660631 -0.6562181 0.3996334 0.5094149 -0.7620956 0.5870673 0.6259713 -0.5133342 0.2438719 0.2621973 -0.9336912 0.6823701 0.5796785 -0.445358 0.5768061 0.382093 -0.7220109 0.6016495 0.3133344 -0.7347378 0.7505453 0.3466219 -0.5626145 0.3072945 0.1105275 -0.945174 0.8608797 0.2677013 -0.4326919 0.6738606 0.09483665 -0.7327468 0.8952806 0.06546401 -0.4406667 0.7178792 0.05433428 -0.6940442 0.599545 -0.03234428 -0.7996873 0.6666713 -0.08948534 -0.7399607 0.624016 -0.1544824 -0.7659892 0.7879766 -0.3062316 -0.534149 0.734146 -0.3510308 -0.5812117 0.203302 -0.09628587 -0.9743702 0.7812148 -0.51437 -0.3537329 0.3727178 -0.2302439 -0.8989267 0.715016 -0.5222862 -0.4647249 0.4153836 -0.3076539 -0.8560407 0.6318099 -0.6414105 -0.4352112 0.3760151 -0.3316684 -0.8652219 0.4872283 -0.5648682 -0.6659824 0.433794 -0.5842909 -0.6858767 0.4619812 -0.763463 -0.4513287 0.3953192 -0.806573 -0.4395028 0.170825 -0.3324604 -0.9275177 0.2151718 -0.6139534 -0.7594488 0.1877852 -0.6491506 -0.7371162 0.1685979 -0.8225235 -0.5431665 0.1022775 -0.8545119 -0.509263 0.0264256 -0.3625415 -0.9315929 0.004075527 -0.7397629 -0.6728553 -0.02820211 -0.7617769 -0.6472254 -0.1261564 -0.6460986 -0.7527558 -0.005816817 -0.1589494 -0.9872696 -0.2185595 -0.789995 -0.5728348 -0.1626309 -0.6792691 -0.7156429 -0.3229198 -0.8543258 -0.4072474 -0.4326066 -0.7275427 -0.5324784 -0.4300265 -0.7048479 -0.5641511 -0.1908423 -0.3554612 -0.9150009 -0.2274635 -0.3929816 -0.890969 -0.5592197 -0.6864809 -0.4647766 -0.5675593 -0.568992 -0.5950838 -0.37164 -0.3459883 -0.8614963 -0.3023898 -0.2948332 -0.9064403 -0.1204618 0.9923756 -0.02606993 -0.1194662 0.9925209 -0.02510601 0.8002818 0.5990978 -0.02511727 0.8008605 0.5982832 -0.02607077 0.919757 -0.3919256 -0.02100938 0.9213181 -0.3879926 -0.02519285 0.06557661 -0.6620133 -0.7466178 0.1107702 -0.8377352 -0.5347241 0.778342 -0.3331733 -0.5321461 0.7743576 -0.3304128 -0.5396276 0.5198441 0.4068795 -0.7511399 0.6822481 0.4983664 -0.5349473 -0.07804167 0.6607909 -0.7465019 -0.0806812 0.6704133 -0.7375884 -0.6082431 0.275048 -0.7445731 -0.7804087 0.3229245 -0.535427 -0.5297142 -0.4127375 -0.7409795 -0.6786072 -0.4959327 -0.5417961 -0.9170153 0.3980715 -0.02494317 -0.918886 0.3939908 -0.02049314 -0.7996237 -0.6001557 -0.02037942 -0.7966462 -0.6039232 -0.02513432 0.1202794 -0.992403 -0.02587312 0.1140801 -0.9932729 -0.01986634 0.01039725 -0.004333615 -0.9999366 1.38354e-4 -0.009445369 -0.9999554 -0.009464144 0.003685951 -0.9999485 0.009515881 -0.00445044 -0.9999448 0.002467751 -0.004507064 -0.9999869 0.001336336 -0.008276224 -0.999965 -0.00134027 0.005853414 -0.999982 0.006414353 -0.002476215 -0.9999765 0.01088702 -0.005195438 -0.9999274 0.006536185 -0.006799817 -0.9999556 -0.005793213 -0.002254724 -0.9999807 0.003902733 0.004001319 -0.9999845 0.003843665 0.002870738 -0.9999885 0.002045333 0.005113542 -0.9999849 6.71201e-4 -0.007444083 -0.9999722 0.00318849 -0.006308436 -0.999975 0.002388179 0.001660287 -0.9999958 -5.3802e-4 0.004546165 -0.9999895 -0.007279515 0.001051127 -0.9999729 -0.004612088 3.26151e-4 -0.9999894 -0.003960371 -0.002804934 -0.9999883 -0.008828222 -0.001586735 -0.9999598 -0.006280004 0.002543866 -0.9999771 0.005777537 0.004120647 -0.9999749 -0.008612513 -0.009128153 -0.9999213 -0.01979982 -0.01202899 -0.9997316 -0.06163972 0.0154519 -0.9979789 -0.009990215 -0.002572655 -0.9999469 -0.0291059 0.03481316 -0.9989699 -0.03200435 0.001967787 -0.9994858 -0.001115441 7.67243e-4 -0.9999992 -0.0518921 -0.02715915 -0.9982833 -0.02694112 -0.09705144 -0.9949147 -0.02657014 0.08074319 -0.9963808 -0.05176037 -0.09919619 -0.9937208 -0.0533002 -0.05036419 -0.9973077 0.01474213 0.01518774 -0.9997761 -0.02059668 -0.06057804 -0.997951 -0.01047343 -0.04996407 -0.9986961 -0.01384055 -0.04490047 -0.9988956 0.002045214 -0.002819478 -0.9999939 1.8744e-4 -1.44419e-4 -1 0.02143895 0.006415605 -0.9997496 0.07607841 -0.09524178 -0.9925428 0.1517333 -0.400982 -0.9034326 0.4734153 -0.6245821 -0.6211081 0.3759511 -0.321752 -0.8689858 0.6237199 -0.3664289 -0.6904371 0.4540218 -0.0990985 -0.8854624 0.6186146 -0.04269343 -0.7845337 0.4719533 0.1197416 -0.8734541 0.5180814 0.1666196 -0.8389456 0.4341775 0.3542745 -0.8282389 0.4509013 0.3916345 -0.8020663 0.2876579 0.4991675 -0.8173646 0.2815852 0.5819686 -0.7629039 -0.01144772 0.4904366 -0.8714017 -0.08008337 0.6331719 -0.7698571 -0.2535364 0.4312672 -0.8658683 -0.2857859 0.4536855 -0.8440948 -0.4665555 0.3342242 -0.8189141 -0.4562391 0.2884603 -0.8418056 -0.5473192 0.2246301 -0.8062153 -0.4874103 0.06924796 -0.870423 -0.5911657 0.01848065 -0.8063386 -0.5165578 -0.1908254 -0.8347179 -0.4651919 -0.2015561 -0.861958 -0.4388303 -0.368844 -0.819379 -0.3240017 -0.3679407 -0.8715748 -0.305063 -0.5495095 -0.777802 -0.06640523 -0.4929016 -0.8675474 -0.115763 -0.5587337 -0.8212281 0.1498734 -0.514853 -0.8440761 0.1514042 -0.5169956 -0.8424918 0.3844603 -0.4593596 -0.8007366 0.3762775 -0.3504642 -0.8576655 0.5017381 -0.3059238 -0.8091166 0.4730681 -0.1678051 -0.8648978 0.5490659 -0.1329258 -0.8251409 0.5148645 0.04310053 -0.8561874 0.5510402 0.06776916 -0.8317225 0.480707 0.2550804 -0.8389606 0.4721906 0.2448422 -0.8468108 0.4048752 0.4219064 -0.8112158 0.2883976 0.424275 -0.8583808 0.2770649 0.5133236 -0.8122401 0.07388561 0.5103431 -0.8567911 0.06613111 0.5348741 -0.8423399 -0.1355728 0.5826637 -0.8013258 -0.1711451 0.3990469 -0.9008168 -0.4581224 0.4386693 -0.7731061 -0.4046753 0.2464359 -0.880629 -0.5563988 0.2116152 -0.8035169 -0.5845302 0.03375846 -0.8106694 -0.4966975 -0.0181173 -0.8677347 -0.4909091 -0.1978214 -0.8484544 -0.5292425 -0.1906999 -0.8267624 -0.3993004 -0.3802838 -0.8342323 -0.3396199 -0.366869 -0.8660632 -0.245934 -0.554192 -0.7952281 -0.04165065 -0.4456046 -0.8942605 -0.002929925 -0.5571931 -0.8303779 0.220664 -0.5550143 -0.802039 0.2631919 -0.4136078 -0.8715841 0.4053999 -0.4562228 -0.7921564 0.439538 -0.2416722 -0.8651017 0.4825645 -0.2444808 -0.8410474 0.6221093 -0.1009145 -0.7763996 0.4882277 0.06870865 -0.8700075 0.5406337 0.1057309 -0.8345874 0.4890592 0.3208386 -0.8111004 0.4204829 0.3168762 -0.8501668 0.2254732 0.4729847 -0.851732 0.2798033 0.5040745 -0.8170796 0.08409261 0.5975468 -0.7974123 -0.01532471 0.4994781 -0.866191 -0.1583201 0.5672278 -0.8082001 -0.2062039 0.4911055 -0.8463424 -0.2969613 0.5189997 -0.8015319 -0.398975 0.3359808 -0.8531917 -0.3747743 0.2802947 -0.8837303 -0.5947183 0.1423921 -0.7912236 -0.4805193 -0.005111098 -0.8769693 -0.5837379 -0.07608151 -0.8083699 -0.4467362 -0.2593015 -0.856265 -0.4849805 -0.3099948 -0.8177392 -0.3788592 -0.4873517 -0.7867364 -0.2156252 -0.4419319 -0.870748 -0.1799667 -0.5603564 -0.8084632 -0.01581025 -0.5062299 -0.8622537 0.0403828 -0.5810855 -0.81284 0.1752588 -0.5437539 -0.8207412 0.1965928 -0.4840233 -0.8526856 0.3569414 -0.4654344 -0.8099159 0.3561502 -0.3829163 -0.8523687 0.5216526 -0.3097148 -0.7949562 0.4739487 -0.1791756 -0.8621304 0.5878884 -0.09641367 -0.8031761 0.5012639 0.02325332 -0.864982 0.575174 0.09018933 -0.8130442 0.4499617 0.2895333 -0.8448106 0.4048765 0.2917611 -0.866574 0.4259406 0.4358077 -0.7928722 0.2230815 0.5228679 -0.8227052 0.1082196 0.4326896 -0.8950242 -6.19378e-4 0.6271222 -0.7789207 -0.1873332 0.5089257 -0.8401792 -0.1864282 0.5136153 -0.8375225 -0.4203687 0.5071047 -0.7524195 -0.4292623 0.2883831 -0.8559025 -0.5644803 0.2580565 -0.7840719 -0.4970917 0.07216882 -0.8646916 -0.5544108 0.05218631 -0.8306055 -0.5662995 -0.1843112 -0.803327 -0.4584379 -0.2157372 -0.862144 -0.4739769 -0.3525893 -0.8068623 -0.3866235 -0.3742217 -0.8429001 -0.355666 -0.5534211 -0.7531446 -0.1245609 -0.514967 -0.8481119 -0.120633 -0.5226255 -0.8439848 0.08696079 -0.488345 -0.8683069 0.0739749 -0.5102799 -0.8568211 0.2448634 -0.5412483 -0.8044205 0.2715981 -0.4594777 -0.8456447 0.3917349 -0.4562382 -0.7989933 0.4167864 -0.260248 -0.8709536 0.5234963 -0.2658612 -0.8094872 0.5795402 -0.05442112 -0.8131246 0.4994097 7.84499e-5 -0.8663661 0.5559077 0.2135072 -0.8033563 0.4664251 0.2357974 -0.8525534 0.4322068 0.4039872 -0.8062206 0.3195552 0.3901303 -0.8635294 0.2641997 0.582989 -0.7683243 0.05166894 0.4854372 -0.8727434 0.01635432 0.5629444 -0.826333 -0.183942 0.5304028 -0.8275496 -0.1936154 0.416661 -0.8882042 -0.4378386 0.344487 -0.8304373 -0.4001414 0.2264301 -0.8880407 -0.6435627 0.1947545 -0.7402012 -0.4686484 -0.06958055 -0.8806402 -0.5597274 -0.1352077 -0.8175721 -0.4542154 -0.3147028 -0.8334571 -0.4573997 -0.3148511 -0.8316576 -0.2465734 -0.4413053 -0.8628159 -0.3069499 -0.4673563 -0.8290717 -0.123883 -0.6410474 -0.7574373 0.06562978 -0.4319975 -0.8994837 0.1803528 -0.5801064 -0.7943233 0.3344954 -0.326397 -0.8840689 0.363644 -0.3404939 -0.8670795 0.5777198 -0.2618529 -0.7730932 0.4630372 -0.1086928 -0.8796491 0.6257293 0.04326027 -0.7788398 0.4661413 0.1669486 -0.8688156 0.5276834 0.2456119 -0.8131576 0.3833036 0.3870064 -0.8386325 0.3232666 0.3785086 -0.867312 0.2957454 0.5303996 -0.7944879 0.09629851 0.5347134 -0.8395287 0.1381581 0.5844763 -0.7995624 -0.1162825 0.6172983 -0.7780883 -0.1929377 0.4944604 -0.8475165 -0.2728551 0.5130814 -0.8138167 -0.3177506 0.4319084 -0.8440911 -0.4783073 0.453826 -0.7518404 -0.5271432 0.211297 -0.8230879 -0.5615065 0.2041402 -0.8018961 -0.5661308 0.04026061 -0.8233317 -0.4903259 -0.02267998 -0.8712441 -0.6043376 -0.1632795 -0.779818 -0.4278905 -0.2770642 -0.8603169 -0.4452683 -0.3185388 -0.836821 -0.334958 -0.4482808 -0.8287627 -0.2417478 -0.4175118 -0.8759235 -0.1705487 -0.619093 -0.7665749 0.02979063 -0.5272665 -0.8491777 0.03544336 -0.5154059 -0.8562129 0.2328853 -0.5206069 -0.8214214 0.2657251 -0.4022266 -0.8761302 0.4953421 -0.4763461 -0.7264508 0.4383799 -0.1616371 -0.8841361 0.5753223 -0.1346868 -0.8067613 0.5249504 0.06151348 -0.8489071 0.4748242 0.08531743 -0.8759355 0.5613216 0.2744159 -0.7807778 0.3457024 0.3683042 -0.8630423 0.3696871 0.3742396 -0.8504564 0.2846617 0.5425367 -0.7903301 0.09224867 0.4702634 -0.8776916 0.04224461 0.6041862 -0.7957227 -0.149599 0.5709872 -0.8072137 -0.1735274 0.5022644 -0.8471238 -0.3684309 0.5405254 -0.7563669 -0.4364518 0.3327518 -0.8359344 -0.506321 0.3202614 -0.8006696 -0.4479092 0.1460328 -0.8820726 -0.6124943 0.07953983 -0.7864632 -0.495024 -0.09600406 -0.8635591 -0.5349472 -0.1341558 -0.8341665 -0.4420714 -0.3018998 -0.8446475 -0.463761 -0.3435983 -0.8166186 -0.2909924 -0.4473199 -0.8457118 -0.2959732 -0.4967421 -0.8158721 -0.04836493 -0.4511314 -0.8911461 -0.001838505 -0.5595635 -0.8287855 0.1642726 -0.5365645 -0.8277156 0.1825134 -0.5565702 -0.8105052 0.3315948 -0.4010821 -0.8539192 0.4019463 -0.4228146 -0.812199 0.4773519 -0.2463373 -0.843477 0.5070112 -0.2455661 -0.8262185 0.5434209 -0.0433489 -0.8383405 0.5308292 -0.04820799 -0.8461065 0.5862537 0.1048457 -0.8033144 0.4839107 0.1666529 -0.8591027 0.5073834 0.3030151 -0.8066871 0.367188 0.3342131 -0.8680291 0.3919531 0.499528 -0.7725571 0.1908893 0.4870483 -0.852259 0.1302945 0.6497473 -0.7489004 -0.114791 0.5626278 -0.818702 -0.1056045 0.5494199 -0.8288459 -0.3151293 0.5091924 -0.8008849 -0.3179352 0.4371133 -0.8413378 -0.562238 0.3757597 -0.7366771 -0.4678878 0.1686831 -0.8675409 -0.5656502 0.03105592 -0.8240604 -0.5196478 -0.004165172 -0.8543704 -0.5454456 -0.23059 -0.8058024 -0.4678387 -0.1639683 -0.8684709 -0.4676564 -0.4182861 -0.7786748 -0.3260231 -0.3834576 -0.8641003 -0.1582111 -0.5254654 -0.8359758 -0.1691409 -0.5341167 -0.8283181 0.03097444 -0.5643242 -0.824972 0.06469601 -0.5061561 -0.8600119 0.2762145 -0.5806767 -0.7658461 0.3056391 -0.341239 -0.8888986 0.4679605 -0.3591106 -0.8074978 0.4566719 -0.1779862 -0.8716489 0.660695 -0.1362818 -0.7381799 0.4766314 0.1000787 -0.8733881 0.5195163 0.1367308 -0.8434498 0.4718497 0.3369141 -0.8147679 0.3688457 0.3350806 -0.8669913 0.3632826 0.4074488 -0.8378611 0.1684429 0.4965876 -0.8514856 0.1129318 0.4627857 -0.8792473 0.03996229 0.6004388 -0.7986716 -0.1332473 0.5204886 -0.8434079 -0.1258262 0.5426527 -0.8304793 -0.3208032 0.377402 -0.8687077 -0.3151255 0.4574525 -0.8315246 -0.4976888 0.3920742 -0.7736819 -0.5173583 0.1656202 -0.8395895 -0.4874575 0.132081 -0.863099 -0.5874282 -0.01929634 -0.8090463 -0.465955 -0.11645 -0.877112 -0.608361 -0.280978 -0.742259 -0.3100658 -0.3671082 -0.8769782 -0.3321549 -0.4735014 -0.8157631 -0.1475805 -0.5154929 -0.8440896 -0.09282982 -0.4675084 -0.879101 0.04188275 -0.6188932 -0.7843578 0.2112739 -0.4546873 -0.86523 0.2051724 -0.5003588 -0.8411572 0.4081268 -0.45852 -0.7894251 0.4071009 -0.2952969 -0.8643313 0.5273696 -0.2692726 -0.8058372 0.4888636 -0.0866608 -0.8680451 0.5759578 -0.05260813 -0.815785 0.5038741 0.1531484 -0.8500921 0.5473698 0.1331678 -0.826228 0.5224474 0.2814704 -0.8048747 0.3742829 0.3329338 -0.8654868 0.392924 0.4969155 -0.7737479 0.1636988 0.464885 -0.8701062 0.1671829 0.4376291 -0.8834765 -0.02754026 0.5783257 -0.815341 -0.1547684 0.5039776 -0.8497372 -0.1374957 0.4818143 -0.865419 -0.36521 0.4808547 -0.7971201 -0.3273021 0.2912574 -0.8989119 -0.5986828 0.214454 -0.7717438 -0.4839429 0.07450562 -0.8719221 -0.5870379 -0.03334593 -0.8088724 -0.4787465 -0.1329971 -0.8678212 -0.5414508 -0.2664065 -0.7974075 -0.3459222 -0.3169795 -0.8830979 -0.384212 -0.4886974 -0.7832983 -0.1478404 -0.4835826 -0.862723 -0.1343643 -0.5523107 -0.8227389 0.1191508 -0.5531204 -0.8245369 0.07224589 -0.4640771 -0.8828438 0.3270385 -0.5718311 -0.7523664 0.3629312 -0.2818406 -0.8881705 0.4851462 -0.3112466 -0.8171651 0.6065396 -0.1185361 -0.7861673 0.4753693 7.27877e-4 -0.8797862 0.6047651 0.1431832 -0.783427 0.4256767 0.2299309 -0.875175 0.4521835 0.3723583 -0.8104811 0.2980657 0.387272 -0.8724548 0.2988693 0.5667102 -0.7678 0.02806407 0.5040944 -0.8631926 0.02536147 0.5122997 -0.8584322 -0.1694594 0.5767876 -0.7991243 -0.232091 0.4509192 -0.8618618 -0.3374674 0.4848044 -0.8068956 -0.4114774 0.3058865 -0.8585568 -0.4524425 0.3122292 -0.8353494 -0.5843732 0.121917 -0.8022744 -0.5385304 0.08599847 -0.8382059 -0.5514522 -0.1548575 -0.8197071 -0.5078561 -0.1661583 -0.8452654 -0.4168239 -0.3173474 -0.8517915 -0.4372236 -0.318133 -0.8412058 -0.2628253 -0.4507097 -0.8531024 -0.3009153 -0.4638077 -0.8332661 -0.08875542 -0.5841554 -0.8067745 -0.1047085 -0.4857068 -0.8678278 0.07292628 -0.5958044 -0.7998118 0.1610023 -0.4827657 -0.8608226 0.2614549 -0.538475 -0.8010531 0.3491578 -0.4065079 -0.8442987 0.4581558 -0.4303103 -0.7777702 0.5958541 -0.2005386 -0.7776518 0.4970328 -0.2027803 -0.8437054 0.6198357 -0.06412029 -0.7821076 0.4860022 0.09537971 -0.8687375 0.5448183 0.1452184 -0.8258842 0.4776369 0.3076667 -0.8229242 0.3495351 0.3210065 -0.880216 0.3765133 0.4530155 -0.8080933 0.1854583 0.5637118 -0.8048815 0.05474054 0.4032234 -0.9134629 -0.1553345 0.5888658 -0.7931635 -0.227552 0.4353379 -0.8710346 -0.3360049 0.4784073 -0.8113119 -0.4015589 0.3261268 -0.855799 -0.4839708 0.3305162 -0.8102662 -0.5052466 0.1121985 -0.8556503 -0.5644653 0.1023426 -0.8190879 -0.5918241 -0.1668274 -0.7886146 -0.4249181 -0.1994302 -0.8829905 -0.4775776 -0.3808587 -0.7917488 -0.2410974 -0.4565756 -0.8563941 -0.2600312 -0.4677352 -0.8447531 -0.02455097 -0.5173048 -0.8554491 -0.07609415 -0.5852563 -0.8072699 0.216811 -0.5861785 -0.7806331 0.254041 -0.4123071 -0.8749092 0.4023325 -0.4477266 -0.7985422 0.4396461 -0.2704117 -0.856498 0.5100547 -0.2626032 -0.819075 0.5340746 -0.09025752 -0.8406056 0.5440577 -0.08664721 -0.834562 0.6113364 0.0753566 -0.7877749 0.5599974 0.09863114 -0.8226026 0.5058649 0.3838613 -0.7724969 0.4502479 0.2959899 -0.8424172 0.3416563 0.4777219 -0.8093533 0.216585 0.4168172 -0.8828105 0.0597608 0.6859301 -0.7252093 -0.07185208 0.4742907 -0.8774313 -0.2288932 0.5455862 -0.8061909 -0.2888451 0.3961966 -0.8715485 -0.4039462 0.4323142 -0.8061836 -0.4662041 0.2072507 -0.8600587 -0.5299882 0.2045216 -0.8229724 -0.5451725 0.004037976 -0.8383143 -0.5417933 0.005474984 -0.840494 -0.5558574 -0.219438 -0.8017915 -0.4530387 -0.2442755 -0.8573713 -0.4424715 -0.4136916 -0.7956623 -0.2836728 -0.4008494 -0.8711197 -0.2705316 -0.526038 -0.8062858 -0.02240926 -0.4535948 -0.8909263 0.04117649 -0.5965688 -0.801505 0.1803414 -0.4740774 -0.8618165 0.2364604 -0.5131477 -0.8250855 0.3945113 -0.3747149 -0.8390171 0.3947814 -0.3761706 -0.8382383 0.5181283 -0.2599688 -0.814837 0.4756951 -0.1699302 -0.86304 0.607269 -0.07213628 -0.7912148 0.4787597 0.08497351 -0.8738242 0.5256544 0.1256041 -0.8413745 0.5201939 0.2979086 -0.8004055 0.452556 0.3132922 -0.8348899 0.4431167 0.4923132 -0.7491831 0.2004809 0.507969 -0.8377202 0.1973287 0.5386332 -0.8191066 0.07794028 0.6037859 -0.7933272 -0.07907187 0.4838658 -0.8715627 -0.1132007 0.5321944 -0.8390203 -0.3316445 0.4072307 -0.8509848 -0.3331632 0.4579219 -0.8242026 -0.4913014 0.3199014 -0.8101149 -0.4646028 0.2500239 -0.8494895 -0.561514 0.1397451 -0.8155816 -0.4900841 0.02396994 -0.8713455 -0.5686363 -0.02502673 -0.8222083 -0.5664642 -0.2183988 -0.7946196 -0.4762529 -0.2392876 -0.8461233 -0.4966778 -0.4322292 -0.7526546 -0.2920265 -0.5011596 -0.8145917 -0.291135 -0.5244842 -0.800098 -0.0702306 -0.5460519 -0.8348025 -0.04242819 -0.5104528 -0.8588585 0.1362588 -0.5947416 -0.7922853 0.1836864 -0.5032083 -0.8444173 0.2633753 -0.5208269 -0.8120179 0.4655538 -0.360768 -0.8081499 0.3938313 -0.3341085 -0.8563111 0.5484234 -0.2571319 -0.7956853 0.4859778 -0.1001153 -0.868218 0.5912991 -0.05856633 -0.804323 0.5491957 0.159704 -0.8202919 0.5658413 0.1545257 -0.8099047 0.5296238 0.3789896 -0.758858 0.3517817 0.3959718 -0.8482075 0.3165739 0.5340823 -0.7839241 0.1575652 0.4648998 -0.8712298 0.05144906 0.6259465 -0.7781671 -0.06223946 0.5011242 -0.8631344 -0.1942562 0.5651869 -0.8017657 -0.2683705 0.4181745 -0.8678176 -0.3751586 0.4639873 -0.8024787 -0.4912014 0.2959324 -0.8192345 -0.4517298 0.2049406 -0.8682969 -0.5797399 0.1443808 -0.8019077 -0.5185804 -0.0261175 -0.8546299 -0.5981751 -0.08815699 -0.7965018 -0.4616484 -0.226998 -0.8575271 -0.5075717 -0.3004908 -0.8075124 -0.3213928 -0.4429763 -0.8369461 -0.2899162 -0.4303575 -0.854834 -0.1689859 -0.5427951 -0.8226891 -0.08788752 -0.4784788 -0.8736898 0.09618949 -0.5706737 -0.815524 0.09539824 -0.5723303 -0.8144553 0.4327378 -0.5533839 -0.7116912 0.2571567 -0.4317749 -0.8645467 0.4540252 -0.3894503 -0.8013674 0.4111663 -0.2049486 -0.8882221 0.597568 -0.1697761 -0.783638 0.4631263 0.1014974 -0.8804615 0.5510997 0.07160639 -0.8313614 0.5557678 0.3327428 -0.7618429 0.3274155 0.4022127 -0.8549996 0.31564 0.3974302 -0.8616383 0.2050399 0.5553165 -0.8059666 0.07081288 0.4784016 -0.8752815 -0.02563631 0.602983 -0.797342 -0.1644954 0.4849476 -0.8589337 -0.2269334 0.5385702 -0.8114452 -0.3942012 0.398859 -0.8279595 -0.3682639 0.301331 -0.8795347 -0.6044592 0.2356783 -0.7609763 -0.4990861 0.02034306 -0.8663136 -0.5537725 -0.004527807 -0.8326558 -0.4947144 -0.2298535 -0.8381081 -0.5280069 -0.2222142 -0.8196521 -0.4350813 -0.3834404 -0.8146643 -0.3412896 -0.3782327 -0.8605008 -0.2927043 -0.5249673 -0.7992082 -0.2133817 -0.5007277 -0.8388922 -0.08199006 -0.6620134 -0.7449939 0.1050464 -0.5468716 -0.8306003 0.1358496 -0.5777554 -0.8048253 0.2952464 -0.4455124 -0.8451914 0.2948325 -0.4348759 -0.8508566 0.4750258 -0.293932 -0.8294302 0.3915522 -0.276024 -0.87778 0.591311 -0.156916 -0.7910302 0.4223428 -0.008855342 -0.906393 0.602122 0.1488596 -0.7844043 0.3489668 0.2515278 -0.9027491 0.4193416 0.376118 -0.8262494 0.2306298 0.43675 -0.8695167 0.1662284 0.4060099 -0.8986235 0.1103038 0.5229886 -0.8451722 -0.09685778 0.3677414 -0.9248703 -0.05977076 0.8222395 -0.5659945 -0.2206141 0.2858073 -0.9325469 -0.8053778 0.5815644 -0.1146711 0.129716 0.9897757 0.05931335 -0.3301385 0.9205878 -0.2086307 -0.3750331 0.8101245 0.4506092 -0.6845737 0.5982945 -0.4164164 -0.782312 0.586385 0.2100968 -0.9743516 0.2192629 0.05062413 -0.9764663 0.198271 -0.08486646 -0.9255574 -0.3272922 -0.1903246 -0.9299488 -0.3305839 -0.1609641 -0.6418626 -0.5962106 0.4822296 -0.4269793 -0.6619425 -0.6160528 -0.2549407 -0.842108 0.4752468 -0.0170381 -0.878853 -0.4767884 0.1586655 -0.8299071 0.534864 0.4220947 -0.6297121 -0.6521493 0.5961126 -0.6733577 0.4373093 0.9123127 -0.4062527 0.05142372 0.8858267 -0.3265556 -0.3296552 0.9831408 0.00294733 0.1828263 0.9090673 0.1323062 -0.3950845 0.8000608 0.3344959 0.4980113 0.6711852 0.5575966 -0.4884634 0.5895079 0.7134784 0.3787204 0.3797014 0.8374575 -0.3930546 0.2103406 0.8706542 0.4446553 -0.07300829 0.8368052 -0.5426111 -0.2099186 0.7359361 0.6436865 -0.4971204 0.5613054 -0.6616703 -0.6307777 0.4930772 0.5991615 -0.7792292 0.1804034 -0.6002137 -0.9558249 0.1254407 0.265826 -0.9311722 -0.2577677 0.2578259 -0.7608783 -0.3549203 -0.5432274 -0.6374183 -0.5579566 0.5313968 -0.4576972 -0.709998 -0.5351788 -0.1762564 -0.8474919 0.5006909 -0.1694578 -0.8902214 0.4228358 0.2011831 -0.8108 -0.5496624 0.3808026 -0.7685243 0.5141594 0.6006734 -0.7320172 -0.3214691 0.7393257 -0.5039777 0.4465468 0.8650377 -0.4241179 -0.2680186 0.9454317 -0.02754437 -0.3246541 0.8568744 0.0296635 0.5146711 0.8091514 0.5375093 -0.2373982 0.8485859 0.5274956 -0.04062604 0.5370857 0.8365175 -0.1085237 0.4808923 0.8199312 0.3105732 0.04205161 0.9570012 -0.28702 0.03601264 0.9788817 -0.201231 -0.2860941 0.8929973 0.3474276 -0.4346259 0.7804094 -0.4495124 -0.633055 0.5886479 0.5027276 -0.7343159 0.4515262 -0.5068572 -0.8680073 0.08343058 0.4894921 -0.9357343 -0.05796587 -0.3479099 -0.8535932 -0.4016248 0.3317773 -0.8202397 -0.5035009 -0.2714658 -0.511904 -0.8585413 0.02934694 -0.5092269 -0.8582834 0.06354373 -0.1099555 -0.9868006 0.1188889 0.01888394 -0.8718788 -0.4893577 0.2528646 -0.8510847 0.4601243 0.5163379 -0.7967878 -0.3138861 0.6045712 -0.7635616 0.2268643 0.7651975 -0.473746 -0.4359331 0.8407863 -0.4119691 0.3512264 0.9995456 -0.02654951 -0.01427298 0.9986029 -0.03479403 0.03977072 0.8708048 0.366661 -0.327504 0.6942055 0.3947451 0.6018763 0.4537426 0.6130993 -0.6467046 0.2532597 0.6254126 0.7380506 0.0181542 0.7839078 -0.6206119 -0.2960186 0.77961 0.551889 -0.7206749 0.6882985 -0.08290261 -0.941877 0.2201009 0.2538178 -0.9724155 0.2045521 0.112101 -0.8757333 -0.2301395 -0.4244138 -0.8531545 -0.304757 0.4233798 -0.679394 -0.7151294 -0.164359 -0.3742086 -0.9040831 -0.2064018 0.04827713 -0.9126124 0.4059655 0.2225461 -0.8270081 -0.5162663 0.407164 -0.8486979 0.3375343 0.6537441 -0.6552246 -0.3785492 0.6981934 -0.5388276 0.4713714 0.793341 -0.2326766 -0.5625581 0.8092303 -0.08826708 0.5808229 0.8219245 0.2758081 -0.4983674 0.9180142 0.377496 0.1214355 0.6857432 0.7073264 0.1715977 0.5976623 0.7320915 -0.3268668 0.2035201 0.9738035 0.1014221 0.1870838 0.9492179 0.2529526 -0.2220457 0.9502554 -0.218427 -0.2914702 0.8575829 0.4237886 -0.5134791 0.7169432 -0.4715206 -0.6640963 0.4826798 0.5709609 -0.8603209 0.5033118 0.08077901 -0.8496782 0.09444683 -0.5187743 -0.8101567 -0.02648121 0.5856149 -0.8089011 -0.3853076 -0.4440915 -0.8438625 -0.4915509 0.2151139 -0.5334771 -0.8251703 -0.185732 -0.5611918 -0.7148926 0.417124 -0.1808427 -0.856554 -0.4833334 0.01515954 -0.7740515 0.6329411 0.211416 -0.9355774 -0.2828395 0.584551 -0.7871667 -0.1966441 0.5649121 -0.6798558 0.4676221 0.8859096 -0.3169983 -0.3386389 0.947901 -0.3086842 0.07872647 0.9677624 0.2440095 -0.06241285 0.9583015 0.2546246 0.1297094 0.7082048 0.6873171 -0.1613733 0.7052147 0.7058923 0.06624364 0.2126435 0.9771223 -0.003850579 -0.1754752 0.9764333 0.1256448 -0.6256802 0.7790984 0.03911519 -0.8549768 0.5133335 -0.07418483 -0.9964441 0.07880127 -0.0298267 -0.9446116 0.04536586 0.3250399 -0.8063482 -0.3965713 -0.4387868 -0.8759389 -0.4752779 0.08271735 -0.5367032 -0.7461001 0.3940614 -0.4241857 -0.8049977 -0.4147835 -0.02123034 -0.9994413 0.0258159 -0.01131993 -0.9863439 0.1643102 0.4604629 -0.882077 -0.09956991 0.4716312 -0.8674618 0.1583477 0.8707801 -0.4381994 -0.2229875 0.8939562 -0.4261092 0.1388288 0.9993314 0.03226745 -0.01719421 0.9166663 0.07275319 0.3929757 0.7173486 0.3702549 -0.5901883 0.5863208 0.5017021 0.6360213 0.4847053 0.7681041 -0.4184219 0.2629655 0.870082 0.4169012 0.1160728 0.9123816 -0.3925392 -0.3097006 0.8440257 0.4378427 -0.6006119 0.5746123 -0.5559551 -0.7512555 0.3434561 0.5636073 -0.8607885 0.1231719 -0.493834 -0.9447647 -0.09618091 0.3133194 -0.8894062 -0.2618505 -0.3746877 -0.7894903 -0.4414106 0.4264526 -0.6502499 -0.6757668 -0.3471519 -0.5851066 -0.7561769 0.2929963 -0.3207141 -0.8796526 -0.3512177 -0.1965067 -0.920379 0.3380645 0.04874962 -0.9263963 -0.3733812 0.1897784 -0.882 0.4313471 0.5022336 -0.7977343 -0.333739 0.5754519 -0.8153413 0.06382721 0.8407021 -0.5177137 -0.1587215 0.8554915 -0.5161654 -0.04132527 0.916045 -0.1529994 0.3707466 0.8551255 0.04389786 -0.5165593 0.9208598 0.2284919 0.315925 0.7790205 0.5073397 -0.3684206 0.7490808 0.5661036 0.3440997 0.3272217 0.8832542 -0.3358392 -0.04837137 0.992077 0.1159459 -0.5953981 0.786018 -0.1663642 -0.8585842 0.5122825 0.01999747 -0.9979276 0.06352263 -0.01027077 -0.9631636 0.01362943 -0.2685707 -0.8855125 -0.2975055 0.3568727 -0.7160261 -0.438405 -0.5432383 -0.6197923 -0.5943801 0.5124157 -0.3278948 -0.813822 -0.4797695 -0.3415709 -0.9264514 -0.1581684 0.0273016 -0.8959704 0.4432741 0.1839057 -0.8795859 -0.4387567 0.5966747 -0.8021164 0.02426165 0.5973686 -0.7985921 0.07349443 0.8239793 -0.414732 0.3860771 0.7363559 -0.1907713 -0.6491428 0.8119965 0.07880324 0.5783182 0.8214081 0.3071694 -0.4805578 0.7066494 0.5238207 0.4756665 0.529142 0.6464567 -0.5496386 0.2836589 0.7704026 0.5709794 0.1303224 0.9219079 -0.3648315 -0.1712234 0.9712983 0.1651129 -0.2668074 0.9149345 -0.3028343 -0.4807536 0.7025842 0.5246444 -0.6519336 0.6276695 -0.4254571 -0.9313345 0.3612796 -0.04575222 -0.9128183 0.3333072 0.2359433 -0.985108 -0.1665303 -0.04277789 -0.8775665 -0.07592421 0.4734054 -0.7168364 -0.4320858 -0.547218 -0.6232095 -0.5933707 0.5094322 -0.5083795 -0.7849952 -0.3540239 -0.2592474 -0.833652 0.487663 -0.02730917 -0.7688568 -0.6388376 0.2479954 -0.7348727 0.6312372 0.4870919 -0.7509227 -0.4459334 0.7175782 -0.6261478 0.3049927 0.7762242 -0.4353132 -0.4560466 0.8122825 -0.2334721 0.5344979 0.8924595 0.03395426 -0.449848 0.9241132 0.1959683 0.3280417 0.7935087 0.4155128 -0.4446272 0.7230921 0.5234856 0.4506669 0.4874964 0.8230345 -0.2914815 0.3764544 0.8004184 0.4664895 0.05945146 0.8034626 -0.5923795 -0.1543886 0.7795442 0.6070214 -0.4063349 0.8301352 -0.3817954 -0.6227682 0.6866393 0.3750819 -0.7086496 0.5586639 -0.4309413 -0.8648464 0.2246897 0.4489493 -0.801115 0.01720225 -0.5982631 -0.8911439 -0.1566576 0.4258181 -0.7219035 -0.5793225 -0.3784716 -0.8110602 -0.5844404 -0.02471768 -0.3654575 -0.9294632 0.05038833 -0.2728444 -0.881766 -0.3847658 0.105261 -0.8463307 0.5221538 0.2642057 -0.9100064 -0.3195055 0.6270027 -0.7409047 -0.2406823 0.5393893 -0.5350647 0.6502038 0.7980699 -0.3126961 -0.5150783 0.907862 -0.09388351 0.4086228 0.9903659 0.01028251 -0.1380935 0.9116957 0.39781 0.1027545 0.8292256 0.4524489 -0.3281387 0.5922886 0.6205525 0.5139153 0.391339 0.7239509 -0.5681101 0.1347721 0.8969415 0.4211086 0.05015891 0.9942204 -0.09492111 -0.3768259 0.9101402 0.1721835 -0.4417062 0.8185205 -0.3673146 -0.6889093 0.617451 0.3796818 -0.8043643 0.5468372 -0.2323087 -0.9717615 0.2034097 0.1196002 -0.9703865 0.2192924 -0.1012966 -0.9696585 -0.2013233 0.1386772 -0.861544 -0.2921968 -0.4151663 -0.7610039 -0.4744576 0.4424515 -0.5248534 -0.7036054 -0.4790286 -0.5605517 -0.825528 -0.06546443 -0.2109726 -0.9200835 0.3300563 -0.0802806 -0.9387043 -0.3352453 0.2267922 -0.9420452 0.247217 0.3297526 -0.8972522 -0.2936013 0.6232216 -0.6796447 0.3868824 0.8562116 -0.3794754 -0.3505712 0.9786606 0.1444367 0.1461563 0.960578 0.1237295 -0.2489597 0.7076501 0.5276339 0.4699296 0.6042116 0.6349834 -0.4813778 0.3000674 0.9422866 0.1485108 0.2150943 0.7912577 0.5724035 -0.1157739 0.8082862 -0.5772953 -0.307886 0.7841532 0.5388044 -0.5645244 0.6102469 -0.5557976 -0.7235429 0.6854145 0.08180963 -0.8891721 0.2817079 0.3605742 -0.7901861 0.1055764 -0.603705 -0.7830733 -0.264658 0.5628076 -0.8806368 -0.4355234 -0.186543 -0.5741066 -0.7758246 -0.2617209 -0.5287844 -0.7858296 0.3207166 -0.1211879 -0.9905813 0.06373661 -0.09887653 -0.9914963 -0.08460849 0.2980658 -0.8916961 -0.3406389 0.3615545 -0.7620277 0.5372077 0.6312699 -0.6947447 -0.3447148 0.7780337 -0.5747885 0.2535386 0.8295584 -0.3743363 -0.4143733 0.8721789 -0.2281526 0.4327243 0.9369424 0.1496082 -0.3158425 0.8766056 0.4811909 0.004257738 0.5328822 0.8394932 0.1062444 0.5188999 0.7188804 0.4625514 0.1473876 0.8239757 -0.5471206 -0.0358504 0.8606854 0.5078735 -0.2689715 0.8533696 -0.4465589 -0.4264816 0.7356101 0.5262996 -0.6082974 0.4767068 -0.6346063 -0.781221 0.440705 0.4421234 -0.9760332 0.06301414 -0.2082988 -0.917493 0.02913957 -0.3966832 -0.8280029 -0.3482108 0.4395003 -0.644733 -0.4900294 -0.5866776 -0.5556297 -0.6330567 0.5389945 -0.2038753 -0.7423889 -0.6381958 -0.1439576 -0.9075914 0.3944033 0.2857834 -0.9582943 -2.51672e-4 0.320634 -0.8803926 -0.3494321 0.6437888 -0.7191668 0.2614097 0.72136 -0.6086475 -0.3304361 0.8373981 -0.389152 0.38383 0.9216449 -0.2539784 -0.2933695 0.972558 0.08454197 0.2167575 0.9918574 0.1263795 -0.01572102 0.8010437 0.5901567 -0.1002205 0.5084205 0.8186481 0.2670655 -0.04395717 0.9688492 -0.2437196 -0.07234001 0.9739649 0.2148471 -0.5591851 0.8069411 -0.1901531 -0.5759216 0.814233 -0.07306861 -0.8257365 0.5318009 0.1880085 -0.8355249 0.4007666 -0.3758784 -0.8439415 0.1296374 0.5205355 -0.8118116 -0.09595644 -0.575981 -0.7300168 -0.3843322 0.5651232 -0.6161638 -0.7742941 -0.1442605 -0.1781828 -0.9834086 -0.03403633 -0.1610938 -0.9696146 0.1841097 0.3705127 -0.9266011 -0.06427001 0.6936524 -0.7120197 -0.1089696 0.9403989 -0.2790559 0.194365 0.9609639 -0.2301629 -0.153537 0.9571369 0.285587 -0.0482617 0.7693814 0.5650926 0.2978637 0.4887081 0.8110392 -0.3215277 0.3730828 0.8220002 0.4302614 0.0602988 0.9017086 -0.428119 -0.03448259 0.9518588 0.3045915 -0.4673987 0.8402268 -0.2748774 -0.4189466 0.8884665 0.1873793 -0.8040065 0.5360484 -0.2573433 -0.8061878 0.4634836 0.3677556 -0.917758 0.1761789 -0.3559234 -0.925388 0.03802996 0.3771085 -0.9222649 -0.2393172 -0.3035699 -0.868829 -0.3308053 0.3683803 -0.5873673 -0.5691282 -0.5754067 -0.5666865 -0.6946364 0.4431104 -0.2588503 -0.9624829 0.08138304 -0.1828184 -0.9323699 -0.3118717 0.2034628 -0.9653185 0.1635946 0.5043962 -0.7465983 -0.433792 0.7592892 -0.4831597 0.4359322 0.8672144 -0.4040726 -0.2909718 0.9968032 0.03599667 -0.07132828 0.7899482 0.07497763 0.6085723 0.6459748 0.4201206 -0.6373503 0.5473645 0.5572382 0.6244019 0.3991599 0.808796 -0.4318803 0.2252785 0.9068453 0.3562041 0.0209667 0.9116988 -0.4103242 -0.2008241 0.8580014 0.4727615 -0.4032658 0.719736 -0.5651167 -0.513966 0.5368028 0.6690902 -0.6956755 0.3265795 -0.6398293 -0.8473126 0.1227519 0.5167139 -0.9409679 -0.04535979 -0.335443 -0.8932598 -0.3293417 0.3059753 -0.7310955 -0.4779062 -0.4869343 -0.6569002 -0.6013575 0.4548091 -0.3205988 -0.8354788 -0.446309 0.02709269 -0.999502 -0.01618319 0.475626 -0.8434392 0.2497808 0.5486753 -0.7360824 -0.3964065 0.7668475 -0.5652714 0.3039952 0.8093105 -0.3794398 -0.448377 0.7723485 -0.1174902 0.6242388 0.7447488 0.1251298 -0.6555088 0.7185176 0.406696 0.5642082 0.662059 0.5947227 -0.4560515 0.4311853 0.7565453 0.4916489 0.1634964 0.7473808 -0.643965 -0.005369603 0.7852931 0.619101 -0.3701962 0.696542 -0.6146416 -0.5191804 0.8546599 0.002885818 -0.7279157 0.5649418 0.388561 -0.7886105 0.362163 -0.4969222 -0.9009796 0.1399329 0.4106758 -0.7956228 -0.07116389 -0.6015981 -0.5714585 -0.2857051 0.7692906 -0.2625135 0.3133017 0.9126493 -0.4126832 0.1262377 0.9020846 -0.810216 0.1162251 0.5744927 -0.3711923 -0.08091026 0.9250243 -0.565343 -0.3585166 0.7428683 -0.2844727 -0.3467852 0.8937647 -0.2904221 -0.4669824 0.8352141 -0.101706 -0.5806062 0.8078073 -0.05968934 -0.5302314 0.8457493 0.1062194 -0.6437457 0.7578318 0.2220959 -0.4342182 0.8729995 0.2789463 -0.4657244 0.8398153 0.5249791 -0.3534253 0.7742658 0.4415807 -0.2112243 0.8720039 0.6023945 -0.1119205 0.790313 0.5567454 0.1059094 0.823904 0.4812622 0.02165961 0.8763091 0.4330862 0.3045363 0.8483479 0.4493808 0.3085805 0.8383526 0.338501 0.4490352 0.8269126 0.2296856 0.3922469 0.8907228 0.1281192 0.5409277 0.8312537 0.01624661 0.430436 0.9024749 -0.09790539 0.5719422 0.8144304 -0.2749946 0.554341 0.785547 -0.2761341 0.3964796 0.8755307 -0.3932738 0.4113913 0.8222487 -0.4902892 0.23304 0.8398268 -0.4372782 0.1569678 0.8855218 -0.601303 0.07701432 0.7953009 -0.5485877 -0.1329742 0.8254511 -0.4448044 -0.1511574 0.8827801 -0.5014408 -0.3602746 0.7866126 -0.3319609 -0.4225361 0.8433654 -0.337598 -0.4262158 0.8392661 -0.125018 -0.5168643 0.8468896 -0.1146607 -0.5439178 0.8312679 0.08179038 -0.5477876 0.8326098 0.09369146 -0.5619882 0.8218219 0.2994402 -0.4731633 0.8285241 0.2932246 -0.4292457 0.8542644 0.4610214 -0.3355295 0.8215104 0.4353531 -0.261593 0.8614157 0.5623258 -0.1698547 0.8092832 0.5152514 -0.06087613 0.8548744 0.5855531 -0.01593792 0.8104774 0.5606606 0.2212408 0.7979425 0.4418463 0.2297162 0.8671807 0.4468923 0.3457185 0.8250855 0.3093736 0.4055242 0.8601384 0.3083677 0.4856475 0.8179584 0.1447675 0.5650973 0.8122238 0.06501895 0.4790159 0.8753951 -0.01035332 0.5561935 0.8309884 -0.1893254 0.4520215 0.8716837 -0.1888085 0.4436126 0.8761047 -0.3911678 0.3592851 0.8472911 -0.377989 0.2917116 0.8786517 -0.5462701 0.2695438 0.7930544 -0.558741 0.05614835 0.8274393 -0.4842165 0.01520794 0.8748161 -0.5701914 -0.1661047 0.804544 -0.442853 -0.21891 0.8694595 -0.4800195 -0.3623512 0.7989261 -0.2799265 -0.3955867 0.8747299 -0.2720354 -0.4997985 0.8223127 -0.03807717 -0.5605491 0.8272454 -0.05382031 -0.5206392 0.8520789 0.1279582 -0.6037791 0.7868148 0.2236108 -0.4280593 0.8756504 0.3606857 -0.4731132 0.8037847 0.4062916 -0.3075888 0.8604163 0.4685129 -0.3078138 0.8280981 0.5833176 -0.1606441 0.7961998 0.4899181 -0.05505168 0.8700286 0.5926064 0.0564053 0.8035149 0.4861951 0.1550065 0.8599926 0.5496344 0.2815107 0.7865455 0.3243373 0.3437033 0.8812907 0.343762 0.4947245 0.79817 0.1264879 0.5713371 0.8109099 0.06765639 0.4946908 0.8664315 -0.06134229 0.5916944 0.8038253 -0.1311059 0.5121927 0.8488051 -0.2861185 0.5641419 0.7745193 -0.4390952 0.4012851 0.8038445 -0.4223102 0.397233 0.8147761 -0.5657666 0.2339014 0.7906948 -0.4769939 0.1373946 0.8681012 -0.5858173 -0.01297569 0.8103393 -0.4748792 -0.0744667 0.8768948 -0.5639601 -0.27943 0.7770894 -0.4322181 -0.3075767 0.8476935 -0.429219 -0.4827374 0.7633712 -0.2177449 -0.5609934 0.7986699 -0.2238336 -0.5154727 0.8271558 -0.04097634 -0.6153059 0.7872229 0.09538155 -0.4547326 0.885506 0.08545845 -0.5101492 0.8558298 0.3171044 -0.5180916 0.7943714 0.3147928 -0.381187 0.8692536 0.4813641 -0.3545429 0.8016158 0.4497509 -0.1889004 0.8729494 0.5700896 -0.1539191 0.8070358 0.5958498 0.05310368 0.8013384 0.4755297 0.1080515 0.8730387 0.533279 0.2078973 0.8199954 0.391147 0.3592167 0.8473296 0.3449037 0.3482266 0.8716534 0.2944157 0.5349606 0.7919195 0.1355817 0.4744158 0.8697972 0.06160193 0.5875219 0.8068602 -0.0747894 0.5045014 0.8601656 -0.1506487 0.5580684 0.8160053 -0.2688681 0.4602156 0.8461155 -0.3302273 0.4851196 0.8096969 -0.4500684 0.3042272 0.8395739 -0.4833285 0.3025313 0.8215038 -0.5141959 0.1091665 0.8506971 -0.5382794 0.1004152 0.8367629 -0.5935962 -0.1136268 0.7967011 -0.4442993 -0.1574558 0.881933 -0.4953788 -0.3105396 0.8112737 -0.3452176 -0.3966493 0.8505847 -0.3489089 -0.4404134 0.8272235 -0.1557729 -0.4928185 0.8560752 -0.09368497 -0.6567453 0.7482706 0.06566983 -0.4872454 0.8707923 0.174401 -0.5505059 0.8164115 0.2600561 -0.423315 0.8678568 0.3384502 -0.4514749 0.825604 0.5052556 -0.328184 0.7981303 0.4287298 -0.2015452 0.8806648 0.6170541 -0.118313 0.7779758 0.49547 0.0830444 0.8646463 0.557452 0.1455168 0.817357 0.4505701 0.3320541 0.8286898 0.3846614 0.3161005 0.8672463 0.3067851 0.545628 0.7798545 0.194374 0.4882488 0.8507832 0.07070368 0.6606505 0.7473567 -0.1221362 0.5775513 0.8071662 -0.09908574 0.5574631 0.8242675 -0.220453 0.4274725 0.876737 -0.4550398 0.4934797 0.7412264 -0.4892387 0.2662419 0.8305184 -0.457861 0.273613 0.8458719 -0.5119709 0.06633418 0.8564378 -0.4808294 0.07903629 0.8732448 -0.6253576 -0.0703212 0.7771633 -0.4519908 -0.1684966 0.8759642 -0.5189154 -0.280546 0.8074781 -0.3741542 -0.4585844 0.8060453 -0.2669255 -0.4059732 0.8740347 -0.1605708 -0.6114435 0.774825 -0.04857146 -0.5088461 0.8594862 0.0365855 -0.5716367 0.8196907 0.1628974 -0.4016149 0.9012048 0.3511605 -0.5198159 0.7787669 0.4303807 -0.3509972 0.831609 0.3632614 -0.2329764 0.9020882 0.542169 -0.165291 0.8238517 0.5747337 -0.03157645 0.8177311 0.5490311 -0.01825648 0.8356026 0.5330124 0.1801902 0.8266979 0.4780399 0.1870422 0.8581917 0.468112 0.3882155 0.7938261 0.3014186 0.4133855 0.8592202 0.3285809 0.429449 0.8411944 0.1531558 0.5497695 0.8211559 0.1123291 0.5063169 0.8550003 -0.05759692 0.6234019 0.7797774 -0.1747179 0.4838823 0.8575147 -0.1664135 0.6022831 0.7807443 -0.4082759 0.4707465 0.7821182 -0.3789438 0.3484494 0.8573126 -0.5524268 0.2681403 0.7892564 -0.4681316 0.0824095 0.8798077 -0.5373728 0.1272958 0.8336824 -0.5542112 -0.08943283 0.8275578 -0.5104709 -0.1024174 0.853774 -0.5185138 -0.3075389 0.7978492 -0.3964294 -0.4272885 0.812569 -0.389447 -0.3372436 0.8570869 -0.2179655 -0.4924446 0.8426087 -0.2332493 -0.5069915 0.8297919 -0.01889348 -0.5191287 0.8544874 0.001772403 -0.5545679 0.8321367 0.1796906 -0.5879215 0.7887076 0.2247018 -0.4449647 0.8668999 0.2711164 -0.4563297 0.8475016 0.3833891 -0.2887564 0.8772872 0.3908281 -0.2898934 0.873622 0.6112884 -0.2121949 0.7624303 0.4934657 -0.02459323 0.8694176 0.5574983 0.02038276 0.8299279 0.5611143 0.1865945 0.8064324 0.4282249 0.2209563 0.8762431 0.47238 0.3705151 0.799735 0.3101843 0.490237 0.8145266 0.2829852 0.4725058 0.8346604 0.1215598 0.6492253 0.7508194 -0.0391767 0.5275504 0.8486199 -0.1055695 0.587145 0.8025684 -0.2677322 0.4821451 0.8341797 -0.2704522 0.5122931 0.8151144 -0.5275374 0.3951946 0.7520145 -0.480536 0.2620208 0.8369172 -0.6038591 0.1452745 0.7837408 -0.4969341 0.0504617 0.86632 -0.5898773 -0.06912094 0.8045292 -0.4381524 -0.2049905 0.8752149 -0.4906257 -0.2910941 0.8213104 -0.3979207 -0.4498906 0.7995359 -0.2000691 -0.3652436 0.9091588 -0.1512807 -0.597159 0.787728 0.05259805 -0.48601 0.8723692 0.1469218 -0.5830256 0.7990589 0.273531 -0.4310457 0.8598724 0.3273896 -0.4535182 0.8289375 0.5270841 -0.3084578 0.7918562 0.4394816 -0.1709438 0.8818358 0.5248794 -0.1374715 0.840002 0.5947021 0.0597012 0.8017264 0.4731549 0.1228455 0.8723724 0.5398597 0.2495778 0.8039046 0.3692809 0.3774479 0.8492142 0.3823031 0.3838577 0.8405343 0.1703572 0.5667385 0.806093 0.1180048 0.5054194 0.8547667 -0.05190157 0.5836297 0.8103595 -0.09730982 0.495498 0.8631411 -0.2831755 0.5611315 0.7777809 -0.3339797 0.3938018 0.8563748 -0.329235 0.3825832 0.8632698 -0.4398598 0.2136773 0.8722761 -0.5047969 0.2095525 0.8374174 -0.6312159 0.131299 0.764413 -0.5007703 -0.01715075 0.8654102 -0.5790539 -0.1273411 0.8052831 -0.4575623 -0.2158679 0.8625763 -0.4724432 -0.2552419 0.843593 -0.3077693 -0.4123423 0.8574684 -0.3029947 -0.378721 0.8745083 -0.2661762 -0.5685198 0.7784187 -0.07258629 -0.4843692 0.8718473 -0.03222984 -0.5652898 0.8242626 0.2275666 -0.5760324 0.7851116 0.2318856 -0.4454666 0.8647477 0.4342552 -0.4253861 0.794021 0.3993996 -0.2813529 0.8725369 0.4805676 -0.2586516 0.8379464 0.5131347 -0.05419945 0.8565952 0.486181 -0.03019535 0.8733364 0.5816987 0.1030943 0.8068447 0.4779009 0.1947136 0.8565614 0.5151942 0.2600957 0.816655 0.3173863 0.4607685 0.8288295 0.3281261 0.4689236 0.8200269 0.1149592 0.5212932 0.8455991 0.08931821 0.4882389 0.8681274 -0.112429 0.5993331 0.7925653 -0.1822212 0.4808628 0.8576518 -0.2540483 0.5113565 0.8209592 -0.3709501 0.3626328 0.8549232 -0.3865351 0.3665257 0.8463153 -0.5749101 0.2471037 0.7800116 -0.4745233 0.06448972 0.8778775 -0.5332131 0.0368666 0.8451774 -0.5914716 -0.1033328 0.7996773 -0.385867 -0.2345489 0.8922408 -0.3946715 -0.2346709 0.888349 -0.4191606 -0.4792603 0.7711123 -0.188727 -0.4566031 0.8694227 -0.1797114 -0.5079339 0.8424412 -0.05643534 -0.6187307 0.7835736 0.09475541 -0.4918813 0.8654908 0.1582151 -0.5422255 0.8252027 0.3162596 -0.4396442 0.8406503 0.3152278 -0.4392015 0.8412691 0.5033752 -0.3082726 0.807206 0.4665326 -0.2367421 0.8522328 0.5838766 -0.1294646 0.8014532 0.5045484 -0.03709232 0.8625863 0.582535 0.06486207 0.8102136 0.4735099 0.2045195 0.8567149 0.4699099 0.2046765 0.8586573 0.4483774 0.4484339 0.7732172 0.2665303 0.3849916 0.8835967 0.173848 0.6079008 0.7747475 0.06611001 0.4909597 0.8686704 -0.1075468 0.6039506 0.7897325 -0.1912018 0.4521158 0.8712252 -0.2155236 0.464433 0.8589829 -0.3911628 0.3388097 0.8556868 -0.375309 0.3069959 0.8745838 -0.4957684 0.1596394 0.8536563 -0.4814926 0.1380749 0.8655058 -0.6076883 0.02140951 0.793887 -0.4770877 -0.1112398 0.8717874 -0.5636277 -0.2207619 0.7959824 -0.4053751 -0.4051008 0.8194903 -0.3395832 -0.3735217 0.8632294 -0.2156651 -0.5767722 0.7879229 -0.08781522 -0.4796805 0.873038 0.02908635 -0.6010521 0.7986804 0.1320205 -0.4890216 0.862223 0.2526779 -0.5580027 0.7904345 0.3011676 -0.4464263 0.8426159 0.5351678 -0.4190893 0.7334573 0.5010188 -0.202984 0.8412953 0.5846327 -0.1708736 0.7930996 0.5617238 0.07935374 0.8235105 0.5067488 0.04054766 0.8611397 0.5117583 0.3222069 0.7964209 0.3555662 0.3004904 0.8850301 0.3331388 0.5215799 0.7854763 0.1862602 0.4712629 0.8621013 0.09856069 0.5870838 0.8035039 -0.0176143 0.4940891 0.8692328 -0.09890204 0.5734519 0.8132473 -0.2816901 0.4896709 0.8251504 -0.2749073 0.3787057 0.8837465 -0.4571437 0.3998299 0.7944531 -0.535282 0.2485308 0.8072829 -0.3965247 0.1041339 0.9120988 -0.5360966 0.0269888 0.8437252 -0.6141121 -0.120668 0.7799395 -0.4545341 -0.1770465 0.8729566 -0.501098 -0.3271287 0.8011791 -0.3727176 -0.4088619 0.8330149 -0.3499407 -0.3987513 0.8476668 -0.1985245 -0.5794474 0.7904612 -0.08753037 -0.4853109 0.8699492 0.001935422 -0.5771155 0.8166602 0.1145117 -0.4949783 0.8613266 0.206398 -0.5503031 0.809053 0.3206956 -0.4188303 0.8495502 0.3809829 -0.432359 0.8172625 0.4438454 -0.26139 0.8571327 0.4636589 -0.2607384 0.8467798 0.5960188 -0.1150994 0.7946785 0.5230549 -0.02089726 0.8520429 0.633416 0.105042 0.7666488 0.5097455 0.3008126 0.8060219 0.4873235 0.2550247 0.8351516 0.4307748 0.413148 0.8023354 0.318138 0.3962521 0.8612623 0.2546991 0.542003 0.8008503 0.1297358 0.4347043 0.8911795 -0.06150555 0.5863568 0.8077146 -0.09833341 0.4821727 0.8705402 -0.307025 0.5410557 0.7829396 -0.3522288 0.3124584 0.8822157 -0.3841009 0.3696151 0.84608 -0.5811477 0.1776357 0.7941744 -0.4429262 0.06358283 0.8943007 -0.6477012 -0.1245684 0.7516423 -0.4082481 -0.2449772 0.8793861 -0.4393328 -0.308453 0.8437082 -0.3793059 -0.5033182 0.7764006 -0.1768328 -0.4269282 0.8868273 -0.1302567 -0.5918479 0.7954554 0.1321331 -0.5243378 0.841196 0.1345756 -0.5011905 0.8548085 0.3604173 -0.4880069 0.794952 0.3512222 -0.3553428 0.8662416 0.4934918 -0.3262295 0.8062507 0.4893171 -0.1815087 0.8530085 0.5534369 -0.1529377 0.8187293 0.5555124 0.04359483 0.8303648 0.5378479 0.03072905 0.8424816 0.5252107 0.2542347 0.8121076 0.508768 0.2548869 0.8223065 0.4286229 0.5176274 0.7405029 0.2764444 0.4669015 0.839989 0.2306921 0.5321993 0.8145827 0.02302771 0.4488232 0.893324 -7.70668e-4 0.4949496 0.8689214 -0.1845853 0.5858453 0.789122 -0.2479454 0.4305373 0.8678483 -0.3678904 0.4668533 0.8041796 -0.4564961 0.271822 0.847186 -0.4900154 0.271172 0.8284628 -0.5982652 0.06713902 0.7984805 -0.4925055 -0.0048123 0.8702961 -0.5851779 -0.148676 0.7971588 -0.5005193 -0.1965978 0.8431072 -0.5151808 -0.4176457 0.748439 -0.3247296 -0.4417892 0.8362853 -0.3051533 -0.5396772 0.784621 -0.1142392 -0.403537 0.9078036 0.02842581 -0.5984127 0.8006836 0.1120996 -0.5273184 0.8422405 0.2178553 -0.5920194 0.7759202 0.3900876 -0.5035347 0.7708986 0.3770741 -0.3638842 0.8517062 0.5168694 -0.3134907 0.7965988 0.4694896 -0.1548572 0.8692519 0.5553323 -0.1220071 0.8226302 0.5542699 0.07267373 0.8291584 0.5608351 0.0692985 0.8250222 0.6035064 0.2643207 0.7522731 0.4396067 0.3577451 0.8238716 0.4393835 0.409509 0.7995277 0.3004404 0.4105909 0.8609012 0.2742999 0.5102981 0.8150802 0.09707158 0.5177695 0.8499952 0.08102667 0.5007272 0.8618046 -0.07445776 0.6292206 0.773652 -0.181161 0.4651076 0.8665193 -0.2696497 0.5121026 0.8154999 -0.4293975 0.3424724 0.8356617 -0.4253396 0.3346924 0.840873 -0.5362594 0.1861655 0.8232669 -0.5082117 0.1443877 0.8490425 -0.586258 0.05391395 0.8083285 -0.4985318 -0.08161854 0.8630205 -0.5612964 -0.1568012 0.8126252 -0.4500949 -0.3088771 0.83786 -0.3806988 -0.2972857 0.8756082 -0.3578112 -0.516389 0.778019 -0.1244568 -0.5334686 0.8366133 -0.1415714 -0.4834696 0.8638373 0.07107144 -0.5993951 0.7972919 0.02427786 -0.5513895 0.8338946 0.3304902 -0.4888021 0.8073715 0.3577723 -0.5036913 0.7863169 0.4595533 -0.29782 0.8367282 0.4275777 -0.2480295 0.8692864 0.5811651 -0.0999639 0.8076227 0.5023481 -0.02272236 0.8643668 0.6023555 0.1080261 0.7908846 0.4763194 0.2731375 0.8357725 0.4522048 0.2294036 0.8619077 0.3616468 0.4820066 0.7980484 0.2642834 0.4244325 0.866032 0.09829521 0.5779069 0.8101615 0.06016701 0.5243417 0.8493797 -0.1314709 0.5854926 0.7999462 -0.1846451 0.4379737 0.8798213 -0.3475729 0.5071861 0.7886415 -0.4619827 0.3747594 0.8038206 -0.4065314 0.2535624 0.8777463 -0.5621071 0.1905153 0.8048228 -0.5240917 0.01939195 0.8514411 -0.5671972 -0.00865674 0.8235365 -0.4688124 -0.2472452 0.8479887 -0.4398104 -0.2077267 0.873737 -0.4120932 -0.4541973 0.7898634 -0.2790469 -0.4310908 0.8580755 -0.2248376 -0.6025803 0.7657317 0.02424204 -0.5933507 0.804579 0.02047598 -0.5874405 0.8090084 0.2406137 -0.5488313 0.8005557 0.2511634 -0.4175375 0.8732579 0.4116987 -0.430204 0.8033859 0.413892 -0.2501765 0.8752743 0.5308791 -0.2294875 0.8157836 0.5374959 0.02179765 0.8429847 0.5109392 0.03031003 0.8590824 0.5514208 0.2453863 0.7973211 0.3790929 0.2725863 0.8842993 0.407226 0.4226267 0.8096628 0.2356967 0.5183603 0.8220401 0.1552058 0.4537246 0.8775222 0.06048244 0.615957 0.7854546 -0.1628147 0.5146347 0.841809 -0.1677508 0.437133 0.8836144 -0.4065297 0.4987035 0.7655249 -0.4452108 0.237997 0.8632177 -0.4768514 0.2726573 0.835626 -0.5723878 0.05913043 0.8178483 -0.4929082 0.009450793 0.87003 -0.5962041 -0.1708416 0.7844449 -0.488698 -0.2254551 0.8428192 -0.5098075 -0.3836819 0.7699899 -0.3465929 -0.4391925 0.8288447 -0.3385601 -0.5061702 0.7932017 -0.1559934 -0.5142786 0.843317 -0.1418721 -0.5615129 0.8152152 0.09167438 -0.5710941 0.8157495 0.1130563 -0.4855194 0.8668848 0.319936 -0.6028103 0.7309314 0.3461268 -0.3451824 0.8723792 0.3743628 -0.3912184 0.8407145 0.9247997 -0.3395959 -0.1715236 0.6391816 -0.1164925 0.7601819 0.3277652 0.6734601 -0.662587 0.1610769 0.7748289 0.6113055 -0.0800234 0.6611452 -0.7459781 -0.1637621 0.7140337 -0.6806893 -0.3304347 0.7097502 0.6221475 -0.4809558 0.4677044 -0.7415754 -0.07936656 -0.4458744 0.89157 -0.2965868 0.8883005 -0.3506545 -0.5722649 0.616126 0.541204 -0.5697919 0.1676464 -0.8045072 0.2019044 -0.6607665 -0.7229261 0.3973931 -0.5858199 0.7063242 0.5153812 -0.2289055 -0.8258236 0.3894192 -0.3599591 -0.8478103 -0.3828673 -0.6369025 -0.6691546 -0.1619512 -0.6464762 0.7455471 -0.5111151 0.3378963 -0.7903085 -0.4550018 -0.4082015 -0.7914196 0.459223 -0.07933586 -0.8847712 0.3199015 0.4652156 0.8253711 -0.5114548 -0.2444965 -0.8237934 0.1561009 0.5264226 0.8357702 -0.4477944 0.5936256 -0.6686471 -0.6158355 0.4968929 0.611428 -0.6241922 0.2277313 -0.7473437 -0.5452654 0.1108592 -0.8309007 0.3142383 0.923241 -0.2210893 -0.09122234 0.8238336 0.5594432 0.01648801 0.4241799 -0.9054278 -0.3731496 -0.7215349 0.5832211 0.03015321 -0.7311475 -0.6815528 0.2849088 -0.4306168 0.8563855 0.626962 -0.1669529 -0.7609505 0.9521683 -0.1264355 0.2781899 0.8947119 0.1917233 -0.4034017 0.9705993 0.2286415 -0.07523381 0.7149749 0.5883013 -0.3777731 0.3728401 0.2377923 0.8969087 0.4746574 0.1885569 0.8597365 0.8484725 0.4328662 0.3045017 0.8567374 0.4358973 0.2756713 0.3518081 0.08067071 0.9325897 0.7816382 0.2639964 0.5651085 0.851139 0.2102162 0.4810112 0.6560914 -0.05314129 0.7528082 0.9597212 0.1787723 0.2167388 0.6329686 -0.002352833 0.7741739 0.9531029 -0.05270707 0.2980216 0.4999393 -0.09700047 0.8606111 0.5766429 -0.1899887 0.7945988 0.9838073 -0.1718264 0.05098181 0.9122308 -0.2853865 0.2939211 0.5332413 -0.2573441 0.8058709 0.2515933 -0.2022011 0.9464753 0.849292 -0.4807443 0.2181466 0.7377432 -0.5172801 0.43377 0.3318302 -0.3623237 0.8709824 0.5437097 -0.570453 0.6155999 0.653431 -0.6094918 0.4489406 0.6627098 -0.7444728 0.08109366 0.09681385 -0.2384923 0.9663066 0.2181288 -0.3918619 0.893792 0.313889 -0.6982763 0.6433382 0.3483738 -0.725829 0.5931341 0.4219591 -0.8555389 0.3000066 0.2007703 -0.7379313 0.6443204 0.3663682 -0.9302608 0.01972544 0.09409052 -0.6338866 0.7676815 0.2022247 -0.9441032 0.2603353 -0.05608135 -0.4210113 0.9053201 0.01277643 -0.6522123 0.7579287 0.06034415 -0.9955303 0.07265114 -0.05499905 -0.8947832 0.4431007 -0.1233196 -0.4351808 0.8918576 -0.277809 -0.8987959 0.3390989 -0.2988116 -0.6541721 0.694817 -0.3475257 -0.7983369 0.4918171 -0.494028 -0.8077554 0.3216639 -0.06615012 -0.07028293 0.9953314 -0.3569835 -0.4479749 0.8196837 -0.1835669 -0.1755711 0.9672011 -0.5629214 -0.5789087 0.5899021 -0.6135291 -0.6473362 0.4522588 -0.6951248 -0.6590059 0.2872503 -0.5525766 -0.3259036 0.7671024 -0.6665809 -0.3015724 0.6817067 -0.84987 -0.5114391 0.1270872 -0.8468564 -0.4046234 0.3451293 -0.1670459 -0.01080411 0.9858899 -0.6455935 -0.170159 0.744483 -0.7019022 -0.1418421 0.6980073 -0.9814622 -0.1910876 0.01474529 -0.9700123 -0.1480829 0.1927376 -0.6247964 0.08331507 0.77633 -0.582053 0.05381804 0.8113679 -0.9226289 0.1129044 0.3687936 -0.569983 0.2226186 0.7909238 -0.9630627 0.2656072 0.04430782 -0.6811685 0.3209865 0.6580101 -0.9382377 0.3078626 0.157895 -0.2247134 0.1555386 0.9619313 -0.678476 0.419139 0.6033183 -0.7925764 0.5385423 0.2859984 -0.4645473 0.437758 0.7697818 -0.4728212 0.5435256 0.6935561 -0.7551355 0.6551101 0.02452015 -0.6398729 0.7051766 0.3054321 -0.3767414 0.5591776 0.7385028 -0.1625669 0.3956342 0.9039058 -0.438403 0.898062 -0.03588408 -0.1441546 0.5329701 0.833764 -0.3485474 0.8799418 0.3228268 -0.2248449 0.8526073 0.471705 -0.003874301 0.5248709 0.851173 -0.07189434 0.9314138 0.3567907 0.02871412 0.8717306 0.4891435 0.04132723 0.3471624 0.9368941 0.03549838 0.1137323 0.9928771 0.09529268 0.8945951 0.4365994 0.2308655 0.9627094 -0.1410384 0.3012345 0.7453652 0.5947173 0.3065049 0.7631226 0.5689452 0.3598898 0.8149579 0.4542279 0.2555714 0.389383 0.8849091 0.4946095 0.8185687 0.2920734 0.4941642 0.8183516 0.2934321 0.4756696 0.4365754 0.7636363 0.6052303 0.5531607 0.5724592 0.6532865 0.5694664 0.4989236 0.7317703 0.6767904 0.08041805 -0.004357159 0.006205201 0.9999713 -0.008797168 0.002314209 0.9999586 -0.01334953 -0.005540192 0.9998956 0.006229877 0.005414903 0.999966 0.009070456 -0.01208204 0.9998859 -9.24353e-4 0.001828014 0.9999979 0.007297813 -0.005189538 0.9999599 0.003559768 -1.81114e-4 0.9999937 -2.7469e-4 0.001439213 0.999999 -0.643013 -0.5921556 0.4856812 -0.5789667 -0.6687203 0.4664876 -0.252985 -0.2862353 0.924158 -0.3666614 -0.5554136 0.7463747 -0.3672193 -0.5542663 0.746953 -0.4097336 -0.7554674 0.5112606 -0.1518294 -0.4035098 0.9022904 -0.2719183 -0.8073679 0.5236578 -0.2716739 -0.8112787 0.5177069 -0.1612402 -0.484998 0.8595224 -0.1608931 -0.9165703 0.3660771 -0.05790454 -0.8274959 0.5584781 -0.05159431 -0.5912124 0.8048641 0.01194477 -0.3497542 0.9367654 0.03728032 -0.9191064 0.392242 0.1264237 -0.8019225 0.5838986 0.1343023 -0.6422537 0.7546343 0.2984808 -0.9513529 0.07640051 0.1752885 -0.6099008 0.7728486 0.2873908 -0.7027196 0.6508392 0.354479 -0.6477637 0.6743492 0.441413 -0.7186227 0.5373417 0.2125352 -0.3056994 0.9281039 0.6116131 -0.6006241 0.5149566 0.599052 -0.5633612 0.569 0.3928503 -0.3653435 0.8439152 0.7455368 -0.4978076 0.4431282 0.2892953 -0.2039437 0.9352621 0.5971677 -0.2917462 0.747178 0.6338955 -0.2648661 0.7266516 0.5848621 -0.1592071 0.795355 0.5509164 -0.1688551 0.8172999 0.9247486 -0.1691242 0.3409357 0.8846876 -0.03878611 0.464568 0.7679029 0.001522421 0.6405645 0.6217498 -0.01168704 0.7831289 0.8838933 0.134325 0.4479839 0.2817265 0.0365926 0.9587967 0.7219403 0.2301357 0.6525639 0.5773848 0.18703 0.794762 0.7904873 0.2977409 0.5352384 0.3796229 0.2171528 0.8992948 0.6908373 0.4117162 0.5943348 0.54426 0.3716543 0.7520998 0.5633419 0.5511035 0.6155737 0.5128501 0.4583113 0.7259033 0.5289115 0.688649 0.4959992 0.1432651 0.1919054 0.9709004 0.3093838 0.567435 0.7630854 0.3433238 0.857949 0.3821678 0.2966408 0.6350776 0.7132186 0.1570501 0.910547 0.3824129 0.1060848 0.5152953 0.8504215 0.0849604 0.7422634 0.6647005 -0.01500523 0.7557439 0.6546954 -0.06838357 0.891093 0.4486392 -0.003241479 0.07651329 0.9970633 -0.06458479 0.3267959 0.9428857 -0.236957 0.8794934 0.4127262 -0.2552823 0.8197308 0.5127111 -0.1364385 0.4550588 0.8799466 -0.402846 0.8320519 0.3813201 -0.4321992 0.6983881 0.5704892 -0.2977594 0.4914851 0.818402 -0.5245169 0.7201501 0.454165 -0.1986574 0.2287036 0.953011 -0.5447859 0.4787107 0.6885088 -0.08745962 0.08506697 0.9925294 -0.6921857 0.5573272 0.4585471 -0.5666745 0.501147 0.654012 -0.8158511 0.4969894 0.2956159 -0.4639594 0.2803005 0.8403412 -0.7602741 0.33762 0.5549739 -0.626643 0.2544271 0.7366041 -0.5982109 0.2146026 0.7720684 -0.7612027 0.1644272 0.6273229 -0.2554044 0.05754554 0.9651203 -0.737107 0.04744517 0.6741085 -0.6778374 0.02180951 0.7348883 -0.6693114 -0.01348882 0.7428596 -0.9475904 -0.1714528 0.2695856 -0.4792289 -0.08485049 0.8735789 -0.713693 -0.2288932 0.6620048 -0.7134436 -0.3048142 0.630941 -0.61223 -0.3241598 0.7211762 -0.6380838 -0.4336874 0.636211 -0.596215 -0.4800984 0.6434542 -0.7474446 -0.6643203 0.002253353 -0.6680634 -0.7440825 -0.00570625 -0.6167329 -0.7871613 0.004217743 -0.4938189 -0.8695647 -5.4171e-4 -0.5071556 -0.861851 0.002515733 -0.3426316 -0.9394681 -0.001848101 -0.3363828 -0.9417251 -6.2999e-4 -0.1391021 -0.9902692 -0.004206657 -0.1780556 -0.9840164 0.002805411 0.08015048 -0.9967817 -0.001484274 0.0506674 -0.9987056 0.004484355 0.2296594 -0.9732555 -0.005523204 0.3003364 -0.9538204 0.004971623 0.3728627 -0.9278735 -0.004935264 0.5286279 -0.8488309 0.0062083 0.5577383 -0.830017 2.32142e-4 0.6826084 -0.7307807 -0.002304255 0.6927676 -0.7211608 4.89774e-4 0.8261905 -0.5633674 -0.005154132 0.8517196 -0.5239937 0.002131402 0.9023735 -0.4309308 -0.004557132 0.9507007 -0.3099945 0.008464634 0.9358298 -0.3524456 -0.002205848 0.974355 -0.2249002 0.007228314 0.9882893 -0.1525598 -0.003151357 0.9999691 -0.006804704 -0.003958046 0.9999534 0.009589195 -0.001107811 0.9895898 0.1439005 0.002186894 0.9857802 0.1680253 -0.002266168 0.9305341 0.3661996 0.002029657 0.930173 0.3671148 0.002245783 0.8264008 0.5630721 -0.00340408 0.844511 0.5355323 0.00253725 0.7574631 0.6528763 0.001565933 0.705513 0.7086614 -0.007105231 0.5935071 0.8048169 0.004391252 0.5580694 0.8297896 -0.002816677 0.3990963 0.9169084 0.001105606 0.3973858 0.9176506 0.001430213 0.2966975 0.9549495 -0.006494581 0.09351676 0.9956159 -0.001918554 0.1464529 0.9891994 0.006027042 -0.08529323 0.9963511 -0.003125488 -0.04526984 0.9989665 0.004076361 -0.2345203 0.972106 -0.003171741 -0.2664932 0.9638313 0.0032624 -0.4355173 0.900175 0.003132343 -0.4669606 0.8842689 -0.004029035 -0.6150639 0.7884592 0.005359947 -0.6385887 0.769548 5.46031e-4 -0.7558427 0.6547529 7.73611e-4 -0.7408106 0.6717021 -0.004006981 -0.8747875 0.4844902 -0.004023194 -0.8613013 0.5080943 4.76497e-4 -0.9651169 0.261817 -0.001133322 -0.9445826 0.3282254 0.005647122 -0.9727801 0.2317075 0.003268599 -0.9997661 0.02162128 6.10114e-4 -0.9987617 0.04929357 -0.006720781 -0.9859728 -0.1665493 0.01090383 -0.9645065 -0.2639266 -0.008366107 -0.9107016 -0.4129916 0.00778079 -0.8789433 -0.4768481 0.008653759 -0.8449478 -0.5347985 -0.007338404 -0.8054465 -0.5926299 -0.006770968 -0.02600616 0.02687609 0.9993005 5.21551e-4 0.001110434 0.9999993 0.01615655 0.01606512 0.9997405 0.02386724 0.007732689 0.9996852 -0.01977986 0.00251156 0.9998013 0.01224058 0.008139014 0.999892 -0.003701269 0.001405656 0.9999922 0.02191132 -0.00812304 0.999727 0.001935362 0.007041513 0.9999734 0.003907144 5.47523e-4 0.9999923 -0.004351675 -6.71501e-5 0.9999905 0.004754602 0.001880824 0.999987 -0.004804849 7.62785e-4 0.9999883 -0.007204174 -0.005942642 0.9999565 0.004188001 -0.001041471 0.9999907 0.00396955 -2.56947e-4 0.9999922 -0.005966484 -0.008744657 0.999944 -0.01443129 -0.003310739 0.9998904 0.003513753 -0.002136707 0.9999915 0.00293374 -0.002420008 0.9999929 -0.01367282 -0.005480766 0.9998916 -0.002838194 -0.01148307 0.9999301 -0.01870685 -0.003873467 0.9998175 0.01939338 -0.006849825 0.9997885 0.01770728 -0.008722364 0.9998052 -0.005067408 -0.01746845 0.9998347 -0.003053367 -0.01729828 0.9998458 -7.78902e-4 -0.01834142 0.9998316 -0.6762425 -0.5239698 -0.5178339 -0.5656969 -0.3456854 -0.748658 -0.5886401 -0.2954476 -0.7524718 -0.7774767 -0.3334113 -0.5332605 -0.9241299 -0.2577177 -0.2820738 -0.3975905 -0.1476164 -0.905611 -0.7543556 -0.1109974 -0.6470142 -0.7488767 -0.03316897 -0.6618788 -0.5741586 -0.005558133 -0.8187253 -0.8728248 0.01299118 -0.4878608 -0.866621 0.2558089 -0.428404 -0.8053589 0.2103677 -0.5542044 -0.3471049 0.09423446 -0.93308 -0.4044654 0.1215315 -0.9064424 -0.7846884 0.4139301 -0.4614393 -0.7532368 0.4107583 -0.5137237 -0.5272071 0.2845174 -0.8006888 -0.6887618 0.5965828 -0.4119422 -0.2833355 0.2401382 -0.928469 -0.5596894 0.5614649 -0.6095122 -0.1540404 0.1505491 -0.9765279 -0.5319482 0.6996228 -0.4770317 -0.5241235 0.6745066 -0.519938 -0.4480221 0.8480488 -0.2830007 -0.2644968 0.4324132 -0.8620095 -0.3843703 0.821168 -0.4218325 -0.2238731 0.5445353 -0.8083082 -0.2105509 0.461408 -0.8618417 -0.2396975 0.8946923 -0.376923 -0.1840844 0.815335 -0.5489461 -0.16193 0.6336005 -0.7565243 -0.08070647 0.9113482 -0.4036472 -0.03972119 0.4019233 -0.9148114 0.009558379 0.5220819 -0.8528418 0.01812368 0.8041782 -0.5941118 0.1032945 0.9096771 -0.4022659 0.06728887 0.4097601 -0.9097082 0.2002707 0.8472914 -0.4919238 0.20559 0.7772638 -0.5946376 0.06307786 0.2289198 -0.9713994 0.3056592 0.6831341 -0.6632498 0.3055719 0.640632 -0.7044263 0.4071127 0.6116756 -0.6783157 0.4027519 0.48029 -0.7791741 0.4836575 0.49793 -0.7198203 0.525008 0.4135355 -0.7438784 0.7667387 0.4860311 -0.4193872 0.8067185 0.3193099 -0.4972389 0.282692 0.1444128 -0.9482775 0.7616394 0.2737607 -0.5873335 0.105278 0.04555213 -0.993399 0.6782172 0.237157 -0.6955415 0.9251108 0.1709485 -0.3390377 0.739462 0.04238432 -0.6718629 0.6045287 0.0508638 -0.7949578 0.8135408 1.39433e-4 -0.5815079 0.5986809 0.04996472 -0.7994278 0.3001537 -0.03262585 -0.9533327 0.7179083 -0.1485233 -0.6801092 0.7553487 -0.1798818 -0.6301516 0.7383021 -0.2015826 -0.6436416 0.6631731 -0.2894142 -0.6902469 0.07848602 -0.04284018 -0.9959943 0.6079439 -0.2908996 -0.7387704 0.6576672 -0.4917912 -0.5706271 0.5692196 -0.4032332 -0.7165139 0.4492632 -0.3576304 -0.818696 0.6482328 -0.6860533 -0.3303412 0.4590641 -0.5875651 -0.666354 0.3897825 -0.4814259 -0.785047 0.4587964 -0.7441648 -0.4855149 0.2222478 -0.3338366 -0.9160563 0.368744 -0.7641496 -0.5292479 0.2679285 -0.6404773 -0.7197244 0.1489673 -0.590766 -0.7929719 0.1403849 -0.752114 -0.6439073 0.03181421 -0.2279791 -0.9731461 0.03721398 -0.8810223 -0.4716088 -0.07730424 -0.8161092 -0.572704 -0.07655143 -0.6708742 -0.7376095 -0.1301038 -0.9044241 -0.4063127 -0.3001103 -0.8807373 -0.3663819 -0.141483 -0.4587801 -0.8772135 -0.3096852 -0.663236 -0.6813319 -0.3174905 -0.6781752 -0.6627807 -0.420799 -0.747803 -0.5135356 -0.5687506 -0.633579 -0.5245003 -0.2216072 -0.2616676 -0.9393724 -0.5549165 -0.5964599 -0.5799166 -0.1724392 -0.1861932 -0.9672626 -0.1187054 0.9926049 -0.02539205 -0.1180192 0.9926695 -0.02605438 0.7969579 0.6037024 -0.02004051 0.8006729 0.598531 -0.02614903 0.9191592 -0.3933818 -0.01992577 0.918732 -0.3943257 -0.02094697 0.9997941 -0.0096125 -0.01786839 0.990107 0.0109167 -0.1398898 0.9746162 -0.01241368 -0.223538 0.9346697 0.01090317 -0.3553501 0.9003565 -0.008384943 -0.4350723 0.8584392 0.007068514 -0.5128667 0.8061609 -0.009574234 -0.591619 0.750658 0.009579658 -0.6606215 0.6606715 -0.006367802 -0.7506482 0.6385806 0.001532673 -0.7695534 0.5267488 -0.001549661 -0.8500196 0.5019171 0.006362617 -0.8648924 0.386879 -0.009645104 -0.92208 0.2884529 0.01329791 -0.9574018 0.1970916 -0.01243567 -0.9803062 0.051059 0.01260733 -0.9986161 -0.03422617 -0.01104491 -0.9993532 -0.1568866 0.009619235 -0.9875698 -0.2321727 -0.007809281 -0.9726433 -0.3329834 0.004797756 -0.9429206 -0.3974059 -0.007114708 -0.9176154 -0.4551401 0.006932318 -0.8903928 -0.597809 -0.00650376 -0.8016123 -0.6101171 -1.29522e-4 -0.7923114 -0.7550079 0.003620564 -0.6557057 -0.7668988 -0.003265142 -0.6417598 -0.8628889 2.82981e-4 -0.5053936 -0.8699589 0.004778921 -0.493101 -0.9285626 -0.005697727 -0.3711321 -0.9501221 0.008107066 -0.311773 -0.975267 -0.008175432 -0.2208792 -0.9908494 0.006799638 -0.1348009 -0.9996902 -0.007056117 -0.02386784 -0.9999993 1.69397e-4 -0.001183688 -0.9835499 0.003603994 0.1806007 -0.979902 -0.003545522 0.1994484 -0.9302645 7.68541e-4 0.3668888 -0.934667 -0.003726065 0.3555048 -0.8787719 0.006033539 0.4772039 -0.8438016 -0.009612917 0.5365694 -0.7719033 0.01091617 0.6356464 -0.7262454 -0.008009612 0.6873889 -0.6122832 -0.00103259 0.790638 -0.6024694 0.004106938 0.7981315 -0.4650788 0.003400862 0.8852629 -0.4473561 -0.003082752 0.8943506 -0.3007187 2.82242e-4 0.9537129 -0.2879979 0.004500925 0.9576205 -0.1552038 -0.005578994 0.9878667 -0.09251588 0.008449196 0.9956754 0.001668572 -0.008150219 0.9999655 0.1074677 0.009619355 0.994162 0.1991671 -0.01145523 0.9798986 0.3023214 0.0115928 0.9531356 0.4197262 -0.01091217 0.9075852 0.477034 0.006158053 0.8788633 0.608164 0.001532435 0.7938099 0.591768 -0.004034638 0.8060984 0.719691 -0.003483474 0.6942858 0.7226518 -0.001906514 0.6912097 0.8151024 0.007313609 0.5792707 0.8580639 -0.01015412 0.5134426 0.8958466 0.007384538 0.444302 0.943019 -0.006784558 0.3326699 0.9623747 0.007946431 0.2716099 0.9850584 -0.008733272 0.1719988 0.9975851 0.01005631 0.06872379 0.2285089 0.973502 0.008811652 0.2507489 0.9673982 -0.03557807 0.2200992 0.9719353 -0.08305448 0.2337014 0.969167 -0.07809585 0.1940017 0.97219 -0.1311868 0.20939 0.9697275 -0.1256365 0.1868962 0.9685628 -0.1641828 0.1533924 0.9708096 -0.1843897 0.1384386 0.9731363 -0.1839577 0.1249009 0.9682891 -0.21637 0.06372034 0.9719041 -0.226588 0.07038569 0.9703617 -0.2311799 -0.01655584 0.9731717 -0.2294838 0.01212334 0.968338 -0.2493484 -0.03898924 0.9686336 -0.2454155 -0.08366209 0.9679136 -0.2369472 -0.1067484 0.9721137 -0.2088056 -0.1084739 0.9734204 -0.2017083 -0.1538689 0.9676753 -0.1998224 -0.1824347 0.9703682 -0.1584405 -0.1806128 0.9731534 -0.1426585 -0.2194069 0.9676753 -0.1243594 -0.2297065 0.9703749 -0.07488411 -0.2242957 0.9723385 -0.06518769 -0.2449989 0.9689282 -0.03396731 -0.2299321 0.9731329 0.01198285 -0.2406262 0.9706179 -2.768e-4 -0.2476875 0.9677492 0.04596132 -0.2299527 0.9693244 0.08678734 -0.2029626 0.9737768 0.1027871 -0.2060318 0.972127 0.1118935 -0.197744 0.9666011 0.1630327 -0.142729 0.9726305 0.1833534 -0.1602131 0.9690994 0.1875589 -0.09275007 0.9728175 0.2121878 -0.1131626 0.9697266 0.2163902 -0.07210123 0.9677489 0.2413783 -0.02317917 0.9693775 0.2444792 -0.004772782 0.9734911 0.2286751 0.02683913 0.9683156 0.2482836 0.08204054 0.973158 0.2150184 0.07353305 0.9699716 0.2318362 0.1184402 0.9685857 0.2186632 0.1482735 0.9697274 0.1940205 0.1542449 0.9730949 0.1711576 0.1746553 0.9701778 0.1680798 0.2002559 0.9692993 0.1426761 0.2036002 0.9730809 0.1079847 0.2129269 0.9713521 0.1055334 0.2476534 0.9663707 0.06924957 0.2370981 0.9713441 0.01659011 -2.86164e-6 1 -2.44857e-6 -9.81669e-6 1 -2.65989e-6 -4.63225e-5 1 1.70483e-6 1.11677e-4 1 -4.33739e-5 1.30625e-5 1 -8.99331e-5 -1.03117e-4 1 1.75887e-4 1.12694e-4 1 -6.89071e-5 -9.57934e-7 1 -2.79595e-7 1.42194e-5 1 5.96541e-5 3.61799e-6 1 -1.01156e-6 1.52369e-5 1 -1.35218e-6 2.98384e-6 1 0 -1.51357e-4 1 -3.0917e-5 -2.38926e-5 1 2.76725e-6 2.65757e-5 1 3.60604e-7 0 1 -2.11026e-6 0 1 -4.3362e-6 0 1 2.30238e-5 0 1 -8.58142e-6 0 1 -8.4569e-6 0 1 4.24371e-6 0 1 5.79707e-6 0 1 -8.64348e-6 0 1 2.23158e-6 0 1 -5.32786e-6 0 1 6.01902e-6 0 1 2.33961e-6 0 1 -4.20176e-6 0 1 1.06213e-5 0 1 4.83009e-6 0 1 -9.27201e-6 0 1 3.57934e-6 0 1 -9.33032e-6 0 1 4.08851e-6 0 1 2.46062e-6 0 1 -3.71691e-6 0 1 -2.08498e-6 0 1 4.25884e-6 0 1 -2.91572e-6 0 1 5.66255e-6 0 1 -5.776e-6 0 1 2.27777e-6 0 1 -1.19743e-5 0 1 -4.82459e-6 0 1 4.79222e-6 0 1 4.568e-6 0 1 -1.03156e-5 0 1 5.1465e-6 0 1 -9.40503e-6 0.9970053 -0.002679586 -0.07728809 0.9953789 0.002381563 -0.0959962 0.9650219 -0.002829492 -0.2621545 0.9606845 0.002820074 -0.277628 0.8939431 -0.002829432 -0.4481717 0.8906322 -2.4878e-4 -0.4547244 0.7979331 0.002995252 -0.6027386 0.787414 -0.003325402 -0.6164157 0.6496663 -9.82325e-5 -0.7602196 0.6502417 -4.00553e-4 -0.7597274 0.5085667 0.002839028 -0.8610179 0.4861385 -0.005371809 -0.8738653 0.3521545 0.004205942 -0.9359325 0.3033474 -0.007003247 -0.9528544 0.2248041 0.006477892 -0.9743825 0.1085267 -0.008447647 -0.9940577 0.04279285 0.008437812 -0.9990484 -0.09060013 -0.008446991 -0.9958516 -0.1473895 0.006203532 -0.9890592 -0.2861326 -0.004758 -0.9581783 -0.3172198 0.005197346 -0.9483378 -0.47031 -0.008062601 -0.8824645 -0.5130634 0.006824851 -0.8583236 -0.6372575 -0.004897177 -0.7706354 -0.6525231 0.001441597 -0.7577676 -0.781391 -0.004805505 -0.6240233 -0.7697635 5.77352e-4 -0.6383291 -0.8513992 0.005925893 -0.524485 -0.8787124 -0.005647003 -0.4773184 -0.934459 0.003349363 -0.3560552 -0.9302626 -8.77882e-4 -0.3668932 -0.9781493 0.004226267 -0.2078613 -0.983521 -0.004223406 -0.1807448 -0.9998419 0.001395225 -0.0177266 -0.9995898 -0.002643108 -0.0285207 -0.9914872 0.005780041 0.1300768 -0.9855337 -0.005428731 0.1693936 -0.9487128 0.001814126 0.3161343 -0.9497528 7.09577e-4 0.3130005 -0.8809044 -0.004325449 0.4732746 -0.8882277 7.09689e-4 0.4594032 -0.7590478 -0.008132576 0.6509841 -0.7910876 0.005814194 0.6116754 -0.6711891 0.009274661 0.7412282 -0.6226847 -0.007057487 0.7824412 -0.5128121 -0.001492261 0.8584996 -0.4832456 0.008575022 0.8754428 -0.3695587 -0.008395969 0.9291695 -0.2915638 0.01137512 0.9564839 -0.1630158 -0.01201725 0.9865503 -0.06544017 0.01119881 0.9977937 0.02593338 -0.006631612 0.9996418 0.1279034 0.003898918 0.991779 0.1589915 -0.002302348 0.9872773 0.2652487 0.003821909 0.9641726 0.2925382 -0.002728939 0.95625 0.416072 -7.78886e-4 0.9093313 0.4165741 -5.93847e-4 0.9091016 0.5376552 0.006008863 0.8431434 0.5882993 -0.008658707 0.808597 0.678242 0.00803405 0.7347947 0.7175883 -0.005103826 0.6964489 0.8104842 0.001814126 0.5857578 0.8085463 7.09461e-4 0.5884323 0.8915047 7.1004e-4 0.4530111 0.8962255 -0.002672374 0.443591 0.9629077 0.003069758 0.2698137 0.9650257 -9.72945e-5 0.2621555 0.997004 -0.003140926 0.07728725 0.9984892 0.003638803 0.05483067 0.2331709 -0.9719578 -0.03048783 0.2429291 -0.9698668 -0.01854538 0.2410815 -0.9682927 -0.06549155 0.2142805 -0.9708465 -0.1074287 0.2032977 -0.9727309 -0.1116446 0.1989431 -0.9675577 -0.1557365 0.1603769 -0.969051 -0.1876688 0.1266911 -0.9740096 -0.1877629 0.1184459 -0.9698646 -0.2129163 0.07699042 -0.9672577 -0.2418372 0.02529907 -0.9724499 -0.2317355 0.02176016 -0.9732733 -0.2286167 -0.02289044 -0.9675574 -0.251612 -0.07063591 -0.9690515 -0.2365367 -0.08116936 -0.9720305 -0.2203823 -0.1163012 -0.9689449 -0.2182201 -0.1433475 -0.9717684 -0.1873971 -0.155855 -0.9697058 -0.1880955 -0.1976861 -0.967342 -0.1586499 -0.2055246 -0.9723252 -0.1111016 -0.2029673 -0.9739547 -0.1010776 -0.2277531 -0.9698762 -0.08642214 -0.2502991 -0.9670226 -0.04709237 -0.2409594 -0.97053 -0.003188312 -0.2282443 -0.9735464 0.0105834 -0.2430074 -0.9691253 0.04175639 -0.2362359 -0.9685589 0.0780152 -0.2058628 -0.9725249 0.1087006 -0.2069313 -0.9719296 0.1119489 -0.1938416 -0.9669321 0.1657339 -0.1358255 -0.9728248 0.1875187 -0.1494093 -0.9707544 0.1879168 -0.12525 -0.9700858 0.2079567 -0.09118598 -0.968475 0.231822 -0.05484622 -0.9725137 0.2262942 -0.04053026 -0.969205 0.2428972 0.006536543 -0.9688003 0.2477567 0.03056287 -0.9707397 0.2381815 0.03632265 -0.9722396 0.2311513 0.09728193 -0.971242 0.2173139 0.07255202 -0.9694009 0.2345172 0.1003521 -0.970758 0.2180791 0.1470565 -0.9680156 0.2032744 0.1649391 -0.9719112 0.1678801 0.1726747 -0.9707766 0.1666624 0.2001795 -0.9688955 0.1454984 0.2115451 -0.9712008 0.1096258 0.2168564 -0.9703195 0.1070201 0.2319619 -0.9718199 0.04195046 0.2387349 -0.9689167 0.06485396 0.2463765 -0.9689916 0.01881283 -6.33087e-5 -1 -8.96052e-5 1.5908e-6 -1 5.54811e-6 -2.5612e-5 -1 8.07355e-5 1.14047e-5 -1 1.99031e-5 1.80145e-5 -1 -4.83869e-6 8.89571e-6 -1 -3.52424e-5 -3.92731e-5 -1 5.59799e-5 2.62695e-6 -1 3.04227e-6 1.34816e-6 -1 4.28085e-5 -1.50864e-4 -1 -2.66049e-4 -5.86866e-6 -1 -1.36679e-5 7.10452e-6 -1 4.19764e-6 1.66438e-5 -1 -1.29688e-5 3.58106e-6 -1 2.06676e-5 -0.9621381 -0.1919202 -0.1935378 -0.865446 0.1346782 -0.4825609 -0.7406322 -0.1005162 -0.6643496 -0.5382884 0.1147323 -0.8349146 -0.2807036 -0.1832876 -0.9421312 -0.03304201 0.1665306 -0.9854825 0.4528191 -0.1347967 -0.881354 0.368801 0.1132399 -0.9225848 0.7340132 -0.1123638 -0.6697754 0.8623307 0.1317616 -0.4889017 0.9642263 -0.1492002 -0.2191051 0.9856735 0.1684077 0.00931096 0.8736242 -0.1912071 0.4474601 0.8024476 0.1112989 0.5862513 0.4107435 -0.05020952 0.9103675 0.3868647 -0.09881043 0.9168274 -0.02553325 0.1255356 0.9917606 -0.2194768 -0.1397227 0.9655608 -0.5806562 0.1472048 0.8007305 -0.6424255 0.01202476 0.7662538 -0.9054146 -0.1461143 0.3985916 -0.9524673 0.2500864 0.1739622 -0.9948025 -0.08352172 0.05824214 -0.8997157 0.04517567 0.4341323 -0.9118234 -0.1292002 0.3897247 -0.7170131 0.1689819 0.6762673 -0.5863909 -0.1902343 0.7873734 -0.4009586 0.128054 0.9071022 -0.2361051 -0.131837 0.9627426 -0.07699406 0.1326292 0.9881708 0.1723639 -0.1285598 0.976608 0.2825351 0.106914 0.9532803 0.5404877 -0.1349806 0.8304538 0.6258631 0.1645988 0.7623664 0.8709013 -0.1668353 0.4622738 0.9164249 0.1015106 0.3871189 0.997356 -0.07011419 0.01910966 0.9999299 0.01044428 -0.005595803 0.8997114 0.01043212 -0.4363607 0.8705323 -0.141983 -0.4711843 0.6580731 0.1684016 -0.7338806 0.4682634 -0.2062968 -0.8591688 0.4026716 0.03048235 -0.9148369 -0.03251171 -0.07598394 -0.9965789 -0.008316755 0.001529693 -0.9999642 -0.3642282 0.09916609 -0.9260151 -0.4544388 -0.1716997 -0.8740736 -0.7084175 0.159419 -0.6875538 -0.8032378 -0.1151181 -0.5844288 -0.9015259 0.09690582 -0.4217351 -0.9470494 -0.1144908 -0.2999822 -0.9898619 0.1393799 -0.02733021 0 -1 -6.43077e-6 0 -1 5.5936e-6 0 -1 -2.93648e-6 0 -1 -4.27448e-7 0 -1 2.88177e-6 0 -1 1.43547e-5 0 -1 -4.89619e-6 0 -1 9.33714e-6 0 -1 1.12224e-5 0 -1 -1.11321e-5 0 -1 -3.26833e-6 0 -1 -2.80281e-6 0 -1 4.69037e-6 0 -1 5.38181e-6 0 1 7.75311e-6 0 1 2.91489e-6 0 1 -6.9542e-6 0 1 -3.46235e-6 0 1 -2.62219e-6 0 1 5.8576e-6 0 1 6.88517e-6 0 1 -7.08461e-6 0 1 7.16779e-6 0 1 -2.0224e-6 0 1 3.33713e-6 0 1 1.36049e-5 0 1 -6.3207e-6 0.02834957 -0.9988473 -0.03873693 0.04201889 -0.9989725 -0.01698559 -0.005558133 -0.9999207 -0.01131319 0.01422333 -0.9998705 0.007542967 0.007155418 -0.9999733 -0.001514971 -1.01851e-5 -0.9999971 -0.00238198 -8.13365e-4 -0.9999994 -8.3842e-4 0.009154856 -0.9999544 -0.002753615 -4.33573e-4 -0.9999999 -2.92123e-4 0.01759648 -0.9998257 0.006235539 -4.6295e-4 -0.9998681 -0.01623606 0.04825294 -0.9988099 0.007104635 0.08360719 -0.9875508 0.1332415 0.02784591 -0.991513 0.1269912 -0.01001507 -0.9104147 0.4135758 0.2575252 -0.6943544 0.6719768 0.2705616 -0.8805016 0.3892472 0.4554271 -0.7536906 0.4738531 0.4794922 -0.8630454 0.1588709 0.4637975 -0.8748251 0.1399033 0.6504809 -0.7595214 -0.001395225 0.5545802 -0.825314 -0.1062912 0.5979875 -0.7608566 -0.2520083 0.3650288 -0.8707137 -0.3295632 0.3811517 -0.8387119 -0.3889545 0.1604576 -0.8438003 -0.512108 0.06701737 -0.9088774 -0.4116438 -0.09854465 -0.7976431 -0.5950248 -0.2541466 -0.8537138 -0.4545133 -0.2753713 -0.8375809 -0.4718357 -0.4732236 -0.7915377 -0.3866879 -0.4377776 -0.8755894 -0.204191 -0.588605 -0.7917371 -0.1633916 -0.5056345 -0.8608204 0.05763769 -0.5740987 -0.8127805 0.09898847 -0.4585863 -0.83415 0.3064188 -0.3163467 -0.90009 0.2996045 -0.3091959 -0.8180641 0.4849423 -0.1542967 -0.8305306 0.5351743 -0.1576067 -0.862764 0.4804148 0.08391934 -0.7877971 0.6101912 0.06033724 -0.7536277 0.6545264 0.4197445 -0.7724442 0.4765968 0.2715714 -0.887515 0.3722448 0.5536047 -0.7612952 0.3375673 0.5298884 -0.8045625 0.2681372 0.6700254 -0.7375103 0.08452624 0.5781039 -0.8149112 -0.04142129 0.6292381 -0.7669543 -0.1258592 0.5200009 -0.8157128 -0.2534003 0.5468329 -0.7623592 -0.3460959 0.3908338 -0.773753 -0.4985533 0.3812923 -0.8078482 -0.4494414 0.2062667 -0.7515394 -0.6266121 0.1186387 -0.8080724 -0.577013 -0.07998102 -0.7078878 -0.7017819 -0.1855496 -0.8272385 -0.5303281 -0.3962552 -0.7363402 -0.5484386 -0.4134364 -0.847706 -0.332363 -0.5296006 -0.7868648 -0.3168079 -0.5253714 -0.8418136 -0.1238336 -0.540283 -0.8300915 -0.1379941 -0.6343579 -0.7628644 0.125012 -0.52749 -0.8266423 0.1960018 -0.5658282 -0.7405205 0.362585 -0.4386072 -0.764107 0.4730372 -0.3679462 -0.8130087 0.4512565 -0.1750396 -0.7926252 0.5840434 -0.04555714 -0.8607637 0.5069621 0.02297562 -0.7852903 0.6187014 0.2311597 -0.8413726 0.4885256 0.2652371 -0.814679 0.515701 0.6021987 -0.7265263 0.3309327 0.3791192 -0.8841873 0.2729131 0.6210566 -0.7524785 0.2192369 0.4854354 -0.8728005 -0.05071365 0.5131331 -0.8575073 -0.03709143 0.5603574 -0.7873651 -0.2570138 0.3797783 -0.8551134 -0.3529157 0.3902991 -0.8495417 -0.3548881 0.2932001 -0.7999269 -0.5235939 0.1122809 -0.8767905 -0.4675804 0.07481992 -0.8134447 -0.5768102 -0.1331965 -0.8225244 -0.5529127 -0.1426835 -0.8353449 -0.5308865 -0.3516915 -0.7427976 -0.569706 -0.4658992 -0.7848575 -0.4085788 -0.4551602 -0.8095324 -0.3707919 -0.6487637 -0.7495238 -0.1316047 -0.5414042 -0.8271077 -0.1509119 -0.6593341 -0.7479655 0.07632952 -0.5638505 -0.8123586 0.1488154 -0.5943593 -0.7342048 0.3281469 -0.4147728 -0.8173413 0.3998962 -0.4208357 -0.7763343 0.4692574 -0.0896427 -0.8503221 0.5185717 -0.1783626 -0.7925302 0.5831661 0.02728891 -0.7835084 0.6207817 0.1884945 -0.8832582 0.4293308 0.2870841 -0.805435 0.5185146 0.5109755 -0.7826454 0.355486 0.5267713 -0.7569511 0.3867001 0.6121958 -0.7885262 0.0586766 0.5141441 -0.8572655 -0.02742099 0.5905207 -0.7906588 -0.1616917 0.4780372 -0.8295958 -0.2885329 0.4120986 -0.8652185 -0.2856078 0.3241198 -0.824992 -0.4629631 0.2110393 -0.8797351 -0.4260618 0.1568935 -0.7793719 -0.6066003 -0.06192052 -0.8312599 -0.5524246 -0.1045514 -0.8796419 -0.4640036 -0.2988402 -0.7754045 -0.5562757 -0.3600395 -0.8559061 -0.3712093 -0.4507236 -0.8039733 -0.3879114 -0.5846157 -0.8036109 -0.1115088 -0.7014612 -0.7093271 -0.06933456 -0.510609 -0.8489155 0.1364585 -0.5697334 -0.7747309 0.2742187 -0.3574599 -0.8873128 0.2913736 -0.349729 -0.7416529 0.5723991 -0.09509831 -0.8880124 0.4498783 -0.04201829 -0.8065397 0.5896849 0.2182068 -0.8433757 0.4910227 0.2151203 -0.8230293 0.5256863 0.4567963 -0.7996134 0.3898148 0.415856 -0.8783493 0.2357252 0.5750653 -0.793215 0.2002747 0.4731175 -0.8779685 -0.07301503 0.5541203 -0.8242367 -0.1165531 0.5025452 -0.7899383 -0.3513488 0.4007413 -0.8451672 -0.3536933 0.3738663 -0.7312912 -0.5704709 0.08127397 -0.845611 -0.5275762 0.05271071 -0.7877931 -0.6136804 -0.1926158 -0.870793 -0.4523482 -0.3005456 -0.7827281 -0.5449855 -0.3767659 -0.8579546 -0.3492297 -0.5541135 -0.7512814 -0.3585174 -0.5389121 -0.8410049 -0.04779946 -0.5923141 -0.8003795 -0.09250187 -0.5803496 -0.7938653 0.1815826 -0.4689167 -0.8587411 0.2065935 -0.4667246 -0.7373756 0.4883087 -0.2979773 -0.8247672 0.4805918 -0.236151 -0.7434981 0.6256544 -0.09667897 -0.8018806 0.5896107 0.004426002 -0.7389157 0.6737834 0.174753 -0.8181872 0.5477511 0.2653336 -0.7545509 0.6002093 0.3953548 -0.8103137 0.4325348 0.512129 -0.7309929 0.4509693 0.5616959 -0.803535 0.1970516 0.6177503 -0.733343 0.2838887 0.6025225 -0.7960824 -0.05674028 0.5815905 -0.8122703 -0.04437887 0.4979555 -0.8277117 -0.2587157 0.4471705 -0.8552926 -0.2617504 0.3568401 -0.8097268 -0.4658411 0.3894947 -0.7887605 -0.4755533 0.1516179 -0.7597126 -0.632336 -2.0526e-4 -0.8700215 -0.4930139 -0.1731647 -0.7685582 -0.6158996 -0.1881524 -0.7912154 -0.5818736 -0.4486889 -0.7240377 -0.5238777 -0.4443038 -0.8159359 -0.3699229 -0.5320833 -0.7843403 -0.3189007 -0.5185817 -0.8472284 -0.1152269 -0.6095399 -0.7887053 -0.08003228 -0.6547779 -0.7404329 0.1517404 -0.5907567 -0.7875222 0.1755429 -0.4551185 -0.7894824 0.4118065 -0.3657222 -0.8409299 0.3988536 -0.2533077 -0.8136382 0.5232858 -0.280884 -0.7980844 0.5330718 -0.05488413 -0.7530961 0.6556174 0.07743996 -0.8699597 0.4870042 0.2757083 -0.760923 0.5873512 0.3015033 -0.8677957 0.395002 0.5166859 -0.7561008 0.4016807 0.5764003 -0.8075916 0.1247336 0.5564149 -0.8211726 0.1268 0.5633814 -0.7987498 -0.2111876 0.4764013 -0.852146 -0.2165387 0.3284764 -0.8288881 -0.4528222 0.3318194 -0.8210151 -0.4645753 0.1277146 -0.8119264 -0.5696179 0.2180924 -0.7224945 -0.6560774 -0.1122415 -0.7908584 -0.6016186 -0.148871 -0.8275669 -0.5412676 -0.321371 -0.7408506 -0.5897975 -0.3908052 -0.8037912 -0.4485434 -0.5415556 -0.7226872 -0.4294657 -0.5183949 -0.8431324 -0.1428096 -0.5281516 -0.8373405 -0.1411272 -0.5753965 -0.8129726 0.0894128 -0.4605008 -0.8735706 0.1575227 -0.5158571 -0.822263 0.2403646 -0.3948488 -0.8237703 0.4068132 -0.3342545 -0.8549807 0.3965879 -0.2550094 -0.7328769 0.6307628 -0.01394593 -0.828548 0.5597444 -0.006430506 -0.8169551 0.5766655 0.2026519 -0.7725677 0.6017239 0.2916799 -0.883941 0.365474 0.3172173 -0.868938 0.3798949 0.5435441 -0.7659692 0.3432946 0.4838531 -0.8561145 0.1815327 0.6852416 -0.7275771 0.03279751 0.4838074 -0.8570466 -0.1772049 0.6088025 -0.7289097 -0.3131297 0.2752954 -0.8719657 -0.4048314 0.2901999 -0.8068293 -0.5145976 0.1082124 -0.8691396 -0.4825834 -0.02519375 -0.7343563 -0.6782965 -0.1978185 -0.8213541 -0.5350189 -0.3373929 -0.7181741 -0.6085984 -0.4636452 -0.8058872 -0.3682109 -0.5559697 -0.7431478 -0.3723293 -0.5187186 -0.8502991 -0.08900928 -0.456221 -0.8888283 -0.04297322 -0.6323704 -0.7542842 0.1765308 -0.3744508 -0.8726136 0.3135799 -0.4548252 -0.8289116 0.3256373 -0.3361845 -0.7378539 0.5852792 -0.1762026 -0.8275506 0.5330224 -0.08370995 -0.7527617 0.6529492 0.1579099 -0.8452589 0.5104919 0.1382977 -0.8138824 0.5643308 0.3726124 -0.7849632 0.4949676 0.3632183 -0.8879898 0.28204 0.5580056 -0.7768342 0.2918193 0.5631589 -0.8220142 0.08452743 0.4748008 -0.879922 0.01736444 0.6576896 -0.7095843 -0.252853 0.4326385 -0.8305495 -0.35073 0.4376859 -0.774896 -0.4560343 0.233097 -0.8535287 -0.4659985 0.2260974 -0.7925891 -0.5662884 -0.1006953 -0.6861397 -0.7204672 0.02943789 -0.8593308 -0.5105724 -0.2528563 -0.8525774 -0.4573573 -0.2530967 -0.8437504 -0.4733152 -0.5127989 -0.805233 -0.2977201 -0.4386842 -0.8797069 -0.1834992 -0.6209475 -0.7835824 -0.02056705 -0.4679453 -0.8773342 0.1063571 -0.5603552 -0.7974252 0.2238638 -0.3803094 -0.8563938 0.34922 -0.4079339 -0.8032472 0.4340323 -0.2516265 -0.7487028 0.6132931 -0.08832883 -0.8397721 0.5357061 0.05966973 -0.8088637 0.5849608 0.04623025 -0.8305616 0.5550048 0.3329724 -0.8338729 0.4402107 0.3029009 -0.855436 0.4200956 0.5045249 -0.7942491 0.3385602 0.4965836 -0.8115206 0.3079599 0.6522189 -0.740555 0.1618297 0.4825286 -0.8723852 -0.07816845 0.5796917 -0.8018818 -0.1447175 0.472257 -0.8034971 -0.3624441 0.3239914 -0.8801673 -0.3468936 0.3156864 -0.8032569 -0.5050945 0.1093807 -0.8105257 -0.5753992 0.07808279 -0.841719 -0.53424 -0.271389 -0.7310491 -0.6260314 -0.2354181 -0.7708652 -0.5918997 -0.3680236 -0.8582813 -0.3576476 -0.4251374 -0.8233901 -0.3758818 -0.5500909 -0.8061686 -0.2179273 -0.4611582 -0.8846056 -0.0693258 -0.6159569 -0.7870521 0.03385674 -0.55122 -0.8276748 0.1054085 -0.6040607 -0.7483191 0.2740973 -0.4186398 -0.8256008 0.3783174 -0.4304643 -0.7750492 0.4626005 -0.2430065 -0.7876901 0.5661204 -0.2653296 -0.771636 0.5780816 0.05599606 -0.7742699 0.6303734 0.02382349 -0.8321841 0.5539876 0.2882912 -0.8254101 0.4853725 0.3114683 -0.8072181 0.5013846 0.5852189 -0.7399662 0.3316156 0.4394645 -0.841305 0.314765 0.6356099 -0.7471547 0.1943195 0.5273538 -0.8490043 -0.03301292 0.638131 -0.7583571 -0.1329795 0.4962344 -0.8413292 -0.2142816 0.5342841 -0.7517966 -0.3864483 0.332888 -0.8260009 -0.4548717 0.3138726 -0.7659488 -0.5610763 0.1270732 -0.7939116 -0.5946064 0.1131955 -0.7652162 -0.6337438 -0.2318931 -0.687098 -0.6885652 -0.1134006 -0.8137606 -0.5700298 -0.2368821 -0.8390237 -0.4898226 -0.3865406 -0.7442536 -0.5446769 -0.5011138 -0.8058541 -0.315411 -0.4598582 -0.8583231 -0.2276228 -0.6122357 -0.7885109 -0.0584656 -0.5939114 -0.8035874 -0.03894299 -0.6640822 -0.7342079 0.1411868 -0.4961301 -0.8272768 0.2635681 -0.5333737 -0.7578312 0.3757721 -0.3254899 -0.7859919 0.525617 -0.2148846 -0.8551772 0.4716957 -0.08164906 -0.7785102 0.6222985 0.1128389 -0.8810012 0.4594611 0.08918088 -0.8421514 0.5318156 0.3234527 -0.8168263 0.4776749 0.3205902 -0.7874736 0.5264098 0.5168423 -0.7637673 0.3866959 0.4725492 -0.8690088 0.1467003 0.6122477 -0.7803446 0.127339 0.580763 -0.8048526 -0.1221755 0.3976659 -0.9004042 -0.176449 0.4839593 -0.7703863 -0.4150766 0.2859976 -0.8601738 -0.4222635 0.2530448 -0.7829379 -0.5683104 0.06431436 -0.8789047 -0.4726418 -0.07657873 -0.7578826 -0.647881 -0.2047488 -0.88659 -0.4147725 -0.351648 -0.7914042 -0.5000231 -0.4759031 -0.8320624 -0.284936 -0.4688631 -0.8401358 -0.2726523 -0.7426134 -0.6693342 0.0227403 -0.5687676 -0.8212701 -0.04493248 -0.6483194 -0.6848325 0.332696 -0.5458026 -0.8087635 0.2190918 -0.4377747 -0.8143362 0.3810641 -0.3004298 -0.8826387 0.3615122 -0.2633232 -0.770013 0.5811549 0.007833123 -0.8812015 0.4726762 0.01356124 -0.8726183 0.4882146 0.2250783 -0.7599624 0.6097515 0.3524041 -0.8482407 0.3953468 0.3539747 -0.8438187 0.4033262 0.6009765 -0.742376 0.2961508 0.5129278 -0.8568179 0.05261349 0.5524756 -0.8327867 0.0351718 0.5183449 -0.8302466 -0.2049615 0.6075331 -0.7721381 -0.1862967 0.4379512 -0.7661757 -0.4702911 0.4242165 -0.8013702 -0.4217181 0.2586712 -0.7686494 -0.5850361 0.1831535 -0.8168236 -0.5470412 -0.1012287 -0.7207114 -0.6858045 -0.04000306 -0.822536 -0.5673044 -0.3508781 -0.7398442 -0.5740342 -0.3604004 -0.8025694 -0.4753882 -0.5433669 -0.7506873 -0.3757941 -0.519967 -0.8291054 -0.2054716 -0.6173546 -0.7705634 -0.1584469 -0.5082625 -0.8584827 0.06838876 -0.4839399 -0.8716638 0.07748848 -0.5305913 -0.7769586 0.338834 -0.3210593 -0.8781546 0.3546343 -0.3384035 -0.8108908 0.4774297 -0.1344 -0.8304319 0.5406659 -0.04726541 -0.8879801 0.4574465 0.09658575 -0.7807579 0.6173236 0.2826335 -0.8659707 0.4125688 0.2948771 -0.7894586 0.5383332 0.556137 -0.7874044 0.265906 0.4386458 -0.8636221 0.2484891 0.5793459 -0.8100525 0.0904076 0.5340055 -0.8447381 0.03543812 0.6600016 -0.7256743 -0.1944089 0.4795709 -0.8299521 -0.2849408 0.4842888 -0.7709599 -0.4136247 0.2694633 -0.8820311 -0.3865368 0.09872359 -0.2240909 -0.969555 0.1385266 -0.8751469 -0.4636036 -0.04708588 -0.7836779 -0.6193802 -0.1487646 -0.8781471 -0.4546724 -0.3387948 -0.7797637 -0.5264853 -0.3574312 -0.8374332 -0.4134592 -0.6148637 -0.7065091 -0.3504106 -0.5436342 -0.813281 -0.2074511 -0.5849895 -0.8108568 0.01728481 -0.6161963 -0.7867789 0.0357955 -0.561528 -0.7388029 0.3726349 -0.4150035 -0.8825538 0.221068 -0.4154536 -0.7640541 0.4935784 -0.1884194 -0.8428904 0.5040179 -0.1083389 -0.8952804 0.4321295 0.02822124 -0.7893912 0.6132414 0.2346511 -0.8488726 0.4736604 0.18984 -0.8830323 0.4292026 0.4024798 -0.7996614 0.4455916 0.4627984 -0.8480508 0.258123 0.4407507 -0.8602495 0.256339 0.5955142 -0.7963399 0.105857 0.5063852 -0.8622701 0.008030772 0.6409869 -0.7520772 -0.1533488 0.5198529 -0.7934532 -0.3165205 0.5414044 -0.7405331 -0.3981105 0.2736944 -0.8474466 -0.454891 0.2713711 -0.8146371 -0.5125662 0.05455708 -0.8432178 -0.5347965 0.02353084 -0.7851791 -0.6188215 -0.3010565 -0.7501704 -0.5887355 -0.2784442 -0.7705602 -0.5733287 -0.4566121 -0.800238 -0.3887475 -0.4567154 -0.7999987 -0.3891187 -0.637245 -0.7569211 -0.1448772 -0.6104429 -0.7773822 -0.1517775 -0.4924611 -0.8547922 0.1637455 -0.6299256 -0.7694283 0.1057065 -0.5269521 -0.7552319 0.3898032 -0.269787 -0.8826159 0.3849729 -0.2760628 -0.8301988 0.4843132 0.02050578 -0.8468551 0.5314283 0.007402658 -0.8736373 0.4865216 0.2636439 -0.7527186 0.6032468 0.3183414 -0.8891083 0.3288542 0.4573545 -0.8077017 0.3720819 0.5570225 -0.8258623 0.08762127 0.5717508 -0.8159617 0.08548492 0.8604131 -0.4687553 -0.1998943 0.5071989 -0.8268156 -0.2431573 0.3558753 -0.8484138 -0.3918506 0.3623884 -0.8030804 -0.473008 0.1300595 -0.8714158 -0.4729897 0.1084245 -0.8136846 -0.5711055 -0.06169563 -0.8095016 -0.5838672 -0.1488496 -0.8921659 -0.4264785 -0.2788201 -0.8063189 -0.521641 -0.4519544 -0.8034391 -0.3875857 -0.4245497 -0.8695172 -0.2523834 -0.5072188 -0.8269225 -0.2427517 -0.5676685 -0.8228327 -0.02643793 -0.4813961 -0.8759351 0.03155487 -0.5746824 -0.7761244 0.2595598 -0.3597071 -0.8804169 0.3089935 -0.4014531 -0.8071696 0.4327963 -0.2449671 -0.7846747 0.5694532 -0.07179254 -0.880886 0.4678522 -0.03395229 -0.8392056 0.5427534 0.1445146 -0.813117 0.5638762 0.1975909 -0.9037681 0.3796856 0.4304811 -0.7800436 0.4541124 0.4713945 -0.8576877 0.2053272 0.4207488 -0.884554 0.2013324 0.6258215 -0.7769954 0.06801307 0.5011388 -0.8622331 -0.07358175 0.6515361 -0.7031961 -0.2846333 0.3573909 -0.8661089 -0.3494672 0.3656113 -0.7928307 -0.487594 0.2207984 -0.7741557 -0.5932377 0.2122161 -0.780364 -0.5882145 -0.04801768 -0.7640403 -0.6433792 -0.1321896 -0.8561 -0.4996186 -0.3145369 -0.7775261 -0.5445362 -0.3232661 -0.7983868 -0.5080134 -0.5404733 -0.724514 -0.4277479 -0.4589502 -0.8756443 -0.1503731 -0.6289893 -0.7727232 -0.0852732 -0.4853033 -0.8626624 0.1424586 -0.5432143 -0.8295488 0.1294872 -0.4396023 -0.816073 0.3751996 -0.3220731 -0.8779165 0.3543044 -0.2003037 -0.8172491 0.5403538 -0.3172579 -0.7267452 0.6092528 -0.01687806 -0.7731281 0.6340254 0.02519458 -0.8116234 0.5836375 0.2832089 -0.7287867 0.6234282 0.2981762 -0.8912248 0.3417742 0.5253371 -0.7911542 0.3132029 0.3859395 -0.9172211 0.09877282 0.5698365 -0.8214104 0.0239076 0.5999079 -0.7801531 -0.1774027 0.4285848 -0.8781167 -0.2126649 0.4566882 -0.7553064 -0.4700513 0.1995487 -0.8933065 -0.4027205 0.1563039 -0.7688757 -0.6199995 -0.08173614 -0.8550893 -0.5119978 -0.108054 -0.8295926 -0.5478144 -0.3546971 -0.7129014 -0.6049478 -0.37251 -0.8252611 -0.4244767 -0.6016553 -0.7344601 -0.3139736 -0.5498213 -0.8140686 -0.1870536 -0.672923 -0.7390848 -0.03046798 -0.4894827 -0.8641097 0.117138 -0.5978392 -0.7323588 0.3259433 -0.3222041 -0.8812492 0.3458099 -0.329443 -0.7972948 0.5057553 -0.06673228 -0.8954283 0.4401762 -0.01085883 -0.7732835 0.6339676 0.2663409 -0.8113758 0.520319 0.2672493 -0.8810407 0.3903142 0.4683464 -0.7866495 0.4022864 0.5041173 -0.8511464 0.1463411 0.6860263 -0.6453674 0.3359594 0.5223762 -0.8501117 -0.06658267 0.5882827 -0.7995831 -0.1207914 0.4303411 -0.8532105 -0.2946841 0.4368165 -0.8463131 -0.30487 0.323133 -0.7981568 -0.5084594 0.2777651 -0.8261905 -0.4901592 0.1217181 -0.7447912 -0.6561028 -0.04342812 -0.8401368 -0.5406332 -0.1641976 -0.7534794 -0.6366381 -0.2646931 -0.8088672 -0.5250442 -0.4939308 -0.6696256 -0.5546476 -0.4816911 -0.8230079 -0.301051 -0.6602712 -0.7232406 -0.2023983 -0.5542578 -0.8303008 -0.05830007 -0.6710472 -0.7204439 0.1750895 -0.5544324 -0.8012779 0.224852 -0.499533 -0.7456752 0.4409483 -0.3339766 -0.8418667 0.423934 -0.2389662 -0.7443335 0.6235887 -0.00184524 -0.8505717 0.5258559 0.03094327 -0.8001552 0.5989944 0.306079 -0.8450239 0.4384636 0.374136 -0.7905687 0.4847921 0.4647604 -0.8592328 0.2138152 0.5474139 -0.8086692 0.2153887 0.579006 -0.8142744 -0.04134654 0.4476649 -0.8860658 -0.1203474 0.5538936 -0.7958988 -0.2444319 0.3716207 -0.8194051 -0.4364325 0.2858201 -0.8678094 -0.406465 0.1760814 -0.7838968 -0.5954 0.06930917 -0.8517464 -0.5193499 -0.09857648 -0.74628 -0.6582924 -0.2635559 -0.8311647 -0.4895954 -0.2646083 -0.8345271 -0.4832671 -0.4227912 -0.8297095 -0.3644584 -0.3978419 -0.8697179 -0.2920833 -0.6400716 -0.7552062 -0.1413223 -0.4644195 -0.8850709 0.03105235 -0.5926092 -0.7932736 0.1397549 -0.3729436 -0.8621433 0.3429606 -0.4754143 -0.8007414 0.3644096 -0.2821161 -0.7666971 0.576703 -0.2229138 -0.8000653 0.5569607 -0.06304997 -0.7379129 0.6719444 0.09443622 -0.8739396 0.4767718 0.2953639 -0.7822896 0.548437 0.3002857 -0.8317342 0.4669547 0.5842322 -0.723008 0.3686901 0.5084429 -0.8457716 0.1617293 0.6339667 -0.7693151 0.07899731 0.455007 -0.8818796 -0.1235197 0.5334241 -0.8234258 -0.1934654 0.4168886 -0.818539 -0.3952188 0.325895 -0.8632552 -0.3854648 0.2856113 -0.7861643 -0.5480621 0.1856944 -0.83893 -0.5115799 0.02781915 -0.7588095 -0.6507183 -0.1560745 -0.8442165 -0.5127762 -0.184445 -0.8210857 -0.5401836 -0.3730648 -0.807177 -0.45748 -0.3664315 -0.8591481 -0.357201 -0.5369862 -0.7872688 -0.3030741 -0.4895868 -0.8609024 -0.1383902 -0.5581401 -0.8239015 -0.09831649 -0.5192783 -0.8472154 0.1121433 -0.5096744 -0.8526648 0.1148697 -0.4335209 -0.7992173 0.4163069 -0.2845776 -0.8830851 0.3730635 -0.2087572 -0.7572908 0.6188143 0.01828467 -0.8748924 0.4839723 0.04298841 -0.8491124 0.5264601 0.272069 -0.8069683 0.5241954 0.2717423 -0.8049387 0.5274749 0.5746845 -0.744981 0.3387345 0.4735139 -0.8221353 0.3160353 0.5298886 -0.8459835 0.0594142 0.6109144 -0.7910641 0.03164327 0.6436889 -0.7426643 -0.1847006 0.4466308 -0.8438172 -0.297479 0.4905105 -0.7679697 -0.4118522 0.2317188 -0.8504815 -0.472216 0.1664737 -0.8888593 -0.4268674 0.04400557 -0.7898158 -0.6117636 -0.1363188 -0.8398143 -0.5254799 -0.153215 -0.8676158 -0.4730412 -0.3661367 -0.7844339 -0.5006072 -0.3663038 -0.7898629 -0.4918721 -0.5471422 -0.7901504 -0.276221 -0.5905856 -0.7592737 -0.2733355 -0.5483965 -0.8333286 0.0694617 -0.4777413 -0.8775548 0.04075616 -0.6123387 -0.7243155 0.3168728 -0.445498 -0.8314883 0.3319022 -0.3697561 -0.7392855 0.5627944 -0.1508069 -0.853743 0.4983775 -0.05690079 -0.760255 0.6471281 0.09092509 -0.8849166 0.4567881 0.2368918 -0.7970324 0.5555373 0.3328662 -0.843276 0.422002 0.404825 -0.8010544 0.4409406 0.577139 -0.7783877 0.247029 0.5215811 -0.8160058 0.2491741 0.6807843 -0.729964 0.06070727 0.5281981 -0.841927 -0.1102988 0.5903853 -0.7797481 -0.2084184 0.3458428 -0.8916759 -0.2920733 0.4026346 -0.7990069 -0.4466245 0.1867985 -0.8118714 -0.5531467 0.08982318 -0.8805571 -0.4653505 -0.07821124 -0.7948795 -0.6017057 -0.1345306 -0.8469232 -0.5144147 -0.2992964 -0.7606612 -0.5760351 -0.4712781 -0.7894763 -0.3932227 -0.4076035 -0.8309553 -0.3786461 -0.5912407 -0.7751523 -0.2226513 -0.5504773 -0.8165959 -0.1736262 -0.6775161 -0.7339383 0.0480259 -0.5274448 -0.8339661 0.1621811 -0.5748595 -0.742833 0.3431267 -0.298653 -0.8685371 0.3955371 -0.3344978 -0.8482213 0.4106482 -0.159932 -0.8784131 0.4503468 -0.0213834 -0.9317613 0.3624415 -0.0601679 -0.896992 0.4379329 0.1701603 -0.9324508 0.3187175 0.7829225 0.3654997 -0.5034307 0.3541178 -0.3179509 -0.879493 0.2458955 0.5268475 -0.8136137 -0.07312971 -0.3199526 -0.944607 -0.3466712 0.6592563 -0.6672332 -0.4204147 -0.1182892 -0.8995884 -0.8111765 0.3216816 -0.4883788 -0.7905809 -0.52729 -0.3113636 -0.8379416 0.5457592 0.001020312 -0.7145861 -0.6631711 0.222645 -0.6348236 0.6256123 0.4534405 -0.4608842 -0.5688211 0.6811963 -0.3143919 0.5413819 0.7797842 0.06042683 -0.7533365 0.6548534 0.3217771 0.7268707 0.6067278 0.6574379 -0.6837393 0.3166638 -0.667678 -0.05400234 -0.742489 -0.9736974 0.01896238 -0.2270545 -0.2498497 0.6699705 0.6990813 0.1527848 -0.4856549 0.8606953 0.3424625 0.6358309 0.6916925 0.8040993 -0.2150906 0.5542207 0.9578586 -0.2754651 0.08140063 0.8230782 0.5677987 0.01212662 0.7594074 -0.4954892 -0.4216528 0.6948326 0.5092425 -0.5078186 0.361766 -0.5824986 -0.7278879 0.2955961 0.5155456 -0.804261 -0.2527806 -0.3589718 -0.898466 -0.3200269 0.5514851 0.7703551 0.2062017 -0.4065374 0.8900609 0.254514 0.4923756 0.8323396 0.6038382 -0.6669202 0.4365742 0.7593363 0.6300233 0.162724 0.7804535 -0.5200832 -0.3469955 0.8859275 0.1284124 -0.4456937 0.5075771 0.3129149 -0.8027764 0.3181554 -0.5895894 -0.7424025 -0.09066683 0.4920684 -0.8658223 -0.2464029 -0.4287387 -0.8691771 -0.6079259 0.5266733 -0.5941729 -0.7600277 -0.6357178 0.1349843 -0.7123242 0.5425692 0.4452112 -0.447712 -0.7035094 0.5519317 -0.2361865 0.7228569 0.6493796 0.0689845 -0.7571854 0.6495472 0.2271943 0.6431846 0.7312294 0.6376025 -0.5192997 0.5690264 0.7119011 0.4750828 0.5171976 0.8457319 -0.5123976 0.1489511 0.7691708 0.6387986 -0.01768279 0.8276304 -0.4813053 -0.2887445 0.7080917 0.302549 -0.6380205 0.2644914 -0.2952649 -0.9180757 -0.2618024 0.436347 -0.860849 -0.4023174 -0.5750395 -0.7123696 -0.5769711 0.6064386 -0.5471166 -0.922869 -0.3412401 -0.178516 -0.9108439 -0.01056832 0.4126159 0.7901522 -0.6127153 -0.01548421 0.7238801 0.6136021 -0.3154206 0.4043546 -0.7682514 -0.4962731 0.1922567 0.6947244 -0.6931056 -0.260087 -0.6195167 -0.7406442 -0.6913668 0.5418649 0.4779064 -0.3523835 -0.5923222 0.7245552 -0.06839746 0.4650487 0.8826391 0.579427 -0.3079395 0.754611 0.9407956 -0.08077812 0.3292089 0.9282163 -0.09025001 -0.3609288 0.8931477 -0.2955517 -0.3390228 0.5810729 0.4811768 -0.6563713 0.2010488 -0.7895601 -0.5798053 -0.6177282 0.7010732 -0.356242 -0.8538842 -0.5098071 -0.1047781 -0.8186746 0.5459439 0.1780939 -0.7477838 -0.5470327 0.376264 -0.4813426 0.6742258 0.560115 -0.08553642 -0.5426024 0.8356233 0.5133959 0.2696824 0.8146755 0.5052161 0.3338038 0.7958216 0.8245086 -0.4844289 0.2924284 0.8763849 0.4659005 -0.1220097 0.6120401 -0.5860453 -0.530997 0.5367211 0.5751857 -0.6173264 0.1628779 -0.5019269 -0.8494352 -0.5077409 -0.7457422 -0.4313558 -0.6657005 0.7285583 -0.1613867 -0.7864102 -0.6163672 0.04062533 -0.7275593 0.4594478 0.5094754 0.08528476 0.4341607 0.8967893 0.688955 -0.3220321 0.6493354 0.7301526 -0.1031061 0.6754602 0.9275808 0.3725934 0.0277127 0.5748938 -0.708398 -0.4094747 0.3049858 0.7147386 -0.6293905 -0.1070568 -0.7162715 -0.6895607 -0.2992091 0.5889883 -0.7507108 -0.5855008 -0.5813831 -0.5649624 -0.7180694 0.5638681 -0.4079573 -0.9032036 -0.3207483 -0.2852085 -0.930748 0.3488327 0.1096546 -0.8537583 -0.4619222 0.2402596 -0.5718657 0.6205381 0.5365652 -0.2097429 -0.6208618 0.75534 0.007651329 0.499064 0.8665313 0.3094321 -0.5572775 0.7705153 0.4636753 0.4602586 0.7570782 0.6852805 -0.6013154 0.4108656 0.641629 0.7639942 0.0680086 0.7266446 -0.5776094 -0.371961 0.6390408 0.5545712 -0.5329896 0.5313758 -0.4317624 -0.7288492 0.1362425 0.631691 -0.7631544 -0.2748678 -0.7009315 -0.6581359 -0.5195036 0.5760028 -0.6311393 -0.6732567 -0.6448774 -0.3617439 -0.7683449 0.6008967 -0.2203844 -0.7440526 -0.6475509 0.1645103 -0.0325163 -0.1553538 0.9873236 0.5251228 0.1053273 0.8444835 0.9936248 -0.03112268 0.1083567 0.8734148 0.2562932 -0.4140776 -0.2344862 -0.8421116 -0.4856587 -0.6131595 0.597599 -0.5166342 -0.8174495 -0.5747202 -0.03838026 -0.5090834 0.5418485 0.6687558 -0.1186754 -0.5809914 0.8052113 0.04027658 0.6198105 0.7837173 0.3814061 -0.693253 0.6114978 0.4860936 0.8120087 0.3230403 0.7448017 -0.6644607 0.06133812 0.7447097 0.6337398 -0.2092399 0.6700677 -0.6081909 -0.4255741 0.543709 0.5477891 -0.6358519 0.2650405 -0.5152673 -0.8150173 0.2246744 0.2208521 -0.9490763 -0.3080284 -0.327081 -0.8933849 -0.3446234 0.1655913 -0.9240208 -0.8539032 0.1247107 -0.5052691 -0.6535356 -0.6794647 0.3334951 -0.5777873 0.6153036 0.5362493 -0.3443511 -0.6084486 0.7149913 -0.08432036 0.619807 0.7802113 0.06083977 -0.259989 0.963693 0.6515834 0.03415685 0.7578077 0.8204063 0.5039644 0.270099 0.7978107 -0.5450091 -0.2578045 -0.800584 -0.4071305 -0.4396704 -0.9469241 0.3194052 0.03626507 -0.9937445 -0.05530005 0.09702539 -0.7321062 -0.09578591 0.6744225 -0.7332947 -0.04491865 0.6784256 -0.2004375 0.2750639 0.9403003 -0.1289386 -0.2363875 0.9630659 0.4767116 -0.08573746 0.8748687 0.7444483 0.4042982 0.5313566 0.9673565 -0.2506069 0.03765344 0.8139395 -0.4522966 -0.3645963 0.4858649 0.4438866 -0.7529277 -0.06547045 -0.7083671 -0.7028014 -0.2003467 0.3246489 -0.9243724 -0.6651945 -0.1748786 -0.7259021 -0.8875062 0.1042481 0.4488487 -0.4088145 -0.4379202 0.8006851 -0.2784047 0.6669315 0.6911535 0.1248669 -0.5942774 0.7945079 0.274095 0.5948252 0.7556819 0.5436048 -0.4493785 0.7089096 0.7175796 0.4791769 0.5054396 0.8241139 -0.458173 0.3330372 0.8034238 0.5953121 -0.01067256 0.5619097 -0.4018597 -0.7230259 0.08301508 0.337616 -0.9376161 -0.970184 0.1959565 0.1426331 -0.6777618 -0.4802195 0.5568018 -0.5154929 0.6426109 0.5668495 -0.2660023 -0.5604447 0.7843114 -0.05840075 0.6118276 0.7888323 0.1940177 -0.6452931 0.738887 0.4133796 0.706133 0.5748857 0.5919687 -0.7014247 0.3969591 0.7415068 0.6405172 0.1997631 0.6455522 -0.7543923 -0.118973 0.7959991 0.1618645 -0.583254 0.3509187 0.1097089 -0.929957 0.263921 -0.3395292 -0.9028099 -0.2063696 0.3618991 -0.9090879 -0.3086879 -0.2763828 -0.9101232 -0.7978962 0.1590597 -0.5814308 -0.8240301 -0.1748068 -0.5389035 -0.9630905 0.2673255 -0.03152453 -0.8315219 -0.5464029 0.100077 -0.6412729 0.6435142 0.4179219 -0.60934 -0.4733636 0.6361067 -0.2607905 0.02920001 0.9649538 -0.2408972 0.2570865 0.935882 0.3618624 0.09617781 0.927257 0.3739005 0.01751637 0.9273035 0.7586514 -0.4005242 0.5138371 0.7005409 0.5877799 0.4046695 0.8257197 -0.5491918 -0.1287463 -0.00645101 0.5616391 -0.8273572 -0.4392676 -0.6117388 -0.6578903 -0.631256 0.6538875 -0.4170698 -0.8543589 -0.5136734 -0.0788083 -0.8162603 0.5674922 0.1080364 -0.7873308 -0.5049072 0.3538064 -0.6591152 0.487233 0.5728622 -0.3284397 -0.693982 0.6407157 0.5006002 -0.1846226 0.8457623 0.8496955 0.4049544 0.3376825 0.9510165 -0.04119092 0.306384 0.9031245 -0.3731872 -0.2123616 0.764218 0.5881485 -0.2646737 0.6378266 -0.4988805 -0.5867671 0.4401909 0.6168633 -0.6524659 0.2568501 -0.5208232 -0.8141076 -0.1373988 0.3995259 -0.9063668 -0.9924682 -0.09768903 0.0739175 -0.7288486 -0.02931517 0.6840471 -0.713216 -0.2455762 0.6565176 -0.2358322 0.4495981 0.8615363 -0.09323656 -0.4806571 0.8719379 0.4465216 0.1866238 0.8750944 0.4229214 0.4207652 0.8025547 0.7496891 -0.5534052 0.3629173 0.8258207 0.5557469 0.09573686 0.7828392 -0.537923 -0.3127325 0.7623128 0.4980263 -0.4133388 0.4336677 -0.4201657 -0.7971156 -0.1548064 0.7891471 0.5943753 0.1903429 -0.6239033 0.7579673 0.4167639 0.5010414 0.7584627 0.6283648 -0.460121 0.6272532 0.7047363 0.567366 0.4259608 0.7362918 -0.6641954 0.1293015 0.7021106 0.7064378 -0.08936679 0.793972 -0.4909871 -0.358525 0.6146678 0.2353782 -0.7528483 0.6422842 -0.02807176 -0.7659523 0.111219 0.2723257 -0.9557558 -0.3340789 -0.3606322 -0.8708248 -0.5982099 0.5750502 -0.5580881 -0.7103826 -0.5906916 -0.3826749 -0.9124363 0.4072845 -0.03974127 -0.9994573 0.02279335 0.02378332 -0.7941139 -0.02923148 0.6070657 -0.03870147 0.353821 0.9345121 0.5152369 -0.3574507 0.778948 0.8913094 -0.02976042 0.4524177 0.9673356 -0.2436668 -0.06991642 0.8432618 0.5226234 -0.1255966 0.6995306 -0.5137627 -0.496694 0.631744 0.4962736 -0.5954933 0.2509206 -0.5960281 -0.7627512 -0.02818995 0.6717716 -0.7402217 -0.3700056 -0.4568885 -0.8089184 -0.5579299 0.4854113 -0.6731197 -0.6773567 -0.5989559 -0.4271296 -0.8062364 0.4937698 -0.3258441 -0.9258607 -0.346938 0.1497201 -0.959673 0.2727131 0.0682305 -0.6968144 -0.4667599 0.544596 -0.5243234 0.6697633 0.5258347 -0.1751783 -0.6977445 0.6945971 -0.06872761 0.6335201 0.7706677 0.4050019 -0.5244475 0.7489516 0.7615039 -0.3408582 0.5512964 0.8307073 0.5505272 0.08273619 0.7897881 -0.4592437 -0.4066078 0.450228 0.2676436 -0.8518579 0.4345981 0.3449231 -0.8319572 -0.06798171 -0.4898685 -0.8691418 -0.1643012 0.5458742 -0.8216 -0.5441575 -0.5030565 -0.6714365 -0.8158493 0.5751028 -0.0603891 -0.6177818 -0.6265805 0.4751237 -0.4688916 0.0984255 0.8777546 0.09162735 0.2323852 0.9682983 0.1764017 -0.340012 0.9237285 0.6180334 0.2403064 0.7485237 0.9178447 -0.3902587 -0.07252144 0.7178379 0.5138767 -0.4697229 0.675275 -0.3872284 -0.6277403 0.3110192 -0.09219276 -0.9459215 0.2784584 0.2880838 -0.9162253 -0.2886607 0.003921449 -0.9574235 -0.60773 -0.4937241 -0.6220135 -0.8808048 0.3926241 -0.26463 -0.6670093 -0.3925126 0.6332712 -0.2302551 0.3665689 0.9014488 -0.05985236 -0.534418 0.8430987 0.207057 0.49175 0.8457596 0.4520997 -0.6069469 0.6536218 0.7037542 0.4294671 0.56594 0.7765007 -0.5689952 0.2707234 0.8109824 0.5703189 0.1305527 0.7939682 -0.520966 -0.3133832 -0.5302678 -0.06321471 -0.8454704 -0.3037353 0.9351804 -0.1821607 -0.7649778 0.6381247 -0.0872128 -0.4295084 0.9004334 0.06886494 -0.5675733 0.7562426 0.3255116 -0.3265936 0.8649221 0.3811119 -0.336579 0.7877112 0.5159708 -0.1852418 0.7512319 0.633511 -0.08835202 0.8539959 0.512723 0.1735946 0.7325202 0.6582394 0.2588342 0.8391441 0.4783745 0.4205804 0.7650459 0.4876648 0.3815838 0.8914623 0.2443135 0.4813073 0.7944192 0.370461 0.6014866 0.7961973 0.06545126 0.5964055 0.8002768 0.06211084 0.5910458 0.775094 -0.22337 0.5769915 0.7912623 -0.2024475 0.4403634 0.7958619 -0.4155527 0.4543044 0.7433661 -0.4909321 0.1625728 0.8393275 -0.5187479 0.0727871 0.7058168 -0.7046451 -0.08524906 0.8425032 -0.5319032 -0.288327 0.7365834 -0.6118108 -0.3695113 0.8409544 -0.3952938 -0.4105875 0.8189556 -0.4009114 -0.5319394 0.8161408 -0.2257315 -0.511878 0.8343258 -0.2046498 -0.6602452 0.7491491 0.05340427 -0.5627312 0.8204519 0.1009573 -0.5541988 0.6590913 0.508392 -0.4956845 0.7875457 0.3661541 -0.2070324 0.7789212 0.5919623 -0.2151611 0.8167139 0.535429 0.01122057 0.8008497 0.5987604 0.03854173 0.8462046 0.5314625 0.2377094 0.8366315 0.4934996 0.2370444 0.7953522 0.5578752 0.4852008 0.7982228 0.3569605 0.4588002 0.833952 0.3066378 0.544045 0.8303582 0.1205014 0.5107194 0.8549583 0.09062057 0.6163175 0.784667 -0.06671094 0.4720108 0.859807 -0.1947758 0.4650148 0.8635862 -0.1948853 0.423937 0.8007292 -0.4232143 0.2611254 0.8809859 -0.39456 0.244727 0.8120718 -0.5297623 -0.01735985 0.7929445 -0.6090465 -0.04518187 0.8486758 -0.5269802 -0.3421475 0.7317431 -0.5894805 -0.3632372 0.8350949 -0.4131284 -0.5230426 0.7594878 -0.3867878 -0.550424 0.8100967 -0.2019324 -0.6320073 0.7567669 -0.1669458 -0.6768727 0.7354941 0.02986067 -0.5721399 0.815025 0.09159755 -0.576225 0.764324 0.2894369 -0.4586033 0.8296622 0.3183457 -0.4521633 0.7358637 0.5040368 -0.2238528 0.7977885 0.5598426 -0.2410533 0.8417201 0.4831156 -0.035048 0.7917635 0.6098216 0.0532642 0.8838241 0.4647774 0.2356948 0.7725443 0.5895959 0.3336505 0.8640707 0.3769075 0.3389762 0.8542827 0.3940767 0.6117477 0.7442857 0.2679621 0.5329523 0.839034 0.1094709 0.6201741 0.7840195 0.02641171 0.4697304 0.8707202 -0.1456018 0.4626621 0.875768 -0.1377483 0.5128606 0.7738755 -0.3716058 0.2949066 0.8481822 -0.4400196 0.236556 0.8832444 -0.4048714 0.1523277 0.7810478 -0.6056078 -0.05729156 0.8337891 -0.5491026 -0.08085852 0.8743898 -0.4784398 -0.2488944 0.8021849 -0.5427256 -0.3367437 0.8523285 -0.4001747 -0.4587711 0.7848469 -0.4165866 -0.6023555 0.7563259 -0.2552239 -0.5977662 0.7622756 -0.2482166 -0.6583113 0.7527056 0.007790625 -0.4931101 0.8640531 0.1012664 -0.5602653 0.7902968 0.2480604 -0.3756493 0.8602145 0.344846 -0.3584338 0.8698961 0.3388306 -0.276295 0.7561219 0.5932459 -0.008200287 0.8732542 0.487196 -0.01837706 0.8843063 0.4665457 0.225556 0.750149 0.6216117 0.2932169 0.8949412 0.3363096 0.4656884 0.8043621 0.3689664 0.4968707 0.8557004 0.1445559 0.5554422 0.8223395 0.1234575 0.5725385 0.8154727 -0.08487743 0.495437 0.8609493 -0.1153618 0.5171735 0.8112674 -0.2727214 0.4451802 0.8465358 -0.2918764 0.4265301 0.7533204 -0.5005803 0.1624004 0.8112536 -0.5616884 0.1786314 0.8704588 -0.4586855 0.01052296 0.7616685 -0.6478815 -0.1859549 0.8542208 -0.4855178 -0.184042 0.8759613 -0.4458931 -0.4775847 0.776467 -0.4111107 -0.5462389 0.6444832 -0.535037 -0.509465 0.8567072 -0.08061122 -0.5718464 0.8183615 -0.05723863 -0.5404 0.820318 0.1872066 -0.6141063 0.7664679 0.1881503 -0.3922318 0.7978546 0.4578018 -0.3979064 0.743236 0.537839 -0.1439012 0.7824616 0.6058435 -0.1351145 0.7727664 0.6201421 0.07247918 0.8317273 0.550433 0.2036952 0.7320055 0.6501355 0.3248329 0.819581 0.4719859 0.467109 0.7393154 0.484997 0.5366617 0.7964342 0.2787238 0.6011382 0.757543 0.2544828 0.5350589 0.8447976 0.005385696 0.5786581 0.8152951 -0.02118492 0.5025665 0.8136982 -0.2920997 0.4083931 0.8666871 -0.286476 0.4127694 0.7474309 -0.5205464 0.1474961 0.8137951 -0.5621233 0.1041662 0.751146 -0.6518659 -0.05527973 0.8616858 -0.5044222 -0.2547969 0.7249462 -0.6399466 -0.3405104 0.8419919 -0.4184526 -0.532386 0.7409012 -0.4094271 -0.5469343 0.8132783 -0.1985985 -0.6291183 0.7599172 -0.1635116 -0.5808563 0.8102754 0.07784456 -0.6507163 0.7417363 0.1624671 -0.491331 0.7884609 0.3700318 -0.4937521 0.7784049 0.3876788 -0.3346966 0.8595574 0.3861858 -0.2781091 0.7566261 0.5917536 -0.04160887 0.8142557 0.5790134 -0.03965431 0.8116959 0.5827327 0.17971 0.7604749 0.6240052 0.2120671 0.8757916 0.4336089 0.4611142 0.7452543 0.4816324 0.5327016 0.8260137 0.1842021 0.4606478 0.8661062 0.1940709 0.6409986 0.7668615 0.03231734 0.4591435 0.8788477 -0.129669 0.5122222 0.8371536 -0.1918394 0.4353403 0.7693449 -0.4675332 0.2775518 0.8682172 -0.4112955 0.217302 0.7597387 -0.6128434 -0.05341148 0.8174495 -0.5735185 -0.1006718 0.7731456 -0.6261879 -0.3709059 0.7688899 -0.5208045 -0.3653683 0.772664 -0.5191305 -0.5074754 0.8148295 -0.2802174 -0.5890517 0.7645087 -0.2618101 -0.4700503 0.8752533 -0.113949 -0.6337895 0.7689309 0.08400207 -0.424107 0.8933082 0.1487751 -0.5017037 0.7727673 0.3887472 -0.3530579 0.7397463 0.5728226 -0.4044244 0.8188937 0.4072518 -0.104319 0.7886718 0.6058998 -0.04755586 0.8532932 0.5192583 0.2136844 0.7615404 0.6118785 0.2257986 0.876494 0.4251744 0.420404 0.8043272 0.4199025 0.4185885 0.8671545 0.2698643 0.6364496 0.7408685 0.2145832 0.5388684 0.8384386 -0.08149749 0.6346018 0.7524206 -0.1764766 0.3954244 0.8796294 -0.2643703 0.4330865 0.779139 -0.4531871 0.202288 0.8619877 -0.4648191 0.1648989 0.7849065 -0.5972691 -0.026358 0.7533975 -0.6570369 -0.130604 0.8330512 -0.537558 -0.2389147 0.7739805 -0.5864077 -0.4107255 0.8347321 -0.366779 -0.3801519 0.8526667 -0.3583908 -0.6080363 0.7620177 -0.2227576 -0.4771994 0.8780292 -0.03668016 -0.5297277 0.8481652 -0.002147197 -0.5775845 0.7901072 0.2052485 -0.3747571 0.8839557 0.2796059 -0.5520953 0.7654523 0.3305657 -0.2896971 0.7820867 0.5517392 -0.2575546 0.8069915 0.5314419 -0.06858807 0.7550984 0.652014 0.05721223 0.8445655 0.5323871 0.152455 0.7834963 0.6024044 0.3034056 0.8076645 0.505592 0.2882993 0.8955566 0.3389128 0.4899857 0.7906255 0.3671858 0.5791881 0.8098642 0.09306699 0.5398845 0.8386784 0.07171738 0.6186642 0.7734524 -0.1379356 0.3962907 0.8778159 -0.2690595 0.409168 0.8630185 -0.2962782 0.3827997 0.7302622 -0.565846 0.272531 0.8182175 -0.5062087 0.05690944 0.741724 -0.6682866 -0.06735193 0.8742052 -0.4808629 -0.2597582 0.7677197 -0.5857748 -0.3076901 0.873018 -0.3783732 -0.4462877 0.8064047 -0.3879934 -0.4411642 0.8766266 -0.1920939 -0.585803 0.7978157 -0.1425663 -0.5200631 0.8492065 0.09155809 -0.5091259 0.8567102 0.08269554 -0.5402585 0.7755683 0.3265191 -0.4315954 0.835679 0.3396559 -0.3847925 0.7319061 0.5623596 -0.1379857 0.841632 0.5221261 -0.1324008 0.8334512 0.5364972 0.07588344 0.8004295 0.5946044 0.1239459 0.8769646 0.4642956 0.3273226 0.7841529 0.5272232 0.3625178 0.8571016 0.3660023 0.5143819 0.7760303 0.3649498 0.6148316 0.7860583 0.06398808 0.5547564 0.8273098 0.0883392 0.6301776 0.7607991 -0.1551162 0.4727715 0.8632118 -0.1770664 0.4476713 0.812038 -0.3744124 0.3316036 0.8695724 -0.3659002 0.3047782 0.7944401 -0.5253334 0.1384335 0.8597849 -0.4915347 -0.01316756 0.7113592 -0.7027053 -0.1766243 0.8893271 -0.4217834 -0.2856618 0.8314041 -0.4766179 -0.4091016 0.8565704 -0.3145202 -0.4775578 0.8154792 -0.327005 -0.6213343 0.7790313 -0.08398896 -0.5192834 0.8545416 -0.01017951 -0.6373236 0.7479757 0.1853405 -0.4839954 0.8203585 0.3045661 -0.5057625 0.7459582 0.4333022 -0.3062024 0.7868855 0.5357718 -0.3012239 0.7753159 0.5551123 -0.01613104 0.8131751 0.5817956 -0.006194472 0.7992079 0.6010227 0.2434815 0.840524 0.4839796 0.246852 0.8001411 0.5466611 0.4836408 0.7681487 0.4195705 0.4652323 0.8126991 0.3508263 0.6303055 0.7550294 0.1806809 0.5353369 0.8432152 0.04901653 0.641623 0.7640079 -0.0679118 0.5107317 0.8458361 -0.1539955 0.5597795 0.7493161 -0.353797 0.4133576 0.8105463 -0.4149098 0.3980556 0.7604903 -0.5130364 0.1584913 0.8003054 -0.5782664 0.182297 0.7731777 -0.6074241 -0.1499574 0.8040225 -0.5753787 -0.1515389 0.8148137 -0.5595665 -0.5170988 0.7407172 -0.4288903 -0.3532197 0.8545148 -0.3808416 -0.5414587 0.7968646 -0.2680097 -0.488758 0.8610764 -0.1402258 -0.6406416 0.7665874 -0.04384106 -0.5507271 0.8118469 0.1939187 -0.5652824 0.7962518 0.2154968 -0.5063133 0.7419844 0.4394383 -0.3242906 0.8365733 0.4415664 -0.2984486 0.7999595 0.5205702 -0.1301506 0.8695594 0.476369 -0.04457473 0.7685819 0.6381968 0.2727397 0.7827883 0.559335 0.1489708 0.8652396 0.4787151 0.4783836 0.7642444 0.4325271 0.4602078 0.8343752 0.3033592 0.5422 0.8044475 0.242659 0.4391821 0.892871 0.09950184 0.6537363 0.7529047 -0.07591736 0.4212117 0.884918 -0.1987484 0.4834955 0.8172029 -0.3137062 0.3868762 0.7860113 -0.4821963 0.1945707 0.8887017 -0.4151526 0.1532645 0.8178457 -0.5546517 -0.05243134 0.8154466 -0.5764529 -0.1009008 0.8881593 -0.4483216 -0.3268093 0.7590182 -0.5631049 -0.4409483 0.8264453 -0.3500754 -0.4349921 0.8337702 -0.3400136 -0.6459978 0.7466121 -0.1589253 -0.557248 0.8293687 -0.04028034 -0.6408465 0.7600193 0.1081045 -0.4780417 0.844155 0.2426496 -0.4911417 0.8287157 0.2683473 -0.3723031 0.7987111 0.4727062 -0.2650923 0.8711282 0.4133544 -0.1341493 0.8086993 0.5727212 -0.01861542 0.8740704 0.4854426 0.0608024 0.8160839 0.5747263 0.2725756 0.81014 0.5190144 0.2702025 0.8556593 0.4414047 0.488388 0.7586244 0.4312379 0.5893154 0.7866011 0.1842995 0.5585268 0.8070501 0.1916202 0.5254045 0.8495751 -0.04661041 0.5759325 0.8124833 -0.09040451 0.5802004 0.7295206 -0.3621701 0.441982 0.8237166 -0.3551661 0.2789314 0.7629859 -0.5831381 0.2820258 0.7894082 -0.545249 -0.01184439 0.7584756 -0.6515938 -0.02313798 0.7786529 -0.6270282 -0.3060158 0.7725867 -0.5562951 -0.306123 0.7973331 -0.520143 -0.5140942 0.7681126 -0.38172 -0.4527662 0.8582406 -0.2417147 -0.6140515 0.7812371 -0.1122921 -0.481975 0.8761776 0.003621578 -0.5774685 0.8081268 0.1160221 -0.3687731 0.8869113 0.2781991 -0.3863044 0.8656975 0.3183345 -0.3291872 0.7646304 0.5540544 -0.1090752 0.884463 0.4536828 -0.05306822 0.8216619 0.5674995 0.1420127 0.8062253 0.5743112 0.1634371 0.8482424 0.503759 0.3784982 0.7505061 0.5417377 0.4779436 0.818706 0.3182616 0.5233044 0.7920899 0.314239 0.5283726 0.8399692 0.1235899 0.596809 0.7974504 0.08883547 0.6474102 0.7451896 -0.1598516 0.4648609 0.8584958 -0.2165396 0.4857704 0.7809607 -0.392591 0.2420212 0.8812603 -0.4059634 0.3779108 0.7685615 -0.5162332 0.04262542 0.7946473 -0.6055732 -0.01932334 0.8807296 -0.4732252 -0.2870306 0.778907 -0.5575997 -0.2900943 0.8366825 -0.464551 -0.5043963 0.7522127 -0.423982 -0.5219056 0.8050699 -0.2819173 -0.6060876 0.7590836 -0.2375919 -0.5482079 0.8338875 -0.0640285 -0.6576578 0.7513603 0.05425941 -0.5086109 0.8198916 0.2628552 -0.4938741 0.8359929 0.2391743 -0.4088734 0.8036222 0.4324513 -0.2557075 0.8891558 0.3794939 -0.1921161 0.7993748 0.5692901 0.0241937 0.8514744 0.5238378 0.03216505 0.8441553 0.5351328 0.2783041 0.7946825 0.539469 0.2763534 0.8505216 0.447484 0.4899216 0.7876474 0.3736155 0.4337705 0.8702285 0.2335503 0.570583 0.8049612 0.1627038 0.4788326 0.876127 -0.05586695 0.7662247 0.6425709 -0.001544773 0.5179367 0.8338694 -0.1907971 0.514271 0.7380158 -0.436873 0.3188383 0.8446214 -0.4300662 0.289376 0.7754539 -0.5611888 0.02271234 0.8801905 -0.474077 0.1091706 0.7202922 -0.6850262 -0.2450649 0.8191646 -0.5185678 -0.2468985 0.6668199 -0.7031304 -0.3928895 0.8309264 -0.3939533 -0.5964193 0.7057498 -0.3823627 -0.5426923 0.80802 -0.229323 -0.6599267 0.7492641 -0.05567812 -0.4992557 0.8620684 0.08707553 -0.5705682 0.7914845 0.2190992 -0.4072214 0.8742451 0.2643222 -0.4238665 0.7984529 0.4275631 -0.2436796 0.8335582 0.4957832 -0.222934 0.8493636 0.4784162 -0.05953896 0.8036337 0.5921385 0.05606693 0.8851994 0.4618211 0.1760421 0.8051171 0.5663883 0.3477896 0.7922432 0.5013912 0.423622 0.8500426 0.313005 0.3423518 0.8884774 0.3056194 0.613992 0.770438 0.1715781 0.6066651 0.7916076 -0.07290369 0.4953417 0.8679597 0.03581053 0.5263804 0.7864779 -0.3230731 0.4324801 0.8452312 -0.3139194 0.3495946 0.7947509 -0.4961397 0.1757163 0.888238 -0.4244493 0.09467625 0.7840982 -0.6133731 -0.1021342 0.8855639 -0.4531502 -0.2260302 0.7964498 -0.5608726 -0.4112444 0.7970015 -0.4423425 -0.3586888 0.8870379 -0.2906994 -0.553521 0.7995374 -0.2331407 -0.4532874 0.8913623 -0.001995027 -0.5480346 0.8346158 0.05545127 -0.5478312 0.7732987 0.3192026 -0.362036 0.8825963 0.2999232 -0.3307935 0.7923966 0.5125264 -0.1700014 0.864413 0.4731699 -0.1013607 0.7712331 0.6284311 0.1634503 0.8513576 0.4984721 0.1631278 0.8427222 0.5130386 0.4054841 0.8074639 0.4284678 0.3627673 0.8788732 0.3098093 0.6717958 0.7194948 0.1761182 0.4774878 0.8778097 0.038154 0.6591846 0.7104017 -0.2465871 0.4518111 0.8369937 -0.3087204 0.4556634 0.7265856 -0.5142415 0.2531019 0.7955887 -0.5504346 0.2136053 0.7468085 -0.6298015 -0.01358652 0.820922 -0.5708788 -0.03153252 0.806542 -0.5903354 -0.1895239 0.8241235 -0.5337614 -0.1912302 0.8326357 -0.5197585 -0.4287793 0.7549408 -0.4961984 -0.4613224 0.837071 -0.2940986 -0.5243138 0.8044215 -0.2792868 -0.5324818 0.8414543 -0.0917499 -0.5591223 0.8220139 -0.1080529 -0.5379856 0.8280648 0.1577351 -0.4944545 0.853987 0.1619288 -0.4498741 0.8014218 0.3941275 -0.3349201 0.8634988 0.3770923 -0.3031275 0.7864302 0.5381834 -0.05715018 0.7949138 0.604025 -0.08287757 0.8277389 0.5549593 0.1304613 0.7282827 0.6727439 0.2619736 0.8507962 0.4555391 0.3220013 0.8149438 0.4818527 0.5194309 0.7895407 0.3268288 0.3915404 0.9149543 0.09774911 0.6189782 0.7487815 0.2370493 0.4944105 0.8669466 -0.06294387 0.5009443 0.8626536 -0.06988441 0.4200452 0.8472148 -0.3252525 0.4435958 0.8323481 -0.3322941 0.253908 0.8306318 -0.4955618 0.2010118 0.8673901 -0.4552238 0.01537859 0.8004589 -0.5991904 -0.0126484 0.833653 -0.5521438 -0.2654678 0.7382218 -0.6201254 -0.3226007 0.8323041 -0.4507758 -0.5073112 0.7397332 -0.4420748 -0.492791 0.8265922 -0.2718498 -0.6640871 0.7281056 -0.1698547 -0.5403221 0.8401073 0.04766345 -0.5916212 0.8007457 0.09375894 -0.3879052 0.8776549 0.2815168 -0.4123249 0.8485304 0.3316389 -0.305019 0.7541344 0.5815883 -0.06768912 0.8891401 0.4526017 -0.1115858 0.8388036 0.5328763 0.1038196 0.8142602 0.571141 0.1561419 0.9056993 0.3941174 0.3744312 0.8041646 0.4616498 0.3569341 0.8781238 0.3185857 0.6548873 0.7188937 0.2330549 0.5291519 0.8477458 0.03640967 0.5729225 0.8133897 -0.1007831 0.460058 0.8793143 -0.1230978 0.4955212 0.7466114 -0.443881 0.3368512 0.8538467 -0.3968341 0.2286796 0.7265477 -0.6479461 0.06245326 0.8203411 -0.568454 -0.008036077 0.7710027 -0.6367813 -0.2662056 0.7702505 -0.5795248 -0.3069872 0.737816 -0.6011543 -0.4028034 0.8348191 -0.3752686 -0.5619286 0.743015 -0.3635451 -0.5736938 0.8074554 -0.1374452 -0.6601314 0.7457504 -0.08990472 -0.5605018 0.8141042 0.1518952 -0.6295853 0.7284714 0.2700963 -0.4120828 0.837062 0.3598818 -0.4136089 0.7079932 0.5724276 -0.1521006 0.7951526 0.5870246 -0.1055288 0.7449985 0.658666 0.05248469 0.8869687 0.4588377 0.2246048 0.7842112 0.5784164 0.3084685 0.8699561 0.3847383 0.3841514 0.8317903 0.4006902 0.5525058 0.8013262 0.229377 0.4646632 0.8737169 0.1438995 0.6378818 0.7672935 -0.06608635 0.4808708 0.8627151 -0.1564804 0.5251205 0.8098943 -0.2613806 0.3418796 0.8670127 -0.3625015 0.3552129 0.8159646 -0.4560982 0.1632354 0.7954561 -0.5836127 0.1420566 0.815485 -0.5610741 -0.09093648 0.7475863 -0.6579098 -0.1898771 0.8621718 -0.4696877 -0.4024268 0.7357417 -0.5447356 -0.3634911 0.8941178 -0.2615869 -0.5928378 0.7741472 -0.2219 -0.4912869 0.8704701 -0.0303151 -0.6334194 0.7687625 0.08822727 -0.4462569 0.8657201 0.2266793 -0.5118003 0.7552314 0.409495 -0.2994416 0.7573113 0.5803571 -0.3054375 0.7758167 0.552102 -0.01715677 0.7873452 0.6162736 -0.02490168 0.7982359 0.6018301 0.1949198 0.8548675 0.4808409 0.3427115 0.7496536 0.5661875 0.518779 0.8157153 0.2558847 0.5112737 0.8203406 0.2562042 0.5598535 0.8277202 0.0379917 0.5160965 0.8564692 0.01025795 0.5818213 0.790348 -0.1919223 0.4234701 0.875598 -0.2323815 0.4541439 0.7856827 -0.4200669 0.277538 0.8575456 -0.4331148 0.2408041 0.7697941 -0.5911265 -0.03691464 0.7952209 -0.6051951 -0.03196263 0.7992606 -0.6001341 -0.1601784 0.8621591 -0.4806503 -0.2025268 0.8389629 -0.5050982 -0.4100278 0.8003436 -0.4374099 -0.3634009 0.8826764 -0.298031 -0.6304957 0.7454523 -0.2162781 -0.467597 0.8839366 -0.003035187 -0.5729419 0.8150496 0.08620762 -0.4386964 0.8561571 0.2730213 -0.4606085 0.8282923 0.3190172 -0.3065248 0.8083385 0.5026245 -0.1775653 0.8801509 0.4402329 -0.1102101 0.7697097 0.628809 0.1901914 0.8393769 0.5091893 0.1959336 0.7821764 0.5914475 0.465155 0.7953602 0.3886295 0.4162579 0.8597967 0.2957684 0.5652157 0.8199085 0.09100222 0.5832734 0.8054147 0.1053541 0.6652498 0.7289921 -0.1612865 0.4581027 0.8563916 -0.238192 0.4818433 0.8165734 -0.3178603 0.2738295 0.8305967 -0.4848984 0.2730084 0.853249 -0.4443339 0.1174768 0.7996885 -0.5888103 0.01864647 0.8759638 -0.4820163 -0.1309294 0.7951819 -0.592067 -0.2659726 0.8534269 -0.4482421 -0.2808986 0.7939259 -0.539238 -0.4860748 0.8011538 -0.349119 -0.5064387 0.7888304 -0.3482334 -0.4396871 0.8900565 -0.1203113 -0.6703606 0.740567 -0.04665929 -0.6681002 0.7398672 0.07898586 -0.4707046 0.8561369 0.2132297 -0.5363593 0.7475897 0.3916996 -0.2503257 0.8432076 0.47575 -0.2386707 0.7817289 0.576139 -0.03043425 0.7998669 0.5994054 0.03971374 0.8802936 0.4727643 0.2237523 0.7820444 0.5816713 0.2669275 0.8432073 0.4666382 0.5349165 0.7213255 0.4399476 0.4903831 0.8247892 0.2815089 0.6576963 0.7425482 0.126719 0.477872 0.8775597 -0.03908401 0.5687416 0.8099648 -0.143144 0.4880183 0.8137573 -0.315654 0.3947004 0.8696895 -0.2963984 0.3028095 0.8150639 -0.4939406 0.1925698 0.8746311 -0.4449015 0.1107418 0.79693 -0.5938341 -0.07204586 0.8205918 -0.5669557 -0.08072441 0.8364081 -0.5421301 -0.3388559 0.7415948 -0.5789765 -0.3488417 0.8677597 -0.3539813 -0.568534 0.7646718 -0.3033915 -0.5232825 0.8224012 -0.2232302 -0.6613093 0.7465444 -0.07308584 -0.5400112 0.8380122 0.07825243 -0.6435148 0.7126291 0.2793717 -0.3742315 0.8569328 0.354425 -0.389275 0.796168 0.4632294 -0.09387749 0.8501417 0.518118 -0.09409111 0.8498576 0.518545 0.1692197 0.7893518 0.5901598 0.2188133 0.8812597 0.4189295 0.3355456 0.8238318 0.4568482 0.4758202 0.8254975 0.3035609 0.4216966 0.8824585 0.2084202 0.6009123 0.7892607 0.1263808 0.4823247 0.868606 -0.1135183 0.5268409 0.8357815 -0.1546221 0.5061393 0.7448651 -0.4347402 0.2617954 0.8804717 -0.3952633 0.2477648 0.8085356 -0.5337442 0.0313214 0.8579301 -0.5128108 -0.02024066 0.7772316 -0.6288891 -0.227065 0.7901665 -0.5692787 -0.2174248 0.9088259 -0.3560365 -0.4558324 0.704445 -0.5440351 0.3936794 0.8248596 -0.4057379 0.2155814 -0.7343408 -0.6436368 0.06472492 0.8179008 -0.571707 -0.3780754 0.8883507 0.2605612 -0.5014769 0.7527291 -0.4265207 -0.7041231 -0.7066228 -0.06996446 -0.4360355 0.8758289 -0.2068737 0.371339 -0.9043281 -0.2104714 -8.78559e-4 0.7970523 -0.6039096 -0.2614982 -0.8372274 -0.4802802 0.5135381 -0.8270233 -0.2287164 0.4757148 0.7976255 -0.3707953 0.2513179 -0.7980539 0.5476763 0.4302381 0.7381154 0.519693 0.5649446 -0.7510451 0.3417146 0.5164683 0.8353551 0.1882614 -0.7296584 -0.6179581 -0.2927908 0.6552506 0.7503525 0.08728051 0.7129683 0.6666424 0.2174032 0.9223621 0.3065495 0.2351078 0.6687043 0.6943545 0.2659066 0.9062348 -0.1406225 0.3987028 0.2359552 0.9504812 0.2022636 0.7265225 0.4607185 0.5098074 0.2695507 0.9219567 0.2780975 0.7660695 0.3539603 0.5365163 0.5120821 0.6445127 0.5677812 0.1555613 0.8808256 0.4471542 0.4785379 0.4375361 0.7612908 0.6285079 0.08661133 0.7729661 0.3874061 0.4563868 0.8010167 0.2504144 0.6595773 0.7086964 0.0743035 0.9319785 0.3548173 0.276932 0.09241837 0.9564348 -0.002780973 0.8948851 0.4462881 0.01831918 0.5880134 0.8086437 -0.04860442 0.7139938 0.698463 0.02826553 0.3041919 0.9521914 -0.07658886 0.9796993 0.1852657 -0.149481 0.9483469 0.27981 -0.2006459 0.6849634 0.7004045 -0.08314567 6.73926e-4 0.9965372 -0.3562512 0.4439631 0.8221812 -0.3228312 0.2829303 0.903178 -0.3253344 0.8680877 0.3749418 -0.4216954 0.4397383 0.7929711 -0.4726508 0.704716 0.5291281 -0.6337855 0.05384403 0.7716327 -0.6099913 0.5898478 0.5291411 -0.3569924 0.9183658 0.1707656 -0.7148455 0.221586 0.6632463 -0.6850007 0.593997 0.4218314 -0.6162199 0.7426696 0.2621354 -0.8686698 0.01836061 0.4950512 -0.1828993 0.9822785 0.04095 -0.8764691 0.113738 0.467831 -0.760097 0.6285744 0.164763 -0.906931 0.3969936 0.1409698 -0.5018891 0.8647513 -0.0176782 -0.9338724 0.3435894 0.09913986 -0.9954795 0.0801869 0.05090004 -0.8411515 0.5289513 -0.112582 -0.6356806 0.759913 -0.1358036 -0.6153335 0.7656018 -0.1876661 -0.907386 0.2569841 -0.332581 -0.9395844 0.133087 -0.3153869 -0.9440937 0.09166353 -0.316678 -0.7625151 0.5168527 -0.3891456 -0.0496279 0.9969443 -0.06032758 -0.2789961 0.9388827 -0.2016451 -0.6869193 0.5086314 -0.5190723 -0.4716747 0.7305189 -0.4938271 -0.4155753 0.7035318 -0.5764895 -0.7439982 0.1757366 -0.6446577 -0.6837806 -0.07581824 -0.7257381 -0.148966 0.9092566 -0.3886665 -0.4529858 0.4520784 -0.7683939 -0.4799799 0.3531778 -0.8030472 -0.1371951 0.4555069 -0.8795972 -0.2890425 -0.04615414 -0.9562031 -0.01607179 0.7191776 -0.6946405 -0.1447422 0.3037643 -0.9416884 -0.01608741 0.7313012 -0.681865 0.09853512 0.9151683 -0.3908424 0.0992546 -0.03869175 -0.9943096 0.222886 0.3593207 -0.9062067 0.2194582 0.382815 -0.8973799 0.3766838 0.73456 -0.5643855 0.3669903 0.7511402 -0.5487318 0.5079436 0.5578901 -0.656317 0.3239294 0.8932392 -0.3117589 0.5798154 0.07013857 -0.8117234 0.5856108 0.03813123 -0.8096951 0.6508347 0.7017385 -0.2897884 0.7915 0.4346424 -0.429667 0.8522138 0.2671149 -0.4498683 0.6263657 0.7589604 -0.1778909 0.2085474 0.9778675 -0.0168296 0.9092938 0.06462335 -0.4111067 0.7653887 0.6404246 -0.06353312 0.9508042 0.3025078 -0.06678569 0.978182 0.2064827 -0.02291011 0.009162783 0.9999505 0.003889203 0.00694561 0.9999758 5.33669e-4 -0.003996431 0.9999859 -0.003510177 0.002648055 0.9999961 9.60081e-4 0.004532694 0.9999898 5.97335e-5 0.004843771 0.9999395 -0.009881019 -0.865015 -0.07153332 0.4966209 -0.8651111 -0.07179957 0.4964148 -0.002623736 -0.07223236 0.9973844 -0.001881897 -0.07135623 0.9974492 0.8633195 -0.07099211 0.4996396 0.8628511 -0.07194381 0.5003122 0.8644889 -0.07163465 -0.4975213 0.8646925 -0.0721935 -0.4970868 0.003394067 -0.07167524 -0.9974223 0.001842081 -0.06977617 -0.997561 -0.866598 -0.03819638 -0.497543 -0.8653921 -0.03512388 -0.4998629 0.00801146 -0.9999338 0.008260965 0.004220426 -0.99993 0.01106101 0.01068776 -0.9999351 0.003952205 0.01166832 -0.9999292 -0.002361178 0.008828938 -0.999948 0.005110621 -0.001887261 -0.9999348 0.01126748 2.72369e-5 -0.9999485 0.01015692 -0.007240772 -0.9999287 0.009499132 0.008662164 -0.9999369 -0.007149934 0.008793711 -0.9999487 -0.005042076 0.00557059 -0.9999299 -0.01045268 -0.00860399 -0.9999447 0.00605303 -0.01127904 -0.9999254 0.004707276 4.45118e-4 -0.9999414 -0.01083147 4.04973e-5 -0.9999448 -0.01051288 -0.01256674 -0.9999187 -0.002167761 -0.008990585 -0.9999396 -0.006317734 -0.005603969 -0.9999271 -0.0107035 -0.008987367 -0.9999405 -0.006192922 0.001772105 -0.9999963 0.002085089 -0.003385186 -0.9999585 -0.008465826 0.001644909 -0.9999985 6.91184e-4 6.2193e-4 -0.9999998 8.36618e-5 -0.9994657 0.02431702 0.02183908 -0.9797462 -0.03059041 0.1978931 -0.8891471 0.03219467 0.4564876 -0.771023 -0.02943152 0.6361268 -0.4703634 0.02193653 0.8822002 -0.5175357 -0.006221115 0.8556391 -0.1433814 0.0101518 0.9896154 -0.04103291 -0.02326959 0.9988869 0.2981147 0.03278487 0.9539669 0.4633478 -0.03459328 0.885501 0.7687481 0.02038633 0.6392268 0.8229669 -0.0108878 0.5679852 0.9563651 0.01160532 0.2919437 0.9851052 -0.02504712 0.170119 0.9957563 0.0258935 -0.08831197 0.9157456 -0.02186715 -0.4011634 0.9226277 -0.01337927 -0.3854598 0.6551359 0.01665925 -0.7553274 0.6062161 -0.01161408 -0.7952153 0.1651911 2.22951e-4 -0.9862616 0.1770575 -0.006242573 -0.9841807 -0.2659568 0.01925241 -0.9637928 -0.3566554 -0.01897853 -0.9340433 -0.6961783 0.00718224 -0.7178331 -0.6861107 9.50151e-4 -0.7274966 -0.9378258 -0.0186876 -0.3466031 -0.9161779 0.004056155 -0.4007515 5.58055e-4 0.9999997 -6.45978e-4 -0.007584989 0.9997693 -0.0200982 0.009369075 0.9999478 -0.004102647 0.01510113 0.9998818 0.002910196 0.001464605 0.9999658 -0.008144259 0.01361334 0.9997303 0.0188207 0.003836452 0.9999926 -3.38911e-4 0.02035766 0.9997248 -0.01166981 -0.004300713 0.9998694 -0.01558029 0.00362277 0.9999929 0.001101136 -0.002181828 0.9999734 0.006964802 -0.02389371 0.9997146 2.1283e-4 -1.7661e-4 1 -1.50273e-4 -8.93196e-4 0.9999992 -9.39887e-4 1.58996e-4 1 -2.85553e-4 -0.001266777 0.9999991 -5.46263e-4 -1.73473e-5 1 -4.78115e-5 -0.001418828 0.9999942 -0.003125309 0.0208677 0.9997796 0.002336561 -0.003809928 0.9999928 8.31558e-5 -0.001983463 0.9999044 0.01369065 -0.003537893 0.9999921 0.001814126 -0.007475793 0.9998958 0.01235407 -0.02887243 0.9995427 -0.008987426 -0.005620241 0.9998388 0.01705205 0.0516327 -0.9981538 -0.03198719 0.05464196 -0.9962205 -0.06752043 0.129913 -0.9892386 -0.06730359 -1.11558e-4 -0.9999052 -0.01376956 9.55241e-4 -0.9999961 -0.002653241 0.1349096 -0.9907627 -0.01374441 0.1003299 -0.9948518 0.01427978 -7.42913e-4 -0.9999983 -0.001690626 0.0623418 -0.997858 -0.01982545 -0.03053575 -0.9951858 -0.09312814 -0.01882618 -0.9964156 -0.0824719 0.0346167 -0.999388 -0.00502938 0.07945251 -0.9951514 0.05797493 -0.003434717 -0.9998499 -0.01698368 0.08476418 -0.9946197 0.0595538 0.05927133 -0.990539 0.123772 -0.002969443 -0.9984766 0.05509704 -0.0330168 -0.9717754 0.2335863 -0.1082091 -0.8539743 0.5089389 0.04263192 -0.6645282 0.7460461 0.1429749 -0.8864098 0.440268 0.2944138 -0.7581321 0.581856 0.4169945 -0.818791 0.3945846 0.3965284 -0.8483324 0.3508523 0.5394248 -0.8276533 0.1549546 0.4800413 -0.8721792 0.09414786 0.6919469 -0.7131087 -0.1126303 0.3879714 -0.8793224 -0.2761712 0.6319032 -0.7208085 -0.2848396 0.2892721 -0.8129155 -0.5054605 0.2752171 -0.8523812 -0.4446367 0.04099744 -0.7586317 -0.6502287 -0.07993102 -0.8819339 -0.464547 -0.2541142 -0.774955 -0.5786801 -0.3191709 -0.8893449 -0.3274073 -0.5356326 -0.7561507 -0.375944 -0.5220457 -0.8474752 -0.09619784 -0.5708897 -0.8093073 -0.1382271 -0.616852 -0.776747 0.1271131 -0.60115 -0.7872977 0.137045 -0.5736762 -0.7460122 0.3381737 -0.3825082 -0.843946 0.3760887 -0.395273 -0.7279971 0.5601602 -0.1068899 -0.8204385 0.561654 -0.08603674 -0.7931253 0.6029512 0.1281477 -0.8663237 0.4827645 0.1599378 -0.8353603 0.5259212 0.390311 -0.7785318 0.4914728 0.3539358 -0.8921168 0.2808154 0.6073956 -0.7589179 0.2347643 0.5662627 -0.8239941 -0.01950442 0.5625022 -0.8266021 -0.01789742 0.6006614 -0.7521337 -0.2711104 0.4354709 -0.8514084 -0.2923505 0.4261598 -0.7396057 -0.5209332 0.2292975 -0.8333988 -0.5028609 0.1556341 -0.739526 -0.6548888 -0.04550898 -0.8063893 -0.5896315 -0.1127893 -0.7471024 -0.6550699 -0.3149668 -0.7853626 -0.5329182 -0.2713722 -0.8145176 -0.5127554 -0.4161243 -0.8389772 -0.3506535 -0.3974028 -0.8764583 -0.2718306 -0.6109741 -0.7590363 -0.224888 -0.4671466 -0.8831986 0.04164439 -0.5831499 -0.8055451 0.1050396 -0.4353122 -0.8253076 0.3596816 -0.3417474 -0.8714137 0.351919 -0.3430179 -0.7954524 0.4995942 -0.08492016 -0.8367637 0.5409391 -0.1150689 -0.8083888 0.5772927 0.1854915 -0.7712485 0.6089079 0.2318646 -0.86818 0.4387509 0.4579854 -0.7556522 0.4682298 0.4629513 -0.8588176 0.2193363 0.4597197 -0.8615983 0.2151886 0.5809706 -0.8138807 -0.008449137 0.4853603 -0.8715975 -0.06887131 0.5561193 -0.7673938 -0.3191213 0.3342093 -0.8884638 -0.3145415 0.3342201 -0.7492632 -0.5717532 0.109354 -0.8483828 -0.5179657 0.04489451 -0.7426722 -0.6681486 -0.2181704 -0.8152758 -0.5364021 -0.2818933 -0.7611067 -0.5841684 -0.4690021 -0.8364653 -0.2834838 -0.5012584 -0.7493787 -0.4326333 -0.5123784 -0.8475263 -0.1384481 -0.7088288 -0.6060203 -0.3609724 -0.553906 -0.8301276 0.06384629 -0.6286155 -0.7670363 0.1284444 -0.5058683 -0.7931888 0.3390411 -0.573218 -0.7462616 0.3384003 -0.2728565 -0.8175433 0.5071215 -0.2717304 -0.8328527 0.4822022 -0.03275305 -0.823545 0.5663046 -0.04978507 -0.8719973 0.4869726 0.1628185 -0.7409195 0.6515585 0.3029675 -0.8811123 0.3631141 0.3110017 -0.8604224 0.4036722 0.5589455 -0.794897 0.2360486 0.4438448 -0.8905928 0.09922891 0.6849544 -0.7216938 -0.09997856 0.3884844 -0.887008 -0.2495933 0.4378086 -0.8400722 -0.320316 0.3478823 -0.7787013 -0.5221132 0.1093879 -0.8757483 -0.4702119 0.3606045 -0.617159 -0.6993421 -0.06609439 -0.807335 -0.5863803 -0.04992961 -0.7850622 -0.6174015 -0.3332613 -0.7736934 -0.538828 -0.3364629 -0.8057237 -0.4874444 -0.5849758 -0.7530282 -0.3012508 -0.3953064 -0.8816765 -0.2576422 -0.5981321 -0.7805493 -0.1816067 -0.5416989 -0.839578 0.04087936 -0.4962376 -0.8658735 0.06333482 -0.5550609 -0.7867741 0.2699893 -0.3864696 -0.8651061 0.3197388 -0.4171765 -0.7879055 0.4529557 -0.2518885 -0.7517694 0.6094219 -0.05994606 -0.8785274 0.4739158 -0.005419969 -0.8341265 0.5515467 0.2123024 -0.8477458 0.4860604 0.209115 -0.8423801 0.4966557 0.4462656 -0.7317348 0.5151808 0.4621849 -0.8032348 0.3757646 0.6354239 -0.7133262 0.2956387 0.5346355 -0.8446084 0.0283159 0.6246576 -0.780642 -0.02002561 0.4790515 -0.8615605 -0.1679978 0.573412 -0.7301312 -0.3716277 0.2772123 -0.8459824 -0.4554856 0.2866991 -0.8086326 -0.5137286 0.0727902 -0.7728193 -0.6304378 -0.04912316 -0.8829164 -0.4669536 -0.2299798 -0.7841891 -0.5763307 -0.2841449 -0.8717566 -0.3991268 -0.4418984 -0.7865734 -0.4313098 -0.4975212 -0.8386809 -0.2215564 -0.4353196 -0.891753 -0.1235861 -0.622584 -0.7810397 -0.04864358 -0.5009157 -0.840119 0.2080476 -0.457937 -0.8627247 0.2144759 -0.4287288 -0.7746912 0.4648065 -0.2785517 -0.8667741 0.4136567 -0.09134447 -0.7817884 0.616817 0.01008176 -0.8734102 0.4868808 0.1527003 -0.7917845 0.5914052 0.3384437 -0.8662437 0.3675295 0.3638762 -0.8004181 0.4763667 0.4905453 -0.8462589 0.2078728 0.4777767 -0.8535838 0.2076635 0.6016904 -0.7947544 0.07958829 0.518949 -0.853861 -0.04016619 0.6414977 -0.7454187 -0.1811951 0.4057664 -0.8259332 -0.3913926 0.38875 -0.8479816 -0.3602787 0.2369107 -0.7731887 -0.5882624 0.06114161 -0.8811343 -0.4688968 -0.03531849 -0.7810332 -0.6234899 -0.2182325 -0.8579154 -0.4651406 -0.2774574 -0.8141424 -0.5100878 -0.3877105 -0.8453905 -0.3674176 -0.5663429 -0.7376676 -0.3675628 -0.5573536 -0.8273591 -0.06952667 -0.4912883 -0.8666445 -0.08696687 -0.5893242 -0.8003997 0.1098058 -0.6024549 -0.7915846 0.102186 -0.4916525 -0.7414886 0.456588 -0.3806843 -0.8792417 0.2863801 -0.3289291 -0.7802373 0.5320107 -0.1699321 -0.8565478 0.4872874 -0.1068711 -0.7552305 0.6466882 0.1981253 -0.7028529 0.6831868 0.1050869 -0.8098538 0.5771428 0.3162793 -0.8170564 0.4820647 0.312653 -0.8777253 0.3631067 0.5294865 -0.7715492 0.3526414 0.4796112 -0.8604208 0.1721896 0.6409457 -0.7622082 0.09070432 0.6089788 -0.7776876 -0.1560348 0.5098024 -0.8403261 -0.1842653 0.4385287 -0.8074933 -0.3945214 0.4779315 -0.7826184 -0.398861 0.274578 -0.7506789 -0.6009061 0.1071413 -0.8452858 -0.5234622 0.05491077 -0.801592 -0.5953447 -0.11995 -0.8849723 -0.4499288 -0.2363093 -0.7955927 -0.5578442 -0.4103114 -0.8252053 -0.3881766 -0.3918203 -0.8587453 -0.3302022 -0.5757907 -0.7868058 -0.222265 -0.4847736 -0.8734388 -0.04581689 -0.6433383 -0.7642024 0.04594045 -0.5652201 -0.7427678 0.3589184 -0.5143808 -0.8147633 0.2675319 -0.3479553 -0.8379276 0.4204815 -0.3361577 -0.8585025 0.3872614 -0.113667 -0.7970798 0.5930799 -0.03734362 -0.870673 0.4904426 0.1878598 -0.7925608 0.5801345 0.2513297 -0.8591372 0.4457765 0.3775429 -0.7780396 0.5021112 0.5967711 -0.7475552 0.2915915 0.5414974 -0.7884066 0.2918831 0.6284884 -0.7778134 0.002948999 0.5603899 -0.8274292 -0.03638666 0.4534401 -0.8621578 -0.2260005 0.4899205 -0.8288097 -0.2702822 0.4967008 -0.6845459 -0.533559 0.290748 -0.8426633 -0.4531933 0.08201926 -0.8121838 -0.5776075 0.08790814 -0.8278397 -0.5540338 -0.12949 -0.8156111 -0.5639246 -0.1488813 -0.8364893 -0.5273708 -0.3492997 -0.7263041 -0.5920068 -0.4684916 -0.777444 -0.4196389 -0.5051932 -0.7551834 -0.4177054 -0.5623578 -0.8135707 -0.1478394 -0.5333712 -0.8323969 -0.1504348 -0.6405483 -0.7615519 0.09867441 -0.5153153 -0.8453481 0.1408436 -0.5108295 -0.7398761 0.4377634 -0.3074615 -0.8452931 0.436975 -0.2759731 -0.7755191 0.5678108 -0.1425259 -0.8452474 0.5150177 -0.007112145 -0.7546098 0.6561353 0.1787202 -0.8451467 0.5037721 0.2500276 -0.7867966 0.5643027 0.4173168 -0.8068696 0.4181007 0.4016878 -0.8413909 0.3615361 0.6143159 -0.756282 0.2250637 0.5270885 -0.849182 0.0326758 0.6129001 -0.788943 -0.04384517 0.4622696 -0.8724963 -0.1582942 0.5395054 -0.7686046 -0.3437747 0.3006497 -0.8728612 -0.3843479 0.3260274 -0.7991486 -0.5050423 0.08196604 -0.7941241 -0.602203 -0.04697906 -0.889191 -0.4551179 -0.1252458 -0.8277482 -0.546943 -0.3231477 -0.82474 -0.4640901 -0.323152 -0.886879 -0.3301795 -0.542186 -0.7598301 -0.3587377 -0.5717156 -0.7997998 -0.1829249 -0.4166581 -0.908867 -0.01889383 -0.5454202 -0.8350615 0.07203674 -0.5277328 -0.8071579 0.2645642 -0.4894351 -0.8424858 0.2251021 -0.3388348 -0.8227392 0.4563896 -0.3544707 -0.8127976 0.4622885 -0.1218609 -0.740893 0.6604753 -0.03115445 -0.8221415 0.5684302 0.276578 -0.7199141 0.6365755 0.1697855 -0.8358396 0.5220586 0.4036102 -0.7418518 0.5354949 0.4495851 -0.8521188 0.2678931 0.5921236 -0.7576531 0.2745025 0.5152552 -0.8562279 -0.0372278 0.5781138 -0.8132443 -0.0664702 0.4678041 -0.8203703 -0.3288649 0.5944061 -0.7313508 -0.3343762 0.3317455 -0.7769036 -0.5351315 0.1879971 -0.8562209 -0.481189 0.09777069 -0.7594591 -0.6431662 -0.07548397 -0.8787038 -0.4713616 -0.2182152 -0.7851161 -0.5796335 -0.2987559 -0.8675426 -0.3976367 -0.4710333 -0.7648339 -0.4394962 -0.4626471 -0.845446 -0.2667934 -0.6791669 -0.7141754 -0.1693692 -0.5622882 -0.8255937 0.04719179 -0.6387907 -0.7587428 0.1274985 -0.4121778 -0.850891 0.3257206 -0.4547164 -0.792866 0.405705 -0.2430776 -0.8199846 0.5182071 -0.2977418 -0.7751943 0.5571568 0.06102716 -0.794467 0.6042333 0.08393365 -0.7581101 0.6467027 0.2488095 -0.8536645 0.4575487 0.3548335 -0.7853427 0.5072771 0.5174296 -0.7762095 0.3602299 0.4906225 -0.8237146 0.2842254 0.6696916 -0.7417157 0.03702783 0.6307538 -0.774345 0.05039453 0.6022422 -0.7705166 -0.2088267 0.5827502 -0.7838932 -0.214275 0.4327213 -0.7713203 -0.466709 0.4243014 -0.7941061 -0.4351598 0.2379742 -0.7640116 -0.5997122 0.1572257 -0.8230596 -0.5457593 -0.0753141 -0.7626594 -0.6424006 -0.08249247 -0.7710301 -0.631433 -0.3245205 -0.7706156 -0.5484873 -0.3317011 -0.8620168 -0.3832775 -0.5538712 -0.7595474 -0.3410493 -0.4714149 -0.8731027 -0.1243373 -0.5685405 -0.8178485 -0.08880192 -0.5499933 -0.8351348 -0.007572412 -0.6609768 -0.7292019 0.1771277 -0.4353762 -0.833548 0.3400669 -0.436442 -0.8320448 0.3423739 -0.349298 -0.796903 0.492886 -0.2780233 -0.8354651 0.4740267 -0.189589 -0.7557604 0.6268031 0.06001073 -0.8180082 0.5720677 0.05379021 -0.8250077 0.5625557 0.2656614 -0.8705671 0.4141702 0.2521932 -0.8285159 0.4999601 0.4894992 -0.7529506 0.4398363 0.4518333 -0.8808504 0.1412426 0.5236992 -0.822982 0.2200905 0.5260916 -0.8458613 -0.08801364 0.5650259 -0.8217131 -0.07438671 0.4593896 -0.8201113 -0.3411434 0.3231178 -0.8875325 -0.3284525 0.2936249 -0.7825068 -0.5490606 0.1281721 -0.8667872 -0.4819251 0.007167458 -0.7234905 -0.6902971 -0.2327629 -0.7938148 -0.5618538 -0.1960003 -0.8237278 -0.5320305 -0.4195409 -0.8525596 -0.311653 -0.3601768 -0.8880055 -0.2858656 -0.6442478 -0.7486806 -0.1562759 -0.4846723 -0.8734061 0.04748183 -0.581019 -0.8056842 0.1152818 -0.3546661 -0.8588631 0.3695487 -0.3369519 -0.8785211 0.338621 -0.2646287 -0.7716201 0.5784239 -0.08470821 -0.8594073 0.5042259 0.07883638 -0.6660971 0.7416869 0.2451867 -0.8844528 0.3970224 0.5202921 -0.6977401 0.4923971 0.4387457 -0.8628271 0.2510611 0.6652818 -0.7345031 0.1338114 0.5216309 -0.8478392 -0.09523665 0.5279241 -0.843251 -0.1011139 0.4319202 -0.8497236 -0.3023488 0.3875887 -0.8678319 -0.3108744 0.4201338 -0.742864 -0.5211917 0.2058548 -0.8191347 -0.5353897 0.1160678 -0.7181758 -0.6861136 -0.08021485 -0.8398738 -0.5368219 -0.1735168 -0.7720106 -0.6114669 -0.39485 -0.8215466 -0.4112841 -0.429252 -0.7950735 -0.428487 -0.4900952 -0.8437643 -0.2187889 -0.453561 -0.8762396 -0.162747 -0.6226998 -0.7823605 -0.01254028 -0.5673264 -0.8052598 0.1723298 -0.5652656 -0.8070569 0.1706873 -0.4405406 -0.8024489 0.4024921 -0.2753414 -0.8885275 0.3670232 -0.2467954 -0.8011046 0.5452739 -0.05338126 -0.8513117 0.5219377 -0.01824992 -0.8021173 0.5968876 0.2023727 -0.7709614 0.603874 0.2498437 -0.8103225 0.5300526 0.4387764 -0.7253422 0.5304282 0.4412972 -0.8145706 0.3764726 0.6348925 -0.7244262 0.2685484 0.5480711 -0.831585 0.08991372 0.6552745 -0.7553908 -5.60274e-4 0.5435144 -0.80567 -0.2355592 0.5781642 -0.7826896 -0.2304852 0.3738208 -0.753118 -0.5413606 0.3574041 -0.802086 -0.4784562 0.09099239 -0.8416315 -0.5323317 0.0983802 -0.8604151 -0.5000075 -0.1468032 -0.7103756 -0.6883425 -0.2610645 -0.8660175 -0.4264495 -0.419814 -0.7814673 -0.4615898 -0.5096323 -0.7891069 -0.3429071 -0.4441565 -0.8664593 -0.2279768 -0.6393529 -0.765977 -0.06713563 -0.5472308 -0.8367506 0.01967257 -0.5530827 -0.8132207 0.1810297 -0.4499041 -0.8674936 0.2122296 -0.4440802 -0.8074022 0.3884516 -0.3152428 -0.8659299 0.3883135 -0.2518489 -0.7730687 0.582183 -0.07346814 -0.8830677 0.4634585 0.0543785 -0.7663268 0.6401456 0.2569476 -0.8692463 0.4223609 0.2654969 -0.7852949 0.5593062 0.5550115 -0.7883711 0.265393 0.4799045 -0.8408285 0.2503984 0.6264833 -0.7789656 -0.02704572 0.5625316 -0.8244947 -0.0613743 0.6017276 -0.7457606 -0.285946 0.3780254 -0.8464174 -0.375066 0.3960921 -0.7813392 -0.482307 0.1531304 -0.8764248 -0.4565422 0.09929835 -0.7224334 -0.6842733 -0.1746215 -0.8849071 -0.4317951 -0.2866505 -0.7828893 -0.5521918 -0.4992253 -0.8151337 -0.2938216 -0.4372527 -0.8781181 -0.194213 -0.6304677 -0.7752972 -0.03774815 -0.5325202 -0.8455804 0.03763216 -0.4253445 -0.8257262 0.3704841 -0.6323399 -0.7144158 0.2995937 -0.392279 -0.817643 0.421399 -0.2155288 -0.9023838 0.3731636 -0.1678956 -0.7866218 0.5941695 0.05564409 -0.843 0.5350278 0.07599526 -0.8711778 0.4850504 0.3208132 -0.790125 0.5222848 0.3316044 -0.8633693 0.3803052 0.5354595 -0.7561272 0.3762377 0.6171112 -0.7798023 0.1052722 0.5008795 -0.8569946 0.1211614 0.5930984 -0.7966455 -0.1165775 0.451536 -0.8691666 -0.2016551 0.5196197 -0.7931182 -0.3177404 0.3378803 -0.7828141 -0.5225315 0.3457141 -0.6985405 -0.6265165 0.02990365 -0.8287572 -0.558809 -0.06563925 -0.7238044 -0.6868761 -0.2819684 -0.8293654 -0.4823348 -0.2949956 -0.8198461 -0.4907444 -0.4755003 -0.8092769 -0.3449211 -0.4213415 -0.8820245 -0.2109597 -0.5952506 -0.7906241 -0.143494 -0.5295487 -0.846034 0.06168234 -0.5065029 -0.8591697 0.07268035 -0.5198692 -0.798999 0.3022198 -0.3549509 -0.8871726 0.294847 -0.2970735 -0.7391387 0.604501 -0.07194566 -0.8952789 0.4396585 0.05679154 -0.7581357 0.6496193 0.2381795 -0.8702491 0.4312043 0.2839071 -0.8393189 0.4636168 0.4666703 -0.7905235 0.3966 0.4340994 -0.8725248 0.2241832 0.5696398 -0.7998045 0.1892703 0.5172163 -0.8555749 0.02188426 0.6565675 -0.7496706 -0.08314514 0.5601926 -0.7726774 -0.2985867 0.5930923 -0.7112785 -0.3772592 0.3412316 -0.8348127 -0.4320288 0.2961964 -0.7554187 -0.5844745 0.1299541 -0.8250377 -0.5499317 0.03087466 -0.7172678 -0.6961134 -0.1471316 -0.8233527 -0.5481266 -0.2990632 -0.734124 -0.609609 -0.3713828 -0.8161071 -0.4427686 -0.4659686 -0.7617881 -0.4500582 -0.5886445 -0.7803381 -0.2111165 -0.5631259 -0.7984959 -0.2128232 -0.5514949 -0.8312682 0.0696184 -0.5659832 -0.8219195 0.06412112 -0.3900313 -0.8429286 0.3706038 -0.5565711 -0.7653777 0.3231499 -0.3763685 -0.7945876 0.4764215 -0.2143796 -0.8485438 0.483751 -0.1907303 -0.7904983 0.582009 0.009811997 -0.8834325 0.4684559 0.1469137 -0.7692488 0.6218301 0.2333737 -0.8250373 0.5146361 0.3731013 -0.7439576 0.5543668 0.5033212 -0.8130776 0.2925282 0.4217858 -0.8621287 0.2807689 0.6058669 -0.7807579 0.1527833 0.5199083 -0.8537532 0.02830111 0.6687814 -0.7363083 -0.1028665 0.4767292 -0.8271742 -0.29751 0.5173043 -0.7607346 -0.3920193 0.2611984 -0.7969092 -0.544712 0.2610713 -0.7935737 -0.5496203 0.02915698 -0.8706619 -0.4910172 -0.03152221 -0.7925236 -0.6090261 -0.2272095 -0.8229703 -0.5206685 -0.1757109 -0.6624201 -0.7282344 -0.4002343 -0.8592191 -0.3186771 -0.4251059 -0.7945033 -0.4336466 -0.5802401 -0.7925975 -0.1873783 -0.5700218 -0.802623 -0.1757035 -0.5922881 -0.7920953 0.1475805 -0.5763627 -0.8055865 0.1372461 -0.4779909 -0.8138112 0.3305089 -0.4894967 -0.8065464 0.3314752 -0.2401272 -0.7852178 0.5707643 -0.1477008 -0.8542862 0.498377 0.07818889 -0.789076 0.6092992 0.1294891 -0.8486953 0.5127854 0.2887046 -0.7622722 0.5793021 0.4395403 -0.8144586 0.3787632 0.461524 -0.7520755 0.4705083 0.5626858 -0.8010985 0.2040248 0.6624546 -0.7295319 0.1701092 0.5578025 -0.828121 -0.05542755 0.6740918 -0.7137248 -0.1902556 0.4307342 -0.8495051 -0.3046458 0.4433671 -0.7799435 -0.4417168 0.231941 -0.8361634 -0.4970254 0.2314987 -0.79912 -0.5548115 -0.01860958 -0.8229076 -0.5678704 -0.08489328 -0.8787059 -0.4697545 -0.216987 -0.7884866 -0.5755046 -0.3698952 -0.8494126 -0.3763987 -0.3612154 -0.8680716 -0.3405513 -0.56887 -0.7879068 -0.2357752 -0.4979345 -0.8641806 -0.07247996 -0.6037822 -0.796946 -0.01800578 -0.5218135 -0.8418357 0.137926 -0.6056981 -0.7489725 0.2686448 -0.3518905 -0.8400218 0.4129607 -0.3602919 -0.8163651 0.4513733 -0.1521371 -0.8401888 0.5205162 -0.1293352 -0.8538386 0.5042144 0.004879474 -0.7947028 0.6069793 0.05813914 -0.83047 0.5540213 0.2400775 -0.7392938 0.6291324 0.3591204 -0.8029581 0.4757007 0.4544506 -0.7473276 0.4847435 0.4990382 -0.8172438 0.2882248 0.5961495 -0.7560694 0.2701202 0.6060867 -0.795171 0.01902276 0.6403126 -0.7681144 -3.70877e-4 0.5890014 -0.7793307 -0.2138249 0.4933505 -0.8323538 -0.252572 0.5043005 -0.7392014 -0.4463881 0.326013 -0.8146884 -0.4795816 0.3085306 -0.7793822 -0.5453186 0.1114156 -0.7963482 -0.5944882 0.02896523 -0.8490073 -0.5275868 -0.06208759 -0.7950475 -0.6033611 -0.2208742 -0.8513947 -0.4757537 -0.2325235 -0.8842479 -0.4050166 -0.4811407 -0.7511742 -0.4519305 -0.4247378 -0.8934404 -0.146158 -0.6135932 -0.7795914 -0.1254628 -0.5396186 -0.8244834 0.1704083 -0.4339822 -0.8817765 0.1847427 -0.4068183 -0.8078291 0.4265104 -0.5030058 -0.7438932 0.4400092 -0.1497805 -0.8048481 0.5742694 -0.1550606 -0.8393574 0.5209946 0.04058682 -0.8228089 0.5668671 0.1029189 -0.8678678 0.4860178 0.2236808 -0.8048428 0.5497227 0.3575271 -0.8621137 0.3590745 0.3445744 -0.8699651 0.3527452 0.5930319 -0.7726957 0.2263949 0.448061 -0.8938052 0.01880884 0.557705 -0.8292841 -0.03539931 0.5935482 -0.7671456 -0.2432863 0.3743239 -0.8806455 -0.2904222 0.405808 -0.8146769 -0.4142722 0.184278 -0.8574602 -0.4804204 0.173646 -0.7808974 -0.6000387 -0.02127796 -0.8678966 -0.4962891 -0.1900196 -0.7345261 -0.6514322 -0.3299682 -0.8210168 -0.4658889 -0.3866575 -0.7927118 -0.4712791 -0.4721143 -0.8124403 -0.3421241 -0.4229544 -0.8735818 -0.2407581 -0.6213815 -0.7714699 -0.1368193 -0.5194787 -0.8535215 0.04053449 -0.5380642 -0.8412601 0.05261415 -0.5000218 -0.8194136 0.2802495 -0.520394 -0.8075509 0.2775818 -0.448032 -0.7326866 0.5122867 -0.2124584 -0.8425948 0.4948693 -0.175525 -0.7167972 0.674828 0.0411902 -0.855048 0.5169103 0.2346748 -0.6922076 0.6824782 0.3305292 -0.8233863 0.4612868 0.4322555 -0.7740916 0.4625337 0.537776 -0.8070617 0.2438206 0.5355846 -0.8084768 0.2439559 0.5424083 -0.8382149 -0.05647188 0.6650565 -0.7428403 0.07673454 0.6014579 -0.7836041 -0.1556056 0.4233748 -0.8628901 -0.2759972 0.4498887 -0.826274 -0.3389269 0.3165951 -0.8259844 -0.4663877 0.2758457 -0.8485507 -0.4515205 0.1583966 -0.7950029 -0.5855604 -0.004515051 -0.9020421 -0.4316247 -0.2033047 -0.7896206 -0.5789359 -0.2242982 -0.8529303 -0.4713812 -0.4265097 -0.8139095 -0.3945135 -0.4092416 -0.8620198 -0.2990708 -0.5747057 -0.7946963 -0.1953747 -0.5665423 -0.8031699 -0.18425 -0.6063308 -0.7902928 0.08831948 -0.6149861 -0.7841565 0.08301222 -0.5474126 -0.7726556 0.3214697 -0.3508979 -0.8714287 0.3427577 -0.366063 -0.7767933 0.5124354 -0.1080834 -0.8513855 0.5132843 -0.2329151 -0.7412964 0.6294683 0.1016712 -0.7578344 0.6444766 0.1313483 -0.8078875 0.5745134 0.3877434 -0.7739148 0.5007105 0.3823984 -0.8658289 0.3226639 0.4938788 -0.8151822 0.3025918 0.4998637 -0.8613581 0.09054732 0.5632712 -0.8228351 0.07528704 0.5520927 -0.8202271 -0.1497374 0.4713703 -0.8641613 -0.176169 0.453613 -0.8020529 -0.3885182 0.3377263 -0.8624064 -0.3770892 0.2680927 -0.8165241 -0.5112873 0.1121191 -0.8782765 -0.4648222 0.04065519 -0.7757232 -0.6297625 -0.1709477 -0.8635439 -0.4744143 -0.2192274 -0.8223368 -0.5250729 -0.4191983 -0.8027178 -0.4241662 -0.3903871 -0.8850992 -0.2533724 -0.574633 -0.7854571 -0.2299001 -0.4310146 -0.9023255 -0.005935788 -0.5745598 -0.8064881 0.1394922 -0.4878863 -0.8512004 0.1934551 -0.5150846 -0.8120043 0.2744759 -0.2949572 -0.8729225 0.3885957 -0.751651 -0.3246201 0.5741453 -0.04647439 -0.9153252 0.4000248 -0.4266828 -0.4064009 0.8079482 0.07340103 -0.8764441 0.4758763 0.3619619 -0.2546689 0.8967315 0.5987874 0.2481572 -0.761493 0.09048169 -0.4475495 -0.88967 -0.03473645 0.5924647 -0.8048473 -0.4730529 -0.3266402 -0.8182464 -0.4749337 0.6074185 -0.6367737 -0.6499381 -0.7431068 -0.1592885 -0.3860829 0.8826613 0.2680469 -0.1048979 -0.8235961 0.5573923 0.09346061 0.6970477 0.7109076 0.4167701 -0.644995 0.6405342 0.5401993 0.7152978 0.4433215 0.9347969 -0.3489021 0.06649941 0.8251688 0.07375454 -0.5600506 -0.3657757 -0.4965656 -0.7871664 -0.6808884 0.4402484 -0.5852968 -0.8153795 -0.1972886 -0.5442733 -0.9898642 -0.1183273 -0.07853394 -0.8527452 0.5216052 -0.02745026 -0.7836665 -0.4800224 0.3942656 -0.6306745 0.5830318 0.5121754 -0.6442419 -0.1750061 0.7445303 -0.1892178 -0.0118395 0.9818638 0.2229686 0.525811 0.8208581 0.5942366 -0.5863702 0.5505025 0.6760023 0.604882 0.4208785 0.8459419 -0.4940047 0.200853 0.8335468 0.55202 -0.0217697 0.7320293 -0.6102219 -0.302923 0.6117334 0.6613101 -0.4341096 0.4478533 -0.584197 -0.6768614 0.1811093 0.4424188 -0.8783308 -0.4543662 -0.8502596 -0.2657252 -0.5869734 -0.219165 0.7793773 -0.1354002 0.4587754 0.8781754 0.04266291 -0.5934889 0.8037108 0.448186 0.5106765 0.7337158 0.6105259 -0.2873227 0.7380406 0.9200431 0.2426607 0.3076304 0.9592529 -0.009163379 0.2824004 0.9113057 -0.1069082 -0.3976087 0.7672981 0.5255928 -0.3674316 0.3469536 -0.6603367 -0.666017 -0.7059371 -0.5794841 -0.4072481 -0.7735777 0.6336774 0.005524873 -0.6848689 -0.6924538 0.2268532 -0.547266 0.7237161 0.4203987 -0.2799599 0.2254087 0.9331738 0.3504511 -0.4421254 0.8256569 0.8731444 0.4219838 0.2440257 0.9006434 -0.2717202 -0.3391308 0.5260697 0.6655344 -0.5294476 0.1337667 -0.6715173 -0.7288148 0.01752299 0.5797318 -0.814619 -0.3806822 -0.3594773 -0.8519726 -0.4568765 0.3705545 -0.8086739 -0.6713455 -0.5764474 -0.4658366 -0.6201702 0.733379 -0.2784678 -0.6534484 -0.7538924 0.06820237 -0.7220152 0.650864 0.2346704 -0.631591 -0.4826188 0.6067717 -0.5909098 0.380726 0.7112477 -0.248374 -0.4441165 0.8608548 -0.08125889 0.5901806 0.8031712 0.1735458 -0.5391021 0.8241667 0.4644717 0.4873687 0.7394172 0.5819718 -0.6372289 0.5052209 0.7002234 0.5954982 0.3937882 0.7374473 -0.6722198 -0.06551325 0.6590935 0.6336368 -0.4050929 0.2789673 -0.5683348 -0.7740625 0.2123826 0.502496 -0.8380881 -0.2071828 -0.3838865 -0.8998369 -0.296158 0.4376855 -0.8489534 -0.5708603 -0.6420314 -0.5117756 -0.7182365 0.6413272 -0.2698816 -0.7495291 -0.6452495 0.1478491 -0.8116155 0.1240966 0.5708593 -0.3030214 0.1311569 0.9439153 0.2024289 -0.8297756 0.5200914 0.4034512 0.6761201 0.6165135 0.7323974 -0.6323248 0.2525063 0.8448338 0.5251222 -0.1024819 0.6133056 -0.5817655 -0.5342333 0.3773784 0.08660769 -0.9220004 -0.142759 0.3578748 -0.9227923 -0.2689766 -0.5397942 -0.7976678 -0.6125659 0.464067 -0.6398475 -0.7440987 -0.3401324 -0.575002 -0.9068013 0.4155125 -0.0711404 -0.5121212 -0.7859047 0.3465343 -0.6136149 0.5135897 0.5997519 -0.2504606 -0.3852927 0.888155 -0.1618492 0.4627459 0.8715912 0.1767261 -0.4903852 0.8533993 0.3523561 0.7105399 0.6090798 0.7589519 -0.6511464 7.58211e-4 0.7939268 0.5343361 -0.2901124 0.4516102 -0.7568077 -0.4725361 0.3080045 0.4191541 -0.8540744 -0.2866122 -0.2401866 -0.9274502 -0.9119849 -0.2122637 -0.3510382 -0.9515462 -0.1471282 0.2700246 -0.7016693 0.2564156 0.6647641 -0.2313583 0.005246102 0.9728546 0.1761632 -0.03870683 0.9835997 0.7334418 -0.1901053 0.6526279 0.9210423 -0.3393934 0.1910323 0.8593837 0.4743722 -0.1908692 0.6901162 -0.6129453 -0.3847566 0.5311628 0.665704 -0.5241224 0.2649001 -0.7290192 -0.6311569 0.02677267 0.7063598 -0.7073466 -0.2279763 -0.5665519 -0.7918622 -0.4942061 0.5796527 -0.6478913 -0.6948309 -0.345174 -0.6309239 -0.9814925 -0.09893637 -0.1639639 -0.9830191 0.0969246 -0.1558171 -0.8940346 0.2612262 0.3639548 -0.7575752 -0.4772605 0.4453116 -0.4925686 0.5571302 0.6685672 0.6575824 0.4471784 0.6063142 0.842243 -0.5193681 0.1445114 0.792783 0.608397 0.03672075 0.6433506 -0.6715348 -0.3676155 0.4925937 -0.2097905 -0.8445942 -0.04831779 0.3293598 -0.9429674 -0.1997026 -0.6366143 -0.7448766 -0.4119386 0.5751526 -0.7067574 -0.6220904 -0.7024269 -0.3458322 -0.6749875 0.6650736 0.3194822 -0.3565847 -0.6365723 0.6838297 0.01873475 -0.5674744 0.8231779 0.3920739 0.5751258 0.7179892 -0.3834816 0.536602 -0.7516651 -0.7179694 -0.5546934 -0.4205178 -0.7813383 0.5439174 -0.3060463 -0.7984145 -0.6007953 0.03973913 -0.7874181 0.5013195 0.3586803 -0.467229 -0.2770138 0.8396193 -0.02526974 -0.3026211 0.9527759 0.4034324 0.4286391 0.8084002 0.5315295 -0.4037287 0.7446339 0.8720346 0.1932196 0.4496909 0.8913144 -0.2643175 0.3683679 0.8787951 0.4763098 -0.02912229 0.87228 -0.4473067 -0.1975963 0.759597 0.165647 -0.6289465 0.7510364 0.2115802 -0.6254423 0.2400226 -0.07891541 -0.9675545 -0.2598249 -0.4839491 -0.8356341 -0.7122577 0.2925957 -0.6380258 -0.7237488 0.2566667 -0.6405545 -0.909369 -0.4025114 -0.1050367 -0.8006718 0.5987716 -0.01993101 -0.7566813 -0.5438143 0.3629046 -0.5896386 0.6502809 0.479021 -0.5563976 -0.3725268 0.7427285 -0.1513071 -0.07103884 0.9859309 0.3643255 -0.1402218 0.9206546 0.840166 0.2598047 0.4760488 0.9327729 -0.3572757 -0.04784303 0.7249017 0.391829 -0.5665577 -0.3690451 0.6998314 -0.6115895 -0.7285726 -0.453616 -0.5132392 -0.7446479 0.6189761 -0.249736 -0.8794106 -0.439572 0.1827939 -0.6591039 0.2663943 0.7032895 -0.6210758 -0.1814864 0.7624483 -0.08974069 0.2776063 0.9564943 0.4166025 -0.7026352 -0.5768417 0.1238803 0.7155728 -0.6874659 -0.3786808 -0.3306494 -0.8644489 -0.7699521 0.3989937 -0.4979737 -0.9286512 -0.3576204 -0.09856355 -0.8943545 0.316915 0.3157454 -0.7089015 -0.5563564 0.4335045 -0.6162867 0.5016003 0.6071144 -0.3429224 -0.4139115 0.8432565 -0.2384126 0.4704849 0.8495901 0.1023414 -0.5597729 0.822302 0.3025063 0.7026714 0.6440054 0.832603 0.1160996 0.5415654 0.8886356 -0.446751 -0.1036356 0.7477608 0.4812313 -0.4574607 0.4012787 0.04450821 -0.914874 0.3671206 -0.1698849 -0.9145281 -0.1678711 -0.2601357 -0.9508674 -0.1828653 0.6761301 -0.7137285 -0.5469022 -0.6914079 -0.4720734 -0.666374 0.6262732 -0.4046326 -0.898099 -0.4183307 -0.1357128 -0.7746819 0.6267111 0.08426904 -0.6173105 -0.6547662 0.4361296 -0.4894307 0.6067241 0.6263732 -0.2092446 -0.6796996 0.7030116 0.02318698 0.6623883 0.7488019 0.2775352 -0.4791599 0.8326944 0.5701429 0.5054934 0.6476215 0.8331053 -0.5166553 0.1974913 0.7702244 0.5475245 -0.3270646 -0.351933 -0.5814637 -0.7335143 -0.7023117 0.5399048 -0.4639624 -0.8009042 -0.5090709 -0.3152768 -0.9099915 0.414294 0.01661849 -0.8260872 -0.5255324 0.2034596 -0.6550322 0.6346746 0.4100258 -0.3628141 -0.7684344 0.5271382 -0.1960728 0.7751143 0.6006274 0.1393572 -0.7332486 0.665527 0.3038364 0.5863288 0.7509341 0.6357069 -0.5743649 0.5157344 0.7587434 0.4181224 0.4994818 0.9567413 -0.2906332 0.01336199 -0.7180129 -0.6252656 -0.3057784 -0.8157941 0.5700077 0.09783333 -0.6372832 -0.5927522 0.4924582 -0.4297631 0.5082813 0.7462934 -0.1746494 -0.5041031 0.8458001 -0.08193439 0.3309671 0.9400785 0.3587746 -0.5685045 0.7403267 0.7290894 -0.4284017 0.5337609 0.8230676 0.5659484 0.04756444 0.4219883 -0.5559434 -0.7161374 0.1483545 0.5041094 -0.8508025 -0.1425929 -0.7441881 -0.652573 -0.4871615 0.5666382 -0.6645261 -0.8085223 -0.5325713 -0.2503188 -0.8551847 0.5165511 0.04282635 -0.6448631 -0.6146501 0.4542654 -0.4326282 -0.05141746 0.9001051 0.2440493 -0.1519818 0.9577795 0.5462042 -0.1100829 -0.8303871 0.01066911 -0.2223635 -0.9749056 -0.05231678 0.5418291 -0.838859 -0.4053784 -0.4827309 -0.7762985 -0.5221596 0.5776779 -0.6274055 -0.6614131 -0.6500074 -0.3741966 -0.752089 0.6270995 -0.2027524 -0.6961048 -0.692709 0.1886595 -0.6536055 0.5748478 0.4922904 -0.3941357 -0.4885276 0.7784586 -0.3162124 0.3955923 0.8622739 0.1354762 -0.4104373 0.901769 0.2359549 0.4329481 -0.8699892 -0.2999629 -0.5004124 -0.8121637 -0.3624763 0.4172607 -0.8333695 -0.9038625 -0.1341365 -0.4062513 -0.8139118 0.3834545 -0.4364748 -0.847162 -0.5222063 0.09806811 -0.7614475 0.6106681 0.2174446 -0.5419335 -0.6863356 0.4850274 -0.3518418 0.6802951 0.6429665 -0.05447632 -0.5481946 0.8345747 0.08200579 0.5118126 0.8551743 0.5149488 -0.5101314 0.6889076 0.6121014 0.2718112 0.7425972 0.9468061 -0.2642456 0.1836637 0.9075897 0.3940888 0.1448271 0.7707089 -0.4698247 -0.430433 0.8131895 0.2912306 -0.5038924 0.4329461 0.06489729 -0.8990808 0.3133767 -0.4430276 -0.8399534 -0.05927449 0.5292499 -0.8463931 -0.4064783 -0.5786623 -0.707054 -0.6614762 0.5767297 -0.4794082 -0.8688156 0.4831652 -0.1082182 -0.7177486 -0.5696296 0.4004487 -0.4900193 -0.3112098 0.8142663 0.08613026 -0.1568818 0.9838545 0.7987185 -0.6015291 -0.01454526 0.7863944 0.4716496 -0.3989116 0.6453204 -0.5048495 -0.5733138 0.5398448 0.4480816 -0.7125943 0.1724025 -0.6136846 -0.7704991 0.1022259 0.4046072 -0.9087591 -0.3453435 0.182726 -0.9205157 -0.3807618 -0.6888507 -0.6168511 -0.6092172 0.5546988 -0.5667132 -0.8592754 -0.4457034 -0.2509868 -0.7710906 0.4228536 0.4760401 -0.2761297 -0.575295 0.7699273 0.4323757 0.6716463 0.6016167 0.7486367 -0.6063129 0.2681934 0.9229635 0.2854107 0.2582235 0.9485732 0.1816789 -0.2592332 0.7500118 -0.5734626 -0.32958 0.6539222 0.4763279 -0.5877904 0.3819651 -0.5742949 -0.7240775 0.3065629 0.4551596 -0.8359719 -0.1344372 -0.4109399 -0.9016957 -0.210096 0.4705591 -0.8569912 -0.5332675 -0.5679721 -0.6269239 -0.5901761 0.6305015 -0.504143 -0.7817125 -0.6073065 -0.1417897 -0.9915745 0.05581325 -0.1168981 -0.8753677 0.4025511 0.2677388 -0.606359 -0.6973889 0.3820701 -0.0510469 -0.02017027 0.9984926 0.3320229 0.1171479 0.9359686 0.4752812 -0.5116084 0.7157965 0.6817314 0.2263395 0.6957104 0.855745 -0.3102328 0.4140727 0.9147582 0.1478151 0.3759895 0.9046242 -0.4087883 -0.1206113 -0.4767957 -0.2860901 -0.8311548 -0.3282673 0.9171398 -0.2260427 -0.8777633 -0.4431844 0.1819871 -0.6002366 0.7973024 -0.06344181 -0.542152 0.7654445 0.34665 -0.5339607 0.7786878 0.3294412 -0.4262478 0.8435703 0.3266527 -0.2428936 0.7614049 0.6010534 -0.09406369 0.8729786 0.4786028 -0.00828886 0.7952732 0.6061947 0.2008652 0.8121547 0.5477754 0.2130745 0.8727939 0.4391242 0.4079011 0.7887053 0.4599575 0.4127937 0.8264195 0.3829257 0.6300782 0.7246256 0.2791404 0.50139 0.8645547 0.03396147 0.6253207 0.7787342 -0.05047011 0.4835374 0.8457409 -0.2256413 0.5116544 0.8102145 -0.2859414 0.4162505 0.7406663 -0.5273984 0.2981498 0.8214193 -0.4861864 0.111271 0.7344492 -0.6694798 0.03520888 0.8153081 -0.577956 -0.2147506 0.7568967 -0.6172435 -0.2370783 0.8476608 -0.4746208 -0.4427355 0.8013174 -0.402338 -0.406569 0.8530186 -0.3272019 -0.5631771 0.8122453 -0.1519513 -0.4994724 0.8622173 -0.08431327 -0.6143452 0.7875905 0.04776167 -0.4802404 0.8535752 0.2019371 -0.5219926 0.8284431 0.2029925 -0.3693118 0.8582742 0.3563346 -0.3859462 0.7980067 0.4628508 -0.1925088 0.8505421 0.4894062 -0.1464103 0.7828165 0.6047829 0.07342272 0.8538214 0.5153622 0.181344 0.7477499 0.6387367 0.356904 0.7994666 0.4831904 0.344649 0.8490986 0.4003107 0.5332018 0.7864886 0.3116596 0.4507033 0.877722 0.1626978 0.6049705 0.7938614 0.06160259 0.512605 0.840862 -0.173745 0.4738202 0.8707409 -0.1315483 0.4060739 0.8042156 -0.433983 0.3398146 0.847733 -0.4072775 0.2160314 0.8029497 -0.5555197 0.178352 0.8306831 -0.527405 -0.04250514 0.7483616 -0.6619277 -0.1499945 0.838631 -0.5236409 -0.2692443 0.7691074 -0.579639 -0.4260178 0.7754811 -0.4659806 -0.4059016 0.8518235 -0.3311206 -0.5985464 0.7469095 -0.2896005 -0.5477613 0.8353697 -0.04599112 -0.6886768 0.7220679 0.06589573 -0.5393621 0.7981826 0.2683156 -0.5509942 0.7746185 0.310438 -0.3289387 0.8354425 0.4402672 -0.3277606 0.8413498 0.4297716 -0.1697723 0.7799439 0.6023827 -0.0366761 0.8888456 0.4567365 0.1412165 0.7530169 0.6426691 0.2939789 0.8567442 0.423752 0.2962063 0.8520076 0.4316769 0.5180684 0.8071776 0.2829657 0.4542058 0.8731595 0.1768887 0.6342877 0.7688819 0.08062213 0.5390604 0.8060443 -0.2443488 0.465927 0.8713151 -0.1540202 0.3279601 0.8467506 -0.4188744 0.3640687 0.8204026 -0.4409011 0.09894609 0.7617273 -0.6402979 0.04689818 0.8266012 -0.5608307 -0.2310503 0.7544093 -0.614396 -0.2552465 0.8219496 -0.5091642 -0.4538224 0.7586216 -0.467481 -0.4316434 0.866741 -0.2498884 -0.6000812 0.7684739 -0.2221494 -0.5784391 0.8141939 0.04996472 -0.4589647 0.8845422 0.08328729 -0.5635384 0.7669616 0.3069111 -0.320063 0.8639121 0.3888648 -0.6222333 0.5631568 0.5437648 -0.1421896 0.8329903 0.5347051 -0.1448789 0.8377816 0.5264335 0.08599567 0.826453 0.5563994 0.09513062 0.848025 0.521348 0.2940496 0.852571 0.432039 0.5846598 0.605778 0.5396351 0.6198326 0.7080476 0.3383435 0.4946009 0.8584785 0.1355899 0.6473506 0.761436 -0.03394901 0.5281022 0.8446587 -0.08752042 0.5891904 0.7387826 -0.3271926 0.3731701 0.8432605 -0.3868537 0.3672589 0.8065955 -0.4631682 0.1943337 0.8387095 -0.5087249 0.1486994 0.8729445 -0.4646036 -0.005740284 0.7761368 -0.6305385 -0.1528494 0.8708913 -0.4671034 -0.2795061 0.7932421 -0.5409653 -0.3934489 0.8335033 -0.3879052 -0.3713939 0.8686339 -0.3279358 -0.5751016 0.7827104 -0.2379551 -0.506889 0.8613806 -0.03297042 -0.4796872 0.877182 -0.0212565 -0.5992512 0.7671989 0.2287006 -0.3864979 0.8682699 0.3110094 -0.4065229 0.8567477 0.3173684 -0.2763888 0.804015 0.5264686 -0.1884939 0.8669404 0.4613939 0.07330691 0.7790488 0.622663 0.0456739 0.8173979 0.57426 0.3246996 0.8187013 0.4736015 0.2948014 0.8939759 0.3374897 0.5629968 0.7633848 0.3166677 0.5112214 0.8586516 0.03701645 0.5995857 0.7971476 0.07108426 0.5643148 0.7479743 -0.3494042 0.4982923 0.8291714 -0.2533371 0.3832581 0.7803633 -0.4941118 0.2031159 0.8963267 -0.3941351 0.1062198 0.791803 -0.6014695 -0.06332844 0.8621063 -0.5027547 -0.155782 0.7946251 -0.5867734 -0.2804138 0.8575369 -0.4312757 -0.3877809 0.7988449 -0.459862 -0.6569928 0.7141035 -0.2416958 -0.4467397 0.8549748 -0.263518 -0.6139219 0.782414 -0.1045395 -0.5288003 0.8483443 -0.02611696 -0.6423932 0.7500211 0.157478 -0.4350812 0.8469444 0.3055971 -0.4821338 0.754466 0.4453406 -0.2170481 0.8640826 0.4541493 -0.1700207 0.7586879 0.6288767 0.07838809 0.9058738 0.4162308 0.1779884 0.8260304 0.534784 0.3797299 0.7374119 0.5585955 0.4295226 0.8620685 0.2689765 0.4671753 0.8428424 0.2671405 0.6450263 0.7534334 0.1275905 0.5860139 0.8063654 -0.07976609 0.600139 0.7942813 -0.09460675 0.4616792 0.8527292 -0.2443465 0.5103116 0.7764033 -0.369838 0.2396891 0.7794365 -0.578816 0.2424827 0.8660058 -0.4373058 0.03670865 0.7544697 -0.6553075 -0.09297722 0.8895406 -0.4472951 -0.2575955 0.7881711 -0.5589552 -0.3764693 0.8559567 -0.3544136 -0.4443838 0.8175493 -0.3662461 -0.5723723 0.7987814 -0.1853062 -0.4972482 0.8622684 -0.09611308 -0.6434056 0.7640465 0.04756331 -0.4849295 0.8331 0.2660601 -0.4188996 0.8699615 0.2601737 -0.3856422 0.7672295 0.5124831 -0.1816455 0.8710494 0.4563747 -0.1484464 0.8261699 0.5435136 0.03049117 0.8263009 0.562403 0.05090498 0.8541907 0.5174621 0.2700856 0.8083694 0.5230609 0.2704321 0.8116248 0.5178143 0.5358306 0.737271 0.4114817 0.5221544 0.7687585 0.3692765 0.6364219 0.7416282 0.2120257 0.4723669 0.8813828 -0.005828738 0.6155613 0.7784705 -0.1227519 0.4453942 0.8516913 -0.2761269 0.4709896 0.8135048 -0.3411435 0.3503159 0.750483 -0.5604053 0.1744385 0.8528813 -0.4921023 0.08250713 0.768989 -0.6339154 -0.07068914 0.8504031 -0.5213614 -0.1393979 0.8020727 -0.5807304 -0.4070867 0.7721638 -0.487897 -0.4179745 0.7319802 -0.5380542 -0.5491831 0.811497 -0.1996765 -0.450927 0.8673546 -0.2106208 -0.6309005 0.7758239 -0.007865965 -0.5372615 0.8416128 0.05511951 -0.6143123 0.7595682 0.2137207 -0.420394 0.8190867 0.3903411 -0.4267517 0.8044941 0.413125 -0.2895684 0.8224048 0.4896944 -0.2080865 0.8681274 0.4506164 -0.07345998 0.7725536 0.6306859 0.1111022 0.8137516 0.5704951 0.08919334 0.8319897 0.5475745 0.3256331 0.7887954 0.5213107 0.3197404 0.8533259 0.4118268 0.573873 0.7291499 0.3728408 0.5634206 0.8036516 0.191576 0.4595764 0.8834095 0.09152835 0.5841827 0.8095545 -0.05789881 0.4990837 0.8394481 -0.2150406 0.4929795 0.8449792 -0.2073197 0.4173976 0.7865004 -0.4551885 0.2325168 0.8938795 -0.3832956 0.162308 0.7727174 -0.6136482 -0.05516976 0.8393919 -0.5407195 -0.07761251 0.8760417 -0.4759491 -0.2503537 0.8012244 -0.5434728 -0.33916 0.8617119 -0.3773899 -0.3925952 0.8338411 -0.388044 -0.5494388 0.8001486 -0.2405813 -0.4473613 0.8862084 -0.1204266 -0.6783481 0.7322278 0.06071513 -0.4425478 0.8745483 0.1982847 -0.4970174 0.8090018 0.3138313 -0.3710333 0.8424218 0.390717 -0.3418858 0.7319437 0.5893832 -0.09411114 0.8117547 0.5763658 -0.05229938 0.7657566 0.6410005 0.1758149 0.7818881 0.5981138 0.1767235 0.7844295 0.5945075 0.4196023 0.7576251 0.4999381 0.3960525 0.8476614 0.3530054 0.5333797 0.8012971 0.2709785 0.4542241 0.8805812 0.1351195 0.623794 0.7812767 0.02208775 0.4709208 0.8719062 -0.1342139 0.5557517 0.7865108 -0.2693339 0.3791181 0.7893988 -0.482824 0.2532166 0.8725188 -0.4178425 0.1425435 0.7815737 -0.6073089 -0.06498509 0.8713769 -0.4862915 -0.06017446 0.8752991 -0.4798235 -0.2950283 0.7666072 -0.570326 -0.3891177 0.8536958 -0.3461086 -0.3964979 0.8448309 -0.3592358 -0.67544 0.7241601 -0.1391865 -0.5788247 0.8130218 -0.06291002 -0.653777 0.6894701 0.31178 -0.5452721 0.8170908 0.1871922 -0.4291989 0.7954539 0.4278337 -0.3297505 0.8635042 0.3816087 -0.1617435 0.7293239 0.6647749 0.01036489 0.8568974 0.515383 0.1056755 0.7914353 0.6020491 0.2767077 0.8381853 0.4699769 0.2943574 0.7334852 0.6126608 0.4849533 0.8045765 0.3427493 0.5711674 0.7486453 0.3365977 0.5529872 0.8231074 0.129226 0.712019 0.7020927 -0.009745061 0.5261068 0.8367194 -0.1520273 0.5622256 0.7581409 -0.3303402 0.4642959 0.8135414 -0.3501141 0.4097657 0.7403509 -0.5328907 0.2336095 0.8186075 -0.5246984 0.1629853 0.7273318 -0.6666515 -0.0205878 0.8165888 -0.5768525 -0.1718987 0.7397324 -0.6505742 -0.2477889 0.8475973 -0.469233 -0.4226768 0.7689471 -0.4796506 -0.3770325 0.8805776 -0.2871057 -0.582632 0.7864108 -0.2051782 -0.5063779 0.8566563 -0.09859842 -0.6704795 0.736872 0.0864697 -0.4995359 0.8348405 0.2313122 -0.5459207 0.7539524 0.3654125 -0.3265959 0.8636211 0.3840491 -0.3070493 0.7666328 0.5639104 -0.01065534 0.8060862 0.5917024 -0.003500819 0.7961218 0.6051263 0.2530666 0.8596186 0.4438618 0.2563228 0.8576518 0.4457938 0.4765297 0.7907509 0.3842298 0.4277751 0.8741451 0.2299543 0.6346746 0.7590939 0.1447921 0.4760603 0.8777477 -0.05408942 0.5614945 0.8140359 -0.1485582 0.4132329 0.8619676 -0.2936843 0.4337125 0.8294477 -0.3520085 0.2733701 0.7940775 -0.5428717 0.2085063 0.8465607 -0.4897553 -0.005525529 0.7293514 -0.684117 -0.1566564 0.8561006 -0.4924944 -0.2673915 0.7901179 -0.5515573 -0.3516516 0.8645669 -0.3589781 -0.4605425 0.8063056 -0.3711767 -0.5317808 0.83706 -0.1286075 -0.5079976 0.8543052 -0.1100046 -0.6135065 0.7836796 0.09724372 -0.4713096 0.8669068 0.1622956 -0.50267 0.8233866 0.2633581 -0.3447861 0.8599272 0.3763612 -0.3504399 0.8337604 0.4266562 -0.2154216 0.8148683 0.5381295 -0.1759521 0.8403257 0.5127316 -0.01510339 0.7412913 0.6710136 0.2053998 0.8288408 0.5204169 0.1766914 0.8496226 0.4969123 0.4248048 0.7571148 0.4963044 0.3747479 0.8780658 0.2975981 0.5988236 0.7703754 0.2189342 0.590942 0.806077 -0.03205567 0.5532922 0.8329226 -0.01038539 0.483743 0.8256053 -0.2904626 0.4778382 0.8292186 -0.2899439 0.3225776 0.6533532 -0.6848893 0.3276954 0.8016399 -0.4999893 0.09399449 0.7518197 -0.6526348 0.02365988 0.8270596 -0.5616162 -0.4067153 0.5872116 -0.6998324 -0.1778376 0.8372172 -0.5171471 -0.4181458 0.7720546 -0.4786291 -0.3741675 0.8671819 -0.3286249 -0.5459203 0.8077207 -0.2226173 -0.5580391 0.7953026 -0.2368252 -0.5857253 0.8005943 0.1263913 -0.5240226 0.8476079 0.08343416 -0.5082061 0.774968 0.3757009 -0.3375028 0.8777114 0.3401687 -0.3113398 0.7909972 0.5266795 -0.115783 0.8533262 0.5083589 -0.1246744 0.8442305 0.5212785 0.1524903 0.7632322 0.6278721 0.190876 0.8008612 0.5676159 0.3135004 0.7617855 0.566922 0.3439202 0.8524287 0.3938076 0.5013526 0.7811108 0.3721715 0.564664 0.8044568 0.1844014 0.5878677 0.7892474 0.1774828 0.6442546 0.7396395 -0.1946008 0.5961993 0.7888456 -0.1492285 0.4317494 0.7830137 -0.4477523 0.2986214 0.8696679 -0.3930688 0.1600214 0.7635107 -0.6256554 0.1304759 0.7933053 -0.5946787 -0.1152459 0.7496957 -0.6516708 -0.2077704 0.8658171 -0.4551838 -0.2270779 0.8567914 -0.4629731 -0.410372 0.8497193 -0.3310166 -0.4138188 0.8409823 -0.3485727 -0.6618077 0.7164962 -0.2205536 -0.5046193 0.8622628 -0.04315352 -0.6117123 0.7816137 0.1220176 -0.4226225 0.8862351 0.1896783 -0.4915888 0.7894057 0.3676673 -0.2992923 0.8255966 0.4783454 -0.2291235 0.873349 0.4298421 -0.07093721 0.8041154 0.5902259 0.004056096 0.8626504 0.5057844 0.09918528 0.8196176 0.5642601 0.3881428 0.7327167 0.5589915 0.187815 0.8449515 0.5007818 0.4497355 0.847014 0.2833819 0.527374 0.8026622 0.278586 0.5464938 0.8361381 0.04709345 0.5467962 0.8359309 0.04726159 0.6676617 0.7134749 -0.2125592 0.4563537 0.8413753 -0.2895321 0.4621067 0.7307112 -0.5025125 0.1463538 0.9086568 -0.3910544 0.2569785 0.8126053 -0.5231012 0.04015862 0.8379495 -0.5442683 -0.02648997 0.9022478 -0.4304037 -0.2004331 0.8146184 -0.5442641 -0.3420833 0.8030142 -0.4880034 -0.3176597 0.8776709 -0.3588677 -0.484237 0.8053811 -0.3418713 -0.5030937 0.8544226 -0.1298417 -0.5419762 0.8325785 -0.1143448 -0.5338135 0.8456015 -0.001119971 -0.6387908 0.7542603 0.151782 -0.4640495 0.8220329 0.3300306 -0.4509214 0.8409616 0.2990875 -0.2973999 0.7982892 0.5237249 -0.1958677 0.8773441 0.4380677 -0.008422255 0.7772377 0.6291508 0.09923291 0.8767341 0.4706275 0.2610461 0.7864596 0.5597646 0.297154 0.8495408 0.4358669 0.6024908 0.6938611 0.3944129 0.4811637 0.8684908 0.1191861 0.6511735 0.7581666 0.03401029 0.550224 0.8151509 -0.18106 0.5500423 0.8152703 -0.1810744 0.484413 0.7266245 -0.487197 0.3507345 0.8204867 -0.4514277 0.154802 0.7525546 -0.6400765 0.1254504 0.7900187 -0.6001107 -0.2660577 0.78215 -0.5634312 -0.1928284 0.8480279 -0.4936255 -0.5033387 0.7816873 -0.3682598 -0.4214601 0.878309 -0.2257093 -0.6366146 0.7630373 -0.1117854 -0.4535236 0.8895618 0.05473762 -0.5792436 0.7879044 0.2090061 -0.330514 0.8818 0.3364363 -0.3423016 0.862278 0.3732377 -0.2779267 0.7606738 0.5866278 -0.008667886 0.8322763 0.5542934 0.02663403 0.8905847 0.4540371 0.2818674 0.7704559 0.5717941 0.3368086 0.8784766 0.3388791 0.3434415 0.8703734 0.3528428 0.6027408 0.7765181 0.1836391 0.5242557 0.8453738 0.1024652 0.6415681 0.7661533 -0.03741127 0.5238433 0.8159381 -0.2446088 0.65672 0.7153037 -0.2388716 0.4142953 0.7828173 -0.4642809 0.4148656 0.8143383 -0.4058816 0.1953064 0.8380303 -0.5094708 0.185085 0.820787 -0.5404186 -0.003334701 0.7280369 -0.6855298 -0.05595129 0.7964788 -0.6020724 -0.2836441 0.7464864 -0.6019171 -0.3155495 0.8287965 -0.4620875 -0.4950342 0.7480039 -0.4420761 -0.4878845 0.8475417 -0.2089067 -0.5462068 0.814727 -0.1946232 -0.5892412 0.8079542 0.0022372 -0.5642784 0.8254118 0.01689463 -0.6155991 0.7300661 0.2967175 -0.3970885 0.8633778 0.3112867 -0.3664925 0.7195292 0.5898822 -0.1473889 0.8861822 0.4392696 -0.006477415 0.7671442 0.6414421 0.1095495 0.8617205 0.4954158 0.2545735 0.7816088 0.5694559 0.4345673 0.7855821 0.4404679 0.4028 0.8641406 0.301684 0.5989966 0.7596611 0.2532156 0.5398795 0.8409696 0.03606271 0.6400278 0.7646999 0.07482433 0.5180855 0.8191731 -0.2460551 0.5594961 0.7657766 -0.3170967 0.2868291 0.8225033 -0.4911389 0.2856526 0.8401994 -0.460942 0.09582078 0.7694557 -0.6314716 0.01578879 0.8617855 -0.5070273 -0.2309303 0.7399019 -0.6318358 -0.3209711 0.8413248 -0.4349141 -0.4136007 0.7928922 -0.4475004 -0.4917052 0.8261714 -0.275076 -0.5066154 0.8111872 -0.2920897 -0.6489233 0.7590813 0.05190604 -0.6198862 0.7840565 0.0315718 -0.5088818 0.8354516 0.2075088 -0.5084176 0.8357399 0.2074863 -0.4684203 0.7566024 0.4562185 -0.2334361 0.8458961 0.4795492 -0.2261794 0.8045941 0.5490641 0.05152165 0.8331347 0.5506651 0.04740852 0.8238523 0.5648185 0.341753 0.739887 0.5794584 0.3679372 0.8057108 0.4641686 0.4779087 0.7607906 0.4390912 0.5218781 0.8114547 0.2630298 0.5882055 0.7733395 0.2365596 0.5510861 0.834048 0.02584856 0.6602674 0.748086 -0.06643939 0.5283389 0.811003 -0.251261 0.565516 0.7438886 -0.35612 0.3165305 0.8112987 -0.4915314 0.3167204 0.8050513 -0.5015782 0.03549772 0.8291895 -0.5578393 0.05141264 0.8480154 -0.5274718 -0.1811686 0.8258085 -0.5340582 -0.1921035 0.8515518 -0.4878073 -0.3809109 0.7832088 -0.4914174 -0.3667103 0.8876691 -0.2785092 -0.5905367 0.7657252 -0.2548168 -0.5111895 0.8590987 0.02519464 -0.5781537 0.815848 0.01142716 -0.4900572 0.7755447 0.3979627 -0.4954258 0.7640942 0.4131749 -0.23927 0.9049186 0.3519549 -0.1955448 0.8158417 0.54421 -0.005834639 0.8196793 0.5727931 -0.0163902 0.8307208 0.5564479 0.2449132 0.7669178 0.5931736 0.2598943 0.7917619 0.5527821 0.463409 0.7262653 0.5077313 0.4482215 0.832814 0.3248361 0.6467992 0.7299866 0.2208406 0.5658088 0.8174196 0.1081001 0.6314772 0.7753871 -0.003388166 0.4990411 0.8477297 -0.1797568 0.6022298 0.7068984 -0.3709636 0.3879526 0.828814 -0.4031875 0.3174661 0.7393668 -0.593761 0.1252049 0.8434832 -0.5223599 0.0698238 0.8084298 -0.5844365 -0.1143824 0.878776 -0.4633244 -0.1423617 0.8578361 -0.4938123 -0.4129513 0.7421091 -0.5279634 -0.4108639 0.8787887 -0.2427369 -0.4312522 0.8617041 -0.2673717 -0.5902562 0.8006778 -0.1025316 -0.4624892 0.8866183 -0.003446817 -0.5669861 0.796436 0.2102773 -0.4646815 0.8545094 0.2321311 -0.4363361 0.4888077 0.7554323 -0.3649746 0.8597168 0.3573243 -0.2487158 0.802088 0.5429505 -0.0889824 0.874132 0.4774677 -0.05039495 0.830991 0.5539987 0.1740633 0.7819462 0.59855 0.2344948 0.8836141 0.4052634 0.3055839 0.846103 0.4367244 0.5512058 0.7777753 0.3020559 0.4476184 0.883869 0.1356961 0.5681321 0.8191667 0.07868891 0.4111265 0.9031676 -0.1235458 0.4956066 0.8420236 -0.2130033 0.5034395 0.7915854 -0.3463252 0.3341819 0.8164823 -0.4708282 0.2106153 0.8846736 -0.4159252 0.1694722 0.8231509 -0.5419426 -0.001599311 0.810841 -0.5852643 0.01840072 0.7895654 -0.6133906 -0.2073197 0.7636897 -0.6113892 -0.280983 0.8476037 -0.4501297 -0.4183162 0.7721156 -0.4783819 -0.413096 0.8293688 -0.3761638 -0.6716335 0.71165 -0.2060651 -0.5224378 0.8511511 -0.05099737 -0.5970901 0.7888375 0.1456675 -0.5215938 0.8374772 0.1630095 -0.5393596 0.7270555 0.4248313 -0.2572457 0.8695945 0.4214619 -0.2330894 0.7991412 0.5541146 -0.03062456 0.852209 0.5223045 -0.05090808 0.8292935 0.5564898 0.1898938 0.7520763 0.6311273 0.2812951 0.8234509 0.4927491 0.3926535 0.7626019 0.5140638 0.4873616 0.8360615 0.2519522 0.5849964 0.7172337 0.3786226 0.5838266 0.8102912 0.05074256 0.4912877 0.8709322 -0.01065891 0.6053216 0.7698747 -0.2021851 0.3775735 0.8749266 -0.303219 0.4509943 0.8301347 -0.3278424 0.3205825 0.8224675 -0.4698661 0.1459088 0.9101417 -0.3877536 0.09159165 0.8278082 -0.5534842 -0.10354 0.7482141 -0.6553284 -0.1681041 0.9022282 -0.3971466 -0.3244826 0.8197426 -0.4719463 -0.4946178 0.7830019 -0.3771752 -0.4561618 0.8535655 -0.2516793 -0.5860687 0.787777 -0.1895549 -0.6174833 0.7864459 0.01474368 -0.6136711 0.7894757 0.01166033 -0.6089943 0.7521567 0.2517663 -0.4545114 0.8431274 0.2873249 -0.4556862 0.7859252 0.4179373 -0.2759125 0.8618597 0.4255235 -0.232932 0.7480419 0.6214307 0.02122741 0.8441154 0.5357414 0.1847946 0.6987838 0.6910515 0.3377795 0.8273807 0.4487164 0.5166832 0.72311 0.4584217 0.3911364 0.8977274 0.2027264 0.616522 0.7770006 0.1271638 0.5777742 0.8106815 -0.09472304 0.4430215 0.8867522 -0.131919 0.5122686 0.8086103 -0.2893618 0.3826189 0.8164592 -0.4324315 0.265759 0.8852403 -0.3817353 0.1761292 0.7562806 -0.6300938 -0.00734812 0.9117826 -0.4106074 -0.1876231 0.8077371 -0.5588904 -0.2696424 0.8737116 -0.4048716 -0.3701211 0.8195337 -0.4374644 -0.545916 0.7975489 -0.2566934 -0.4298245 0.8921549 -0.1389625 -0.6298809 0.7762904 0.02496755 -0.4727093 0.8621683 0.182241 -0.5188806 0.8156333 0.2559399 -0.4401356 0.7616952 0.4755009 -0.3327282 0.8286793 0.4500917 -0.2346097 0.7590602 0.6072776 -0.0202955 0.8531981 0.5211921 0.05179244 0.7832364 0.6195632 0.2251071 0.8694086 0.439836 0.2809941 0.8373767 0.4688739 0.3824415 0.8806659 0.279582 0.4821743 0.8278617 0.2866234 0.6047667 0.7783905 0.1684209 0.4879081 0.8726468 0.02081495 0.6056047 0.7895474 -0.0992878 0.4766247 0.8186632 -0.3203427 0.4812557 0.8115137 -0.3314189 0.2781243 0.83244 -0.4792604 0.2754642 0.8661949 -0.4169245 0.04194515 0.7202301 -0.692466 0.09867185 0.8989665 -0.4267591 -0.1964554 0.7204349 -0.6651158 -0.2070313 0.9117619 -0.3547232 -0.5839621 0.4909151 -0.6465221 -0.9106873 -0.03167855 -0.41188 -0.6065664 -0.631536 0.4829488 -0.3591839 0.1765209 0.9164209 0.01591289 0.92025 0.3910073 -0.08550155 -0.8682066 0.4887812 0.5357252 -0.8443757 -0.005316972 -0.5052145 0.8551172 -0.1163316 0.05877822 -0.9046113 0.4221656 0.3195474 -0.9103525 0.26296 0.400687 0.9124734 -0.08271807 -0.3015264 -0.9116262 -0.2793202 -0.4306039 0.8877059 -0.1629678 -0.1186237 -0.8589433 -0.4981414 0.1762745 -0.9158146 -0.3608475 -0.4309053 0.8326787 0.3478029 -0.222251 -0.8118483 0.5399139 0.5313172 -0.8329483 -0.1545935 0.4467605 0.8532418 -0.2690423 0.1268295 -0.8719662 -0.4728524 0.3342038 0.886788 0.3192412 0.1853644 0.6911016 -0.6985834 -0.2094391 -0.7647376 -0.6093535 -0.8764646 -0.3122253 -0.3665043 -0.9464386 0.2879824 -0.1460143 -0.9918848 -0.03467559 0.1223198 0.2434209 0.9674947 0.06855905 0.6280653 0.7714559 0.1019316 0.4290918 0.8945139 0.1254007 0.1050814 0.9932537 0.04904317 0.9527785 0.2735805 0.1317837 0.8941788 0.4000476 0.2010131 0.8513599 0.3125748 0.4212877 0.537932 0.739695 0.4043272 0.3781111 0.8554427 0.3539066 0.5991282 0.6596851 0.4537192 0.7776523 -0.3179996 0.5423404 0.5999507 0.4143092 0.6844027 0.2783454 0.8400604 0.465642 0.1105217 0.9509631 0.2888844 0.3348334 0.6673234 0.6652565 0.4985212 0.4348503 0.7499213 0.2292129 0.6180481 0.7519828 0.3832787 0.01982438 0.92342 0.05621451 0.7798405 0.6234491 0.2400225 0.311037 0.9195897 0.007838428 0.7758371 0.6308848 0.04669296 0.2221863 0.9738855 -0.05334448 0.7019541 0.7102217 -0.06310808 0.9794645 0.191486 -0.07355231 0.5184555 0.8519354 -0.1100683 -0.3850625 0.9163033 -0.127552 0.9506589 0.2828041 -0.2118731 0.7629022 0.6108109 -0.2093217 0.280124 0.9368644 -0.2209913 0.1702618 0.9602988 -0.3342776 0.6199807 0.7098468 -0.352184 0.5501056 0.7571991 -0.4490083 0.3463955 0.8236516 -0.5181227 0.6864503 0.5102303 -0.3777162 0.8478428 0.3721466 -0.5246999 0.639955 0.5613801 -0.6317763 0.1077499 0.7676253 -0.6204344 0.1569046 0.7684023 -0.3360819 0.9206055 0.1988329 -0.554996 0.8025386 0.2188863 -0.7674489 0.5013619 0.3995733 -0.8372239 0.3717228 0.4010964 -0.04563218 0.9989457 0.005014002 -0.860517 0.1420674 0.4892109 -0.6517166 0.7499563 0.1132738 -0.9208251 0.3324585 0.2038444 -0.8315345 0.5434301 0.115041 -0.4564165 0.88783 -0.05866891 -0.2525122 0.9661474 -0.05288386 -0.6805155 0.7156001 -0.1575284 -0.8589291 0.4967156 -0.1245572 -0.9342252 0.3201087 -0.1573337 -0.6747271 0.6079872 -0.4184436 -0.9106201 0.03424191 -0.4118236 -0.3934847 0.8457332 -0.3604237 -0.5609512 0.6968935 -0.4468481 -0.322131 0.8804236 -0.3479741 -0.8488117 0.2120121 -0.4843237 -0.7444581 0.01981335 -0.6673751 -0.6152037 0.3229144 -0.7192014 -0.07442647 0.9883483 -0.1327726 -0.5036807 0.3034575 -0.8088383 -0.2603769 0.7254699 -0.6371008 -0.3094035 0.5756404 -0.7569066 -0.1261195 0.8520318 -0.5080708 -0.3748303 -0.280044 -0.8837859 -0.2133027 0.3614316 -0.9076724 -0.001196146 0.8297545 -0.5581274 0.04232645 0.6941599 -0.7185753 0.0565266 0.9690642 -0.2402482 -0.02412831 0.3859992 -0.9221835 0.007518231 0.2973238 -0.9547471 0.2131845 0.893773 -0.3946165 0.3019366 0.6184905 -0.725468 0.2866849 0.5918166 -0.753369 0.292436 0.07569628 -0.9532845 0.3321372 0.1946164 -0.9229353 0.4637606 0.5933569 -0.6579163 0.3619571 0.8510658 -0.3803605 0.3618769 0.8507547 -0.3811321 0.1155866 0.9908363 -0.0698803 0.6196567 0.2489424 -0.7443475 0.6177847 0.2076886 -0.7584245 0.5479157 0.7543396 -0.361608 0.3006193 0.9479672 -0.1048157 0.7705 0.4202804 -0.4792644 0.4623141 0.8714832 -0.1636542 0.8268832 0.3393495 -0.4484485 0.7196265 0.6849688 -0.1138223 0.8991734 0.3914379 -0.1956109 0.8825939 0.4416108 -0.1612704 -0.002647578 0.9999885 -0.003996431 0.00320965 0.9999631 0.007973074 0.00859481 0.999963 -2.47483e-4 0.002650976 0.9998481 0.01722443 -0.002356171 0.9999902 -0.003777205 -0.8652436 -0.07153642 0.4962217 -0.8651469 -0.07125526 0.4964309 -0.001600027 -0.07160919 0.9974315 -0.001882851 -0.07194489 0.9974069 0.8627436 -0.0716651 0.5005376 0.8629794 -0.07116478 0.5002021 0.8640273 -0.07077544 -0.4984452 0.8647979 -0.07290548 -0.4967994 0.003858625 -0.07242119 -0.9973667 0.0016945 -0.06977921 -0.9975611 -0.8665977 -0.03819924 -0.4975432 -0.86539 -0.03511601 -0.4998672 0.006320536 -0.999926 0.01039451 8.71726e-4 -0.9999412 0.01081347 0.01201319 -0.9999278 3.91947e-4 0.01022601 -0.9999362 0.004795968 0.008794248 -0.9999467 0.005409777 0.01079219 -0.9999337 -0.004034161 -0.003187596 -0.9999336 0.01108795 2.68853e-5 -0.9999467 0.01033526 -0.007934629 -0.9999296 0.008833885 0.008440136 -0.9999495 -0.005466282 0.00732702 -0.9999306 -0.009235262 -0.008534848 -0.9999455 0.006017863 -0.01216369 -0.9999201 0.003462135 0.001617193 -0.999939 -0.01093226 2.95594e-4 -0.9999483 -0.01016908 -0.01215523 -0.9999222 -0.002839207 -0.004348814 -0.9999275 -0.01123332 -0.008932352 -0.9999404 -0.00627315 -0.008932232 -0.9999382 -0.006626904 3.38428e-6 -0.9999998 7.11824e-4 0.003069698 -0.9999951 7.17547e-4 -0.00419563 -0.9999516 -0.00891143 0.001624763 -0.9999974 0.001646697 -0.9623059 0.01842123 0.2713452 -0.9363774 -0.0155307 0.3506512 -0.6213746 -0.01862514 0.7832922 -0.674846 0.01156586 0.737868 -0.2942987 0.02386051 0.9554157 -0.1463505 -0.02943062 0.9887949 0.2298975 0.02317774 0.9729389 0.3606728 -0.02804362 0.9322708 0.6718701 0.03822416 0.739682 0.8029006 -0.03054869 0.5953297 0.973594 0.01947158 0.227455 0.9609141 -0.007817029 0.2767362 0.9881658 0.01671099 -0.1524766 0.9612931 -0.03190129 -0.2736749 0.7902742 0.03046458 -0.6119956 0.6678212 -0.02829092 -0.7437839 0.4587271 0.01951199 -0.888363 0.2761991 -0.01567536 -0.9609727 0.08769541 0.02174174 -0.9959101 -0.08029878 -0.02360528 -0.9964913 -0.5195694 -0.02230608 -0.854137 -0.435827 0.01570403 -0.8998935 -0.7885156 0.03394156 -0.6140775 -0.9048994 -0.03181046 -0.4244351 -0.98251 0.02172261 -0.1849385 -0.9993596 -0.01429587 -0.03280633 -0.01334571 0.9996926 -0.0208984 0.01086688 0.9999055 -0.008418262 0.001251459 0.9999963 -0.002433121 0.01510626 0.9998261 0.01094037 2.35079e-4 0.9999965 -0.002660632 0.006566941 0.999978 -0.001009762 0.02799654 0.9994255 -0.01910471 0.006024479 0.9999803 0.001735746 -0.005592942 0.9999344 0.01000374 -0.006513237 0.9998885 -0.01344144 -0.01685363 0.9998492 0.004199206 -2.33926e-4 0.9999995 9.30228e-4 -6.41443e-5 1 -7.74215e-5 -0.001076221 0.9999991 -8.37532e-4 4.80598e-5 1 -5.29458e-5 -2.16541e-5 1 -9.07505e-5 -8.50836e-5 0.9999946 -0.003280222 -0.00372833 0.9999929 -7.00333e-4 -0.00425136 0.9999904 0.001202583 0.008533835 0.9999635 5.68996e-4 -0.00151807 0.9999868 0.004930675 -0.004007816 0.999991 0.001444041 -0.003598868 0.9999859 0.003923296 -0.9932118 0.1154795 0.01396 -0.9720333 -0.130078 -0.1955279 -0.9135189 0.09707254 -0.3950445 -0.7067567 -0.1531131 -0.690689 -0.5941004 0.1055462 -0.7974363 -0.1728571 0.002230763 -0.9849444 -0.1333994 -0.08045721 -0.9877911 0.3414039 0.03915756 -0.9391008 0.3953976 -0.05005496 -0.9171452 0.6909283 0.07201898 -0.719327 0.7989165 -0.1449864 -0.5837051 0.937164 0.1681761 -0.3056802 0.9878395 -0.1551967 -0.009331345 0.9438081 0.1699181 0.2834678 0.8542313 -0.1618441 0.4940602 0.5496147 0.1636876 0.8192254 0.4091903 -0.1198571 0.9045429 0.03325039 0.08652824 0.9956945 -0.1237348 -0.1105492 0.9861383 -0.4181348 0.1402318 0.8974957 -0.6167361 -0.1398918 0.7746399 -0.8538463 0.1065628 0.5095008 -0.9119189 -0.08504354 0.401462 -0.9925199 -0.1073669 0.05810844 -0.9482842 0.1462726 0.2817119 -0.8796291 -0.2147368 0.4244302 -0.6531095 0.2479026 0.7155364 -0.594934 -0.08913624 0.7988168 -0.2458285 -0.06229597 0.9673095 -0.1662116 0.1736356 0.9706825 0.1156108 -0.1210414 0.9858921 0.2739888 0.1229122 0.9538463 0.4024516 -0.0974223 0.9102427 0.6274514 0.1487008 0.7643252 0.6976974 -0.08590751 0.7112232 0.9015165 -0.03987932 0.4309034 0.9164255 0.1015049 0.3871189 0.9973559 -0.07011437 0.01910972 0.9999298 0.01044428 -0.005595803 0.8997169 0.01043313 -0.4363493 0.87053 -0.1420009 -0.4711828 0.6580717 0.1683943 -0.7338835 0.4962978 -0.162675 -0.8527752 0.4014802 0.08302146 -0.9120971 0.1179144 -0.1286923 -0.9846494 -0.008248746 0.1273027 -0.9918297 -0.2500315 -0.1448853 -0.9573362 -0.3620212 0.1477997 -0.9203781 -0.6971056 -0.1150428 -0.7076786 -0.7170351 -0.03965365 -0.6959083 -0.9020774 0.09043717 -0.4219923 -0.9338852 -0.1421289 -0.3281127 -0.9921278 0.1095174 -0.06073302 0 -1 1.93137e-6 0 -1 2.71779e-6 0 -1 -4.38056e-7 0 -1 -7.41422e-6 0 -1 1.87398e-5 0 -1 2.91393e-6 0 -1 6.08064e-6 0 -1 -4.41711e-6 0 -1 -5.45703e-6 0 -1 4.42635e-6 0 -1 -1.22906e-6 0 -1 -2.76575e-6 0 -1 -5.14039e-6 0 1 7.64751e-6 0 1 -2.91487e-6 0 1 -2.32209e-6 0 1 -2.6222e-6 0 1 -6.40016e-6 0 1 8.16817e-6 0 1 6.88513e-6 0 1 -1.14213e-5 0 1 -8.13299e-6 0 1 5.7657e-6 0 1 -2.58624e-6 0 1 -5.05969e-6 0 1 -4.21445e-6 0 1 2.25783e-6 0.0292319 -0.9990903 -0.03105276 0.03020602 -0.9984695 -0.04632848 0.171763 -0.9839096 -0.04918634 -0.001981079 -0.999911 -0.01319324 5.31071e-4 -0.9999946 -0.003261327 0.1804282 -0.982883 -0.03723901 -8.20773e-4 -0.9999996 -4.00415e-4 0.04201847 -0.9988059 0.02492582 -0.04636633 -0.9974835 -0.05363655 0.02040088 -0.9997918 4.18308e-4 -0.03840208 -0.9908123 -0.129678 0.04406499 -0.999028 0.001237273 0.08462667 -0.9903786 0.1094921 0.001013159 -0.9969795 0.07765805 -0.006083607 -0.8980802 0.4397897 0.170976 -0.6912744 0.7020733 0.2470785 -0.9014253 0.3555061 0.4073801 -0.7898894 0.4583845 0.5589259 -0.7555898 0.3415932 0.403821 -0.9093986 0.0996139 0.6490092 -0.760528 0.01960176 0.4855447 -0.8325061 -0.2667963 0.4808828 -0.8368729 -0.2615255 0.3646732 -0.8077454 -0.463207 0.2125482 -0.878454 -0.4279509 0.1940578 -0.8118148 -0.5507254 0.01228296 -0.7981808 -0.6022928 -0.09074372 -0.8796229 -0.4669359 -0.2029792 -0.8097411 -0.5505623 -0.3377207 -0.8707615 -0.3573782 -0.3416481 -0.8306083 -0.4397347 -0.5242429 -0.7808586 -0.339749 -0.5260722 -0.842346 -0.1170527 -0.5802556 -0.7968451 -0.1683484 -0.6351049 -0.7623367 0.1244375 -0.5628188 -0.8116741 0.1562696 -0.4865461 -0.7629514 0.4256504 -0.4551804 -0.8137204 0.3614833 -0.3713954 -0.7295482 0.574304 -0.2330082 -0.8104373 0.5374929 -0.09881889 -0.7536509 0.6498042 -0.003314316 -0.8197787 0.5726709 0.2138001 -0.7354399 0.6429757 0.2954213 -0.8419777 0.4514419 0.3812949 -0.7989795 0.4650226 0.4194923 -0.8654824 0.2738001 0.531166 -0.8054113 0.2630122 0.5030869 -0.8629434 0.04724758 0.5884156 -0.808525 0.007379293 0.3970391 -0.8987076 -0.1862381 0.5630336 -0.7204498 -0.4049015 0.2193779 -0.8821883 -0.4166741 0.2224451 -0.829542 -0.5122287 0.008404195 -0.8133708 -0.5816849 -0.06657099 -0.8718144 -0.4852916 -0.161035 -0.8166347 -0.5542343 -0.3278889 -0.8352423 -0.4414287 -0.3309994 -0.8031972 -0.4952917 -0.5579071 -0.770159 -0.3091841 -0.4834241 -0.8639815 -0.1408442 -0.6327358 -0.7703639 -0.07864475 -0.5092806 -0.8449596 0.1633301 -0.4397771 -0.8796895 0.1809489 -0.4825347 -0.8048099 0.3456027 -0.2739485 -0.8626192 0.4252536 -0.2971065 -0.7831609 0.5462479 0.07134556 -0.8589808 0.5070128 0.04707032 -0.8138992 0.5790963 0.334446 -0.8369451 0.4332075 0.3283118 -0.8617793 0.3867141 0.5785906 -0.7650919 0.2826085 0.464277 -0.8781258 0.1155077 0.5490598 -0.8302448 -0.09605658 0.6013458 -0.7957456 -0.07191962 0.4910826 -0.8103609 -0.3196142 0.2985452 -0.9040369 -0.305922 0.2976729 -0.757358 -0.5812055 0.03761899 -0.8642683 -0.5016225 0.03887677 -0.8630582 -0.5036064 -0.2031849 -0.8061174 -0.5557796 -0.256174 -0.8817996 -0.3959854 -0.4054653 -0.7941203 -0.4527373 -0.52249 -0.8084778 -0.2708652 -0.4327346 -0.8910098 -0.1372684 -0.6487115 -0.7610343 6.14501e-4 -0.4700568 -0.8705001 0.1458637 -0.6295797 -0.671905 0.3900936 -0.3072353 -0.8412608 0.4448448 -0.2440579 -0.8103405 0.5327138 -0.1096904 -0.8900207 0.4425281 0.06666427 -0.7087045 0.7023488 0.1975947 -0.8935005 0.4032533 0.4042445 -0.7775564 0.481656 0.4129756 -0.8728597 0.2599371 0.5639606 -0.7834525 0.2610571 0.5548791 -0.8319288 -0.001971006 0.5612033 -0.827675 0.002263844 0.607966 -0.7721241 -0.1849378 0.4371266 -0.8479979 -0.2997002 0.4781245 -0.7793129 -0.4050537 0.2765548 -0.8580753 -0.4326941 0.2496102 -0.7390403 -0.6257111 -0.00306183 -0.7812968 -0.6241522 -0.009483993 -0.7732337 -0.6340503 -0.261775 -0.811524 -0.5224011 -0.2814006 -0.7964791 -0.5351962 -0.4906294 -0.7614386 -0.4236676 -0.4475037 -0.8598736 -0.2456784 -0.6357282 -0.7510631 -0.178196 -0.5059693 -0.8625483 0.002378165 -0.6717748 -0.7194371 0.1764339 -0.4018375 -0.8530371 0.3329483 -0.4315567 -0.7969954 0.4225605 -0.1703471 -0.8677852 0.4668307 -0.2210178 -0.8346108 0.5045553 -0.01198226 -0.758573 0.6514779 0.1800456 -0.8806908 0.4381406 0.2351954 -0.8395112 0.4898 0.42201 -0.7992654 0.4278813 0.4077061 -0.8724928 0.2693179 0.4544536 -0.85174 0.2607892 0.4996343 -0.8659469 0.02239251 0.4781433 -0.8778424 0.02778214 0.6193339 -0.7798424 -0.09094804 0.467497 -0.856304 -0.2195224 0.5235521 -0.7800381 -0.3426862 0.3828937 -0.7682527 -0.5130112 0.3768711 -0.7726067 -0.5109277 0.06649565 -0.7974811 -0.5996687 0.08006954 -0.8432474 -0.5315287 -0.09627401 -0.7669419 -0.6344538 -0.2628154 -0.853076 -0.4507655 -0.2617232 -0.8747648 -0.4077839 -0.4740058 -0.7918428 -0.3851021 -0.4395608 -0.8782513 -0.1883109 -0.5912846 -0.7897081 -0.163535 -0.5182045 -0.8477629 0.1129701 -0.6030446 -0.7932634 0.08408504 -0.53146 -0.7704792 0.3520118 -0.4691496 -0.8039333 0.3654995 -0.3898853 -0.7422997 0.5449593 -0.1823938 -0.8562892 0.4832199 -0.09486943 -0.7356199 0.6707184 0.1334657 -0.8667916 0.4804782 0.1350526 -0.8701461 0.4739268 0.3678025 -0.7989062 0.4758892 0.3770278 -0.8525182 0.3620262 0.5499469 -0.7547184 0.3577132 0.6819902 -0.7248161 0.09762734 0.6079096 -0.7830201 0.131626 0.5549451 -0.8308687 0.04114878 0.683248 -0.698628 -0.2123469 0.4036687 -0.8616713 -0.3075295 0.4462178 -0.7771496 -0.4437658 0.211656 -0.832795 -0.5115216 0.1204224 -0.8886691 -0.4424542 -0.02504914 -0.785971 -0.6177559 -0.1371724 -0.8694447 -0.4746047 -0.273184 -0.7755947 -0.5690549 -0.4642131 -0.750994 -0.4695896 -0.44613 -0.8250867 -0.3466991 -0.6003591 -0.7578153 -0.2555095 -0.5227888 -0.8522368 -0.0196104 -0.6611253 -0.7475537 0.06385153 -0.4558717 -0.8653397 0.2082505 -0.547292 -0.7530322 0.3652589 -0.2825339 -0.7604153 0.5847592 -0.28492 -0.7789779 0.5585822 -0.04085403 -0.8670861 0.4964805 -0.007218897 -0.8078258 0.5893773 0.2135744 -0.808776 0.5479667 0.2305426 -0.8446236 0.4831783 0.4322336 -0.7511586 0.4989337 0.5152157 -0.8140802 0.2680044 0.5724868 -0.7786136 0.2569433 0.4581695 -0.8870748 0.05638444 0.6478465 -0.7570711 -0.0844888 0.3951026 -0.8905624 -0.2253722 0.5082234 -0.7630572 -0.3993155 0.181446 -0.8315485 -0.5249804 0.1406684 -0.8659589 -0.4799245 -0.1529933 -0.7776546 -0.6097923 -0.1984455 -0.8886396 -0.4134479 -0.3635486 -0.8264201 -0.4299562 -0.4087902 -0.8562787 -0.3157172 -0.5528576 -0.7674227 -0.3246704 -0.6271544 -0.7776046 -0.04481709 -0.6386008 -0.7676172 -0.05433964 -0.6127308 -0.7691829 0.1814355 -0.5260681 -0.8212853 0.2207776 -0.5153574 -0.7438411 0.4255669 -0.3654738 -0.8192726 0.4418387 -0.3113004 -0.7454675 0.5893813 -0.1392263 -0.8080354 0.5724464 -0.09422868 -0.7420399 0.6637 0.1868577 -0.7819685 0.5946506 0.1850029 -0.7835925 0.5930908 0.3115014 -0.8628397 0.3980888 0.3885281 -0.8194386 0.4213863 0.4683203 -0.8520222 0.2339535 0.46773 -0.852662 0.2328013 0.6112682 -0.788717 0.06539618 0.4290816 -0.8993924 -0.08355981 0.5830884 -0.7830146 -0.2165551 0.4130743 -0.7999585 -0.4352424 0.416319 -0.7977867 -0.4361364 0.2348139 -0.7413913 -0.6286505 0.05479174 -0.8624798 -0.5031168 -0.09768861 -0.7259597 -0.680764 -0.2559433 -0.8134317 -0.5223236 -0.2637542 -0.8919522 -0.3672263 -0.4993523 -0.7839111 -0.3689591 -0.4608711 -0.8466188 -0.2661473 -0.6351755 -0.7646549 -0.1088802 -0.5685338 -0.8188601 0.078978 -0.5448111 -0.835942 0.06619745 -0.5391022 -0.7826076 0.3112786 -0.4047399 -0.8571373 0.3185929 -0.3722029 -0.7260305 0.5782254 -0.1922621 -0.8142493 0.5477529 -0.1128732 -0.7326278 0.6712051 0.1376131 -0.8353184 0.532265 0.1337403 -0.838528 0.5281896 0.3458969 -0.8111622 0.4715627 0.3420104 -0.8693088 0.3568351 0.50958 -0.7992162 0.3187193 0.4615568 -0.876235 0.1384834 0.632353 -0.7715007 0.07011705 0.4904263 -0.8591824 -0.1459027 0.5660744 -0.815045 -0.1235375 0.5177447 -0.7673833 -0.3782373 0.4242776 -0.8170031 -0.3905053 0.3046599 -0.7399584 -0.5997033 0.2972791 -0.8159579 -0.4958205 0.1652925 -0.7412898 -0.6505136 -0.04525971 -0.8320958 -0.5527824 -0.1194143 -0.7734488 -0.6225088 -0.2211924 -0.8792197 -0.421956 -0.4471266 -0.7431551 -0.4977934 -0.4310758 -0.8672918 -0.2489551 -0.5438522 -0.8084422 -0.2250469 -0.5286289 -0.8483458 -0.02934235 -0.5036959 -0.8638336 -0.009058594 -0.5948901 -0.7849631 0.1730286 -0.4066529 -0.8781854 0.2518413 -0.4814724 -0.7496308 0.4541345 -0.2205638 -0.8019563 0.5551738 -0.221831 -0.8072196 0.5469805 -0.03324609 -0.8195115 0.5720977 0.03664821 -0.8841664 0.4657325 0.2158109 -0.7853966 0.5801534 0.3590344 -0.8300305 0.4267831 0.3507025 -0.853231 0.3860114 0.5111857 -0.8295383 0.2248452 0.5190411 -0.8246396 0.2248684 0.5729886 -0.8195012 0.01009762 0.5972632 -0.801466 0.03048193 0.602104 -0.7622579 -0.2375581 0.5749076 -0.7806496 -0.2450869 0.3858189 -0.7886921 -0.478653 0.4283379 -0.7580782 -0.4917766 0.08076584 -0.8195297 -0.5673167 0.08564352 -0.8372068 -0.5401389 -0.08484852 -0.7913542 -0.6054415 -0.1682855 -0.8579789 -0.4853373 -0.2972586 -0.7754241 -0.5570951 -0.5535411 -0.7318874 -0.397408 -0.4525412 -0.8116606 -0.369342 -0.4674025 -0.8814809 -0.06727826 -0.5315737 -0.8389105 -0.1168707 -0.5462293 -0.8078545 0.2213701 -0.4138938 -0.8819292 0.2255942 -0.3337906 -0.8024894 0.4945651 -0.1900983 -0.8820133 0.4311788 -0.107478 -0.7795572 0.6170408 0.08878725 -0.8486261 0.521489 0.1307057 -0.808687 0.5735341 0.3247793 -0.8659201 0.3803955 0.3313018 -0.8431825 0.4234177 0.5249624 -0.8090544 0.2642831 0.4548339 -0.8850225 0.09930574 0.5966355 -0.8005098 0.05665904 0.599594 -0.7770699 -0.1914406 0.379136 -0.8955576 -0.2328786 0.4316339 -0.794458 -0.4272337 0.2360665 -0.8412986 -0.4863017 0.2358838 -0.8332419 -0.5000669 0.1040829 -0.7351971 -0.669815 -0.1250921 -0.8070817 -0.5770365 -0.1269499 -0.8057624 -0.578473 -0.2806424 -0.8636782 -0.4186882 -0.2786272 -0.8446338 -0.4571224 -0.4791825 -0.7919863 -0.3783411 -0.4335231 -0.8840909 -0.1744734 -0.5546219 -0.8174648 -0.1553893 -0.6553286 -0.7539297 0.04620081 -0.5611365 -0.8226598 0.09141576 -0.5350034 -0.7454042 0.3976734 -0.5218446 -0.7665799 0.3742105 -0.3301675 -0.7721814 0.5428861 -0.3349404 -0.7686532 0.5449655 -0.06208628 -0.8043322 0.5909274 -0.01897138 -0.73605 0.6766613 0.178207 -0.827994 0.5316656 0.3361964 -0.7263385 0.5995036 0.4061078 -0.8537206 0.3259413 0.4845841 -0.8081192 0.3348457 0.5083165 -0.8427984 0.1769331 0.6489297 -0.7520507 0.1153694 0.6244524 -0.7744202 -0.1016496 0.6183367 -0.7788817 -0.1048956 0.5625278 -0.7473727 -0.3535486 0.418061 -0.831623 -0.3655522 0.3480069 -0.7383286 -0.5777215 0.1284788 -0.8535987 -0.5048391 0.07755333 -0.8033666 -0.590413 -0.05415284 -0.8652311 -0.4984402 -0.2782057 -0.6875503 -0.6707282 -0.350776 -0.8683174 -0.3506866 -0.534501 -0.7646685 -0.3599873 -0.4992005 -0.860095 -0.1050508 -0.5894756 -0.7853423 -0.1890933 -0.6594811 -0.7466406 0.08724999 -0.5423077 -0.8223849 0.1720044 -0.5588015 -0.744704 0.3649067 -0.32304 -0.8642468 0.3856458 -0.3299593 -0.827256 0.4547246 -0.05527186 -0.8324245 0.5513751 -0.02981877 -0.8572877 0.5139734 0.2254987 -0.7864957 0.5749565 0.2340993 -0.8282099 0.5091817 0.6316582 -0.6769443 0.3778284 0.5132811 -0.7802535 0.3574172 0.4918587 -0.862401 0.1197481 0.6082494 -0.7906494 0.07004499 0.606462 -0.7875321 -0.1095321 0.4963248 -0.8566709 -0.1406292 0.4467564 -0.7854942 -0.4282612 0.5088415 -0.7397837 -0.4402278 0.227721 -0.7929851 -0.5650822 0.194407 -0.8146488 -0.5464005 -0.01042157 -0.7764266 -0.6301216 -0.03925234 -0.8023403 -0.595575 -0.241669 -0.7429998 -0.6241374 -0.3095561 -0.8062574 -0.5041073 -0.4127971 -0.760375 -0.5014265 -0.4647192 -0.8411343 -0.2766392 -0.5282245 -0.804122 -0.2727025 -0.4767435 -0.8788763 -0.0170983 -0.5379492 -0.8397743 -0.07341498 -0.6335822 -0.7574182 0.1577706 -0.3721173 -0.8858172 0.2772305 -0.4132316 -0.8347795 0.3638445 -0.2467966 -0.7950942 0.5540006 -0.1594749 -0.8589422 0.4866069 0.05632865 -0.7826716 0.6198808 0.1287838 -0.876621 0.4636275 0.3593268 -0.7746608 0.5203701 0.3504145 -0.8916741 0.2865781 0.6249855 -0.7248884 0.289707 0.5221191 -0.8528612 -0.004423737 0.5926049 -0.804724 0.03519743 0.5915536 -0.7740666 -0.2255781 0.4216151 -0.8560593 -0.2990036 0.4699755 -0.7616105 -0.4461756 0.1568856 -0.8604364 -0.4848052 0.128336 -0.8809532 -0.4554684 -0.07353419 -0.7826682 -0.6180803 -0.1281489 -0.8403508 -0.5266768 -0.369147 -0.7412291 -0.5606336 -0.3995889 -0.8205178 -0.408753 -0.5976557 -0.7219968 -0.3486092 -0.5298891 -0.8269816 -0.1879341 -0.6721553 -0.7403842 -0.006200671 -0.4792122 -0.8642341 0.1531512 -0.5816904 -0.7564268 0.2990898 -0.3120819 -0.856311 0.411505 -0.4701198 -0.7412005 0.4791756 -0.1083515 -0.7979203 0.5929446 -0.1833425 -0.7108474 0.6790299 0.09057289 -0.8436961 0.5291252 0.3094388 -0.687264 0.6572031 0.3190914 -0.8950407 0.3115814 0.5101277 -0.8068448 0.2979453 0.470482 -0.8796299 0.06998646 0.4944763 -0.8667255 0.06542295 0.6255617 -0.764811 -0.1540672 0.3867231 -0.8886192 -0.2465792 0.4604605 -0.7535763 -0.469147 0.199837 -0.8869488 -0.4163979 0.1580055 -0.7696948 -0.6185502 -0.11313 -0.8497259 -0.5149443 -0.09961253 -0.8208555 -0.5623822 -0.3191022 -0.8350795 -0.448125 -0.3178783 -0.8153856 -0.4838388 -0.5421559 -0.7548068 -0.369234 -0.512743 -0.8252735 -0.2366818 -0.6383685 -0.7627696 -0.1032878 -0.5135498 -0.8567352 0.04766219 -0.5937343 -0.7956172 0.1203036 -0.4481367 -0.840615 0.3042041 -0.3880706 -0.868286 0.3089998 -0.418215 -0.7335488 0.5357261 -0.1388328 -0.8019492 0.5810363 -0.1056415 -0.7489856 0.6541105 0.1180056 -0.865481 0.4868443 0.09488552 -0.8172674 0.5683932 0.3177891 -0.8487549 0.4226408 0.3187241 -0.8425599 0.4341748 0.4859631 -0.8355565 0.2562913 0.4582933 -0.8686306 0.1882774 0.5917688 -0.7955035 0.1303222 0.5386763 -0.8391344 -0.07537502 0.5321235 -0.8430162 -0.07853871 0.5789764 -0.744875 -0.3315834 0.3708757 -0.8444282 -0.3865129 0.3730545 -0.773011 -0.5131124 0.2118032 -0.7886239 -0.577245 0.1147512 -0.8666595 -0.4855239 -0.162961 -0.7133072 -0.6816425 -0.07876443 -0.8197535 -0.5672747 -0.2417839 -0.811368 -0.5321866 -0.2196975 -0.7711321 -0.5975686 -0.4970962 -0.7368622 -0.4581808 -0.4705801 -0.8204312 -0.3247261 -0.6303472 -0.7504733 -0.1986263 -0.5522255 -0.8301765 -0.07651096 -0.6543326 -0.7521225 0.0784893 -0.4946804 -0.8308351 0.2549598 -0.489421 -0.8358532 0.2486293 -0.4456604 -0.7713798 0.4542686 -0.2171238 -0.8680968 0.4463912 -0.1810896 -0.8884109 0.4218205 -0.04267811 -0.7572087 0.6517773 0.1248895 -0.9034549 0.4100878 0.2849187 -0.7857904 0.548958 0.4322018 -0.8244987 0.3652445 0.409323 -0.8664067 0.2859969 0.5791711 -0.7835029 0.2251316 0.4901942 -0.8714483 0.01695281 0.5840332 -0.8106907 -0.04106026 0.5263298 -0.8241358 -0.2092296 0.4404532 -0.866556 -0.2346951 0.4488605 -0.8131058 -0.3706526 0.3399592 -0.815626 -0.4681689 0.2610901 -0.8665842 -0.4252811 0.07669746 -0.8650175 -0.4958452 0.0237466 -0.7627974 -0.6462015 -0.2246082 -0.7711918 -0.595663 -0.2365975 -0.7935398 -0.5606393 -0.4345544 -0.7422476 -0.5101285 -0.4495405 -0.8325211 -0.3237623 -0.587144 -0.7512173 -0.3015535 -0.6162382 -0.7854284 -0.05790209 -0.6115815 -0.789325 -0.05416923 -0.5732618 -0.7774844 0.258629 -0.4736566 -0.838312 0.2699675 -0.3742694 -0.823323 0.426687 -0.2472022 -0.8808229 0.4037848 -0.2076786 -0.7832806 0.5859533 0.003560185 -0.8400388 0.5425146 0.02929627 -0.8651365 0.5006802 0.2151115 -0.7958204 0.5660362 0.3083994 -0.8697201 0.3853272 0.3397372 -0.8505235 0.4014828 0.5403082 -0.8152356 0.2084656 0.5028878 -0.8519936 0.14564 0.6866145 -0.7270146 0.003231227 0.5064192 -0.8362809 -0.2101759 0.5585724 -0.7842016 -0.2702309 0.3467648 -0.8215979 -0.4524722 0.3710821 -0.8050459 -0.4628166 0.1125485 -0.7761608 -0.6204089 0.02664303 -0.8480971 -0.5291708 -0.1936249 -0.8359694 -0.5134828 -0.2032497 -0.8259861 -0.5257725 -0.4522607 -0.7989801 -0.3963472 -0.424436 -0.8443439 -0.3270129 -0.4939598 -0.853439 -0.1662702 -0.6834767 -0.7229111 -0.1012874 -0.5541094 -0.8232909 0.123106 -0.6291826 -0.7436199 0.2261832 -0.4590935 -0.8009204 0.3843954 -0.4727034 -0.737322 0.4826052 -0.2751967 -0.8277559 0.4889653 -0.16684 -0.7088484 0.6853454 0.02089703 -0.8385217 0.5444675 0.1291902 -0.7906922 0.5984278 0.2058001 -0.8580842 0.4704657 0.3924108 -0.7430149 0.5421649 0.4597918 -0.8527372 0.2478525 0.6394588 -0.7332954 0.2310203 0.493958 -0.8692514 0.02018487 0.6526557 -0.7500604 -0.1070042 0.5078262 -0.7918812 -0.339171 0.4997252 -0.7970135 -0.3391818 0.3288256 -0.800547 -0.5009975 0.3297471 -0.7822599 -0.5285229 0.09760105 -0.7418959 -0.6633737 0.03167092 -0.8077628 -0.5886565 -0.3215985 -0.7402632 -0.5904107 -0.1996599 -0.8694725 -0.4518337 -0.4655287 -0.7698171 -0.4366518 -0.4281575 -0.8849883 -0.1829671 -0.5167599 -0.8379392 -0.1755486 -0.5779287 -0.8160865 -0.00114113 -0.5380408 -0.8421181 0.03673547 -0.6397796 -0.723718 0.2586782 -0.3645558 -0.8640659 0.3471156 -0.4018757 -0.7624964 0.5070456 -0.1752495 -0.8467528 0.5022921 -0.1473262 -0.7921438 0.5922864 0.04488343 -0.752636 0.6569054 0.1914839 -0.8546447 0.482614 0.2097116 -0.8412786 0.4982686 0.4217651 -0.8045918 0.4180266 0.4159697 -0.8411579 0.345576 0.6571307 -0.7031642 0.2715498 0.4963327 -0.8680118 -0.01447695 0.6468532 -0.754724 -0.1094205 0.3922981 -0.8601435 -0.3259685 0.389755 -0.8627641 -0.3220703 0.2843896 -0.7517496 -0.594975 0.06868588 -0.8903071 -0.4501504 -0.06356948 -0.7543351 -0.6534046 -0.2105216 -0.8947411 -0.3938517 -0.356073 -0.801215 -0.4809017 -0.5000239 -0.8229587 -0.2696577 -0.4957224 -0.8272474 -0.2644262 -0.6313163 -0.7681414 0.1067641 -0.5856073 -0.8060353 0.08585566 -0.548154 -0.754999 0.3598665 -0.4082183 -0.8491998 0.334989 -0.2001259 -0.7975459 0.569096 -0.2006294 -0.8188593 0.5377893 0.05896794 -0.8574536 0.5111715 0.09410279 -0.8151646 0.5715342 0.2601661 -0.8858644 0.3841329 0.4868026 -0.7235694 0.4893574 0.5316092 -0.8281261 0.1777607 0.6171786 -0.7730917 0.1463547 0.4696195 -0.8817018 -0.04538375 0.5685241 -0.81195 -0.1323539 0.4177759 -0.8576153 -0.2999323 0.4651265 -0.7968551 -0.3855895 0.1745311 -0.8468303 -0.5024118 0.1734356 -0.8588665 -0.4819425 -0.02519011 -0.7557244 -0.6544052 -0.1406671 -0.8657869 -0.4802352 -0.3210339 -0.7523102 -0.575297 -0.4474321 -0.8372417 -0.3143737 -0.4027799 -0.8634989 -0.3035426 -0.5709038 -0.8030803 -0.1706783 -0.4948274 -0.8685488 -0.02772879 -0.6195632 -0.7824704 0.06230419 -0.459171 -0.866713 0.1948605 -0.5150194 -0.7898104 0.3330985 -0.3077712 -0.8675763 0.3906254 -0.31777 -0.8303679 0.457724 -0.1789956 -0.7887967 0.588014 -0.03747665 -0.8733723 0.4856093 0.08468621 -0.7714354 0.630647 0.2354656 -0.8878917 0.395227 0.3663665 -0.7961919 0.4815122 0.5234708 -0.8149567 0.2486448 0.4668386 -0.8712697 0.1514955 0.623071 -0.7799056 0.0594139 0.4184726 -0.899568 -0.1251338 0.5420688 -0.7902981 -0.2856403 0.3195441 -0.8586026 -0.4008656 0.3212556 -0.8556855 -0.4057061 0.1901859 -0.745425 -0.6388826 0.00932914 -0.8778443 -0.4788554 -0.1533654 -0.7414503 -0.6532462 -0.3530636 -0.8229851 -0.445019 -0.3175494 -0.8474882 -0.4253542 -0.5332641 -0.7631662 -0.3649752 -0.4566621 -0.8795682 -0.1334899 -0.5869518 -0.8033804 -0.1003372 -0.4511393 -0.8728311 0.186116 -0.5021461 -0.8473426 0.1727998 -0.4880619 -0.7837708 0.3840562 -0.2940879 -0.8633803 0.4099839 -0.2835002 -0.7951317 0.5360906 -0.07961815 -0.8653208 0.4948543 -0.02436125 -0.7922464 0.6097149 0.1160419 -0.847457 0.518026 0.3192213 -0.6955878 0.6436268 0.4031775 -0.8369733 0.3700321 0.5818313 -0.7303615 0.357833 0.5509181 -0.8146168 0.1813532 0.6375751 -0.7631614 0.1052745 0.5688754 -0.8143953 -0.1146355 0.5463497 -0.8319411 -0.09683001 0.4275481 -0.8544285 -0.2952198 0.4841059 -0.8271237 -0.285496 0.4363306 -0.7628766 -0.4771112 0.2216853 -0.8002618 -0.5571684 0.2211372 -0.7983572 -0.5601109 0.01602143 -0.7610488 -0.6484969 -0.1045408 -0.8564708 -0.5054988 -0.2444654 -0.7815433 -0.5739572 -0.2872726 -0.8479835 -0.4454194 -0.5052241 -0.7398424 -0.444277 -0.4669116 -0.8496626 -0.2450859 -0.6526327 -0.7501212 -0.1067183 -0.5715273 -0.8203753 0.01846826 -0.687061 -0.7107899 0.1507487 -0.5853692 -0.7788187 0.2253537 -0.5575122 -0.7089816 0.4318857 -0.1889334 -0.8866474 0.4220909 -0.4989389 -0.5607379 0.6607822 -0.0272752 -0.9334722 0.3576115 0.2312906 -0.7315832 0.6413195 0.6352586 -0.70185 -0.3222626 0.4129227 0.6730145 -0.6136338 0.3411278 -0.3991442 -0.8510675 -0.06462049 0.1942897 -0.9788135 -0.08001583 0.3516553 -0.9327036 -0.5286749 -0.02981483 -0.8483008 -0.481901 0.585118 -0.6522334 -0.7110658 -0.672581 -0.2049885 0.387413 0.1010825 0.916348 0.7684954 0.191987 0.6103737 0.7344337 -0.5379385 0.4137988 0.836023 0.5206052 0.1733086 0.7452837 -0.6513478 -0.1424722 0.8070806 0.5303894 -0.2594378 0.5323587 -0.40968 -0.7407811 0.5395228 0.2188314 -0.8130364 0.01403003 -0.2648231 -0.964195 -0.03191143 0.3350383 -0.941664 -0.5281111 -0.3660841 -0.7662122 -0.5610653 0.7539559 -0.3416964 -0.6837235 -0.7239428 0.09180933 -0.7597594 0.6166554 0.2061601 -0.6278715 -0.3913289 0.6727846 -0.5733024 0.4028096 0.7134906 -0.1432245 -0.5741582 0.8061198 -0.01764529 0.6297881 0.7765666 0.3627665 -0.4800166 0.7987394 0.4740017 0.5246526 0.7071507 0.6622721 -0.5615717 0.496017 0.7989466 0.5214148 0.299685 0.8524605 -0.5218479 0.03140139 0.9477522 0.3081267 -0.08260631 0.8085588 -0.3535339 -0.4703686 0.6334531 0.5999538 -0.4886643 0.4053862 -0.6140499 -0.6772037 0.1501625 0.6336075 -0.758942 -0.07151991 -0.5600425 -0.825371 -0.3538592 0.5769153 -0.7361743 -0.5540068 -0.4740325 -0.6843755 -0.856611 0.3538673 -0.3754937 -0.8673598 0.3177339 -0.3830566 -0.8948082 -0.4410349 0.06932979 -0.6316772 0.7484767 0.2019071 -0.4943506 -0.6535872 0.573098 -0.291928 0.5872461 0.7549306 -0.04969006 -0.6464222 0.7613601 0.2453282 0.6181744 0.7467761 0.4711325 -0.563506 0.678598 0.6440661 0.5630725 0.5178111 0.7782298 -0.542932 0.3155684 0.9147233 0.4040679 -0.003236472 0.9014213 0.1752327 -0.3958954 0.4832233 -0.3825219 -0.7875102 -0.7368655 0.3004254 -0.6056185 -0.9721503 -0.2340056 0.01284968 -0.8493199 -0.16418 0.5016978 -0.4058098 0.364296 0.8382164 -0.391205 0.0606994 0.9182997 0.1033197 -0.5179221 0.8491654 0.1918371 0.6601001 0.7262688 0.5348052 -0.6459774 0.5446986 0.6993505 0.4190722 0.57904 0.9916792 0.02013927 0.1271491 0.9182175 -0.3920171 0.05656069 0.8421759 0.3483731 -0.4115533 0.2588292 0.143053 -0.9552713 -0.2377162 -0.5013143 -0.8319706 -0.3050141 0.6391265 -0.7060338 -0.6025892 -0.6605402 -0.4478538 -0.7129905 0.5676781 -0.4115656 -0.9082328 -0.3963175 0.1343342 -0.4770021 0.4997915 0.7229644 -0.08190006 -0.609031 0.7889067 0.1154646 0.6504479 0.7507234 0.3785405 -0.4961993 0.7813408 0.5924333 0.6092843 0.5270632 0.5798927 -0.8137067 0.04007411 0.7126962 0.6356909 -0.2965828 0.4910337 -0.5898349 -0.6410779 0.310734 0.5826661 -0.7509626 0.1089296 -0.4952444 -0.8618975 -0.1895465 0.6918854 -0.6966826 -0.8524952 -0.5060716 -0.1309334 -0.7198207 0.5984139 0.351794 -0.3504688 -0.6795531 0.6444993 -0.1625446 0.5382319 0.8269738 -0.004373192 -0.2578457 0.9661762 0.433189 0.2638493 0.8618183 0.6342186 -0.6660353 0.3926369 0.8148328 0.5423583 0.2046825 0.7946254 -0.6008153 -0.08712911 0.678758 0.6824316 -0.2712464 0.6095668 -0.6002734 -0.5177839 0.3383098 0.4740029 -0.8129378 0.339293 0.368704 -0.8654118 -0.2144613 -0.5646631 -0.7969706 -0.2975088 0.4112786 -0.8615908 -0.7819023 0.1931855 -0.5927126 0.1869104 -0.7764734 0.601792 0.4434556 0.5348705 0.7192084 0.8202776 -0.3174673 0.4757723 0.8348149 -0.2287948 0.5007366 0.9924029 0.1120887 -0.05072391 0.8979588 0.4355224 -0.06316876 0.4981377 -0.6900446 -0.5250689 0.146611 0.8685807 -0.4733633 -0.3836038 0.351785 -0.8538709 -0.7093688 -0.5897239 -0.3860334 -0.8742941 0.4822694 -0.05501025 -0.7284119 -0.3586674 0.5837585 0.1215798 -0.3867039 0.9141545 0.5530746 0.4205162 0.719218 0.6304871 -0.5666788 0.530435 0.7727093 0.5379794 0.3368955 0.8657491 -0.4916717 0.09347438 0.8444568 0.4991336 -0.1943153 0.02896493 -0.509056 -0.860246 -0.308062 0.5064029 -0.8053906 -0.4814777 -0.5913271 -0.6469247 -0.6879201 0.5164396 -0.509957 -0.8414067 -0.4403995 -0.3131824 -0.877646 0.4669221 -0.1082653 -0.7795717 -0.6080737 0.1500486 -0.5350433 0.782988 0.3172671 -0.2902454 -0.7034304 0.6488015 -0.03710389 0.5963811 0.8018435 0.1986527 -0.5970722 0.7772014 0.4867002 0.5012045 0.7154837 0.6455057 -0.5518139 0.5280378 0.7800974 0.4507973 0.4338549 0.8810846 -0.472458 0.02176028 0.2731248 -0.08135628 -0.9585323 -0.3370699 0.1621432 -0.9274123 -0.5521994 -0.7337886 -0.3957654 -0.7204832 0.6625475 -0.2047801 -0.7605611 -0.641238 0.1017881 -0.7400527 0.6065803 0.2904864 -0.5582465 -0.652454 0.5125083 -0.3764412 0.7001301 0.6067206 -0.07545793 -0.6701743 0.738358 0.059147 0.4743151 0.8783661 0.4306384 -0.4126313 0.8026742 0.5052024 0.4504729 0.736101 0.7515743 -0.4712859 0.4615473 0.7190266 0.6456049 0.2572841 0.8326717 -0.5522957 0.04034042 0.796945 0.4861778 -0.3584827 0.7662106 -0.4015301 -0.5016922 0.3616948 0.5168949 -0.7758845 -0.114961 -0.7271247 -0.6768114 -0.370457 0.5816787 -0.7241627 -0.6309905 -0.5276572 -0.5687083 -0.7037799 0.5945186 -0.3888978 -0.8640344 -0.4577825 -0.2094755 -0.9754863 0.1094056 0.1909372 0.5561342 0.4569755 0.6941817 0.7938053 -0.5535777 0.2518433 0.417622 0.1679185 -0.8929699 -0.1277694 0.1155204 -0.9850533 -0.5771729 -0.1535571 -0.8020546 -0.9537252 -0.0675916 -0.2929843 -0.6704637 0.5167815 0.5323679 -0.1976544 -0.626746 0.7537388 -0.140569 0.5130038 0.8467984 0.4388713 -0.05045074 0.8971325 0.5690993 -0.7641071 0.3037539 0.8843348 0.349114 0.3099541 0.9809985 0.06777787 -0.1817915 -0.761604 -0.06799131 -0.6444662 -0.9889228 0.07884716 -0.1257566 -0.9716506 0.190287 -0.1403072 -0.8572703 -0.3570241 0.3709736 -0.720374 0.5620049 0.4064627 -0.4632402 -0.5949993 0.6567986 -0.3307865 0.6199305 0.7115241 0.0827499 -0.6491758 0.7561239 0.1673353 0.2208604 0.9608432 0.6658375 0.3105616 0.6783893 0.6772555 -0.503664 0.536328 0.9574654 0.2837153 0.05259186 0.8398777 -0.3198118 -0.4385497 0.4026229 -0.05578148 -0.9136648 0.3373862 0.454204 -0.8245419 -0.2189306 -0.5244792 -0.8227947 -0.9835219 0.1295275 0.1261246 -0.6819236 -0.1979548 0.7041265 0.4830873 0.4026009 0.7775212 0.7260203 -0.5564166 0.404098 0.686775 0.6995539 0.1973941 0.7919116 -0.6088691 -0.04641783 0.7589098 0.5449504 -0.3564901 0.6159164 -0.5832711 -0.5295677 0.4266442 0.6188234 -0.6595699 0.09315925 -0.7390958 -0.6671273 -0.0498349 0.6398449 -0.7668865 -0.4972117 -0.48989 -0.7160924 -0.8398284 0.5335211 -0.1002174 -0.7435527 -0.5936645 0.3077208 -0.4519333 0.8173567 0.3573294 -0.1513792 -0.7835221 0.6026421 0.05292415 0.5733678 0.817587 0.3744942 -0.5680175 0.7328782 0.5168114 0.2202958 0.8272701 0.8815156 0.1043558 0.4604783 0.8618523 -0.3420754 0.3744266 0.942716 0.3032277 -0.1390671 0.7912188 -0.09979861 -0.6033351 0.3134462 0.2395551 -0.9188933 -0.1716617 -0.8428593 -0.5100201 -0.8152473 0.535838 0.2196575 -0.6240154 -0.5141278 0.5884535 -0.4193009 0.6399275 0.6439563 -0.261948 -0.5021827 0.8241334 0.139009 0.5187496 0.8435492 0.2920496 -0.6272804 0.7219601 0.5452416 0.6772987 0.4939414 0.7176092 -0.6233573 0.3105844 0.8739649 0.4689677 0.1274937 0.8483262 -0.5115363 -0.1366511 0.7954152 0.5180951 -0.3144711 0.6013062 -0.5336602 -0.5946745 0.6324848 0.2315033 -0.7391679 0.1462124 -0.0641238 -0.9871728 -0.9311671 0.1195586 0.3444326 -0.5969832 0.0928663 0.7968606 -0.4244812 -0.5400292 0.7267628 -0.04899543 0.6008399 0.7978665 0.1825873 -0.6877546 0.7026063 0.3834977 0.6765546 0.6286521 0.6293715 -0.6059432 0.4865434 0.8375122 0.4900053 0.2418017 0.970766 0.03882175 -0.2368683 0.5873188 -0.2942137 -0.753986 0.1800398 -0.368651 -0.9119662 -0.2228944 0.4981569 -0.8379487 -0.3858566 -0.6564874 -0.6481814 -0.6110805 0.5351511 -0.5832616 -0.7464999 -0.6239849 -0.2310431 -0.1005159 -0.3386727 0.9355198 0.3773114 0.4374207 0.8162715 0.7397966 -0.3985953 0.5420542 0.9012899 0.4318201 0.03475904 -0.3423127 0.2676273 -0.9006652 -0.6825077 -0.5165796 -0.5170387 -0.6651426 0.6333046 -0.3956144 -0.7880696 -0.6120832 0.06557887 -0.7274108 0.5356783 0.4288618 -0.2547722 -0.6083508 0.7516651 0.1541531 0.4400703 0.8846327 0.6824557 -0.4738193 0.5565514 0.8778943 0.4507954 0.161509 0.8332279 -0.3458112 -0.4314464 0.6726648 0.5989663 -0.4344669 0.4191116 -0.6283672 -0.6553626 0.2021678 0.7138575 -0.6704742 -0.1011903 -0.6548329 -0.7489689 -0.277476 0.6114407 -0.7410449 -0.5487594 -0.5188029 -0.6555202 -0.7377818 0.5543395 -0.3852089 -0.9301651 -0.3620005 0.06122756 -0.8238556 0.1243567 0.5529895 -0.4735038 0.274703 0.8368587 0.03488641 0.04754739 0.9982597 0.1031305 -0.3910676 0.9145657 0.5203599 0.4545398 0.722924 0.6317122 -0.733067 0.2520963 0.7977733 0.6024423 0.02492165 0.8188437 -0.5142056 -0.255123 0.7674186 0.4698801 -0.4362126 0.6057889 -0.4760304 -0.6375067 0.3577765 0.5505746 -0.7542306 0.2671529 -0.2622908 -0.9272718 -0.2812517 -0.06165039 -0.9576517 -0.6674297 0.3133428 -0.6755398 -0.990251 -0.001959145 -0.1392806 -0.8600752 -0.5085248 -0.04090714 -0.8495332 0.4613723 0.2557913 -0.6042448 -0.6324906 0.484607 -0.610235 0.4894841 0.6229113 -0.1461424 -0.357084 0.922569 -0.1459665 -0.2586994 0.9548657 0.3660219 0.4465441 0.816472 0.4475386 -0.6414366 0.6231117 0.7168628 0.6111133 0.3356311 0.7458028 -0.6550853 0.1210018 0.8004248 0.5852332 -0.1297004 0.6574765 -0.6421573 -0.3941556 0.5288885 0.6749457 -0.5145146 0.3035719 -0.629848 -0.7149375 0.0203973 0.6523145 -0.757674 -0.4972746 -0.3486345 -0.7944633 -0.9246073 0.1351233 -0.3561503 -0.931261 0.003838956 -0.3643328 -0.9486744 0.1192686 0.2929027 -0.8813577 -0.3273676 0.3406451 -0.6208806 0.3383014 0.7071489 -0.3936437 -0.5785091 0.7144032 -0.2279891 0.5271802 0.8185976 0.1858547 -0.633776 0.7508569 0.9947354 0.1004616 -0.02022647 0.7925414 0.2488142 -0.5567491 0.008400857 0.3591023 -0.9332605 -0.5315995 -0.3135016 -0.786841 -0.6625522 0.3289502 0.6729164 -0.2004212 -0.007370352 0.9796821 -0.09977322 -0.4611765 0.8816812 0.1881014 0.4744598 0.8599453 0.4261957 -0.5321493 0.7315561 0.7319373 0.3057227 0.6089348 0.7807142 -0.4284681 0.4548633 0.8767573 0.4809082 0.004910647 -0.5303477 -0.06361269 -0.8453903 -0.3267111 0.9183995 -0.2231644 -0.8058272 0.5850062 -0.09170913 -0.5417208 0.8361282 0.08618831 -0.5624771 0.7544109 0.3383547 -0.5201695 0.7835015 0.3399256 -0.3683672 0.7283276 0.5777928 -0.3154489 0.7647411 0.561839 -0.1887047 0.7311165 0.6556365 -0.08514904 0.8111799 0.5785645 0.1202693 0.736118 0.6660823 0.2130504 0.8464529 0.4879827 0.3372198 0.7820639 0.5240792 0.409481 0.8671429 0.2835286 0.4208658 0.8556771 0.3011457 0.6441618 0.7590234 0.09454625 0.4403582 0.8976003 -0.01996618 0.6217516 0.7385627 -0.2606726 0.3842729 0.841506 -0.3797397 0.3141635 0.8823246 -0.3504347 0.2571932 0.7981479 -0.5448042 0.07326751 0.8415777 -0.5351438 0.05548232 0.8597928 -0.5076203 -0.1346191 0.7992133 -0.5857779 -0.1950512 0.8542292 -0.4819209 -0.3398711 0.7760896 -0.5311992 -0.4981068 0.7572503 -0.4224472 -0.4647415 0.8410875 -0.2767442 -0.6086189 0.7714987 -0.1853995 -0.4758799 0.8795062 -0.002690315 -0.5618795 0.8254321 0.05434608 -0.5445839 0.7850814 0.295086 -0.3472113 0.8895936 0.2967618 -0.3561732 0.8040636 0.4760487 -0.1454077 0.8613976 0.4866732 -0.1265857 0.8262457 0.5489028 0.1042197 0.7841226 0.6117926 0.1427686 0.8833566 0.4464284 0.3376438 0.815842 0.4694665 0.3523098 0.8729504 0.3373951 0.5057697 0.7975944 0.3286945 0.504586 0.860202 0.07379436 0.5915256 0.8053798 0.03822308 0.5589916 0.8119747 -0.1680048 0.4105504 0.8940036 -0.1794605 0.3806403 0.8420045 -0.3822846 0.3076191 0.8642553 -0.3980369 0.3052674 0.80686 -0.5057559 0.08260202 0.8214405 -0.5642805 0.01799726 0.8826186 -0.469745 -0.1190865 0.8077968 -0.5773064 -0.2829256 0.8210723 -0.4957757 -0.2765938 0.860167 -0.4284957 -0.4976286 0.7894672 -0.3593154 -0.4434282 0.866555 -0.2290282 -0.5984408 0.7918559 -0.1217905 -0.511277 0.8593083 -0.01360517 -0.5935195 0.7975277 0.1080937 -0.5502086 0.821541 0.1494694 -0.5750619 0.7482615 0.3307696 -0.4048919 0.8173586 0.4098628 -0.3095339 0.8763986 0.3689369 -0.1852172 0.8492345 0.4944647 -0.09442073 0.8814993 0.4626486 0.01043635 0.7483399 0.6632334 0.2401776 0.863641 0.4432145 0.2687679 0.8461751 0.4601646 0.5060932 0.8057203 0.3077086 0.4605599 0.8524006 0.2475845 0.5485872 0.8323435 0.07909774 0.6673898 0.7447086 1.21782e-4 0.4962901 0.8337833 -0.2418711 0.5242489 0.7959529 -0.3026917 0.3565415 0.8531063 -0.3809039 0.3599929 0.7739102 -0.5210262 0.1063149 0.765266 -0.6348741 0.07711738 0.7955408 -0.6009725 -0.138065 0.7618939 -0.6328157 -0.1729393 0.8167678 -0.5504384 -0.40135 0.7412249 -0.5380557 -0.4274301 0.8371035 -0.3414108 -0.5267045 0.7797867 -0.3384012 -0.5370903 0.8413285 -0.06083184 -0.5869877 0.8051781 -0.08446162 -0.6068918 0.7824347 0.1395651 -0.4282271 0.8659092 0.2585014 -0.4591886 0.8277981 0.3223294 -0.2952244 0.8165127 0.4961348 -0.2340352 0.8622891 0.4490938 0.01819974 0.7935889 0.6081823 -0.002321124 0.8243356 0.5660968 0.2435598 0.8885324 0.3888302 0.3571274 0.8153986 0.4556149 0.5742009 0.7421796 0.3456339 0.4595389 0.884656 0.07878893 0.512194 0.8571357 0.05455064 0.591728 0.7946019 -0.1358892 0.5367296 0.8256543 -0.1738286 0.5727196 0.7198237 -0.3922325 0.3867633 0.8215994 -0.4187941 0.3136957 0.7475957 -0.5854021 0.1247383 0.8524081 -0.5077804 0.03089386 0.7828906 -0.621392 -0.08253216 0.8672055 -0.4910632 -0.1831617 0.8126063 -0.5532837 -0.3577044 0.853994 -0.3778121 -0.3363932 0.8832916 -0.3265513 -0.6379589 0.7298459 -0.2456286 -0.4850689 0.8739106 -0.03144294 -0.6661636 0.7338075 0.1332395 -0.517474 0.8021893 0.2978475 -0.5304606 0.759932 0.3756527 -0.2937277 0.8299353 0.4742695 -0.2869126 0.8054287 0.5186192 -0.1110928 0.8652638 0.4888529 -0.06580257 0.8152677 0.5753335 0.1865202 0.8380556 0.5127115 0.1561945 0.8599747 0.4858465 0.3739013 0.7987515 0.4713745 0.3763624 0.8383554 0.3943496 0.6289278 0.7185237 0.2969402 0.5015475 0.8573355 0.1158707 0.6709308 0.7397765 -0.0508213 0.508646 0.8347896 -0.2107264 0.4998196 0.8400698 -0.210863 0.3496721 0.8656036 -0.3584128 0.3673399 0.8125253 -0.452619 0.1760562 0.822494 -0.5408401 0.1149207 0.8727393 -0.4744675 -0.05486339 0.7839356 -0.6184133 -0.1982707 0.8473007 -0.4927172 -0.1996392 0.6715397 -0.7135676 -0.4297642 0.8037198 -0.4115064 -0.4258977 0.8060116 -0.4110432 -0.6217756 0.7478891 -0.2325021 -0.4945031 0.865716 -0.07747584 -0.6472446 0.7595817 0.06411123 -0.4590014 0.8601703 0.2223169 -0.5362237 0.8131906 0.2262413 -0.440185 0.7476128 0.497305 -0.2428367 0.8733913 0.422159 -0.1387705 0.8006725 0.5828089 -0.04972296 0.867262 0.4953628 0.1105521 0.7996818 0.5901587 0.1705816 0.8477042 0.5022941 0.3328343 0.7617715 0.5558109 0.4697902 0.7967323 0.3801515 0.4311971 0.8611593 0.2692097 0.6062119 0.7718693 0.1916384 0.4764642 0.8791556 0.008210897 0.6237182 0.7717003 -0.1243153 0.4001184 0.8777207 -0.2636507 0.4350252 0.8231071 -0.3650314 0.2706568 0.8260257 -0.494395 0.214059 0.8633498 -0.4569529 0.03502923 0.7763534 -0.6293239 -0.06989991 0.8774935 -0.4744672 -0.1497236 0.8280135 -0.5403487 -0.393407 0.7881251 -0.4733814 -0.3684852 0.8488205 -0.3791075 -0.597496 0.7485987 -0.2873998 -0.5726425 0.8118977 -0.1135907 -0.7016478 0.7124202 -0.01216387 -0.5225643 0.8397021 0.1477395 -0.5855812 0.729669 0.3530977 -0.4419925 0.8102871 0.3848084 -0.3946467 0.7269841 0.5619147 -0.1903947 0.8358373 0.5149038 -0.08546745 0.7355821 0.6720226 0.137431 0.8622226 0.4875294 0.1432442 0.8581126 0.4930759 0.3871511 0.7708458 0.5058761 0.4146402 0.8721268 0.2597468 0.4963313 0.7946132 0.3496358 0.5306395 0.8475821 -0.005131244 0.5701831 0.8214849 0.00733298 0.4986527 0.8167566 -0.2902656 0.4438847 0.8521049 -0.2772792 0.2388151 0.6946622 -0.6785365 0.2475089 0.7774983 -0.5781313 0.1405013 0.8249449 -0.5474719 -0.1274146 0.6798966 -0.7221539 -0.2416474 0.8574794 -0.4542421 -0.2469397 0.8153222 -0.5237084 -0.4081787 0.8577467 -0.3125073 -0.4550912 0.8009742 -0.3890148 -0.4764178 0.8736306 -0.09897291 -0.6547114 0.754763 -0.04105758 -0.6126618 0.7753893 0.1530268 -0.5003422 0.8010014 0.3287165 -0.4671751 0.8491121 0.2464877 -0.3646389 0.7546613 0.5454584 -0.2551712 0.8181717 0.5152501 -0.1629057 0.7462227 0.645456 0.06529456 0.8574765 0.5103633 0.1185086 0.8125035 0.5707834 0.3458207 0.8184525 0.4588502 0.3218881 0.8816211 0.3451556 0.4895459 0.8086579 0.3262166 0.540935 0.8329703 0.1164044 0.5370645 0.8358311 0.1137902 0.5450038 0.8367283 -0.053447 0.64067 0.7483131 -0.1719579 0.4852828 0.7895935 -0.3755565 0.5229341 0.7611625 -0.3836296 0.3091109 0.8295465 -0.4650841 0.2620805 0.7386555 -0.6210491 0.01775062 0.8302996 -0.5570346 0.007671356 0.8195407 -0.5729696 -0.26377 0.8426476 -0.4694364 -0.2554567 0.8605718 -0.4406338 -0.4712851 0.8543015 -0.2192247 -0.4924064 0.836444 -0.2406188 -0.5583584 0.8295994 -7.83393e-4 -0.4805459 0.8763377 0.03328371 -0.5741367 0.7677828 0.2843883 -0.5166636 0.8027982 0.2976135 -0.4459155 0.7115325 0.5430294 -0.1940937 0.8662897 0.4602931 -0.1488254 0.8058771 0.5730735 0.06182485 0.8745503 0.4809777 0.08127933 0.8599036 0.5039439 0.3116671 0.7770039 0.5469266 0.3315482 0.8772776 0.3470733 0.4457274 0.8201441 0.3587352 0.5621703 0.8171893 0.127147 0.5713621 0.8097475 0.1336199 0.6383501 0.7434827 -0.1993557 0.5313028 0.8427849 -0.08620458 0.5628648 0.742527 -0.3630934 0.442799 0.801014 -0.4028721 0.4258463 0.7454609 -0.5127797 0.1523503 0.8107784 -0.5651794 0.1700454 0.8546337 -0.4905974 -0.0519526 0.7605253 -0.6472266 -0.1031244 0.8563145 -0.5060542 -0.4102073 0.7226937 -0.5562769 -0.3844611 0.8773905 -0.2870116 -0.5338844 0.79984 -0.2742689 -0.5970138 0.7955392 -0.1034028 -0.4766526 0.8790868 0.002958416 -0.5779178 0.8088678 0.1083703 -0.4222685 0.8543921 0.302826 -0.4364205 0.8361811 0.3321721 -0.3262518 0.7687075 0.5501353 -0.1091465 0.8858942 0.4508641 -0.06348896 0.8251895 0.5612767 0.1270086 0.7923211 0.5967381 0.1823226 0.8744004 0.4496471 0.3374683 0.8009785 0.4945186 0.384867 0.8731002 0.2992885 0.5264441 0.8000423 0.2877305 0.5108423 0.855727 0.0822885 0.5238454 0.8483898 0.0762943 0.6092254 0.7755301 -0.1655219 0.4008528 0.8943941 -0.198435 0.4621348 0.7507266 -0.4720603 0.2703236 0.8476788 -0.456471 0.1996306 0.7457942 -0.6355618 -0.02510797 0.8009216 -0.5982426 -0.07740777 0.8646363 -0.4963993 -0.2218132 0.7956623 -0.563667 -0.3575177 0.8519582 -0.382555 -0.3710528 0.8331336 -0.410132 -0.48602 0.8564697 -0.1739091 -0.6284901 0.7661424 -0.1342613 -0.4837761 0.8751887 -0.002380788 -0.5834081 0.7707791 0.255997 -0.5254368 0.8048772 0.2758421 -0.4575279 0.7235717 0.5168291 -0.3603039 0.7942434 0.4892431 -0.1929442 0.7825468 0.59194 -0.1523637 0.8166255 0.5566939 0.1272765 0.7546204 0.6436994 0.08340811 0.7992603 0.595169 0.4220731 0.7505423 0.5084688 0.3233987 0.8243349 0.4646345 0.4783234 0.7983047 0.3659461 0.4373487 0.8576407 0.2705158 0.6647763 0.73765 0.1180893 0.5771349 0.8159704 -0.03328531 0.6595436 0.736388 -0.1507817 0.481108 0.8281356 -0.2876222 0.5055259 0.7722769 -0.3847492 0.3285238 0.7716829 -0.5445896 0.2179524 0.8391748 -0.4982796 0.1440114 0.7835923 -0.6043543 -0.04686754 0.8629151 -0.5031709 -0.00139153 0.7771669 -0.6292931 -0.265309 0.7583665 -0.5953919 -0.3073698 0.8578045 -0.4119408 -0.4450179 0.7886424 -0.4242669 -0.4679856 0.8556803 -0.2209093 -0.4778879 0.8470876 -0.2325208 -0.6835336 0.7299146 0.002581119 -0.594089 0.8018923 0.06345832 -0.6051195 0.7264817 0.3256607 -0.3896246 0.8616946 0.3250771 -0.3347347 0.7985426 0.5002824 -0.1733568 0.8853165 0.4314652 -0.08513134 0.7378591 0.6695646 0.1994398 0.8625888 0.464935 0.211582 0.7763537 0.593724 0.4779922 0.771079 0.4206669 0.4108932 0.8788403 0.2425008 0.5780169 0.7947986 0.1849101 0.540096 0.8403556 -0.04581189 0.5971195 0.8017516 -0.0253542 0.6092996 0.7285426 -0.313017 0.4558814 0.824655 -0.3348378 0.3906328 0.7451685 -0.5404905 0.2929316 0.8081936 -0.5108956 0.1511058 0.7288367 -0.6678055 0.01266026 0.8207833 -0.5710994 -0.04050219 0.7978554 -0.6014868 -0.1998537 0.8350133 -0.5126513 -0.2924217 0.7790243 -0.5546267 -0.4818445 0.7864187 -0.3864861 -0.4127683 0.8300328 -0.3750572 -0.5538236 0.81041 -0.1910898 -0.471766 0.8753432 -0.1058834 -0.5939029 0.8038166 0.03403443 -0.4832175 0.861861 0.1539372 -0.544704 0.7956343 0.2650728 -0.3256955 0.874756 0.358782 -0.33478 0.8447531 0.4175102 -0.1587725 0.7539744 0.6374275 -0.01525682 0.8988336 0.4380245 0.192086 0.7313438 0.6544001 0.3488584 0.8715569 0.3445089 0.4104931 0.8369861 0.3618699 0.5845381 0.798809 0.1421951 0.5335363 0.8397083 0.1011384 0.6442997 0.7547134 -0.1236349 0.4560664 0.8566261 -0.241237 0.5176913 0.7590494 -0.3947658 0.23483 0.8743831 -0.4246281 0.2320054 0.8586016 -0.4571397 0.04973399 0.785946 -0.6162918 -0.01983892 0.8461348 -0.5325998 -0.1474323 0.7749338 -0.6146069 -0.3627219 0.7933743 -0.4888663 -0.3543432 0.7987263 -0.4862891 -0.5472984 0.7541205 -0.3629969 -0.5181687 0.811112 -0.2712909 -0.6427721 0.7462108 -0.1732445 -0.5547357 0.8287811 0.07341998 -0.5734102 0.8144947 0.0883134 -0.4804661 0.821618 0.3067514 -0.4280602 0.8523431 0.3004595 -0.3417689 0.7241943 0.5989463 -0.2042117 0.8250936 0.5268002 0.01563048 0.7685058 0.639652 0.0136978 0.7710055 0.6366811 0.3041877 0.7615523 0.5722833 0.2945771 0.8419043 0.45213 0.4229452 0.8543899 0.3018863 0.4992927 0.810989 0.3049651 0.5258066 0.8500211 0.03149318 0.4720293 0.8798487 0.05527025 0.5768855 0.7979683 -0.1744988 0.408055 0.8702083 -0.2760953 0.4273677 0.8449092 -0.3216913 0.2488389 0.7877073 -0.563557 0.1314793 0.8802385 -0.4559532 -0.001363515 0.76029 -0.6495825 -0.2252281 0.8554036 -0.4664301 -0.2313758 0.8243993 -0.5165569 -0.5325453 0.7634156 -0.3655027 -0.5408306 0.7498947 -0.3809991 -0.6059203 0.7919456 -0.07538396 -0.5657928 0.8230457 -0.0497424 -0.480381 0.8666623 0.1346502 -0.5324935 0.8232264 0.1968479 -0.3838397 0.8304012 0.4038577 -0.528019 0.7105374 0.4651157 -0.1426172 0.8255442 0.5460193 -0.139499 0.8166794 0.5599775 0.109137 0.8054159 0.5825756 0.1352657 0.9107855 0.3900936 0.4894575 0.7216691 0.4895152 0.3841859 0.8960384 0.2225229 0.58453 0.7972178 0.1508929 0.5085567 0.8581767 -0.07002145 0.6591918 0.751158 -0.03504276 0.5314458 0.8002508 -0.2777841 0.3695928 0.8813185 -0.2944131 0.3753315 0.798537 -0.4706008 0.2182437 0.8301442 -0.5130599 0.2524806 0.7959132 -0.5502506 -0.06160426 0.7803819 -0.6222614 -0.09705764 0.848887 -0.5195871 -0.3398249 0.760169 -0.5537707 -0.3974781 0.823706 -0.4043754 -0.4906294 0.7714771 -0.4051 -0.6058387 0.7762923 -0.1741543 -0.5890966 0.7926388 -0.1571275 -0.6472935 0.7576695 0.08335644 -0.5226505 0.8391276 0.15067 -0.5299677 0.8138575 0.238265 -0.3979998 0.867015 0.2998022 -0.4156517 0.7970486 0.4381177 -0.1970709 0.8774827 0.4372495 -0.1652823 0.8082451 0.565174 0.08306157 0.8406423 0.5351834 0.11037 0.8933697 0.435556 0.3472107 0.7575328 0.552801 0.4730228 0.7984645 0.3724298 0.4007592 0.8848373 0.2376026 0.5632646 0.807738 0.1740471 0.5463301 0.8375596 -0.00418806 0.5040165 0.8633458 -0.02452951 0.5688042 0.7862515 -0.2413927 0.3590844 0.8915129 -0.276158 0.3925772 0.8038088 -0.4469617 0.1954328 0.8246619 -0.5307911 0.1673067 0.8467957 -0.5049213 -0.02296721 0.7382762 -0.6741074 -0.1742497 0.8064916 -0.5649854 -0.2047377 0.7879642 -0.5806849 -0.4274038 0.7642192 -0.4830065 -0.4079172 0.8195987 -0.4023203 -0.6330974 0.734299 -0.2449343 -0.5663942 0.8122666 -0.1393581 -0.6803872 0.7328522 -9.89772e-4 -0.5455964 0.8102022 0.214236 -0.5063902 0.8469723 0.1618862 -0.4522647 0.8011837 0.3918691 -0.2785823 0.888676 0.3642073 -0.2765656 0.8466852 0.4545721 -0.09022486 0.7402126 0.6662919 0.05251342 0.8910312 0.4508944 0.2068869 0.7897905 0.5774331 0.3735034 0.8266078 0.4209688 0.3493022 0.871482 0.3442486 0.5309606 0.8080398 0.2552501 0.5110821 0.8317775 0.2166599 0.6632049 0.7477872 0.03120565 0.5177745 0.8450442 -0.1334535 0.5347564 0.8305502 -0.1556348 0.5043289 0.7981638 -0.3295255 0.3940997 0.8537519 -0.340284 0.3820871 0.7598438 -0.5259724 0.1092213 0.807857 -0.5791699 0.1163033 0.8213832 -0.5583937 -0.1585297 0.8334083 -0.5294327 -0.1787316 0.8882411 -0.4231815 -0.3654894 0.793789 -0.4861242 -0.4900348 0.801003 -0.3438899 -0.4485242 0.8527938 -0.2675234 -0.6615428 0.737272 -0.1370806 -0.532103 0.8451425 0.05099576 -0.6412979 0.7324692 0.22853 -0.5092006 0.8135475 0.2808122 -0.4730582 0.7508655 0.4608871 -0.330922 0.8108717 0.4826778 -0.2897462 0.7521935 0.591821 -0.05581647 0.8246192 0.5629279 -0.07055729 0.842361 0.5342749 0.1529411 0.8048852 0.5733839 0.1718885 0.8339384 0.5244056 0.4088849 0.7314934 0.545647 0.4353423 0.843116 0.3156467 0.4869648 0.8163061 0.3106601 0.5446903 0.8370087 0.05224096 0.591085 0.8030029 0.07618987 0.6243159 0.7480415 -0.2250857 0.5221148 0.8177956 -0.2420879 0.4102033 0.7440667 -0.5273501 0.3951668 0.8123247 -0.4289196 0.154358 0.8053398 -0.5723648 0.1287593 0.7447003 -0.6548608 -0.1493374 0.7312065 -0.6656091 -0.1929952 0.8616415 -0.4693898 -0.4273349 0.8128613 -0.3957797 -0.3521455 0.8604695 -0.3682198 -0.6341562 0.7580481 -0.152345 -0.5248374 0.8478012 -0.07601857 -0.6619144 0.730139 0.1696066 -0.4665714 0.8379679 0.2830563 -0.4979432 0.7637743 0.4107328 -0.2615999 0.8779434 0.4009751 -0.2140238 0.7484807 0.6276707 0.1024827 0.8143399 0.5712686 0.06486588 0.8495054 0.523577 0.3359137 0.7645787 0.550074 0.3178669 0.8596744 0.3999007 0.6553337 0.6887735 0.3100464 0.5069493 0.8573312 0.08936339 0.6573013 0.7520667 -0.0484845 0.4195016 0.8815463 -0.216552 0.563387 0.7915456 -0.2367506 0.3432239 0.8496642 -0.4003351 0.3191573 0.8642858 -0.3887785 0.1515082 0.7472199 -0.6470762 0.003575801 0.8942757 -0.4475023 -0.1866129 0.7716635 -0.6080388 -0.280627 0.8631075 -0.4198738 -0.4000847 0.8021013 -0.4433576 -0.5628107 0.7811207 -0.2703604 -0.4515361 0.8427702 -0.2930077 -0.6264559 0.7749894 -0.08333504 -0.5054477 0.8620255 0.03787791 -0.592411 0.7859765 0.1768907 -0.4736099 0.8549151 0.2116929 -0.4709655 0.721857 0.5070641 -0.2584655 0.8411296 0.4750756 -0.2213159 0.7988213 0.559378 -0.01267445 0.8487428 0.5286541 0.005213022 0.8695965 0.4937358 0.1711981 0.7956511 0.5810597 0.2898731 0.8650441 0.4094782 0.3162258 0.7900275 0.5252215 0.5449411 0.793044 0.2722508 0.4819992 0.8530794 0.1998305 0.630685 0.7748285 -0.04332786 0.4822639 0.8712183 -0.0916537 0.5225208 0.7887877 -0.3237068 0.3792647 0.8688606 -0.3181815 0.3184481 0.7833068 -0.533874 0.1780224 0.8766276 -0.4470257 -0.01839834 0.7583196 -0.6516234 -0.06287658 0.8317024 -0.55165 -0.3385384 0.7247295 -0.6001324 -0.3844534 0.841976 -0.3785131 -0.4091069 0.8297406 -0.3796872 -0.5315369 0.8324032 -0.1567596 -0.4000712 0.9135968 -0.07269185 -0.5865901 0.7989431 0.1326731 -0.4916378 0.8254935 0.2772238 -0.4234135 0.8677743 0.2601708 -0.268713 0.7594084 0.5925305 -0.1223317 0.8820837 0.4549323 -0.08732855 0.8564879 0.508726 0.1873247 0.8364146 0.5150923 0.1807376 0.9161178 0.3578576 0.4791829 0.770841 0.4197476 0.5493394 0.8080607 0.2127544 0.4515537 0.8819648 0.1350459 0.6205831 0.7814181 -0.06528627 0.423507 0.8869719 -0.1841816 0.5072727 0.790725 -0.3426784 0.2594517 0.8503316 -0.457844 0.2613304 0.8488106 -0.4595944 0.007004618 0.7812121 -0.6242265 0.06056725 0.8404889 -0.5384329 -0.2658689 0.7507178 -0.6047618 -0.2816646 0.8532636 -0.4388694 -0.4253266 0.7963587 -0.4300116 -0.4314461 0.877786 -0.2081969 -0.4319318 0.8774105 -0.208772 -0.6584527 0.7525452 0.01075577 -0.4410226 0.8897113 0.117953 -0.5340374 0.8007954 0.2711655 -0.3771908 0.8268265 0.4172354 -0.2776694 0.8816222 0.381631 -0.2414743 0.8006514 0.5483134 0.02569067 0.8391407 0.5433076 0.01996338 0.8268371 0.5620872 0.3537057 0.7406405 0.5712652 0.3515818 0.8126446 0.464757 0.5383935 0.7477924 0.3885087 0.4963917 0.8393713 0.2214754 0.7176722 0.6960569 -0.02124851 0.5128139 0.8568017 0.05397105 0.6185807 0.7556729 -0.2152126 0.4764995 0.845293 -0.2417191 0.4854123 0.7445403 -0.4582954 0.2765395 0.8244193 -0.4938207 0.2279835 0.7370738 -0.6361963 -0.008319318 0.8310095 -0.5561961 -0.09167522 0.7604681 -0.6428717 -0.2317756 0.8573335 -0.4596295 -0.2356974 0.8060904 -0.5428308 -0.4855405 0.7608258 -0.430575 -0.4541547 0.8305809 -0.3223026 -0.6352262 0.7601523 -0.1365874 -0.5887588 0.8032876 -0.08995747 -0.548183 0.8312967 0.09187608 -0.7483172 0.5804608 0.3210712 -0.5512048 0.763114 0.3373876 -0.3593595 0.8649924 0.3502128 -0.342301 0.7664998 0.5434227 -0.08443111 0.8731647 0.4800574 -0.1154337 0.8343998 0.5389362 0.215725 0.7916143 0.5716727 0.2108224 0.8559358 0.4721523 0.4592743 0.8253663 0.3283864 0.4387524 0.8377995 0.3249437 0.5811492 0.7943246 0.1769579 0.6172245 0.7853152 -0.0481044 0.5024219 0.8631624 0.05023044 0.5637958 0.7880175 -0.2473112 0.4668614 0.8432524 -0.266394 0.4576128 0.7913675 -0.4053741 0.2584802 0.867922 -0.4241456 0.25402 0.8362191 -0.4860159 0.03638708 0.8003015 -0.5984928 0.07243818 0.8788164 -0.4716297 -0.2205787 0.7233052 -0.6543505 -0.2249112 0.8726904 -0.4333896 0.3517907 -0.8928943 -0.2810394 -0.1972404 -0.8986943 0.3917204 -0.3303734 -0.9148854 0.232031 0.4506455 0.8626139 0.2298173 -0.3024299 0.7981259 -0.5210866 -0.5412735 -0.7363498 -0.4059706 -0.5723593 0.7772056 -0.2614505 -0.5803653 0.8039431 -0.1298137 -0.5497427 -0.8051959 0.2223573 -0.1870803 -0.8956735 -0.4034477 0.2404523 -0.8381592 0.4895629 0.3420998 0.8719107 0.350342 0.3181034 -0.8843807 -0.3415862 -0.5204343 -0.8072517 -0.2783755 -0.6440538 0.7438429 -0.178585 -0.6051225 -0.791441 0.08630192 0.09620535 -0.8020567 0.5894488 0.2333058 0.7557978 0.611832 0.4305433 -0.7989197 0.4199522 -0.6848642 -0.3917728 -0.6143901 -0.7939428 -0.00208342 -0.6079889 -0.9639809 -0.005688369 -0.2659111 -0.9801372 -0.06518673 0.1873018 0.1034582 0.9944447 0.0193935 0.6897311 0.7176189 0.09640651 0.8678659 0.4686077 0.164972 0.4324222 0.8828715 0.1831635 0.8829985 0.4121851 0.2245379 0.6522924 0.6050288 0.4565686 0.5458352 0.7302519 0.4108481 0.9080756 -0.1001618 0.4066526 0.4551056 0.7781145 0.4329165 0.379215 0.8282217 0.4126071 0.7536165 0.3383918 0.5635187 0.2561277 0.8390181 0.4800495 0.07788538 0.9616515 0.2629836 0.6196457 -0.02086222 0.7846045 0.2767135 0.7516906 0.5986578 0.4237858 0.3747861 0.8245853 0.4186987 0.4162011 0.8071358 0.286204 0.3385974 0.8963477 0.02166122 0.8737874 0.4858257 0.09262961 0.6800693 0.7272727 0.07638174 0.6879038 0.7217716 -0.01504975 0.531715 0.8467896 0.1009019 -0.1631654 0.9814255 -0.1139606 0.8956101 0.429995 0.03868168 0.02803581 0.9988582 -0.2304872 0.6819956 0.6940878 -0.179499 0.5356231 0.8251594 -0.1055271 0.9767284 0.1867241 -0.2435234 0.2294162 0.9423718 -0.4294359 0.5395987 0.7241672 -0.4142261 -0.1184956 0.9024276 -0.4910957 0.1732378 0.8537058 -0.3977676 0.8436527 0.3605985 -0.5046204 0.7177075 0.4798481 -0.761709 0.3836752 0.5221042 -0.7809166 0.1415951 0.6083749 -0.3881345 0.9166623 0.09529882 -0.6873674 0.7139003 0.133688 -0.2394275 0.9706839 0.02115237 -0.8452655 0.4099611 0.3427216 -0.8437923 0.5366687 0.001157999 -0.9459486 0.3242415 -0.00698775 -0.6650887 0.7143874 -0.2175036 -0.6104666 0.7644326 -0.2073007 -0.962431 0.06147682 -0.2644755 -0.8325086 0.4079219 -0.374872 -0.3825725 0.8775035 -0.2891818 -0.7754741 0.3498622 -0.5255819 -0.4434757 0.7778018 -0.4453694 -0.7846956 0.1329721 -0.6054512 -0.571508 0.5990836 -0.5607829 -0.6411244 -0.09335619 -0.7617377 -0.5317795 0.3518577 -0.7703291 -0.06509602 0.9669523 -0.2465076 -0.270235 0.8285263 -0.4904256 -0.3179888 0.4759113 -0.8199949 -0.3001012 0.4576947 -0.8369319 -0.2653428 0.2432089 -0.9329752 0.01363563 0.8541756 -0.519806 -0.007705509 0.6764174 -0.7364783 0.1400671 0.9015426 -0.4093925 0.06909674 0.511494 -0.8565043 0.04246163 0.2287937 -0.9725485 0.1537779 -0.3001527 -0.9414143 0.3106911 0.4852998 -0.8172853 0.3133344 0.7600325 -0.5693612 0.3468484 0.3675554 -0.8629016 0.3917845 0.7580886 -0.521351 0.343904 0.9030779 -0.2572555 0.4530041 0.8515944 -0.2637693 0.6346672 -0.01977109 -0.7725327 0.6841934 0.3430111 -0.6436014 0.7986242 0.40911 -0.4413939 0.8003929 0.3773095 -0.4658421 0.5832411 0.8098827 -0.06260937 0.8865423 0.4003094 -0.231938 0.569736 0.8206101 -0.04472416 0.9908761 0.0769087 -0.1106782 0.007449567 0.9999343 -0.008719444 -0.008607804 0.9999392 -0.006902098 0.004342973 0.9999899 0.001204013 0.004078447 0.9999913 9.26422e-4 0.004484295 0.9999698 0.006367266 0.004695475 0.9999865 0.002250075 -0.003266274 0.9999762 -0.006090044 -0.8650147 -0.07153338 0.4966212 -0.8651109 -0.07179921 0.4964151 -0.002623736 -0.07223206 0.9973844 -0.001722514 -0.07116627 0.997463 0.8631446 -0.0708217 0.4999657 0.8625696 -0.0720064 0.5007882 0.8625198 -0.07200288 -0.5008747 0.8624622 -0.07211613 -0.5009572 0.003781855 -0.07183843 -0.9974092 0.002091228 -0.0697782 -0.9975603 0.00818026 -0.999931 0.008429288 0.004194796 -0.9999266 0.01137048 0.01020914 -0.9999412 0.003682076 0.009265601 -0.999948 0.004276633 0.01091593 -0.9999366 -0.002777814 -0.002406716 -0.9999331 0.01131606 -2.4112e-4 -0.9999482 0.01018214 -0.007297396 -0.9999297 0.00935465 0.008469343 -0.9999288 -0.008408486 0.009221971 -0.9999493 -0.004041492 -0.00860399 -0.9999446 0.0060606 -0.01057857 -0.9999313 0.005060195 0.00444442 -0.9999258 -0.01134896 -0.0127393 -0.9999187 6.9535e-4 -3.92208e-4 -0.9999447 -0.01051092 -0.001711905 -0.9999344 -0.01132959 -0.01100796 -0.9999285 -0.004678606 -0.008601129 -0.9999446 -0.006077408 -0.007719039 -0.9999298 -0.009001016 0.001774251 -0.9999976 0.001315414 -0.004054903 -0.9999528 -0.008828461 0.001301407 -0.9999989 8.84578e-4 0.001622378 -0.9999982 0.001064658 -0.9689528 -0.01967865 0.2464618 -0.9690828 -0.01993662 0.2459293 -0.8398387 0.02275377 0.5423589 -0.7099153 -0.02636164 0.7037937 -0.5430963 0.01764899 0.8394849 -0.3645604 -0.01969498 0.9309716 -0.2062392 0.02222776 0.9782492 0.1493273 -0.02721571 0.9884132 0.2846044 0.03159564 0.9581243 0.6505243 -0.03363287 0.7587404 0.768684 0.02413767 0.6391732 0.9202668 -0.01855123 0.3908518 0.9563472 0.01313996 0.2919372 0.9984431 -0.009818315 -0.05491024 0.996089 0.001611948 -0.08834087 0.9159626 0.001614391 -0.4012605 0.9019412 -0.01009553 -0.431741 0.6761608 0.01485997 -0.7366043 0.6149834 -0.01450902 -0.7884066 0.3157712 0.01044374 -0.9487779 0.2080258 -0.02404421 -0.9778279 -0.04195445 0.02733421 -0.9987456 -0.3461306 -0.003375053 -0.9381803 -0.381076 -0.02141553 -0.9242957 -0.6961219 0.01460403 -0.7177751 -0.7127979 0.003374934 -0.7013614 -0.9404863 -0.02997493 -0.3385072 -0.9789444 0.03176635 -0.2016402 5.68249e-4 0.9999998 -6.20608e-4 -0.002693235 0.9999611 -0.00840944 0.00569427 0.9999808 -0.002500534 0.01429194 0.999886 0.004891932 0.002537071 0.9999678 -0.007629036 0.006451249 0.9999791 -5.71371e-4 -3.37792e-4 0.9999676 -0.008036851 0.01988971 0.9996352 -0.01827812 0.005834519 0.9999814 0.001780211 -0.006060242 0.9998737 -0.01469302 -0.002874791 0.9999516 0.009416282 -0.02299052 0.9997344 0.001633763 -1.7661e-4 1 -1.50273e-4 -9.48346e-4 0.9999992 -9.29395e-4 1.58998e-4 1 -2.79348e-4 -1.67259e-5 1 -5.23803e-5 3.25868e-4 0.9999953 -0.003067433 -0.003575801 0.9999933 -7.34627e-4 0.03116458 0.9994966 0.005946636 -0.004105627 0.9998018 0.01948285 -0.003923594 0.9999919 9.95503e-4 -0.02726185 0.9995869 0.009100914 -0.003274857 0.9999924 0.002104341 -0.006257593 0.9999337 0.009674549 -0.01866924 0.999819 -0.003674089 -0.9994998 -0.02288442 -0.02183061 -0.8713502 -0.0849865 -0.4832453 -0.7728233 0.1573056 -0.6148163 -0.600013 -0.1072389 -0.79277 -0.2578614 0.1655496 -0.9518934 -0.0818367 -0.16139 -0.9834918 0.4149989 0.1104592 -0.9030917 0.4914985 -0.04034483 -0.8699434 0.8356697 -6.04395e-4 -0.5492321 0.8263683 0.03003352 -0.5623286 0.9997705 -0.01946443 0.008963167 0.9915444 -0.1253455 -0.03359013 0.9115247 0.1444019 0.3850598 0.7555158 -0.1704625 0.6325649 0.5662283 0.1817387 0.803963 0.2647316 -0.206979 0.9418476 -0.08028274 0.178386 0.9806799 -0.3499734 -0.1691812 0.9213557 -0.5654798 0.1334437 0.8138951 -0.8450624 -0.1234532 0.52022 -0.8932986 0.0237717 0.4488347 -0.9992921 0.0370928 0.006288349 -0.9649534 -0.2437 0.097341 -0.8801117 0.2326242 0.4138714 -0.7917236 -0.195333 0.5788081 -0.6540073 0.1529623 0.7408624 -0.4701647 -0.1793176 0.8641703 -0.3077142 0.1496642 0.9396343 -0.09064835 -0.09681314 0.9911661 0.01612842 0.07856971 0.9967783 0.2219761 -0.109268 0.9689104 0.3534951 0.1457078 0.9240186 0.5920449 -0.1576218 0.7903406 0.6878892 0.1545919 0.7091614 0.8735246 -0.1486403 0.4635309 0.9285924 0.1234347 0.3499717 0.986779 -0.1244717 0.1037982 0.9942312 0.1072214 0.002827346 0.9431886 -0.06595551 -0.3256461 0.9179322 0.09985321 -0.3839662 0.7667376 -0.1420319 -0.6260514 0.6722195 0.1317604 -0.728533 0.4737227 -0.09590262 -0.8754368 0.4014687 0.08301943 -0.9121024 0.09284907 -0.1460793 -0.984906 -0.0594744 0.2501947 -0.9663671 -0.3227073 -0.2245364 -0.9194799 -0.5664164 0.1614161 -0.8081568 -0.6664401 -0.1303169 -0.7340812 -0.8387497 0.183312 -0.5127338 -0.9183106 -0.2024403 -0.3401817 -0.9716188 0.2192475 -0.08881145 0 -1 3.77706e-6 0 -1 -2.62852e-6 0 -1 -5.19096e-6 0 -1 -7.31517e-6 0 -1 6.05572e-6 0 -1 1.15243e-5 0 -1 -1.30106e-5 0 -1 3.13015e-6 0 -1 7.55533e-6 0 -1 1.25438e-5 0 -1 3.61199e-6 0 1 -2.96655e-6 0 1 5.27136e-6 0 1 -3.27204e-6 0 1 8.22421e-6 0 1 -1.17438e-5 0 1 -4.38008e-6 0 1 4.86217e-6 0 1 -1.03407e-5 -0.9115659 -0.01357078 -0.4109299 -0.9307094 0.08717149 -0.3552199 -0.5873494 -0.08152538 -0.805217 -0.6293849 0.01456648 -0.7769573 -0.09809833 0.1498475 -0.9838305 0.06416231 -0.1621335 -0.9846807 0.4821084 0.1110307 -0.8690476 0.6069834 -0.1036179 -0.7879307 0.8432954 0.1185711 -0.5242079 0.9265966 -0.1473787 -0.3459745 0.9923401 0.1209541 -0.02512842 0.9758211 -0.09579765 0.1964585 0.9178595 0.08487135 0.3877251 0.7866691 -0.1157953 0.6064185 0.5893454 0.1566951 0.7925395 0.3596132 -0.1726166 0.9169962 -0.01154446 0.2073421 0.9782004 -0.2247006 -0.1494139 0.9629045 -0.7045385 0.1117001 0.70082 -0.6462087 -0.1117081 0.7549409 -0.9472459 0.156915 0.2794692 -0.9802359 -0.1641719 0.1103862 -0.9922212 -0.1101057 0.05808496 -0.9710434 0.1669801 0.1708583 -0.8903297 -0.174962 0.4203586 -0.7901511 0.2044769 0.5777981 -0.6201961 -0.1754676 0.7645705 -0.4728534 0.1544612 0.8674972 -0.2913512 -0.1417458 0.9460564 -0.0820614 0.1651476 0.9828491 0.1142103 -0.2064519 0.9717684 0.351504 0.2479981 0.9027414 0.5669022 -0.2524596 0.7841468 0.7516468 0.2428963 0.6132116 0.8702962 -0.1712041 0.4618159 0.9893903 -0.1013689 0.1040726 0.9748366 0.1132121 0.1920335 0.9708557 0.1491773 -0.1875779 0.9354842 -0.143382 -0.3229723 0.8150036 0.1390835 -0.5625165 0.7727098 -0.06964296 -0.6309276 0.4758939 0.006850242 -0.8794761 0.4759816 0.006491184 -0.8794313 0.1067318 0.02999162 -0.9938354 0.09384351 -0.01494365 -0.9954748 -0.3461088 -0.07389229 -0.93528 -0.4016774 0.1441899 -0.9043586 -0.7134591 -0.1303892 -0.6884583 -0.7710743 0.0952453 -0.6295815 -0.9416857 -0.0613327 -0.330857 -0.9556228 0.0702207 -0.2861018 0 -1 -5.82183e-6 0 -1 3.60217e-6 0 -1 -6.84604e-6 0 -1 3.07698e-6 0 -1 6.60749e-6 0 -1 7.25428e-6 0 -1 -1.27488e-5 0 -1 -7.25884e-6 0 -1 1.2756e-5 0 -1 -1.06763e-5 0 1 -2.27615e-6 0 1 1.02771e-5 0 1 -1.62319e-5 0 1 4.39524e-6 0 1 8.04018e-6 0 1 -1.11368e-5 0 1 -1.09633e-5 0 1 1.22329e-5 0 1 -1.03624e-5 0 1 -1.10482e-6 0 1 2.21573e-6 0 1 -4.63166e-6 0 1 4.6471e-6 0.01881778 -0.9993582 -0.03048282 0.02281564 -0.9987351 -0.04480737 0.00680387 -0.9996452 -0.02575355 0.1018146 -0.994284 -0.0321452 0.007155835 -0.999704 -0.02325505 0.02944195 -0.9993028 0.02295786 -1.44863e-4 -0.9999315 -0.01170831 -8.20263e-4 -0.9999996 5.08249e-4 0.003046274 -0.9999743 -0.006486356 -0.00832349 -0.9997509 0.02071255 0.02814453 -0.9995615 -0.009213447 -0.04729229 -0.9950668 -0.08721101 0.07011598 -0.9963027 0.04964756 0.01878231 -0.9981352 0.05808085 0.06617695 -0.9753342 0.21058 7.55485e-4 -0.9874929 0.157662 0.004956126 -0.8861927 0.4632905 0.1104911 -0.6090357 0.7854091 0.2643878 -0.8862226 0.380406 0.4790344 -0.7090297 0.5174969 0.4750634 -0.8710552 0.1248102 0.455962 -0.8831481 0.1102191 0.6605739 -0.7325385 -0.164407 0.3657761 -0.8932861 -0.2612429 0.4611704 -0.7539185 -0.4678982 0.09231311 -0.9083367 -0.407925 0.06945943 -0.787951 -0.6118077 -0.2324901 -0.8240886 -0.5165525 -0.2332013 -0.8379358 -0.4934377 -0.5645133 -0.742643 -0.3602862 -0.5606271 -0.7491037 -0.3529039 -0.5543166 -0.8320569 -0.02035611 -0.6552215 -0.7547638 0.0318818 -0.5083556 -0.8170319 0.2720912 -0.5256431 -0.7862494 0.3248251 -0.3749107 -0.8517715 0.3659608 -0.3672317 -0.7945489 0.4835627 -0.1599138 -0.8760377 0.4549567 -0.1101075 -0.7961319 0.5950215 0.0589624 -0.8341251 0.548415 0.05525094 -0.8299747 0.5550581 0.2979531 -0.7376421 0.6058945 0.3868008 -0.8202711 0.4213557 0.4080937 -0.8077636 0.4254145 0.5654086 -0.7867822 0.247562 0.5001924 -0.8493803 0.1684063 0.643714 -0.7652296 -0.007487416 0.5029987 -0.8538182 -0.1341149 0.5647096 -0.7984511 -0.2087565 0.4062939 -0.8218567 -0.3993456 0.3185843 -0.8700296 -0.3762349 0.2220501 -0.7683104 -0.6003274 0.04988789 -0.8707561 -0.4891779 -0.01260709 -0.8163651 -0.5773988 -0.2398806 -0.8356722 -0.4940742 -0.2468042 -0.874845 -0.4168143 -0.4412726 -0.7937246 -0.4186645 -0.4431844 -0.8735969 -0.2010377 -0.5433663 -0.8172309 -0.1920592 -0.5307276 -0.8443152 0.07389277 -0.5052261 -0.8608064 0.06131017 -0.5247585 -0.7987402 0.2943516 -0.3533493 -0.8665422 0.3524897 -0.3682968 -0.8389537 0.4006425 -0.2280426 -0.8110989 0.5386235 -0.06767797 -0.889791 0.4513222 0.04319709 -0.7165836 0.6961624 0.2256117 -0.861523 0.4548378 0.3599857 -0.7732582 0.5219983 0.5365324 -0.7492374 0.3882992 0.5204323 -0.7845779 0.337028 0.6061406 -0.7819798 0.1452628 0.5861009 -0.8012902 0.1200819 0.6100881 -0.7864661 -0.0962482 0.58377 -0.8036777 -0.1153898 0.586058 -0.7477822 -0.3120223 0.3365077 -0.8660058 -0.3698604 0.3587572 -0.8085319 -0.4664436 0.1343699 -0.8166774 -0.5612332 0.07799404 -0.8588082 -0.5063254 -0.08862638 -0.7476914 -0.6581056 -0.2722426 -0.8278124 -0.4905208 -0.2644512 -0.8009464 -0.537169 -0.498147 -0.7460544 -0.4418739 -0.4775419 -0.8382048 -0.2633752 -0.6219506 -0.7579755 -0.1965976 -0.5630846 -0.8263934 -0.003153502 -0.4449971 -0.8943884 0.04524576 -0.4160713 -0.8586143 0.2994433 -0.4392821 -0.8365108 0.3275377 -0.3236625 -0.7501686 0.5766193 -0.08174252 -0.894542 0.439446 -0.03168433 -0.8249592 0.5643035 0.2384971 -0.8451699 0.4783378 0.2318991 -0.811026 0.5370844 0.4660085 -0.7625111 0.4487904 0.458715 -0.8161864 0.3513122 0.589178 -0.7982973 0.1248625 0.6173315 -0.7471113 0.2464275 0.6718871 -0.7403855 0.01992374 0.5260732 -0.8443711 -0.1014122 0.5927446 -0.7328725 -0.3339937 0.4279701 -0.8276556 -0.3630812 0.3729481 -0.7055744 -0.6025566 0.1819241 -0.8298495 -0.5274974 0.006569266 -0.7439853 -0.6681637 -0.05432158 -0.8029839 -0.59352 -0.3177121 -0.7333156 -0.6010885 -0.3296894 -0.8125696 -0.4806617 -0.5558772 -0.7724651 -0.3070802 -0.4593791 -0.840895 -0.2861234 -0.608581 -0.7875793 -0.09668654 -0.4534947 -0.8899507 0.04827433 -0.5642353 -0.8149426 0.132314 -0.5215452 -0.7886078 0.325712 -0.3901941 -0.8518824 0.3493494 -0.404828 -0.7365673 0.541833 -0.1792426 -0.7842631 0.5939727 -0.1589571 -0.8004068 0.5779981 0.08906328 -0.7724298 0.6288244 0.1742433 -0.8571088 0.484772 0.3025694 -0.788242 0.5358418 0.3964767 -0.8470172 0.3540735 0.3696975 -0.8900148 0.2668289 0.6029281 -0.7684422 0.2144166 0.5498905 -0.8342968 -0.03961569 0.5065929 -0.8603364 -0.05643367 0.5018579 -0.797007 -0.3360335 0.3485071 -0.8778427 -0.3285347 0.3181707 -0.7929946 -0.519545 0.1237233 -0.8648166 -0.4866055 0.07749974 -0.7748196 -0.6274141 -0.1499968 -0.8596336 -0.4883965 -0.24236 -0.7789827 -0.5783144 -0.3676131 -0.8717696 -0.3238495 -0.5427705 -0.760441 -0.3565527 -0.4856333 -0.8618046 -0.1464692 -0.6996403 -0.7141809 -0.0211938 -0.5461168 -0.8206938 0.1679826 -0.6194364 -0.7270299 0.2961862 -0.4213937 -0.7832707 0.4570718 -0.4191906 -0.8033955 0.4228888 -0.1924713 -0.8545429 0.4824018 -0.1802231 -0.8619493 0.4738809 0.008029818 -0.7755819 0.6311959 0.1294193 -0.8917973 0.43353 0.3499249 -0.7218909 0.5970144 0.4014169 -0.8880732 0.2240327 0.501987 -0.8311688 0.2390972 0.5911608 -0.806434 -0.01390337 0.5567346 -0.8299678 -0.03463977 0.6147295 -0.7343449 -0.2878288 0.3429502 -0.8674186 -0.3605138 0.3717904 -0.8065248 -0.4596625 0.1145696 -0.8527994 -0.5095165 0.1356039 -0.8397446 -0.5257763 -0.05206584 -0.7638323 -0.6433113 -0.2131973 -0.8419461 -0.4956547 -0.2460711 -0.8168595 -0.5217181 -0.4412729 -0.7970575 -0.4122835 -0.450975 -0.757142 -0.4726074 -0.6147409 -0.7527526 -0.2354937 -0.5222116 -0.8482717 -0.08792209 -0.6094093 -0.792795 -0.009822428 -0.4777947 -0.8579686 0.1886854 -0.6634122 -0.7341139 0.1447798 -0.4845942 -0.7853075 0.3853061 -0.3129529 -0.8699161 0.3811911 -0.3089537 -0.795139 0.5218254 -0.06786137 -0.8536442 0.516417 -0.07898491 -0.845463 0.5281606 0.09007561 -0.7439809 0.6621019 0.311911 -0.7926419 0.5238611 0.3072834 -0.7958197 0.5217739 0.4143298 -0.8565521 0.3076516 0.4435079 -0.8389351 0.3154183 0.6020547 -0.7812971 0.1646358 0.567904 -0.8148122 0.1164737 0.684334 -0.7211875 -0.1075905 0.4784531 -0.8430955 -0.2455053 0.5219793 -0.7887631 -0.324639 0.3482035 -0.8202559 -0.4538001 0.2206785 -0.8846691 -0.4106844 0.1639751 -0.7648448 -0.6229966 -0.03644031 -0.8754029 -0.4820187 -0.1858361 -0.744085 -0.6417184 -0.4050689 -0.7980088 -0.4462076 -0.3875766 -0.8483392 -0.3607006 -0.5814235 -0.7794512 -0.2332441 -0.4442853 -0.8953674 -0.03045862 -0.5959864 -0.8014524 0.04974269 -0.4768831 -0.8395678 0.2602086 -0.4675055 -0.8444466 0.2614356 -0.4487018 -0.7476298 0.4896084 -0.3221441 -0.8086816 0.4921963 -0.2083023 -0.706181 0.6766968 -0.01432162 -0.8518241 0.5236323 0.1695585 -0.733887 0.6577688 0.3053643 -0.8608325 0.4070876 0.407002 -0.7895597 0.4592872 0.5460262 -0.805486 0.2303209 0.4443928 -0.8905 0.09759575 0.5899508 -0.8071188 0.02274954 0.5540102 -0.8026149 -0.2210928 0.38262 -0.888917 -0.2518503 0.444413 -0.7880932 -0.4259182 0.1965317 -0.8364876 -0.5115311 0.1662393 -0.8573585 -0.4871357 -0.0112456 -0.8079856 -0.5890949 -0.1043245 -0.8779309 -0.4672833 -0.3006261 -0.7557318 -0.5818019 -0.3296885 -0.8781936 -0.3465279 -0.6185375 -0.7009847 -0.3550097 -0.5117512 -0.8581255 -0.04161041 -0.6354597 -0.7716785 0.02652138 -0.4778887 -0.8641911 0.1574681 -0.5575649 -0.7585067 0.3373264 -0.399181 -0.7883595 0.4681282 -0.2605565 -0.8612812 0.4362399 -0.2304204 -0.783376 0.5772596 -0.004990637 -0.8250733 0.5650038 0.04838538 -0.8772323 0.4776217 0.2679885 -0.7727744 0.5753278 0.2767279 -0.8141664 0.5104456 0.5530187 -0.7615028 0.3380589 0.582665 -0.7080265 0.3989987 0.5730443 -0.8169025 0.06550294 0.6688199 -0.7433416 0.01110231 0.5091844 -0.8184587 -0.2661892 0.4787337 -0.846333 -0.2335265 0.3598659 -0.7881349 -0.4993396 0.2134976 -0.8814399 -0.421287 0.06097698 -0.7272673 -0.6836403 -0.1403775 -0.8900565 -0.4336976 -0.2145709 -0.8319676 -0.5116535 -0.4119145 -0.8100123 -0.4173807 -0.4051233 -0.8687996 -0.2847146 -0.5580834 -0.786926 -0.263231 -0.5402372 -0.8194172 -0.1915704 -0.6956918 -0.7182545 0.01111322 -0.4543683 -0.8753862 0.1650712 -0.5066791 -0.8084301 0.2995284 -0.3548426 -0.8539518 0.3805958 -0.3770408 -0.7984517 0.4693775 -0.1294408 -0.8499245 0.5107578 -0.1056261 -0.7887566 0.6055629 0.1416463 -0.8660914 0.4793977 0.2192941 -0.7895508 0.5731664 0.4101843 -0.8466187 0.3390951 0.4905725 -0.7930697 0.3610805 0.6542109 -0.7425982 0.1433737 0.5609258 -0.8267349 0.04326641 0.6602914 -0.7198735 -0.2140033 0.4672081 -0.838207 -0.2812932 0.4643392 -0.7589063 -0.4565637 0.2102817 -0.8925563 -0.3989047 0.1674784 -0.7874679 -0.5931655 -0.001251041 -0.8590772 -0.5118446 -0.09588444 -0.7686395 -0.6324552 -0.3706798 -0.7641965 -0.527826 -0.3054318 -0.8105536 -0.4997141 -0.4121886 -0.867617 -0.2781031 -0.4085398 -0.869646 -0.2771486 -0.6229969 -0.7720286 -0.1258841 -0.492594 -0.8699973 0.02135241 -0.6458699 -0.7458965 0.1627593 -0.4967488 -0.7742248 0.3921945 -0.4785811 -0.8085075 0.3424555 -0.2358278 -0.8541302 0.4635159 -0.255213 -0.8420927 0.4751276 -0.06014025 -0.7969316 0.6010684 0.05859136 -0.8800513 0.4712504 0.16776 -0.7967041 0.5806198 0.3227068 -0.835358 0.445014 0.3009045 -0.9028589 0.307087 0.5688834 -0.786458 0.240532 0.4532379 -0.8879933 0.07773894 0.6597403 -0.7498679 -0.04940563 0.4579435 -0.8593701 -0.227532 0.3354629 -0.9143456 -0.2267971 0.3642115 -0.8056355 -0.4672274 0.1692576 -0.8287757 -0.5333694 0.1699968 -0.8281207 -0.534151 -0.1541759 -0.8423763 -0.5163643 -0.1473467 -0.8498958 -0.505931 -0.4202909 -0.7700628 -0.4799572 -0.373106 -0.896206 -0.2400144 -0.6168823 -0.7603968 -0.2031083 -0.4809229 -0.8762277 0.03063237 -0.5892137 -0.8011996 0.1044347 -0.4094353 -0.8643673 0.291945 -0.4289951 -0.8413799 0.3286991 -0.3032587 -0.8237452 0.4790387 -0.1708827 -0.8819424 0.4392912 -0.1227421 -0.7363057 0.6654235 0.1892026 -0.8471763 0.4964826 0.1891211 -0.8465182 0.4976345 0.4494918 -0.8174222 0.3602476 0.4726609 -0.7760717 0.4174981 0.5904994 -0.7979406 0.1208361 0.632939 -0.7667632 0.1070631 0.5910711 -0.7951968 -0.135266 0.6178024 -0.7670301 -0.1731621 0.4955475 -0.8150566 -0.3001927 0.5244236 -0.7458921 -0.4106395 0.2686632 -0.8225793 -0.5011822 0.2676108 -0.7963457 -0.5424187 0.02412962 -0.8549612 -0.5181307 0.04575639 -0.8374894 -0.5445346 -0.196472 -0.8712511 -0.4498004 -0.1610519 -0.8181403 -0.5520042 -0.4381618 -0.7672192 -0.4683899 -0.4154477 -0.860581 -0.2946244 -0.586908 -0.7849221 -0.1985858 -0.5019619 -0.8594992 -0.09641277 -0.5965874 -0.7975394 0.08952432 -0.6321586 -0.7722198 0.06365716 -0.6160624 -0.7238936 0.3105566 -0.4254533 -0.8264867 0.3686591 -0.4321891 -0.7260178 0.5348933 -0.2209308 -0.8155192 0.5349002 -0.1411215 -0.7386648 0.6591351 0.05686879 -0.8351223 0.5471168 0.09484535 -0.806277 0.5838851 0.2810032 -0.8526793 0.4404264 0.2811719 -0.8491667 0.4470552 0.5882273 -0.719873 0.368472 0.5406023 -0.8076332 0.2355376 0.6780373 -0.7350052 -0.005728602 0.6023898 -0.7979204 0.02120447 0.4999778 -0.8336862 -0.234499 0.5284414 -0.805435 -0.2683731 0.4520714 -0.7436124 -0.4926176 0.2989715 -0.8147888 -0.4967247 0.2558705 -0.7552708 -0.603404 0.06222087 -0.7991454 -0.597909 0.02760738 -0.7567867 -0.6530788 -0.2091823 -0.8197309 -0.5331829 -0.2754927 -0.7676282 -0.5786631 -0.4661025 -0.7962086 -0.3857466 -0.4344671 -0.8515041 -0.293563 -0.5836723 -0.8036896 -0.115801 -0.4929485 -0.8695196 -0.03062015 -0.5688354 -0.814532 0.1138594 -0.469268 -0.859292 0.2034825 -0.5219143 -0.7957415 0.3072474 -0.3421929 -0.8432664 0.4144949 -0.3436523 -0.8393596 0.4211633 -0.1556324 -0.8056997 0.5715126 -0.03732454 -0.8821012 0.4695791 0.0825138 -0.7713792 0.6310037 0.2773608 -0.8731551 0.4008383 0.339845 -0.8298392 0.4425749 0.5177767 -0.7929278 0.3212053 0.4729477 -0.8491953 0.234921 0.6571769 -0.752405 0.04478287 0.5188556 -0.846283 -0.1208056 0.609602 -0.7587364 -0.2295746 0.4176844 -0.8570436 -0.3016884 0.4511693 -0.710774 -0.5396729 0.1431839 -0.8011056 -0.581144 0.1397942 -0.7984754 -0.5855721 -0.01731318 -0.8821554 -0.4706401 -0.07874393 -0.8159027 -0.5728023 -0.3457992 -0.7779634 -0.5245913 -0.3358519 -0.8828608 -0.3282688 -0.5080943 -0.7910209 -0.3407728 -0.4995106 -0.8625434 -0.08067232 -0.588997 -0.8064548 -0.05209022 -0.6067097 -0.7407304 0.2884823 -0.4735947 -0.8653532 0.163927 -0.4852072 -0.7911955 0.3722684 -0.3101295 -0.873939 0.3742331 -0.2595944 -0.7560696 0.6008074 -0.0746454 -0.887111 0.45548 0.1171332 -0.7574888 0.6422544 0.210303 -0.8877396 0.4095011 0.3997626 -0.7812101 0.4794799 0.4186962 -0.8340344 0.3592774 0.5914353 -0.7422885 0.3149797 0.5776852 -0.8126444 0.07673901 0.6321319 -0.7733187 0.04886317 0.5602009 -0.8056235 -0.1927323 0.56193 -0.8039012 -0.194878 0.450717 -0.768812 -0.4536322 0.3384808 -0.8398544 -0.4243529 0.1696748 -0.8160161 -0.5525653 0.08785659 -0.8710839 -0.4832125 -0.08253884 -0.8097049 -0.5810039 -0.1354697 -0.8552682 -0.5001645 -0.3148392 -0.7539532 -0.5765682 -0.4505365 -0.8121989 -0.3706074 -0.4652714 -0.7760666 -0.4257271 -0.6866733 -0.7158845 -0.1264486 -0.547576 -0.820527 -0.1640006 -0.5656157 -0.8242553 0.02612304 -0.4485576 -0.8898798 0.08312684 -0.5281338 -0.7675273 0.3632856 -0.3159715 -0.8752892 0.3661024 -0.3284003 -0.8136298 0.4797497 -0.08500802 -0.8302916 0.5508081 -0.005206406 -0.8837304 0.4679677 0.1094943 -0.787133 0.6069867 0.300706 -0.8188077 0.489009 0.3008117 -0.8376098 0.455985 0.5387849 -0.7421416 0.3986688 0.5087217 -0.8472996 0.1525967 0.6101937 -0.7824717 0.1241036 0.5007851 -0.8557201 -0.1302217 0.4570959 -0.877665 -0.1441102 0.5265415 -0.7667852 -0.3671441 0.3700166 -0.8428735 -0.3907071 0.3326706 -0.7195646 -0.6095549 0.1409538 -0.8087618 -0.5709959 0.06239622 -0.7395365 -0.6702182 -0.1668515 -0.8181941 -0.5501991 -0.1916246 -0.7958334 -0.5743947 -0.4516239 -0.7767997 -0.4388829 -0.4262 -0.8452544 -0.3223328 -0.6260296 -0.7491387 -0.2165138 -0.532658 -0.8459665 -0.02482968 -0.618892 -0.7841117 0.04628056 -0.4838931 -0.8437552 0.232217 -0.5545898 -0.8001695 0.2283835 -0.3999863 -0.7420634 0.5379152 -0.3898267 -0.7873803 0.4775643 -0.1942107 -0.7610651 0.6189202 -0.112523 -0.826254 0.5519449 0.2086697 -0.7270894 0.6540627 0.1389911 -0.8258981 0.5464193 0.3959657 -0.7909981 0.4664045 0.377776 -0.8489878 0.3694662 0.8332871 -0.5214675 0.1835877 0.4953328 -0.8464519 0.1953576 0.6057372 -0.7950497 -0.03128129 0.4535899 -0.8832778 -0.1186444 0.5383539 -0.7921208 -0.2876103 0.3551992 -0.8645706 -0.3554595 0.3681343 -0.8234121 -0.4318216 0.2094975 -0.8487431 -0.4855369 0.1596654 -0.7174709 -0.6780432 -0.1107715 -0.8401625 -0.5309019 -0.207455 -0.7611435 -0.6145105 -0.2865754 -0.8707413 -0.3996053 -0.4707434 -0.7820979 -0.4083182 -0.4168649 -0.882357 -0.2183347 -0.6388788 -0.7570806 -0.1366124 -0.5107254 -0.8545501 0.09436029 -0.5245445 -0.8465906 0.09020763 -0.4714463 -0.8122758 0.3434334 -0.4617192 -0.8177895 0.3435632 -0.3487702 -0.7643399 0.5423505 -0.1402784 -0.8726327 0.4677972 -0.0378164 -0.7846828 0.618743 0.01250845 -0.8277236 0.5609967 0.2129608 -0.7611747 0.6125854 0.3286924 -0.8264114 0.4571713 0.3836501 -0.7921311 0.4747008 0.4577373 -0.8420944 0.2852256 0.5024956 -0.8155601 0.2869845 0.6388435 -0.7673684 0.05499863 0.515109 -0.852139 -0.0923146 0.5654729 -0.813807 -0.1340099 0.5067462 -0.7981442 -0.3258439 0.4673416 -0.8204938 -0.329214 0.3871586 -0.7469557 -0.5405233 0.1501156 -0.8449013 -0.5134269 0.1487197 -0.8394591 -0.5226769 -0.1047163 -0.7908776 -0.6029487 -0.158185 -0.8832667 -0.4413813 -0.4135127 -0.7630682 -0.4967236 -0.4084461 -0.8083359 -0.4239869 -0.6023369 -0.7530251 -0.2648462 -0.5885743 -0.7729337 -0.236968 -0.6485261 -0.7609897 0.01756846 -0.4918152 -0.8620595 0.1223566 -0.5830456 -0.7449235 0.3242639 -0.3101565 -0.8875371 0.3407065 -0.3277786 -0.7569632 0.5653035 -0.04366463 -0.8674755 0.4955601 -0.04010301 -0.870551 0.4904415 0.1834926 -0.7815073 0.5963028 0.280235 -0.8725149 0.4002327 0.3266883 -0.8432234 0.4269064 0.5227801 -0.7857306 0.3306488 0.4689854 -0.8608022 0.1976674 0.6577911 -0.7480549 0.08789134 0.569415 -0.8131977 -0.1203163 0.568548 -0.8139351 -0.119428 0.4898144 -0.8109353 -0.3201028 0.4412741 -0.8400947 -0.3154649 0.2644696 -0.7792152 -0.568225 0.2653728 -0.7540577 -0.6008114 0.01787787 -0.8701986 -0.4923768 0.02043116 -0.8679106 -0.4963003 -0.1958446 -0.8486221 -0.4914117 -0.1455782 -0.7822098 -0.6057679 -0.4182245 -0.7628456 -0.4931076 -0.3965071 -0.8595027 -0.3225484 -0.6202467 -0.7589198 -0.1983304 -0.4811891 -0.8737031 -0.07141429 -0.5852683 -0.7954286 0.1573356 -0.6091169 -0.7791165 0.1481693 -0.3720033 -0.8307605 0.4140661 -0.4599575 -0.7762026 0.4312177 -0.25875 -0.8239033 0.5042142 -0.07937747 -0.9076194 0.4122213 -0.02405881 -0.8218806 0.5691517 0.13945 -0.7581685 0.6369728 0.1768705 -0.8218663 0.5415281 0.4112244 -0.7388399 0.5338636 0.4421491 -0.846789 0.2957242 0.5016004 -0.8121946 0.2978876 0.533288 -0.8457364 0.01828026 0.4240946 -0.9045168 0.04464596 0.6152274 -0.7791988 -0.1197692 0.4279807 -0.844174 -0.3228046 0.3866378 -0.8656661 -0.3180149 0.3174492 -0.7536313 -0.5755571 0.1353722 -0.8662945 -0.4808412 0.009012281 -0.7433289 -0.6688655 -0.1795531 -0.8283377 -0.5306764 -0.2890746 -0.7542433 -0.5895363 -0.4383991 -0.8324435 -0.3388867 -0.4017815 -0.8559791 -0.3253791 -0.6245711 -0.7472741 -0.2269196 -0.5297701 -0.8438436 -0.08527547 -0.6712875 -0.7352169 0.09396415 -0.4658065 -0.8460379 0.2593153 -0.5018907 -0.8028904 0.3216719 -0.3586631 -0.8413169 0.4044091 -0.361142 -0.7672199 0.5300473 -0.06601059 -0.7860292 0.6146549 -0.08810836 -0.8599302 0.5027494 0.1050575 -0.7321345 0.6730096 0.2105956 -0.8589034 0.4668346 0.3918144 -0.7499098 0.5330262 0.4368362 -0.8455546 0.3069393 0.6268393 -0.733655 0.2623409 0.5843437 -0.8090684 0.06285667 0.6442977 -0.764583 0.01712769 0.5926023 -0.7833975 -0.1873789 0.6152292 -0.7576182 -0.217963 0.3982683 -0.8262235 -0.3984186 0.4225411 -0.7675105 -0.482065 0.166905 -0.8457639 -0.5067803 0.15432 -0.8016389 -0.577547 -0.10745 -0.7765456 -0.6208313 -0.1996964 -0.8481633 -0.4906531 -0.3097503 -0.7893909 -0.5300158 -0.3329651 -0.8769365 -0.3465784 -0.6069472 -0.7421197 -0.2843828 -0.5005269 -0.8517509 -0.1548981 -0.5931255 -0.8013924 0.07728087 -0.4785583 -0.8675748 0.1352627 -0.5216703 -0.8059777 0.2797504 -0.3569995 -0.8669252 0.3478391 -0.3830041 -0.7722828 0.5068406 -0.12252 -0.8760564 0.4663842 -0.08020621 -0.7761911 0.6253755 0.1827252 -0.8513699 0.4917122 0.1875784 -0.8656855 0.4641153 0.4192564 -0.7973589 0.4341001 0.3931062 -0.8727155 0.2895432 0.5558464 -0.8079912 0.1954106 0.4538412 -0.8901091 0.04164034 0.6445475 -0.7601389 -0.08214265 0.412531 -0.8694177 -0.271903 0.4189092 -0.8663102 -0.2720694 0.372435 -0.8021193 -0.4667944 0.2071728 -0.8659142 -0.4552716 0.1962273 -0.8160263 -0.5436875 -0.0458818 -0.8110197 -0.583217 -0.1140993 -0.885361 -0.4506853 -0.2847101 -0.7782769 -0.5596653 -0.4158844 -0.8377195 -0.3539296 -0.3822214 -0.8875538 -0.2572064 -0.6152666 -0.7630093 -0.1981512 -0.5164337 -0.8546878 0.05296432 -0.4673603 -0.8806571 0.07757288 -0.5837937 -0.7625244 0.2788217 -0.3605036 -0.8549804 0.3728885 -0.321323 -0.875078 0.3619254 -0.2072987 -0.7986877 0.5649119 -0.1345633 -0.8420842 0.5222902 0.04875648 -0.7291613 0.6826028 0.17584 -0.8579462 0.4827098 0.4211061 -0.6980336 0.5791535 0.4563306 -0.8400112 0.2935022 0.5478083 -0.790894 0.2727508 0.4692785 -0.8789653 0.08484059 0.643717 -0.7631763 -0.05648559 0.4650261 -0.8737082 -0.1427755 0.5311924 -0.7356367 -0.4203254 0.272082 -0.8826327 -0.3833158 0.2518028 -0.8016608 -0.5421581 0.03992676 -0.8372506 -0.5453598 -0.001291632 -0.8762311 -0.4818897 -0.2625274 -0.763564 -0.5899572 -0.2937017 -0.890515 -0.3474514 -0.4803345 -0.7867159 -0.3877591 -0.4865711 -0.8656832 -0.1176484 -0.56912 -0.8158164 -0.1026942 -0.6524801 -0.7577909 0.004771769 -0.4660554 -0.8769863 0.1169927 -0.5643985 -0.7605338 0.3210027 -0.4331397 -0.784073 0.4445443 -0.1245317 -0.9332631 0.3369151 -0.4913402 -0.646522 0.5836045 -0.03759169 -0.9274061 0.3721622 0.03997683 -0.7944344 0.6060329 0.224262 -0.9186422 0.325274 0.8799536 0.05535393 -0.4718236 0.3825828 -0.003457069 -0.9239149 0.3022539 0.4713101 -0.8285586 -0.07133698 -0.3810846 -0.9217839 -0.3106046 0.638458 -0.7041989 -0.5985963 0.7960265 -0.08957934 -0.7410444 -0.5987656 0.3038636 -0.7060328 0.4351313 0.5587294 -0.4139483 -0.5510816 0.7245384 -0.4043848 0.2834131 0.8695688 0.11444 0.1384072 0.9837413 0.5201426 -0.488963 0.7002621 0.9218455 -0.002315938 0.3875508 0.8453949 0.5334439 -0.02729296 0.6970928 -0.6069864 -0.3816139 0.5246569 0.7054098 -0.476584 0.3014501 -0.6185885 -0.7255868 0.1806505 0.5346697 -0.8255264 -0.1671499 -0.5953034 -0.785923 -0.3053551 0.6349128 -0.7096789 -0.6061261 -0.5355369 -0.5880573 -0.754993 0.476374 -0.4506146 -0.8804207 -0.3841638 -0.2779889 -0.8589746 0.5111819 0.02925521 -0.8271895 -0.5174555 0.2190831 -0.6978843 0.441979 0.5635708 -0.5927619 -0.4345614 0.6780781 -0.2203111 0.5769366 0.7865159 -0.0627765 -0.4888068 0.8701305 0.4470072 0.1498575 0.8818885 0.6214078 0.6683331 -0.4088805 0.4013029 -0.5806943 -0.7083433 0.117514 0.7242901 -0.6794073 -0.758811 -0.2908948 -0.5827403 -0.9886934 -0.1057548 -0.1063069 -0.9661805 0.2439492 -0.08357071 -0.854977 -0.02995032 0.5178005 -0.819066 0.3786789 0.4309679 -0.4098184 -0.5544413 0.724323 -0.2327916 0.685144 0.6902071 0.009229302 -0.5210191 0.8534952 0.3341524 0.5303378 0.7791562 -0.7924142 -0.2381239 -0.5615842 -0.9976896 0.06627452 -0.01494044 -0.9469842 0.3212729 -0.002184987 -0.6527596 -0.476693 0.5887859 0.08108764 0.5637763 0.8219376 0.4629164 -0.577454 0.6724992 0.4630341 0.761416 0.4537016 0.653134 -0.7388569 0.1658511 0.7415727 0.6707754 0.01141744 0.7392482 -0.6054645 -0.2948301 0.6523315 0.5877981 -0.4784946 0.5115558 -0.4754509 -0.7157215 0.3151261 0.4114801 -0.8552074 0.09801042 -0.5162075 -0.8508372 -0.1389666 0.6243698 -0.7686682 -0.4198479 -0.6716981 -0.6103684 -0.6093081 0.4294306 -0.6665831 -0.9175744 -0.3008848 -0.2598569 -0.4834915 -0.7245218 0.4912272 -0.3689913 0.608808 0.7022808 -0.07013285 -0.5874107 0.8062446 0.1135663 0.6681385 0.7353188 0.3710615 -0.5944383 0.7134119 0.7356143 0.4219036 0.5299707 0.8371033 0.1075665 0.5363653 0.9832099 -0.1715181 -0.06229025 0.5456672 0.7693753 -0.3321282 0.4840414 -0.5254231 -0.699739 0.1996067 0.3894379 -0.8991637 -0.1756533 0.4810255 -0.8589298 -0.5352121 -0.6479639 -0.5419325 -0.7635807 0.551063 -0.3365624 -0.7612422 -0.6260061 0.1691947 -0.5471811 0.7389572 0.3931096 -0.3968642 -0.5941015 0.6996729 -0.08267068 0.7371422 0.6706616 0.3123294 -0.7913802 0.5255167 0.5370514 0.6704147 0.5119765 0.6417475 -0.756636 0.1251485 0.7979516 -0.5173088 -0.3092975 0.4859037 0.5451661 -0.6831483 0.3398173 -0.5348643 -0.7735919 -0.06478208 0.5401746 -0.8390559 -0.4797471 0.5494816 -0.6840415 -0.78481 -0.5342661 -0.3140591 -0.7682881 0.6207653 -0.1561531 -0.9269715 -0.3695904 0.06424003 -0.8267204 0.335626 0.4515405 0.2353196 0.7768735 0.5840311 0.6054717 -0.6476507 0.4625502 0.6731122 0.6969475 0.2473544 0.8706212 -0.4852012 0.0812326 0.8335457 0.3585122 -0.4203221 0.8672054 0.003913164 -0.4979352 0.3825324 -0.0706287 -0.9212387 0.3818966 -0.1888894 -0.9046965 -0.1050409 0.3719385 -0.922295 -0.2475531 -0.5303024 -0.8108619 -0.54354 0.5992662 -0.5877451 -0.8082835 0.5334947 -0.2491214 -0.8452189 -0.445773 0.2947735 -0.4872798 0.7327762 0.4749709 -0.2038404 -0.6815561 0.7028019 -0.02198451 0.6886277 0.7247818 0.3314597 -0.7293105 0.5985321 0.8405652 0.4850594 -0.2411797 0.5574932 -0.3191404 -0.7663882 0.4912086 0.4462537 -0.7480453 -0.02169919 -0.5712998 -0.8204546 -0.1291721 0.6730162 -0.7282608 -0.4451916 -0.594016 -0.670037 -0.6192803 0.553584 -0.5568094 -0.7140715 -0.6623914 -0.2265824 -0.8015446 0.5951824 0.05730968 -0.7649307 -0.4523504 0.4585415 -0.6563913 0.4936739 0.5704706 -0.364068 -0.5733989 0.7339402 -0.3117856 0.3943728 0.8644419 0.2028099 -0.0611149 0.9773092 0.2171752 -0.1855069 0.9583434 0.7712264 -0.04533427 0.6349447 0.6923845 -0.6348555 -0.3428736 0.4799918 0.5468193 -0.6860005 0.3168286 -0.5201373 -0.7931437 -0.02970856 0.6282395 -0.7774527 -0.3859457 -0.7120942 -0.5864877 -0.5686153 0.654678 -0.4980698 -0.7216517 -0.6553204 -0.2231011 -0.692997 0.7203271 0.02973562 -0.5073809 -0.7650468 0.3965705 -0.444525 0.6309764 0.6358194 -0.1453649 -0.5628479 0.8136777 0.005609035 0.5384644 0.8426297 0.2882063 -0.6182411 0.7312421 0.4236372 0.6921568 0.5843377 0.6859951 -0.6292811 0.3652617 0.7418556 0.6308177 0.227419 0.7274274 -0.6792441 -0.09734982 0.6182279 0.7332206 -0.283164 0.4666262 -0.7257351 -0.5055379 0.2997679 0.6836874 -0.6653652 0.02203112 -0.601484 -0.7985811 -0.1513081 0.5670614 -0.8096588 -0.4133818 -0.6250733 -0.6621171 -0.5668275 0.6608124 -0.4919692 -0.6897082 -0.6755745 -0.2605797 -0.7494775 0.6602224 -0.04888623 -0.6619992 -0.6955457 0.2792369 -0.7997659 0.3934906 0.4533648 -0.4422226 -0.04249161 0.8958982 -0.4624019 0.2238591 0.8579462 0.1123634 -0.5848334 0.8033334 0.1856614 0.6485388 0.7381919 0.6689344 -0.4777126 0.5694888 0.4073446 -0.6430045 -0.6485489 0.1324221 0.5242109 -0.8412297 -0.1616567 -0.5786927 -0.7993634 -0.2851791 0.3507353 -0.8919966 -0.6983446 -0.4097664 -0.5868615 -0.7523092 -0.2318694 -0.6166585 -0.8273256 0.5012472 -0.2535423 -0.6278312 -0.7758305 0.06257045 -0.05783939 -0.08473628 0.9947233 0.4900085 0.4039157 0.7724919 0.8283607 -0.5589063 0.03797829 0.8440811 0.3507925 -0.4055513 -0.6057925 0.467518 -0.643772 -0.8471528 -0.4912234 -0.202563 -0.9361963 0.3159906 -0.1539044 -0.9459915 -0.006947934 0.3241171 -0.7702521 -0.5270297 0.3590981 -0.5885141 0.5725033 0.5708687 -0.2512215 -0.7219696 0.6447075 -0.157829 0.6625835 0.7321702 0.2996863 -0.6487424 0.6995152 0.4217168 0.460725 0.7809529 0.8386301 -0.3622485 0.4067869 0.870276 0.4924858 -0.008790791 0.7821671 -0.1577634 -0.6027649 0.1883811 -0.7454873 -0.6393445 0.06990271 0.6517996 -0.7551629 -0.3000571 -0.6932193 -0.655296 -0.449164 0.681199 -0.5781173 -0.6956899 -0.5627484 -0.4464638 -0.7163965 0.6869704 -0.1218513 -0.6700552 -0.6782608 0.3016426 -0.6285098 0.4923477 0.6021371 -0.3993246 -0.5018466 0.7672615 -0.2368919 0.5420397 0.8062725 0.08936482 -0.664694 0.7417519 0.2485193 0.6694392 0.7000639 0.5587383 -0.6900871 0.4599906 0.724847 0.311922 -0.6142488 0.2551385 -0.2521703 -0.9334424 0.2537583 -0.1281121 -0.9587461 -0.2542211 0.3711863 -0.8930803 -0.6560172 -0.7468628 -0.1087998 -0.7906218 0.610902 0.04142528 -0.7031179 -0.5857536 0.4031351 -0.5810618 0.6206135 0.5265038 -0.4829182 -0.4341831 0.760444 -0.1114462 0.4486007 0.8867567 0.009562253 -0.3346331 0.9423001 0.5209276 0.3458185 0.7804127 0.8975629 -0.03134363 0.4397711 0.972155 -0.1665465 -0.1648541 0.9083149 0.374995 -0.1853181 0.6092709 -0.4247186 -0.6696292 -0.3598757 0.8498702 -0.3849808 -0.7972833 -0.5942952 -0.1056062 -0.7722186 0.5381718 0.3377125 0.2132889 -0.6343273 0.743059 0.525571 0.6951292 0.49048 0.6551198 -0.751407 0.07877606 0.8064348 0.5816376 -0.1065873 0.7069719 -0.5625069 -0.4286919 0.701936 0.4289962 -0.5685492 0.3395466 -0.3928035 -0.8546423 -0.07772445 -0.5136193 -0.8544905 -0.4375988 0.4454169 -0.7810961 -0.5709127 -0.6335716 -0.5221551 -0.7047001 0.5184284 -0.4843859 -0.8409646 -0.5410822 0.002942562 -0.9061123 0.4176234 0.06746268 -0.7323319 -0.3792818 0.5655399 -0.4426003 0.5131552 0.7353753 0.05110836 -0.3989819 0.9155334 0.4414603 -0.2277721 0.8678898 0.7701246 0.420902 0.4793219 0.8115592 0.5834757 0.03045898 0.6198289 -0.6429812 -0.4498746 0.3870397 0.6166971 -0.6854816 -0.1117912 -0.4984791 -0.8596636 -0.1911286 0.5103883 -0.8384352 -0.5621489 -0.6047637 -0.5641362 -0.7779674 0.6282685 -0.006749749 -0.7539153 -0.4629723 0.4661206 -0.6297754 0.5592371 0.5391077 -0.4789488 -0.4334793 0.7633505 -0.1683406 0.4275215 0.888193 -0.08258777 -0.1611204 0.9834732 0.5143373 0.1148464 0.8498633 0.4985741 -0.1895211 0.8458757 0.8826262 0.3028056 0.359555 0.8317716 -0.5462075 -0.09906268 0.6613782 0.6100496 -0.4363697 0.334526 -0.6798925 -0.6525631 0.1295063 0.4980507 -0.8574227 -0.2064273 -0.6170575 -0.7593603 -0.527623 0.4757859 -0.7037342 -0.8686251 -0.3816167 -0.3160052 -0.8515347 0.4743654 -0.2233075 -0.7558653 -0.623215 0.200676 -0.6944646 0.5328297 0.4835407 -0.3502433 -0.4286245 0.832833 -0.2764338 0.475822 0.8349719 0.2432469 -0.6479602 0.7217885 0.4810569 0.6898826 0.540968 0.8474948 -0.5088359 0.151125 0.9461613 0.3011432 0.1187089 0.782127 -0.3714697 -0.5002876 0.811112 0.2088364 -0.5463376 0.2612413 0.01574724 -0.9651451 -0.5270357 0.5909578 -0.6107392 -0.6917917 -0.7145822 -0.1039063 -0.7264627 0.660129 0.1910018 -0.5295511 -0.5703144 0.6279469 -0.1728987 -0.4392274 0.8815812 0.400148 0.2361975 0.88549 0.7843714 -0.2029184 -0.586162 0.3109627 0.1460086 -0.9391399 -0.1741816 0.2676687 -0.9476362 -0.5848084 0.3133397 -0.7482095 -0.6339228 -0.5280313 -0.5650886 -0.8204864 0.4532324 -0.3483999 -0.8870939 -0.4286748 -0.1711802 -0.9030271 0.4011372 0.1537246 -0.8192657 -0.4774806 0.3175153 -0.6905828 0.4822018 0.539052 -0.4177872 -0.615072 0.6686856 -0.2924679 0.6147688 0.7324766 0.08232712 -0.5774605 0.8122572 0.2223762 0.5465796 0.8073411 0.5077346 -0.4606922 0.7279893 0.6513092 0.4623471 0.6016905 0.7704399 -0.5550605 0.3135768 0.7639366 0.6213874 0.1740072 0.7077037 -0.6740017 -0.2118424 0.7295543 0.5812199 -0.3604635 0.5905898 -0.4210331 -0.6884293 0.4410119 0.5059598 -0.7412916 0.155146 -0.5901482 -0.7922467 -0.08504986 0.6662604 -0.7408533 -0.3293337 -0.5257087 -0.7843277 -0.6782678 0.4471698 -0.5830883 -0.7655684 0.219155 -0.604877 -0.8735593 -0.485055 -0.04019713 -0.7756191 0.6305352 0.02899003 -0.6729564 -0.5428531 0.5024343 -0.6633659 0.4516867 0.5965944 -0.2091887 -0.5323309 0.8202828 0.1197034 0.8399226 0.5293403 0.5975348 -0.6626883 0.4514383 0.8210594 0.5144199 0.2474545 0.8654848 -0.4968761 -0.0636419 0.8888273 0.424304 -0.1730673 0.640154 -0.5861735 -0.4965921 0.5312569 0.6261729 -0.5706783 0.2419512 -0.5695225 -0.7855596 0.09612989 0.6171341 -0.7809638 -0.2519475 -0.7005223 -0.6676759 -0.3687697 0.7189409 -0.58918 -0.6343572 -0.7090461 -0.3079685 -0.8447199 0.4421113 -0.3016387 -0.9506366 -0.1746511 0.2564898 -0.6736094 -0.2417559 0.6984301 -0.225702 0.4349663 0.8717012 -0.05293124 -0.5525553 0.8317939 0.3705248 0.427788 0.8244446 0.5162584 -0.2740234 0.8114114 0.8596097 0.1580293 0.4858993 0.879091 -0.2048521 0.4303892 0.9680674 -0.2235565 -0.1134381 -0.5328028 0.03616929 -0.8454661 -0.4372138 0.8255978 -0.3566967 -0.6473588 0.7543709 -0.1088633 -0.8053707 0.5907884 -0.04844856 -0.6118686 0.7839716 -0.1049068 -0.5731074 0.8031442 0.162811 -0.436459 0.8779583 0.1967055 -0.4481621 0.8144818 0.36847 -0.317008 0.8417687 0.4369571 -0.3252922 0.7893128 0.5207403 0.02572065 0.8300653 0.5570727 0.006462454 0.771704 0.6359491 0.3695072 0.7997138 0.4732043 0.3600062 0.8066173 0.4687903 0.4278712 0.8571872 0.2866299 0.6411466 0.7320868 0.2301741 0.5755843 0.8170818 -0.03286582 0.6277229 0.7731381 -0.09067291 0.4542344 0.8727403 -0.1788729 0.4677512 0.857767 -0.2131779 0.3592587 0.8132384 -0.4577955 0.2116831 0.9092311 -0.358454 0.08574777 0.7999673 -0.5938852 -0.04076892 0.8782764 -0.4764122 -0.2065354 0.7557468 -0.6214419 -0.3111521 0.8706696 -0.380945 -0.5306534 0.7422764 -0.4091855 -0.4451815 0.873854 -0.1954296 -0.6596716 0.7509989 -0.02888077 -0.4803436 0.8742603 0.07027906 -0.5530559 0.8038247 0.2190779 -0.3300465 0.8966381 0.2951431 -0.3645123 0.8051347 0.4678557 -0.217602 0.7854927 0.5793536 -0.08676052 0.8866788 0.4541733 0.01484692 0.8206851 0.5711879 0.203208 0.8154665 0.5419603 0.1692277 0.8374015 0.5197314 0.4222564 0.7583913 0.4965301 0.4325272 0.8062611 0.4035634 0.6101287 0.7313364 0.3047789 0.5584063 0.806533 0.1941315 0.6570315 0.7518794 0.05465477 0.588723 0.8073695 -0.03949391 0.6466371 0.7454164 -0.161911 0.4634243 0.8281579 -0.315266 0.4752535 0.7992408 -0.3678969 0.2910611 0.870983 -0.3958185 0.2758857 0.7976869 -0.5362674 0.1285727 0.8499572 -0.5109226 0.01281189 0.7593871 -0.6505131 -0.2328054 0.7703876 -0.5935525 -0.1966815 0.799738 -0.5672175 -0.4238372 0.7546538 -0.500859 -0.4136343 0.8554421 -0.3116497 -0.5463639 0.7926255 -0.2706128 -0.4644508 0.8805592 -0.09434658 -0.6213098 0.7835431 0.005860149 -0.5025647 0.8435401 0.1893907 -0.4406491 0.8762494 0.1949754 -0.4434558 0.7991794 0.4057825 -0.2837455 0.8200243 0.4970399 -0.2986152 0.8617773 0.4100841 -0.1351028 0.8363915 0.5312218 -0.05236077 0.8972194 0.4384697 0.1021557 0.8115426 0.5752938 0.1606366 0.8263374 0.53978 0.3092048 0.7403916 0.5968356 0.4524115 0.7971101 0.3999242 0.4659974 0.7892842 0.3998463 0.5279544 0.8177193 0.2293455 0.6182867 0.7639938 0.1844865 0.6051715 0.7951595 -0.03858625 0.5826423 0.8125001 -0.01927632 0.6071996 0.7501099 -0.2619998 0.4684242 0.8306767 -0.300924 0.4611043 0.7379733 -0.4927252 0.2707312 0.8158428 -0.5109845 0.2312017 0.7577106 -0.6102626 0.01452344 0.813439 -0.581469 -0.03360605 0.7704584 -0.6366039 -0.2420675 0.7859022 -0.5690001 -0.2549055 0.8156688 -0.5193338 -0.4472861 0.7544665 -0.4803286 -0.4403154 0.8480523 -0.2948387 -0.5742585 0.7782844 -0.2539696 -0.4643347 0.8843581 -0.0480023 -0.5791428 0.8148241 0.0256049 -0.5577869 0.7845791 0.2707571 -0.4436695 0.8595699 0.2535691 -0.3625445 0.7448775 0.5601062 -0.2097324 0.8349867 0.5087334 -0.07415628 0.743377 0.6647492 0.06722927 0.8292348 0.5548423 0.1674107 0.7852034 0.5961789 0.2111759 0.8858374 0.4131549 0.4480131 0.761655 0.4681518 0.5172076 0.8017528 0.2994812 0.4255317 0.8879905 0.1743434 0.6312419 0.7732847 0.05970466 0.4772362 0.8697617 -0.1255397 0.5520784 0.8037604 -0.2217627 0.3423278 0.8564823 -0.3863288 0.3555274 0.7931237 -0.4945254 0.09323984 0.8280468 -0.5528517 0.1128019 0.8587099 -0.4998932 -0.2123033 0.8698565 -0.4452829 -0.2474423 0.8444244 -0.4750996 -0.4995352 0.7543929 -0.4258592 -0.4481827 0.8642815 -0.2283637 -0.6191889 0.7680556 -0.1633886 -0.6206721 0.7790297 0.08876311 -0.577992 0.808794 0.1085248 -0.5876132 0.7632861 0.2685241 -0.3745327 0.8515751 0.366804 -0.3802359 0.8379961 0.3913866 -0.1922275 0.8065689 0.5590127 -0.1009443 0.8692704 0.4839209 0.01027739 0.7881111 0.6154474 0.1832668 0.8569174 0.4817737 0.2124249 0.8389104 0.5011039 0.4006064 0.7960839 0.4536134 0.3826029 0.8764317 0.292374 0.5107932 0.8167898 0.2682251 0.5215113 0.8531312 0.01389843 0.6251498 0.7786799 0.05334389 0.5699902 0.746349 -0.3436197 0.543404 0.7869946 -0.2921502 0.3406347 0.8482419 -0.405529 0.3523013 0.8405382 -0.4115575 0.1369582 0.8285167 -0.5429575 0.2058393 0.7398244 -0.6405388 -0.1338675 0.8234859 -0.5513171 -0.2061189 0.7675089 -0.606997 -0.2585121 0.8597502 -0.4404556 -0.5554431 0.6997722 -0.4492236 -0.4740807 0.8569004 -0.2024086 -0.6179983 0.7833319 -0.06685405 -0.5441878 0.8387464 -0.01908069 -0.6516963 0.7284927 0.2111643 -0.4357967 0.8367452 0.33157 -0.4271312 0.8089865 0.4038565 -0.2983205 0.8636919 0.4062527 -0.2889183 0.8147454 0.5027089 -0.06881505 0.8090707 0.5836687 -0.08721917 0.7802215 0.6193928 0.2933248 0.8007832 0.5222133 0.2362467 0.8468222 0.476529 0.5489594 0.7553463 0.3579044 0.4484854 0.8682286 0.2122268 0.6652786 0.7438536 0.06392425 0.4836421 0.8585337 -0.1703239 0.5103982 0.8362483 -0.2004563 0.4762787 0.7375296 -0.4787574 0.182031 0.9079431 -0.3774973 0.2611967 0.8503558 -0.4568057 0.01432412 0.8195782 -0.5727884 0.01046854 0.823849 -0.5667127 -0.2290192 0.7420939 -0.6299579 -0.3198794 0.8373874 -0.4432378 -0.3689984 0.8112612 -0.4535366 -0.4888524 0.8384871 -0.2407545 -0.4574561 0.8552072 -0.2436283 -0.5677231 0.8202401 -0.06997799 -0.5063311 0.8621814 -0.01650118 -0.5847007 0.797313 0.1497232 -0.5129976 0.8373562 0.1888603 -0.5454471 0.7506176 0.3729085 -0.3891775 0.7827203 0.4856852 -0.386268 0.761894 0.519918 -0.1759966 0.7739843 0.6082547 -0.1132181 0.822903 0.5567876 0.03643923 0.7347759 0.6773304 0.2245679 0.8046914 0.5495826 0.2353214 0.7981025 0.5546678 0.3604359 0.8629558 0.3541094 0.3969804 0.8433741 0.3621142 0.5561264 0.8053067 0.2054377 0.4715876 0.8762993 0.098513 0.6280058 0.7775546 -0.03190165 0.4637411 0.856936 -0.2249553 0.4562532 0.863786 -0.2137914 0.4275155 0.7872231 -0.4444214 0.2268209 0.872143 -0.4334959 0.2083076 0.8009632 -0.5613074 -0.0842455 0.8364403 -0.5415445 -0.09235721 0.8625392 -0.4974901 -0.3627556 0.784615 -0.5027801 -0.3532847 0.8184439 -0.4531441 -0.6819884 0.7025733 -0.2031815 -0.4479002 0.8661563 -0.221718 -0.6456633 0.7636145 -0.003453075 -0.5307564 0.8449153 0.06645298 -0.6061251 0.7637588 0.2220023 -0.4756668 0.7809988 0.4047001 -0.3780224 0.8432666 0.3821001 -0.201363 0.8628853 0.4635536 -0.1955657 0.8189572 0.5395027 0.08388793 0.7667636 0.6364248 0.1219426 0.8648019 0.4870809 0.3944533 0.7311692 0.5565953 0.4339485 0.8210024 0.3710039 0.5883502 0.7425391 0.3201249 0.5355263 0.8323321 0.1429512 0.6486445 0.7590778 0.05532974 0.5940409 0.7848925 -0.1762361 0.5414325 0.8319311 -0.1214144 0.4833443 0.7922025 -0.3725502 0.3032385 0.8936119 -0.3309141 0.2751444 0.7879183 -0.5508905 0.05152279 0.8575665 -0.5117862 0.04444962 0.8496589 -0.5254561 -0.2314954 0.7889302 -0.5692091 -0.2306663 0.859992 -0.4551997 -0.5264092 0.759181 -0.3828024 -0.450734 0.8497315 -0.2734878 -0.7180315 0.6938188 0.05519342 -0.586041 0.8101789 -0.01288819 -0.5328841 0.8225938 0.1984291 -0.4488207 0.8695263 0.206117 -0.4102101 0.8075317 0.4238163 -0.2672234 0.8720337 0.4100596 -0.2633612 0.8470228 0.4617286 -0.06187152 0.7863458 0.6146806 0.0564683 0.8847588 0.4626156 0.2115964 0.7728549 0.5982661 0.3252261 0.8641419 0.3840401 0.5523198 0.7255048 0.410592 0.5729325 0.8121202 0.110495 0.6525213 0.7547061 0.06807929 0.5859613 0.7885837 -0.186508 0.4337488 0.8777992 -0.2032997 0.4454588 0.7351909 -0.510941 0.2196751 0.8895407 -0.4005749 0.1050915 0.7653148 -0.6350191 0.02186512 0.8276693 -0.5607901 -0.1938129 0.736557 -0.6480128 -0.2798386 0.8550581 -0.4365388 -0.3245432 0.8321421 -0.4496791 -0.5122224 0.800921 -0.3100866 -0.4340353 0.8786591 -0.1989262 -0.6422042 0.7659575 -0.02971321 -0.5933879 0.8049149 0.001743674 -0.6005545 0.7659927 0.2293242 -0.3896191 0.8713797 0.2981517 -0.43014 0.7842672 0.4471069 -0.1563025 0.8359538 0.5260712 -0.1514666 0.8413718 0.5187979 0.1467176 0.8333965 0.5328455 0.1489073 0.8313857 0.5353735 0.4518713 0.7746425 0.4424268 0.3653424 0.8927629 0.2636275 0.6051866 0.7786094 0.1658813 0.4879351 0.8728799 1.26529e-5 0.6185351 0.7771476 -0.1160005 0.3803405 0.8695175 -0.3150883 0.3912719 0.8550987 -0.3401656 0.257984 0.7408733 -0.6201218 0.07148414 0.8835657 -0.4628195 -0.02833437 0.8056997 -0.5916464 -0.2167575 0.8495517 -0.4809138 -0.2163259 0.8592897 -0.4634916 -0.4488187 0.8002218 -0.3977522 -0.3934062 0.8942021 -0.2136217 -0.5595441 0.8097244 -0.176796 -0.5764546 0.8150768 0.0578798 -0.4028012 0.9098508 0.09961313 -0.5194881 0.7816421 0.3452069 -0.3326076 0.8217114 0.4627771 -0.2643623 0.8700204 0.4161456 -0.1154121 0.801283 0.5870484 0.008803188 0.8772485 0.4799559 0.0832318 0.8206583 0.5653253 0.3560854 0.8071358 0.4708875 0.3367252 0.8394569 0.4265307 0.5500113 0.8044559 0.2243624 0.5357714 0.8214769 0.1952558 0.6812331 0.7319138 0.0149551 0.604041 0.7959449 -0.04007899 0.553529 0.7932655 -0.2536447 0.6183961 0.6805176 -0.3930423 0.2654334 0.8674515 -0.4208005 0.2518687 0.7518363 -0.6093475 -0.03815907 0.8737664 -0.4848465 -0.08969306 0.8264712 -0.5557882 -0.3554559 0.7891778 -0.5008487 -0.3149476 0.888865 -0.3327568 -0.609695 0.7454159 -0.2694943 -0.4754813 0.8766311 -0.07372552 -0.6449543 0.762441 0.05213099 -0.5043541 0.8130328 0.2908688 -0.4913477 0.8211722 0.290265 -0.4084743 0.7674446 0.4941431 -0.2861029 0.8246696 0.4879194 -0.184641 0.7401942 0.6465449 -0.01998454 0.8648323 0.501663 0.1889289 0.733974 0.6523711 0.2254983 0.8539392 0.4689759 0.5203921 0.6994609 0.4898433 0.6604539 0.7264165 0.1900522 0.5036602 0.807637 0.3066743 0.5128679 0.8584266 0.00838679 0.584917 0.8055898 -0.09432649 0.4962846 0.8540145 -0.1560799 0.5567055 0.748039 -0.3612708 0.3589489 0.8192414 -0.4472129 0.3436016 0.7574833 -0.5551191 0.1143391 0.8118252 -0.5725963 0.1505557 0.7768912 -0.6113699 -0.1130332 0.7642091 -0.6349866 -0.1407741 0.8153053 -0.5616584 -0.3807814 0.7588067 -0.5284108 -0.3558323 0.8621917 -0.3605675 -0.5290584 0.8201069 -0.2179951 -0.481934 0.8592787 -0.1714051 -0.6278834 0.7781616 0.01507353 -0.4888686 0.8511153 0.191338 -0.4562949 0.877247 0.1491066 -0.465658 0.7585582 0.4557983 -0.212474 0.9059137 0.3662993 -0.1759575 0.807053 0.5636528 0.04892104 0.7992948 0.5989446 0.1212068 0.893325 0.432758 0.2644305 0.8106307 0.5224506 0.476294 0.7959933 0.3735487 0.4536233 0.8250266 0.336982 0.6854467 0.7210636 0.1011436 0.5341036 0.8452566 -0.01657468 0.5904543 0.7756199 -0.2231087 0.4395238 0.8659784 -0.238538 0.4645434 0.7735609 -0.4310489 0.3108878 0.7845212 -0.53654 0.1567467 0.8786513 -0.4510017 0.07104444 0.7788756 -0.6231418 -0.1578869 0.8545808 -0.4947357 -0.1768525 0.8411058 -0.5111402 -0.4283999 0.7938609 -0.4315768 -0.384623 0.8676699 -0.3149826 -0.6166533 0.7620707 -0.1974514 -0.5646733 0.8147317 -0.1317443 -0.6625466 0.7472572 0.05136871 -0.5228933 0.8248723 0.2148681 -0.4621056 0.860035 0.2163289 -0.4055977 0.803491 0.4357671 -0.2739988 0.8709426 0.4079016 -0.231035 0.7944037 0.5617345 -0.002583861 0.8640162 0.5034574 0.0266183 0.8327143 0.553063 0.2993113 0.7721129 0.5605841 0.2863459 0.8761406 0.3877934 0.559203 0.7401354 0.3734859 0.5590215 0.8182111 0.1342592 0.6163545 0.7669648 0.1785278 0.5839655 0.796108 -0.1587338 0.6790297 0.7196641 -0.1449217 0.4147992 0.8323699 -0.3675622 0.4314805 0.7838215 -0.4465965 0.183691 0.8526352 -0.4891534 0.1832541 0.8512312 -0.4917555 -0.01260411 0.7763331 -0.6301969 -0.07622563 0.8380709 -0.5402101 -0.3041288 0.7298079 -0.6122795 -0.3631784 0.8439034 -0.3948779 -0.5273549 0.7533192 -0.3929468 -0.5469821 0.8297411 -0.1110877 -0.5389928 0.8346275 -0.113507 -0.6171926 0.7796994 0.1055569 -0.4486018 0.8728456 0.1920859 -0.4996932 0.8050007 0.3198135 -0.3455974 0.8499674 0.3976407 -0.2989488 0.8784951 0.3726609 -0.1466816 0.8357012 0.5292334 -0.04511928 0.8750768 0.4818766 0.0446487 0.7813848 0.6224504 0.2363908 0.8458204 0.4782334 0.3635013 0.7655594 0.5308349 0.5308234 0.7730204 0.3473704 0.4740538 0.8510479 0.2258107 0.6193659 0.7766367 0.1149843 0.5472222 0.8287337 -0.1172535 0.4716225 0.8811422 -0.0340681 0.493892 0.83249 -0.25106 0.3853765 0.8860552 -0.2576649 0.3897148 0.7877737 -0.4770061 0.2300163 0.7677851 -0.5979955 0.2408009 0.7991899 -0.5507361 -0.09993523 0.7514749 -0.6521491 -0.0185182 0.8430764 -0.5374751 -0.2650704 0.7241725 -0.636641 -0.4009515 0.8038715 -0.4393503 -0.420752 0.7933114 -0.4400283 -0.4233688 0.8070426 -0.4116325 -0.6249656 0.7387148 -0.2524251 -0.5323079 0.8447925 -0.05453425 -0.601749 0.7986067 -0.01120442 -0.5038052 0.834851 0.2218205 -0.6207845 0.7483035 0.2338134 -0.418786 0.8201082 0.3899243 -0.4023902 0.7293464 0.5532956 -0.179054 0.7930074 0.582305 -0.1819209 0.797383 0.5754 0.03649258 0.7641205 0.6440407 0.1359938 0.867019 0.4793577 0.2713162 0.7880743 0.5525637 0.4007766 0.8384714 0.3692479 0.427262 0.7971979 0.4265241 0.6098549 0.7732232 0.1737896 0.5070617 0.8586118 0.07532668 0.62016 0.78158 -0.06733727 0.4552572 0.8658839 -0.2073308 0.4870658 0.8336288 -0.2604417 0.3363667 0.8087159 -0.4825307 0.2976135 0.8379442 -0.4574668 0.1045164 0.7606351 -0.640711 -0.05078703 0.8537666 -0.518173 -0.1508328 0.7770766 -0.6110658 -0.3346769 0.8382141 -0.4305678 -0.3135625 0.8736095 -0.3721358 -0.6100084 0.7462084 -0.2665762 -0.4996767 0.863433 -0.06933069 -0.462738 0.8849005 -0.0531466 -0.5314571 0.8146228 0.2322564 -0.4979328 0.8341327 0.2372461 -0.486756 0.7388277 0.4660496 -0.2779889 0.8248002 0.4923686 -0.2396442 0.7598676 0.6042946 -0.07979547 0.8558765 0.5109874 0.07762986 0.739915 0.6682061 0.2451786 0.8487439 0.4685311 0.3565783 0.7792524 0.5153813 0.406129 0.8497618 0.3361015 0.6061632 0.7343966 0.3053324 0.609136 0.7929264 0.0148763 0.5815862 0.8128894 0.03111845 0.5319315 0.8210051 -0.2073636 0.5058528 0.8369483 -0.2088791 0.4849915 0.743109 -0.4610556 0.2635486 0.8381058 -0.47762 0.2722511 0.8583407 -0.4348917 0.0712316 0.8176537 -0.5712867 -0.009331941 0.867025 -0.4981772 -0.1175347 0.7824347 -0.6115403 -0.2413579 0.8705574 -0.4288077 -0.4998845 0.7145466 -0.489427 -0.5483935 0.7872449 -0.2819756 -0.6294674 0.739134 -0.2396911 -0.5316416 0.8469694 -2.64001e-4 -0.6117684 0.7880707 0.06844019 -0.4636446 0.8571926 0.224175 -0.4839445 0.8342683 0.2641859 -0.3339443 0.8366876 0.4340911 -0.3351701 0.8280038 0.449523 -0.09145975 0.8175523 0.5685449 -0.1034866 0.8409461 0.5311311 0.1270678 0.7972245 0.5901584 0.2097327 0.8806366 0.4248428 0.2657858 0.8501344 0.4545649 0.5165391 0.7882398 0.3344629 0.4861887 0.8296768 0.2743303 0.6473882 0.7491605 0.1401678 0.5539824 0.8292458 -0.07385796 0.5260587 0.8489156 -0.05103641 0.5280362 0.8004843 -0.2835537 0.5230715 0.8034546 -0.2843537 0.4366006 0.7409389 -0.5102838 0.2347181 0.8399881 -0.4892112 0.2237023 0.8131777 -0.5373075 -0.0313853 0.8141765 -0.5797686 -0.03066486 0.8124685 -0.5821982 -0.3898799 0.7645066 -0.5133453 -0.320698 0.817677 -0.4780765 -0.507871 0.8134021 -0.2836267 -0.462444 0.8583774 -0.2221123 -0.5940063 0.8012315 -0.0720058 -0.4975087 0.8674475 -0.004489541 -0.4757101 0.8516002 0.2201753 -0.6535308 0.6024621 0.458189 -0.3691413 0.785389 0.4968891 -0.2304409 0.8816598 0.4117923 -0.1062298 0.7854065 0.6097966 0.0420252 0.8513817 0.5228604 0.1089015 0.8005959 0.5892256 0.3282296 0.7397969 0.5873381 0.3665888 0.8391028 0.4018947 0.5304354 0.7578011 0.3799684 0.4739455 0.869249 0.1406482 0.4724462 0.8702335 0.1396008 0.6242471 0.7770572 -0.08060854 0.4228883 0.8772808 -0.2270329 0.4647747 0.853769 -0.2346551 0.4035269 0.7899982 -0.4615941 0.1397891 0.8995813 -0.4137785 0.2109139 0.8499633 -0.4827814 -0.06282186 0.7114281 -0.6999453 -0.09985554 0.7859452 -0.6101795 -0.3763841 0.7613868 -0.5278496 -0.3581877 0.842283 -0.4028163 -0.4771624 0.817285 -0.32305 -0.4125388 0.8898202 -0.1950176 -0.5952782 0.7958197 -0.1109731 -0.679358 0.7110053 0.1815055 -0.5662514 0.8198843 0.08455222 -0.484714 0.8021184 0.3487958 -0.431307 0.8387295 0.3324262 -0.2465008 0.7369372 0.6294131 -0.09698736 0.8688406 0.4854992 0.08283436 0.7742336 0.627456 0.1406468 0.8490604 0.5092298 0.3538825 0.7473123 0.562398 0.4448046 0.8109599 0.3801221 0.5323942 0.7593529 0.3740853 0.5793541 0.7962313 0.1742551 0.5708739 0.8044188 0.1643574 0.653379 0.7540111 -0.06755298 0.5799606 0.8068838 -0.1121809 0.5684154 0.7680158 -0.295052 0.378633 0.8756771 -0.2997112 0.3198972 0.801564 -0.5051348 0.2371539 0.8572213 -0.4570884 0.0444051 0.7143837 -0.6983439 -0.1159094 0.8198471 -0.5607278 -0.2061788 0.7599271 -0.6164422 -0.337794 0.8571452 -0.388841 -0.3306299 0.8678495 -0.3708382 -0.5530492 0.8012085 -0.2284771 -0.4934642 0.8566944 -0.1502267 -0.6250957 0.7805418 0.003170371 -0.4535889 0.8834207 0.1175798 -0.5483078 0.7872229 0.2822033 -0.3410818 0.8508211 0.3997081 -0.3103095 0.8697816 0.3836511 -0.2105884 0.7954706 0.5682245 -0.008423089 0.8706384 0.4918515 0.036031 0.8283764 0.559012 0.2562273 0.8499608 0.4603416 0.3285564 0.801301 0.4999676 0.4773549 0.830089 0.2882438 0.4432908 0.8624427 0.2443069 0.6118353 0.786273 0.08621209 0.45713 0.882645 -0.1094079 0.5563981 0.8246971 -0.1014685 0.4297782 0.8176925 -0.3829749 0.3823415 0.8490643 -0.3645612 0.1867595 0.8227475 -0.5368494 0.1593797 0.8462357 -0.5084127 -0.01571255 0.7903131 -0.6125018 -0.2589998 0.7957772 -0.5474101 -0.1354113 0.8733868 -0.4678241 -0.3729906 0.8626812 -0.3415541 -0.3479494 0.8742979 -0.3384297 -0.5215377 0.8346697 -0.1769883 -0.4618726 0.8836454 -0.0764501 -0.6100434 0.7922281 0.01489871 -0.551494 0.8045182 0.2204658 -0.4056062 0.8837078 0.2335468 -0.4387673 0.7679379 0.4666421 -0.2462807 0.8670718 0.4330502 -0.150978 0.7228547 0.6743047 0.1198866 0.8179644 0.5626379 0.1473931 0.8060254 0.573235 0.1465371 0.8046743 0.5753489 0.416276 0.7379111 0.5312265 0.3814151 0.8779988 0.2892071 0.557886 0.7882493 0.259666 0.5094071 0.8603574 0.01701879 0.5623413 0.8267893 -0.01385116 0.5131108 0.8198999 -0.2539318 0.4330216 0.8626552 -0.2613778 0.4440144 0.7964005 -0.4106063 0.2237123 0.8486803 -0.4792647 0.2024754 0.864239 -0.4605373 0.02596801 0.778898 -0.6266129 -0.1008862 0.8852893 -0.4539659 -0.2122656 0.8122837 -0.5432665 -0.4240639 0.7756989 -0.4673982 -0.3608115 0.8997342 -0.2455472 -0.5587676 0.7986031 -0.2236337 -0.6303887 0.7750743 -0.04324173 -0.4998759 0.865069 0.04218912 -0.6099317 0.7614727 0.2194148 -0.3922552 0.8245835 0.407674 -0.3727903 0.8628213 0.3414188 -0.2929352 0.7657104 0.5726052 -0.08784157 0.8782213 0.4701185 -0.01757752 0.7956517 0.6054994 0.2412457 0.850794 0.4668512 0.2801008 0.8245011 0.4916723 0.4607611 0.8435197 0.2759962 0.4652137 0.84103 0.276125 0.6047875 0.7960991 0.02140909 0.5676443 0.8232308 0.008435308 0.5138679 0.7837693 -0.3487771 0.5022567 0.8005737 -0.3268336 0.2744689 0.8370358 -0.4733265 0.273521 0.858496 -0.4337869 0.03923004 0.7617596 -0.6466709 0.08470082 0.8876948 -0.4525746 -0.2289661 0.691184 -0.6854482 -0.2109827 0.9121667 -0.351338 -0.7497898 -0.032732 -0.660866 -0.7965971 0.5094243 -0.3254535 -0.3662886 -0.9119411 0.1849223 -0.3906441 0.6346025 0.666841 0.3698276 -0.8469051 -0.3820725 0.438608 0.6862618 -0.5802309 0.09377622 -0.7032156 -0.7047652 0.04266279 -0.8698273 0.4915084 0.3620353 0.8009697 0.4768417 0.576971 -0.7789978 0.2454936 0.3336626 0.9250572 -0.1814899 -0.1650758 -0.893283 0.4180856 0.3139294 -0.888484 -0.3347309 0.1092025 -0.8533596 -0.5097572 0.1460025 -0.9120216 -0.3832751 -0.02378714 0.8888049 -0.457668 -0.3996437 -0.9099949 -0.110429 -0.1890909 0.8758105 0.4440729 -0.3364675 -0.9323723 -0.1321808 -0.997947 -0.04926502 0.04092299 0.1106954 0.9938496 0.003078997 0.6302156 0.7664403 0.124087 0.2616838 0.9623641 0.07332855 0.7631995 0.5776976 0.2894689 0.9792814 0.06967425 0.1901408 0.8740761 0.3660528 0.3193689 0.4067469 0.8512858 0.3314657 0.530672 0.7293828 0.4317268 0.6037469 0.6620528 0.444045 0.2918086 0.9033046 0.3144658 0.8039276 -0.02978968 0.5939807 0.7496286 0.1763542 0.6379313 0.4342088 0.5628792 0.7032993 0.2813073 0.7856051 0.5510817 0.3340409 0.6820953 0.6505096 0.1331316 0.8838285 0.4484676 0.5112397 0.3082319 0.8022637 0.3885701 -0.1234295 0.9131147 0.1357976 0.4429187 0.8862178 0.1401588 0.4705788 0.871155 0.06596434 0.8277246 0.5572439 0.0915364 0.4330531 0.8967086 -0.03310674 0.8648442 0.5009476 -0.1556236 0.7502969 0.6425231 -0.03809082 0.9975516 0.05865085 -0.1394163 0.5591842 0.817237 -0.0880497 -0.09427154 0.9916452 -0.04857337 0.9923684 0.1133392 -0.2469584 0.7802231 0.5746856 -0.2341288 0.2599142 0.9368183 -0.3598756 0.699007 0.6179634 -0.365146 0.2024739 0.9086654 -0.4460811 0.3604274 0.8192093 -0.4381912 0.7403758 0.5097374 -0.3556827 0.8770841 0.3228211 -0.712843 0.3766863 0.5915762 -0.4026309 0.8896126 0.2155872 -0.6854419 0.08774244 0.7228214 -0.1503397 0.9881671 0.03039443 -0.7215279 0.6403726 0.2632875 -0.8316456 0.3972656 0.3880023 -0.8992826 0.2232253 0.3761136 -0.4292401 0.9019731 -0.0468778 -0.7488847 0.6613916 0.04162746 -0.6116066 0.7901102 -0.04078233 -0.9749369 0.220055 -0.03277033 -0.3148835 0.930867 -0.185297 -0.8004748 0.5191956 -0.2994595 -0.9105044 0.2807118 -0.303616 -0.6382396 0.6638471 -0.3898169 -0.2194626 0.9617714 -0.1638048 -0.9210466 0.0604282 -0.3847361 -0.6674532 0.4463496 -0.5960523 -0.7985686 0.1709932 -0.5771046 -0.2562885 0.8728719 -0.4152241 -0.393149 0.6684826 -0.6313201 -0.5526586 0.4520893 -0.7001314 -0.09890931 0.9408869 -0.3239581 -0.5261751 0.07727998 -0.8468575 -0.1584514 0.5674983 -0.8079844 -0.04985058 0.7691788 -0.6370865 -0.2308817 0.1644751 -0.9589795 -0.160695 0.3586701 -0.9195287 0.07257157 0.7676672 -0.6367264 0.1308906 0.7080721 -0.6939031 0.07669216 0.9855359 -0.1511201 0.148011 0.2219565 -0.9637572 0.2831575 0.7426795 -0.6068353 0.2171638 -0.003168284 -0.9761301 0.1983044 0.9366273 -0.2887989 0.5134039 0.3454913 -0.7855267 0.4980721 0.4569233 -0.736984 0.647328 -0.1890081 -0.7384052 0.5339251 0.7567842 -0.3770967 0.6165658 0.5713654 -0.5416534 0.53609 0.7581255 -0.3712859 0.7537853 0.3083587 -0.580278 0.7422165 0.6083159 -0.2811877 0.303795 0.9492759 -0.08114188 0.7064161 0.6979447 -0.1176846 0.9043299 0.1809607 -0.3865756 0.9416419 -0.1198666 -0.3145515 0.7608264 0.6460341 -0.06150674 0.9273759 0.3716069 -0.0433855 2.02017e-4 1 3.65694e-4 -0.003754377 0.9999803 -0.00503242 0.005446374 0.9999851 -5.11607e-4 0.01099032 0.9999395 4.85691e-4 0.01265931 0.9997239 -0.01980292 6.48372e-4 0.9995061 0.03142219 -0.863191 -0.07112365 0.4998427 -0.86313 -0.07126086 0.4999286 -0.002010762 -0.071801 0.997417 -0.002124011 -0.07193452 0.9974071 0.8627436 -0.07166206 0.5005379 0.8629793 -0.07116699 0.500202 0.8640273 -0.07077842 -0.4984448 0.8647977 -0.07290482 -0.4967995 0.00385791 -0.07242023 -0.9973669 0.001695573 -0.06977742 -0.9975612 -0.8664868 -0.03821265 -0.4977354 -0.8654017 -0.03544241 -0.4998238 0.007834374 -0.9999294 0.008940994 0.001201808 -0.9999346 0.01138579 0.01201319 -0.9999278 3.91946e-4 0.01040649 -0.9999365 0.004354834 0.008758902 -0.9999472 0.00538063 0.01081824 -0.9999337 -0.003944456 4.46182e-4 -0.9999418 0.01078623 -0.00600171 -0.9999226 0.01090836 0.00768584 -0.9999338 -0.008557796 0.008464097 -0.9999492 -0.005476593 -0.009051263 -0.9999348 0.006974339 -0.009144902 -0.9999434 0.00544703 0.003604054 -0.9999359 -0.01074308 -0.01163077 -0.9999276 0.003093481 -2.61907e-4 -0.999948 -0.01019227 2.9642e-4 -0.9999431 -0.01066535 -0.01209765 -0.999925 -0.001990258 -0.009024083 -0.9999422 -0.005851626 -0.005671977 -0.9999275 -0.01061809 -0.009042382 -0.9999405 -0.006108462 6.83155e-4 -0.9999996 7.07118e-4 0.003069698 -0.9999951 7.17547e-4 -0.004202187 -0.9999638 -0.007404088 5.0577e-5 -1 3.60386e-4 -0.9749487 0.01304656 0.2220471 -0.9392516 -0.01957315 0.3426707 -0.8062931 0.03120136 0.5906928 -0.6676262 -0.03310823 0.7437602 -0.3181563 0.01472496 0.947924 -0.3422307 0.02634352 0.9392466 0.02567672 -0.02499914 0.9993578 0.2298386 0.03239494 0.9726895 0.4709388 -0.02853238 0.8817045 0.6614282 0.03029656 0.7493963 0.827403 -0.02923995 0.5608469 0.9438818 0.02593111 0.3292642 0.9864709 -0.02029693 0.1626757 0.9900833 0.0239765 -0.1384199 0.9661056 -0.0176512 -0.2575432 0.7918829 0.008334755 -0.6106162 0.7906064 0.009229242 -0.6122552 0.4820542 -0.01380139 -0.8760328 0.4438461 0.005193829 -0.8960881 0.02188181 0.01592123 -0.9996338 -0.1048468 -0.0400021 -0.9936836 -0.4508693 0.03405946 -0.8919401 -0.658712 -0.02973407 -0.7518075 -0.7887676 0.02261614 -0.6142754 -0.9223373 -0.02285873 -0.3857089 -0.98251 0.02172374 -0.1849386 -0.9993595 -0.01429587 -0.03280633 3.25831e-4 1 -2.47469e-4 -4.15245e-4 0.9999374 -0.01118415 1.79961e-4 1 -3.60422e-4 0.01760506 0.9998437 -0.001671195 0.006818473 0.9999763 -9.52198e-4 1.76092e-4 0.9999676 -0.008050322 0.02015089 0.9996258 -0.0185042 0.005964457 0.99998 0.002079427 -0.005004525 0.9999475 0.008953094 -0.007223725 0.9998719 -0.01428693 -0.02061855 0.9997729 0.005406439 -1.50868e-4 1 -1.65978e-4 -0.001076221 0.9999991 -8.37528e-4 1.92114e-4 1 -2.37659e-4 -1.33595e-5 1 -5.84224e-5 -4.07899e-4 0.9999969 -0.002489686 -0.002869486 0.9999958 -5.41112e-4 0.0106697 0.9999386 0.002996027 -0.00301826 0.9999952 6.88592e-4 -0.002412676 0.9999752 0.006620943 -0.005808353 0.9999787 -0.002979099 -0.003326296 0.9999803 0.005334198 -0.005527794 0.9999765 0.004058778 + + + + + + + + + + + + + + +

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

+
+ + + +

1958 3761 1956 3761 1959 3761 1957 3762 1959 3762 1956 3762 1959 3763 1957 3763 1960 3763 1961 3764 2056 3764 1958 3764 1963 3765 1960 3765 1962 3765 1966 3766 1958 3766 1959 3766 1963 3767 1959 3767 1960 3767 1965 3768 2057 3768 1961 3768 1961 3769 1958 3769 1966 3769 1963 3770 1964 3770 1959 3770 1964 3771 1966 3771 1959 3771 1966 3772 1968 3772 1961 3772 1967 3773 1963 3773 1962 3773 1968 3774 1965 3774 1961 3774 1969 3775 1966 3775 1964 3775 1970 3776 1963 3776 1967 3776 1971 3777 1969 3777 1964 3777 1970 3778 1964 3778 1963 3778 1973 3779 1965 3779 1968 3779 1968 3780 1966 3780 1969 3780 1974 3781 1967 3781 1972 3781 1974 3782 1970 3782 1967 3782 1971 3783 1964 3783 1970 3783 1976 3784 1969 3784 1971 3784 1980 3785 1972 3785 1975 3785 1974 3786 1972 3786 1980 3786 1977 3787 1970 3787 1974 3787 1977 3788 1971 3788 1970 3788 1978 3789 1968 3789 1969 3789 1973 3790 1968 3790 1978 3790 1977 3791 1976 3791 1971 3791 1979 3792 1980 3792 1975 3792 1981 3793 1976 3793 1977 3793 1976 3794 1978 3794 1969 3794 1977 3795 1974 3795 1980 3795 1982 3796 1980 3796 1979 3796 1973 3797 1983 3797 1965 3797 1985 3798 1977 3798 1980 3798 1985 3799 1981 3799 1977 3799 1978 3800 1983 3800 1973 3800 1982 3801 1979 3801 1986 3801 1982 3802 1985 3802 1980 3802 1978 3803 1990 3803 1983 3803 1986 3804 1979 3804 1984 3804 1990 3805 1978 3805 1976 3805 1990 3806 1976 3806 1981 3806 1989 3807 1985 3807 1982 3807 1988 3808 1981 3808 1985 3808 1988 3809 1985 3809 1989 3809 1989 3810 1982 3810 1986 3810 1986 3811 1984 3811 1987 3811 1990 3812 1981 3812 1988 3812 1992 3813 1988 3813 1989 3813 1992 3814 1989 3814 1986 3814 1993 3815 1986 3815 1987 3815 1994 3816 1987 3816 1991 3816 1990 3817 1988 3817 1992 3817 1993 3818 1992 3818 1986 3818 1997 3819 1993 3819 1987 3819 1997 3820 1987 3820 1994 3820 1994 3821 1991 3821 1995 3821 1996 3822 1990 3822 1992 3822 1998 3823 1992 3823 1993 3823 1998 3824 1996 3824 1992 3824 1999 3825 1990 3825 1996 3825 1998 3826 1993 3826 1997 3826 2001 3827 1997 3827 1994 3827 2001 3828 1994 3828 1995 3828 2002 3829 1998 3829 1997 3829 2002 3830 1997 3830 2001 3830 2000 3831 2001 3831 1995 3831 1996 3832 1998 3832 2002 3832 2004 3833 1996 3833 2002 3833 2005 3834 2001 3834 2000 3834 2004 3835 1999 3835 1996 3835 2006 3836 2002 3836 2001 3836 2006 3837 2001 3837 2005 3837 2007 3838 2005 3838 2000 3838 2007 3839 2000 3839 2003 3839 2009 3840 1999 3840 2004 3840 2008 3841 2007 3841 2003 3841 2006 3842 2005 3842 2007 3842 2004 3843 2002 3843 2006 3843 2011 3844 2004 3844 2006 3844 2012 3845 2006 3845 2007 3845 2013 3846 2012 3846 2007 3846 2013 3847 2007 3847 2008 3847 2011 3848 2009 3848 2004 3848 2012 3849 2011 3849 2006 3849 2013 3850 2008 3850 2010 3850 2015 3851 2011 3851 2012 3851 2016 3852 2013 3852 2010 3852 2017 3853 2009 3853 2011 3853 2016 3854 2010 3854 2014 3854 2018 3855 2012 3855 2013 3855 2020 3856 2016 3856 2014 3856 2018 3857 2013 3857 2016 3857 2019 3858 2020 3858 2014 3858 2015 3859 2017 3859 2011 3859 2023 3860 2012 3860 2018 3860 2027 3861 2016 3861 2020 3861 2022 3862 2020 3862 2019 3862 2023 3863 2015 3863 2012 3863 2027 3864 2018 3864 2016 3864 2022 3865 2027 3865 2020 3865 2024 3866 2022 3866 2019 3866 2024 3867 2019 3867 2021 3867 2017 3868 2015 3868 2023 3868 2027 3869 2023 3869 2018 3869 2026 3870 2023 3870 2027 3870 2024 3871 2021 3871 2025 3871 2028 3872 2023 3872 2026 3872 2029 3873 2022 3873 2024 3873 2025 3874 2029 3874 2024 3874 2031 3875 2022 3875 2029 3875 2017 3876 2023 3876 2028 3876 2027 3877 2022 3877 2031 3877 2030 3878 2029 3878 2025 3878 2032 3879 2031 3879 2029 3879 2033 3880 2029 3880 2030 3880 2032 3881 2029 3881 2033 3881 2031 3882 2026 3882 2027 3882 2035 3883 2026 3883 2031 3883 2036 3884 2032 3884 2033 3884 2035 3885 2028 3885 2026 3885 2037 3886 2032 3886 2036 3886 2033 3887 2030 3887 2034 3887 2037 3888 2031 3888 2032 3888 2039 3889 2035 3889 2031 3889 2039 3890 2031 3890 2037 3890 2040 3891 2033 3891 2034 3891 2038 3892 2040 3892 2034 3892 2042 3893 2037 3893 2036 3893 2040 3894 2036 3894 2033 3894 2040 3895 2042 3895 2036 3895 2043 3896 2040 3896 2038 3896 2039 3897 2037 3897 2042 3897 2043 3898 2038 3898 2041 3898 2044 3899 2042 3899 2040 3899 2047 3900 2035 3900 2039 3900 2044 3901 2040 3901 2043 3901 2046 3902 2043 3902 2041 3902 2047 3903 2039 3903 2042 3903 2045 3904 2046 3904 2041 3904 2048 3905 2044 3905 2043 3905 2046 3906 2048 3906 2043 3906 2049 3907 2047 3907 2042 3907 2049 3908 2042 3908 2044 3908 2050 3909 2044 3909 2048 3909 2049 3910 2044 3910 2050 3910 2052 3911 2048 3911 2046 3911 2052 3912 2046 3912 2045 3912 2053 3913 2052 3913 2045 3913 2050 3914 2048 3914 2052 3914 2054 3915 2049 3915 2050 3915 2053 3916 2045 3916 2051 3916 2054 3917 2050 3917 2052 3917 2055 3918 2047 3918 2049 3918 2055 3919 2049 3919 2054 3919 1956 3920 2053 3920 2051 3920 2056 3921 2052 3921 2053 3921 2053 3922 1956 3922 1958 3922 2056 3923 2054 3923 2052 3923 2057 3924 2054 3924 2056 3924 2056 3925 2053 3925 1958 3925 2057 3926 2055 3926 2054 3926 2057 3927 2056 3927 1961 3927 1965 3928 2055 3928 2057 3928 1956 3929 2058 3929 1957 3929 1957 3930 2058 3930 1960 3930 2058 3931 2059 3931 1960 3931 1960 3932 2059 3932 1962 3932 1962 3933 2059 3933 1967 3933 2059 3934 2060 3934 1967 3934 1967 3935 2060 3935 1972 3935 1972 3936 2060 3936 1975 3936 1975 3937 2061 3937 1979 3937 2060 3938 2061 3938 1975 3938 1979 3939 2061 3939 1984 3939 1984 3940 2061 3940 1987 3940 2061 3941 2062 3941 1987 3941 1987 3942 2062 3942 1991 3942 1991 3943 2062 3943 1995 3943 2062 3944 2063 3944 1995 3944 1995 3945 2063 3945 2000 3945 2000 3946 2063 3946 2003 3946 2063 3947 2064 3947 2003 3947 2003 3948 2064 3948 2008 3948 2008 3949 2064 3949 2010 3949 2064 3950 2065 3950 2010 3950 2010 3951 2065 3951 2014 3951 2014 3952 2065 3952 2019 3952 2065 3953 2066 3953 2019 3953 2019 3954 2066 3954 2021 3954 2021 3955 2066 3955 2025 3955 2066 3956 2067 3956 2025 3956 2025 3957 2067 3957 2030 3957 2030 3958 2067 3958 2034 3958 2034 3959 2067 3959 2038 3959 2067 3960 2068 3960 2038 3960 2038 3961 2068 3961 2041 3961 2068 3962 2069 3962 2041 3962 2041 3963 2069 3963 2045 3963 2045 3964 2069 3964 2051 3964 2051 3965 2069 3965 1956 3965 2069 3966 2058 3966 1956 3966 1965 3967 1983 3967 2071 3967 1990 3968 2070 3968 1983 3968 1965 3969 2071 3969 2072 3969 1990 3970 2073 3970 2070 3970 1965 3971 2072 3971 2074 3971 2055 3972 1965 3972 2074 3972 1990 3973 2075 3973 2073 3973 1999 3974 2075 3974 1990 3974 2055 3975 2074 3975 2076 3975 1999 3976 2077 3976 2075 3976 2047 3977 2055 3977 2076 3977 2078 3978 2077 3978 1999 3978 2079 3979 2047 3979 2076 3979 2078 3980 1999 3980 2009 3980 2079 3981 2035 3981 2047 3981 2080 3982 2078 3982 2009 3982 2081 3983 2035 3983 2079 3983 2082 3984 2080 3984 2009 3984 2083 3985 2035 3985 2081 3985 2082 3986 2009 3986 2017 3986 2083 3987 2028 3987 2035 3987 2084 3988 2082 3988 2017 3988 2085 3989 2028 3989 2083 3989 2085 3990 2017 3990 2028 3990 2085 3991 2084 3991 2017 3991 2088 3992 2087 3992 2086 3992 2086 3993 2087 3993 2089 3993 2090 3994 2086 3994 2089 3994 2091 3995 2087 3995 2088 3995 2091 3996 2092 3996 2087 3996 2091 3997 2093 3997 2092 3997 2094 3998 2090 3998 2089 3998 2094 3999 2089 3999 2095 3999 2096 4000 2093 4000 2091 4000 2097 4001 2099 4001 2098 4001 2100 4002 2099 4002 2097 4002 2101 4003 2097 4003 2098 4003 2101 4004 2098 4004 2102 4004 2103 4005 2094 4005 2095 4005 2104 4006 2099 4006 2100 4006 2104 4007 2105 4007 2099 4007 2106 4008 2105 4008 2104 4008 2107 4009 2103 4009 2095 4009 2108 4010 2107 4010 2095 4010 2109 4011 2105 4011 2106 4011 2109 4012 2110 4012 2105 4012 2110 4013 2109 4013 2111 4013 2108 4014 2119 4014 2107 4014 2112 4015 2102 4015 2093 4015 2112 4016 2101 4016 2102 4016 2113 4017 2112 4017 2093 4017 2113 4018 2093 4018 2096 4018 2112 4019 2114 4019 2101 4019 2113 4020 2096 4020 2115 4020 2116 4021 2114 4021 2112 4021 2117 1244 2113 1244 2115 1244 2116 4022 2120 4022 2114 4022 2118 4023 2119 4023 2108 4023 2117 1244 2115 1244 2121 1244 2122 4024 2120 4024 2116 4024 2122 4025 2124 4025 2120 4025 2123 4026 2117 4026 2121 4026 2123 1244 2121 1244 2125 1244 2126 4027 2127 4027 2124 4027 2126 1244 2124 1244 2122 1244 2128 4028 2110 4028 2111 4028 2129 4029 2123 4029 2125 4029 2129 1244 2125 1244 2119 1244 2126 1244 2111 1244 2127 1244 2129 4030 2119 4030 2118 4030 2130 4031 2111 4031 2126 4031 2130 4032 2128 4032 2111 4032 2135 4033 2129 4033 2118 4033 2131 4034 2135 4034 2118 4034 2132 4035 2128 4035 2130 4035 2133 4036 2134 4036 2135 4036 2136 1244 2133 1244 2135 1244 2136 4037 2135 4037 2131 4037 2137 1244 2134 1244 2133 1244 2137 4038 2138 4038 2134 4038 2139 4039 2136 4039 2131 4039 2139 4040 2131 4040 2140 4040 2141 1244 2138 1244 2137 1244 2155 4041 2139 4041 2140 4041 2141 4042 2142 4042 2138 4042 2143 1244 2130 1244 2144 1244 2145 4043 2132 4043 2130 4043 2145 1244 2130 1244 2143 1244 2146 1244 2142 1244 2141 1244 2147 4044 2143 4044 2144 4044 2145 4045 2148 4045 2132 4045 2147 1244 2144 1244 2149 1244 2150 4046 2148 4046 2145 4046 2147 1244 2149 1244 2151 1244 2152 1244 2147 1244 2151 1244 2146 4047 2154 4047 2142 4047 2171 1244 2154 1244 2146 1244 2153 4048 2155 4048 2140 4048 2152 4049 2151 4049 2154 4049 2170 1244 2152 1244 2154 1244 2148 4050 2150 4050 2156 4050 2153 4051 2158 4051 2155 4051 2157 4052 2148 4052 2156 4052 2157 4053 2156 4053 2159 4053 2153 4054 2160 4054 2158 4054 2161 4055 2160 4055 2153 4055 2157 4056 2159 4056 2162 4056 2161 4057 2163 4057 2160 4057 2164 4058 2157 4058 2162 4058 2164 4059 2162 4059 2165 4059 2161 4060 2168 4060 2163 4060 2164 4061 2165 4061 2166 4061 2167 4062 2168 4062 2161 4062 2169 4063 2164 4063 2166 4063 2167 4064 2171 4064 2168 4064 2169 4065 2166 4065 2170 4065 2172 4066 2171 4066 2167 4066 2173 4067 2170 4067 2154 4067 2173 4068 2169 4068 2170 4068 2172 4069 2154 4069 2171 4069 2172 4070 2173 4070 2154 4070 2175 4071 2174 4071 2153 4071 2140 4072 2175 4072 2153 4072 2140 4073 2176 4073 2175 4073 2177 4074 2140 4074 2131 4074 2177 4075 2176 4075 2140 4075 2178 4076 2177 4076 2131 4076 2118 4077 2179 4077 2178 4077 2118 4078 2178 4078 2131 4078 2180 4079 2118 4079 2108 4079 2180 4080 2179 4080 2118 4080 2095 4081 2181 4081 2180 4081 2095 4082 2180 4082 2108 4082 2181 4083 2095 4083 2089 4083 2182 4084 2181 4084 2089 4084 2087 4085 2182 4085 2089 4085 2087 4086 2183 4086 2182 4086 2092 4087 2184 4087 2183 4087 2092 4088 2183 4088 2087 4088 2184 4089 2092 4089 2093 4089 2185 4090 2184 4090 2093 4090 2186 4091 2185 4091 2093 4091 2186 4092 2093 4092 2102 4092 2187 4093 2186 4093 2102 4093 2188 4094 2187 4094 2102 4094 2188 4095 2102 4095 2098 4095 2189 4096 2188 4096 2098 4096 2189 4097 2098 4097 2099 4097 2190 4098 2189 4098 2099 4098 2190 4099 2099 4099 2105 4099 2105 4100 2191 4100 2190 4100 2192 4101 2191 4101 2105 4101 2192 4102 2105 4102 2110 4102 2193 4103 2192 4103 2110 4103 2194 4104 2193 4104 2110 4104 2128 4105 2194 4105 2110 4105 2128 4106 2195 4106 2194 4106 2196 4107 2128 4107 2132 4107 2196 4108 2195 4108 2128 4108 2132 4109 2197 4109 2196 4109 2197 4110 2132 4110 2148 4110 2198 4111 2197 4111 2148 4111 2157 4112 2199 4112 2198 4112 2157 4113 2198 4113 2148 4113 2200 4114 2157 4114 2164 4114 2200 4115 2199 4115 2157 4115 2164 4116 2201 4116 2200 4116 2201 4117 2164 4117 2169 4117 2202 4118 2201 4118 2169 4118 2203 4119 2169 4119 2173 4119 2203 4120 2202 4120 2169 4120 2204 4121 2173 4121 2172 4121 2204 4122 2203 4122 2173 4122 2205 4123 2204 4123 2172 4123 2205 4124 2172 4124 2167 4124 2167 4125 2206 4125 2205 4125 2206 4126 2167 4126 2161 4126 2207 4127 2206 4127 2161 4127 2207 4128 2161 4128 2153 4128 2207 4129 2153 4129 2174 4129 2207 4130 2174 4130 2208 4130 2207 4131 2208 4131 2209 4131 2206 4132 2207 4132 2209 4132 2206 4133 2209 4133 2210 4133 2205 4134 2210 4134 2211 4134 2205 4135 2206 4135 2210 4135 2204 4136 2205 4136 2211 4136 2204 4137 2211 4137 2212 4137 2203 4138 2204 4138 2212 4138 2203 4139 2212 4139 2213 4139 2202 4140 2203 4140 2213 4140 2201 4141 2213 4141 2214 4141 2201 4142 2202 4142 2213 4142 2200 4143 2201 4143 2214 4143 2200 4144 2214 4144 2215 4144 2199 4145 2200 4145 2215 4145 2199 4146 2215 4146 2216 4146 2198 4147 2199 4147 2216 4147 2198 4148 2216 4148 2217 4148 2197 4149 2198 4149 2217 4149 2196 4150 2197 4150 2217 4150 2196 4151 2217 4151 2218 4151 2195 4152 2218 4152 2219 4152 2195 4153 2196 4153 2218 4153 2195 4154 2219 4154 2220 4154 2194 4155 2195 4155 2220 4155 2193 4156 2194 4156 2220 4156 2193 4157 2220 4157 2221 4157 2192 4158 2193 4158 2221 4158 2192 4159 2221 4159 2222 4159 2191 4160 2192 4160 2222 4160 2190 4161 2222 4161 2223 4161 2190 4162 2191 4162 2222 4162 2189 4163 2223 4163 2224 4163 2189 4164 2190 4164 2223 4164 2188 4165 2189 4165 2224 4165 2188 4166 2224 4166 2225 4166 2187 4167 2188 4167 2225 4167 2187 4168 2225 4168 2226 4168 2186 4169 2187 4169 2226 4169 2186 4170 2226 4170 2227 4170 2185 4171 2186 4171 2227 4171 2185 4172 2227 4172 2228 4172 2184 4173 2185 4173 2228 4173 2184 4174 2228 4174 2229 4174 2183 4175 2184 4175 2229 4175 2182 4176 2183 4176 2229 4176 2182 4177 2229 4177 2230 4177 2181 4178 2230 4178 2231 4178 2181 4179 2182 4179 2230 4179 2180 4180 2231 4180 2232 4180 2180 4181 2181 4181 2231 4181 2179 4182 2232 4182 2233 4182 2179 4183 2180 4183 2232 4183 2179 4184 2233 4184 2234 4184 2178 4185 2179 4185 2234 4185 2178 4186 2234 4186 2235 4186 2177 4187 2178 4187 2235 4187 2176 4188 2177 4188 2235 4188 2176 4189 2235 4189 2236 4189 2175 4190 2176 4190 2236 4190 2175 4191 2236 4191 2208 4191 2174 4192 2175 4192 2208 4192 2239 4193 2240 4193 2237 4193 2237 4194 2240 4194 2238 4194 2237 1244 2238 1244 2241 1244 2238 1244 2242 1244 2241 1244 2239 4195 2243 4195 2240 4195 2244 4196 2243 4196 2239 4196 2242 1244 2245 1244 2241 1244 2241 1244 2245 1244 2246 1244 2244 1244 2247 1244 2243 1244 2248 1244 2247 1244 2244 1244 2248 4197 2249 4197 2247 4197 2245 1244 2250 1244 2246 1244 2251 1244 2249 1244 2248 1244 2246 1244 2250 1244 2252 1244 2250 4198 2253 4198 2252 4198 2251 1244 2254 1244 2249 1244 2251 1244 2255 1244 2254 1244 2250 4199 2256 4199 2253 4199 2255 1244 2257 1244 2254 1244 2258 1244 2253 1244 2256 1244 2258 4200 2259 4200 2253 4200 2254 4201 2257 4201 2260 4201 2257 1244 2261 1244 2260 1244 2262 1244 2263 1244 2258 1244 2258 1244 2263 1244 2259 1244 2260 4202 2261 4202 2264 4202 2261 1244 2265 1244 2264 1244 2262 1244 2266 1244 2263 1244 2267 1244 2266 1244 2262 1244 2264 1244 2265 1244 2268 1244 2265 4203 2269 4203 2268 4203 2267 1244 2270 1244 2266 1244 2268 1244 2269 1244 2271 1244 2271 1244 2270 1244 2267 1244 2269 4204 2270 4204 2271 4204 2149 4205 2266 4205 2151 4205 2263 4206 2266 4206 2149 4206 2151 4207 2266 4207 2154 4207 2266 4208 2270 4208 2154 4208 2270 4209 2269 4209 2154 4209 2154 4210 2269 4210 2142 4210 2269 4211 2265 4211 2142 4211 2142 4212 2265 4212 2138 4212 2265 4213 2261 4213 2138 4213 2138 4214 2261 4214 2134 4214 2261 4215 2257 4215 2134 4215 2134 4216 2257 4216 2135 4216 2257 4217 2255 4217 2135 4217 2135 4218 2255 4218 2129 4218 2255 4219 2251 4219 2129 4219 2129 4220 2251 4220 2123 4220 2251 4221 2248 4221 2123 4221 2248 4222 2244 4222 2123 4222 2123 4223 2244 4223 2117 4223 2244 4224 2239 4224 2117 4224 2117 4225 2239 4225 2113 4225 2239 4226 2237 4226 2113 4226 2113 4227 2237 4227 2112 4227 2237 4228 2241 4228 2112 4228 2112 4229 2241 4229 2116 4229 2241 4230 2246 4230 2116 4230 2116 4231 2246 4231 2122 4231 2122 4232 2246 4232 2126 4232 2246 4233 2252 4233 2126 4233 2126 4234 2253 4234 2130 4234 2252 4235 2253 4235 2126 4235 2130 4236 2253 4236 2144 4236 2253 4237 2259 4237 2144 4237 2259 4238 2263 4238 2144 4238 2144 4239 2263 4239 2149 4239 2083 4240 2081 4240 2264 4240 2083 4241 2264 4241 2268 4241 2085 4242 2083 4242 2268 4242 2085 4243 2268 4243 2271 4243 2085 4244 2271 4244 2267 4244 2084 4245 2085 4245 2267 4245 2084 4246 2267 4246 2262 4246 2082 4247 2084 4247 2262 4247 2080 4248 2082 4248 2262 4248 2080 4249 2262 4249 2258 4249 2078 4250 2080 4250 2258 4250 2078 4251 2258 4251 2256 4251 2077 4252 2078 4252 2256 4252 2077 4253 2256 4253 2250 4253 2075 4254 2077 4254 2250 4254 2075 4255 2250 4255 2245 4255 2073 4256 2075 4256 2245 4256 2073 4257 2245 4257 2242 4257 2070 4258 2073 4258 2242 4258 2070 4259 2242 4259 2238 4259 1983 4260 2070 4260 2238 4260 1983 4261 2238 4261 2240 4261 2071 4262 1983 4262 2240 4262 2071 4263 2240 4263 2243 4263 2072 4264 2071 4264 2243 4264 2072 4265 2243 4265 2247 4265 2074 4266 2072 4266 2247 4266 2074 4267 2247 4267 2249 4267 2076 4268 2074 4268 2249 4268 2076 4269 2249 4269 2254 4269 2079 4270 2076 4270 2254 4270 2079 4271 2254 4271 2260 4271 2081 4272 2079 4272 2260 4272 2081 4273 2260 4273 2264 4273 2272 4274 2091 4274 2273 4274 2091 4275 2088 4275 2273 4275 2088 4276 2086 4276 2273 4276 2273 4277 2086 4277 2274 4277 2086 4278 2090 4278 2274 4278 2274 4279 2090 4279 2275 4279 2090 4280 2094 4280 2275 4280 2275 4281 2094 4281 2276 4281 2094 4282 2103 4282 2276 4282 2276 4283 2103 4283 2277 4283 2103 4284 2107 4284 2277 4284 2277 4285 2107 4285 2278 4285 2107 4286 2119 4286 2278 4286 2278 4287 2119 4287 2279 4287 2119 4288 2125 4288 2279 4288 2279 4289 2125 4289 2280 4289 2125 4290 2121 4290 2280 4290 2280 4291 2121 4291 2281 4291 2281 4292 2121 4292 2282 4292 2121 4293 2115 4293 2282 4293 2282 4294 2096 4294 2283 4294 2115 4295 2096 4295 2282 4295 2096 4296 2091 4296 2283 4296 2283 4297 2091 4297 2272 4297 2137 4298 2133 4298 2284 4298 2284 4299 2133 4299 2285 4299 2133 4300 2136 4300 2285 4300 2285 4301 2136 4301 2286 4301 2136 4302 2139 4302 2286 4302 2139 4303 2155 4303 2286 4303 2286 4304 2155 4304 2287 4304 2155 4305 2158 4305 2287 4305 2287 4306 2158 4306 2288 4306 2158 4307 2160 4307 2288 4307 2288 4308 2160 4308 2289 4308 2160 4309 2163 4309 2289 4309 2289 4310 2163 4310 2290 4310 2163 4311 2168 4311 2290 4311 2290 4312 2168 4312 2291 4312 2168 4313 2171 4313 2291 4313 2291 4314 2171 4314 2292 4314 2171 4315 2146 4315 2292 4315 2292 4316 2146 4316 2293 4316 2146 4317 2141 4317 2293 4317 2293 4318 2141 4318 2294 4318 2141 4319 2137 4319 2294 4319 2294 4320 2137 4320 2284 4320 2307 4321 2100 4321 2295 4321 2104 4322 2100 4322 2307 4322 2295 4323 2100 4323 2296 4323 2100 4324 2097 4324 2296 4324 2296 4325 2097 4325 2297 4325 2097 4326 2101 4326 2297 4326 2297 4327 2101 4327 2298 4327 2101 4328 2114 4328 2298 4328 2298 4329 2114 4329 2299 4329 2114 4330 2120 4330 2299 4330 2299 4331 2120 4331 2300 4331 2300 4332 2120 4332 2301 4332 2120 4333 2124 4333 2301 4333 2301 4334 2124 4334 2302 4334 2124 4335 2127 4335 2302 4335 2302 4336 2127 4336 2303 4336 2127 4337 2111 4337 2303 4337 2303 4338 2111 4338 2304 4338 2304 4339 2111 4339 2305 4339 2111 4340 2109 4340 2305 4340 2305 4341 2109 4341 2306 4341 2109 4342 2106 4342 2306 4342 2306 4343 2106 4343 2307 4343 2106 4344 2104 4344 2307 4344 2150 4345 2145 4345 2318 4345 2318 4346 2145 4346 2308 4346 2145 4347 2143 4347 2308 4347 2308 4348 2143 4348 2309 4348 2143 4349 2147 4349 2309 4349 2309 4350 2147 4350 2310 4350 2310 4351 2147 4351 2311 4351 2147 4352 2152 4352 2311 4352 2311 4353 2152 4353 2312 4353 2152 4354 2170 4354 2312 4354 2312 4355 2170 4355 2313 4355 2170 4356 2166 4356 2313 4356 2313 4357 2166 4357 2314 4357 2166 4358 2165 4358 2314 4358 2314 4359 2165 4359 2315 4359 2165 4360 2162 4360 2315 4360 2162 4361 2159 4361 2315 4361 2315 4362 2159 4362 2316 4362 2159 4363 2156 4363 2316 4363 2316 4364 2156 4364 2317 4364 2156 4365 2150 4365 2317 4365 2317 4366 2150 4366 2318 4366 2317 4367 2318 4367 2216 4367 2216 4368 2316 4368 2317 4368 2215 1235 2316 1235 2216 1235 2216 4369 2318 4369 2217 4369 2318 1235 2308 1235 2217 1235 2217 4370 2308 4370 2218 4370 2215 1235 2315 1235 2316 1235 2214 1235 2315 1235 2215 1235 2218 1235 2308 1235 2219 1235 2221 1235 2306 1235 2222 1235 2221 1235 2305 1235 2306 1235 2306 1235 2307 1235 2222 1235 2220 1235 2305 1235 2221 1235 2214 4371 2314 4371 2315 4371 2220 4372 2304 4372 2305 4372 2222 4373 2307 4373 2223 4373 2307 4374 2295 4374 2223 4374 2219 1235 2304 1235 2220 1235 2308 4375 2304 4375 2219 4375 2308 4376 2303 4376 2304 4376 2223 1235 2295 1235 2224 1235 2295 1235 2296 1235 2224 1235 2296 4377 2225 4377 2224 4377 2296 1235 2297 1235 2225 1235 2214 4378 2213 4378 2314 4378 2314 1235 2213 1235 2313 1235 2213 1235 2212 1235 2313 1235 2297 4379 2226 4379 2225 4379 2313 4380 2212 4380 2312 4380 2303 1235 2062 1235 2302 1235 2308 1235 2062 1235 2303 1235 2309 4381 2062 4381 2308 4381 2062 1235 2061 1235 2302 1235 2309 1235 2063 1235 2062 1235 2302 1235 2061 1235 2301 1235 2298 4382 2226 4382 2297 4382 2310 1235 2063 1235 2309 1235 2310 1235 2064 1235 2063 1235 2061 1235 2060 1235 2301 1235 2301 4383 2060 4383 2300 4383 2311 4384 2064 4384 2310 4384 2311 4385 2065 4385 2064 4385 2300 4386 2060 4386 2299 4386 2060 1235 2059 1235 2299 1235 2065 4387 2292 4387 2293 4387 2312 1235 2292 1235 2311 1235 2311 1235 2292 1235 2065 1235 2065 1235 2293 1235 2066 1235 2293 1235 2294 1235 2066 1235 2212 1235 2292 1235 2312 1235 2211 4388 2292 4388 2212 4388 2066 4389 2294 4389 2067 4389 2294 1235 2284 1235 2067 1235 2211 4390 2291 4390 2292 4390 2210 1235 2291 1235 2211 1235 2067 4391 2284 4391 2068 4391 2059 1235 2282 1235 2299 1235 2282 1235 2283 1235 2299 1235 2299 1235 2283 1235 2298 1235 2298 4392 2283 4392 2226 4392 2226 1235 2283 1235 2227 1235 2058 1235 2282 1235 2059 1235 2283 4393 2272 4393 2227 4393 2227 4394 2272 4394 2228 4394 2284 1235 2285 1235 2068 1235 2058 1235 2281 1235 2282 1235 2069 1235 2281 1235 2058 1235 2068 1235 2285 1235 2069 1235 2291 1235 2210 1235 2290 1235 2272 1235 2273 1235 2228 1235 2069 1235 2280 1235 2281 1235 2273 1235 2229 1235 2228 1235 2285 4395 2280 4395 2069 4395 2285 4396 2279 4396 2280 4396 2210 1235 2209 1235 2290 1235 2290 1235 2209 1235 2289 1235 2274 4397 2229 4397 2273 4397 2274 1235 2230 1235 2229 1235 2289 4398 2208 4398 2288 4398 2209 4399 2208 4399 2289 4399 2275 4400 2230 4400 2274 4400 2275 1235 2231 1235 2230 1235 2276 1235 2231 1235 2275 1235 2288 1235 2236 1235 2287 1235 2208 1235 2236 1235 2288 1235 2277 4401 2231 4401 2276 4401 2287 1235 2236 1235 2286 1235 2277 4402 2232 4402 2231 4402 2278 4403 2232 4403 2277 4403 2236 4404 2235 4404 2286 4404 2278 1235 2233 1235 2232 1235 2279 4405 2233 4405 2278 4405 2235 1235 2234 1235 2286 1235 2286 1235 2234 1235 2285 1235 2285 4406 2233 4406 2279 4406 2285 1235 2234 1235 2233 1235

+
+ + + +

2319 4407 2320 4407 2321 4407 2320 4408 2322 4408 2321 4408 2323 4409 2324 4409 2320 4409 2320 4410 2324 4410 2322 4410 2323 4411 2325 4411 2324 4411 2325 4412 2326 4412 2324 4412 2325 4413 2327 4413 2326 4413 2327 4414 2328 4414 2326 4414 2329 4415 2330 4415 2327 4415 2327 4416 2330 4416 2328 4416 2319 4417 2321 4417 2329 4417 2329 4418 2321 4418 2330 4418 2328 4419 2330 4419 2331 4419 2331 4420 2330 4420 2332 4420 2330 4421 2321 4421 2332 4421 2332 4422 2321 4422 2336 4422 2321 4423 2322 4423 2336 4423 2336 4424 2322 4424 2335 4424 2329 4425 2327 4425 2319 4425 2319 4426 2327 4426 2320 4426 2320 4427 2325 4427 2323 4427 2327 4428 2325 4428 2320 4428 2334 4429 3191 4429 3197 4429 2334 4430 3190 4430 3191 4430 2335 4431 2334 4431 3197 4431 2335 4432 3199 4432 3202 4432 2335 4433 3197 4433 3199 4433 3205 4434 2335 4434 3202 4434 2333 4435 3237 4435 3190 4435 2333 4436 3234 4436 3237 4436 2333 4437 3190 4437 2334 4437 3230 4438 3234 4438 2333 4438 2336 4439 2335 4439 3205 4439 2336 4440 3205 4440 3209 4440 3211 4441 2336 4441 3209 4441 2331 4442 3225 4442 3230 4442 2331 4443 3230 4443 2333 4443 3223 4444 3225 4444 2331 4444 3215 4445 2332 4445 2336 4445 3215 4446 2336 4446 3211 4446 3219 4447 3223 4447 2331 4447 3219 4448 2331 4448 2332 4448 3218 4449 2332 4449 3215 4449 3218 4450 3219 4450 2332 4450 2337 4451 2338 4451 3082 4451 2337 4452 3077 4452 2338 4452 2339 4453 2337 4453 3082 4453 2339 4454 3082 4454 2340 4454 2341 4455 3077 4455 2337 4455 2339 4456 2340 4456 2342 4456 2341 4457 3074 4457 3077 4457 2343 4458 3074 4458 2341 4458 2343 4459 2344 4459 3074 4459 2339 4460 2342 4460 2345 4460 2346 4461 2339 4461 2345 4461 3090 4462 2346 4462 2345 4462 2343 4463 3069 4463 2344 4463 2347 4464 3069 4464 2343 4464 3065 4465 3069 4465 2347 4465 3065 4466 2347 4466 2349 4466 2350 4467 3065 4467 2349 4467 3057 4468 2350 4468 2349 4468 3057 4469 2349 4469 2351 4469 2352 4470 3057 4470 2351 4470 2356 4471 2355 4471 2354 4471 2356 4472 2357 4472 2355 4472 2360 4473 2357 4473 2356 4473 2360 4474 2359 4474 2357 4474 2358 4475 2359 4475 2360 4475 2358 4476 2361 4476 2359 4476 2362 4477 2361 4477 2358 4477 2362 4478 2363 4478 2361 4478 2364 4479 2363 4479 2362 4479 2364 4480 2365 4480 2363 4480 2364 4481 2366 4481 2365 4481 2367 4482 2366 4482 2364 4482 2367 4483 2368 4483 2366 4483 2369 4484 2370 4484 2367 4484 2367 4485 2370 4485 2368 4485 2369 4486 2371 4486 2370 4486 2372 4487 2371 4487 2369 4487 2372 4488 2373 4488 2371 4488 2374 4489 2373 4489 2372 4489 2374 4490 2375 4490 2373 4490 2374 4491 2376 4491 2375 4491 2377 4492 2376 4492 2374 4492 2377 4493 2378 4493 2376 4493 2379 4494 2378 4494 2377 4494 2379 4495 2380 4495 2378 4495 2381 4496 2380 4496 2379 4496 2381 4497 2382 4497 2380 4497 2383 4498 2382 4498 2381 4498 2383 4499 2384 4499 2382 4499 2385 4500 2384 4500 2383 4500 2385 4501 2386 4501 2384 4501 2385 4502 2387 4502 2386 4502 2388 4503 2387 4503 2385 4503 2388 4504 2389 4504 2387 4504 2390 4505 2389 4505 2388 4505 2390 4506 2391 4506 2389 4506 2392 4507 2391 4507 2390 4507 2392 4508 2393 4508 2391 4508 2392 4509 2394 4509 2393 4509 2395 4510 2394 4510 2392 4510 2395 4511 2396 4511 2394 4511 2397 4512 2396 4512 2395 4512 2397 4513 2398 4513 2396 4513 2399 4514 2398 4514 2397 4514 2399 4515 2400 4515 2398 4515 2399 4516 2401 4516 2400 4516 2402 4517 2401 4517 2399 4517 2402 4518 2403 4518 2401 4518 2404 4519 2405 4519 2402 4519 2402 4520 2405 4520 2403 4520 2404 4521 2406 4521 2405 4521 2407 4522 2406 4522 2404 4522 2407 4523 2408 4523 2406 4523 2409 4524 2408 4524 2407 4524 2409 4525 2410 4525 2408 4525 2409 4526 2411 4526 2410 4526 2412 4527 2411 4527 2409 4527 2412 4528 2413 4528 2411 4528 2412 4529 2414 4529 2413 4529 2415 4530 2414 4530 2412 4530 2415 4531 2416 4531 2414 4531 2417 4532 2418 4532 2415 4532 2415 4533 2418 4533 2416 4533 2417 4534 2419 4534 2418 4534 2420 4535 2419 4535 2417 4535 2420 4536 2421 4536 2419 4536 2420 4537 2422 4537 2421 4537 2423 4538 2422 4538 2420 4538 2423 4539 2424 4539 2422 4539 2425 4540 2424 4540 2423 4540 2425 4541 2426 4541 2424 4541 2427 4542 2426 4542 2425 4542 2427 4543 2428 4543 2426 4543 2429 4544 2428 4544 2427 4544 2429 4545 2430 4545 2428 4545 2429 4546 2431 4546 2430 4546 2432 4547 2431 4547 2429 4547 2432 4548 2433 4548 2431 4548 2434 4549 2433 4549 2432 4549 2434 4550 2435 4550 2433 4550 2436 4551 2435 4551 2434 4551 2436 4552 2437 4552 2435 4552 2436 4553 2438 4553 2437 4553 2439 4554 2438 4554 2436 4554 2439 4555 2440 4555 2438 4555 2441 4556 2440 4556 2439 4556 2441 4557 2442 4557 2440 4557 2441 4558 2443 4558 2442 4558 2444 4559 2443 4559 2441 4559 2444 4560 2445 4560 2443 4560 2444 4561 2446 4561 2445 4561 2447 4562 2446 4562 2444 4562 2449 4563 2448 4563 2447 4563 2447 4564 2448 4564 2446 4564 2449 4565 2450 4565 2448 4565 2451 4566 2450 4566 2449 4566 2451 4567 2452 4567 2450 4567 2451 4568 2453 4568 2452 4568 2454 4569 2453 4569 2451 4569 2454 4570 2455 4570 2453 4570 2456 4571 2455 4571 2454 4571 2456 4572 2457 4572 2455 4572 2458 4573 2457 4573 2456 4573 2458 4574 2459 4574 2457 4574 2458 4575 2460 4575 2459 4575 2461 4576 2460 4576 2458 4576 2461 4577 2462 4577 2460 4577 2463 4578 2462 4578 2461 4578 2463 4579 2464 4579 2462 4579 2465 4580 2464 4580 2463 4580 2465 4581 2466 4581 2464 4581 2465 4582 2467 4582 2466 4582 2468 4583 2467 4583 2465 4583 2468 4584 2469 4584 2467 4584 2470 4585 2469 4585 2468 4585 2470 4586 2471 4586 2469 4586 2472 4587 2471 4587 2470 4587 2472 4588 2473 4588 2471 4588 2474 4589 2473 4589 2472 4589 2474 4590 2475 4590 2473 4590 2474 4591 2476 4591 2475 4591 2477 4592 2476 4592 2474 4592 2477 4593 2478 4593 2476 4593 2479 4594 2478 4594 2477 4594 2479 4595 2480 4595 2478 4595 2481 4596 2480 4596 2479 4596 2481 4597 2482 4597 2480 4597 2481 4598 2483 4598 2482 4598 2484 4599 2483 4599 2481 4599 2484 4600 2485 4600 2483 4600 2486 4601 2485 4601 2484 4601 2486 4602 2487 4602 2485 4602 2488 4603 2487 4603 2486 4603 2488 4604 2489 4604 2487 4604 2490 4605 2489 4605 2488 4605 2490 4606 2491 4606 2489 4606 2490 4607 2492 4607 2491 4607 2493 4608 2492 4608 2490 4608 2494 4609 2492 4609 2493 4609 2494 4610 2495 4610 2492 4610 2496 4611 2495 4611 2494 4611 2496 4612 2497 4612 2495 4612 2496 4613 2498 4613 2497 4613 2499 4614 2498 4614 2496 4614 2499 4615 2500 4615 2498 4615 2501 4616 2500 4616 2499 4616 2501 4617 2502 4617 2500 4617 2503 4618 2502 4618 2501 4618 2503 4619 2504 4619 2502 4619 2503 4620 2505 4620 2504 4620 2506 4621 2505 4621 2503 4621 2506 4622 2507 4622 2505 4622 2508 4623 2507 4623 2506 4623 2508 4624 2509 4624 2507 4624 2508 4625 2510 4625 2509 4625 2511 4626 2510 4626 2508 4626 2511 4627 2512 4627 2510 4627 2513 4628 2512 4628 2511 4628 2513 4629 2514 4629 2512 4629 2515 4630 2514 4630 2513 4630 2515 4631 2516 4631 2514 4631 2515 4632 2517 4632 2516 4632 2518 4633 2517 4633 2515 4633 2518 4634 2519 4634 2517 4634 2520 4635 2519 4635 2518 4635 2520 4636 2521 4636 2519 4636 2520 4637 2522 4637 2521 4637 2523 4638 2522 4638 2520 4638 2523 4639 2524 4639 2522 4639 2523 4640 2525 4640 2524 4640 2526 4641 2525 4641 2523 4641 2526 4642 2527 4642 2525 4642 2528 4643 2527 4643 2526 4643 2528 4644 2529 4644 2527 4644 2530 4645 2529 4645 2528 4645 2530 4646 2531 4646 2529 4646 2530 4647 2532 4647 2531 4647 2533 4648 2532 4648 2530 4648 2533 4649 2534 4649 2532 4649 2535 4650 2534 4650 2533 4650 2535 4651 2536 4651 2534 4651 2535 4652 2537 4652 2536 4652 2538 4653 2537 4653 2535 4653 2538 4654 2539 4654 2537 4654 2540 4655 2539 4655 2538 4655 2540 4656 2541 4656 2539 4656 2542 4657 2541 4657 2540 4657 2542 4658 2543 4658 2541 4658 2544 4659 2543 4659 2542 4659 2544 4660 2545 4660 2543 4660 2546 4661 2545 4661 2544 4661 2546 4662 2547 4662 2545 4662 2548 4663 2547 4663 2546 4663 2548 4664 2549 4664 2547 4664 2548 4665 2550 4665 2549 4665 2551 4666 2550 4666 2548 4666 2551 4667 2552 4667 2550 4667 2551 4668 2553 4668 2552 4668 2554 4669 2553 4669 2551 4669 2555 4670 2553 4670 2554 4670 2555 4671 2556 4671 2553 4671 2555 4672 2557 4672 2556 4672 2558 4673 2557 4673 2555 4673 2558 4674 2559 4674 2557 4674 2558 4675 2560 4675 2559 4675 2561 4676 2560 4676 2558 4676 2561 4677 2562 4677 2560 4677 2561 4678 2563 4678 2562 4678 2564 4679 2563 4679 2561 4679 2564 4680 2565 4680 2563 4680 2564 4681 2566 4681 2565 4681 2567 4682 2566 4682 2564 4682 2567 4683 2568 4683 2566 4683 2569 4684 2568 4684 2567 4684 2569 4685 2570 4685 2568 4685 2571 4686 2570 4686 2569 4686 2571 4687 2572 4687 2570 4687 2571 4688 2573 4688 2572 4688 2574 4689 2573 4689 2571 4689 2574 4690 2575 4690 2573 4690 2576 4691 2575 4691 2574 4691 2576 4692 2577 4692 2575 4692 2578 4693 2577 4693 2576 4693 2578 4694 2579 4694 2577 4694 2580 4695 2579 4695 2578 4695 2580 4696 2581 4696 2579 4696 2580 4697 2582 4697 2581 4697 2583 4698 2582 4698 2580 4698 2583 4699 2584 4699 2582 4699 2585 4700 2584 4700 2583 4700 2585 4701 2586 4701 2584 4701 2587 4702 2586 4702 2585 4702 2587 4703 2588 4703 2586 4703 2589 4704 2588 4704 2587 4704 2589 4705 2590 4705 2588 4705 2591 4706 2590 4706 2589 4706 2591 4707 2592 4707 2590 4707 2591 4708 2593 4708 2592 4708 2594 4709 2593 4709 2591 4709 2594 4710 2595 4710 2593 4710 2596 4711 2595 4711 2594 4711 2596 4712 2597 4712 2595 4712 2596 4713 2598 4713 2597 4713 2599 4714 2598 4714 2596 4714 2599 4715 2600 4715 2598 4715 2601 4716 2600 4716 2599 4716 2601 4717 2602 4717 2600 4717 2603 4718 2602 4718 2601 4718 2603 4719 2604 4719 2602 4719 2605 4720 2606 4720 2603 4720 2603 4721 2606 4721 2604 4721 2607 4722 2608 4722 2605 4722 2605 4723 2608 4723 2606 4723 2607 4724 2609 4724 2608 4724 2610 4725 2609 4725 2607 4725 2610 4726 2611 4726 2609 4726 2612 4727 2611 4727 2610 4727 2612 4728 2613 4728 2611 4728 2614 4729 2613 4729 2612 4729 2614 4730 2615 4730 2613 4730 2614 4731 2616 4731 2615 4731 2617 4732 2616 4732 2614 4732 2617 4733 2618 4733 2616 4733 2619 4734 2618 4734 2617 4734 2619 4735 2620 4735 2618 4735 2621 4736 2620 4736 2619 4736 2621 4737 2622 4737 2620 4737 2623 4738 2622 4738 2621 4738 2623 4739 2624 4739 2622 4739 2625 4740 2624 4740 2623 4740 2625 4741 2626 4741 2624 4741 2627 4742 2628 4742 2625 4742 2625 4743 2628 4743 2626 4743 2627 4744 2629 4744 2628 4744 2630 4745 2629 4745 2627 4745 2630 4746 2631 4746 2629 4746 2632 4747 2631 4747 2630 4747 2632 4748 2633 4748 2631 4748 2634 4749 2633 4749 2632 4749 2634 4750 2635 4750 2633 4750 2636 4751 2635 4751 2634 4751 2636 4752 2637 4752 2635 4752 2636 4753 2638 4753 2637 4753 2639 4754 2638 4754 2636 4754 2639 4755 2640 4755 2638 4755 2641 4756 2640 4756 2639 4756 2641 4757 2642 4757 2640 4757 2643 4758 2642 4758 2641 4758 2643 4759 2644 4759 2642 4759 2643 4760 2645 4760 2644 4760 2646 4761 2645 4761 2643 4761 2646 4762 2647 4762 2645 4762 2646 4763 2648 4763 2647 4763 2649 4764 2648 4764 2646 4764 2649 4765 2650 4765 2648 4765 2649 4766 2651 4766 2650 4766 2652 4767 2651 4767 2649 4767 2652 4768 2653 4768 2651 4768 2654 4769 2653 4769 2652 4769 2654 4770 2655 4770 2653 4770 2654 4771 2656 4771 2655 4771 2657 4772 2656 4772 2654 4772 2657 4773 2658 4773 2656 4773 2659 4774 2658 4774 2657 4774 2659 4775 2660 4775 2658 4775 2661 4776 2660 4776 2659 4776 2661 4777 2662 4777 2660 4777 2663 4778 2662 4778 2661 4778 2663 4779 2664 4779 2662 4779 2663 4780 2665 4780 2664 4780 2666 4781 2665 4781 2663 4781 2666 4782 2667 4782 2665 4782 2666 4783 2668 4783 2667 4783 2669 4784 2668 4784 2666 4784 2669 4785 2670 4785 2668 4785 2671 4786 2670 4786 2669 4786 2671 4787 2672 4787 2670 4787 2673 4788 2672 4788 2671 4788 2673 4789 2674 4789 2672 4789 2673 4790 2675 4790 2674 4790 2676 4791 2675 4791 2673 4791 2676 4792 2677 4792 2675 4792 2678 4793 2677 4793 2676 4793 2678 4794 2679 4794 2677 4794 2678 4795 2680 4795 2679 4795 2681 4796 2680 4796 2678 4796 2681 4797 2682 4797 2680 4797 2683 4798 2682 4798 2681 4798 2683 4799 2684 4799 2682 4799 2685 4800 2684 4800 2683 4800 2685 4801 2686 4801 2684 4801 2687 4802 2686 4802 2685 4802 2687 4803 2688 4803 2686 4803 2687 4804 2689 4804 2688 4804 2690 4805 2689 4805 2687 4805 2690 4806 2691 4806 2689 4806 2692 4807 2691 4807 2690 4807 2692 4808 2693 4808 2691 4808 2694 4809 2693 4809 2692 4809 2694 4810 2695 4810 2693 4810 2696 4811 2695 4811 2694 4811 2696 4812 2697 4812 2695 4812 2698 4813 2697 4813 2696 4813 2698 4814 2699 4814 2697 4814 2700 4815 2699 4815 2698 4815 2700 4816 2701 4816 2699 4816 2702 4817 2703 4817 2700 4817 2700 4818 2703 4818 2701 4818 2704 4819 2703 4819 2702 4819 2704 4820 2705 4820 2703 4820 2704 4821 2706 4821 2705 4821 2707 4822 2706 4822 2704 4822 2707 4823 2708 4823 2706 4823 2709 4824 2708 4824 2707 4824 2709 4825 2710 4825 2708 4825 2711 4826 2710 4826 2709 4826 2711 4827 2712 4827 2710 4827 2711 4828 2713 4828 2712 4828 2714 4829 2713 4829 2711 4829 2714 4830 2715 4830 2713 4830 2716 4831 2715 4831 2714 4831 2716 4832 2717 4832 2715 4832 2718 4833 2717 4833 2716 4833 2718 4834 2719 4834 2717 4834 2720 4835 2719 4835 2718 4835 2720 4836 2721 4836 2719 4836 2720 4837 2722 4837 2721 4837 2723 4838 2722 4838 2720 4838 2723 4839 2724 4839 2722 4839 2723 4840 2725 4840 2724 4840 2726 4841 2725 4841 2723 4841 2726 4842 2727 4842 2725 4842 2728 4843 2727 4843 2726 4843 2728 4844 2729 4844 2727 4844 2728 4845 2730 4845 2729 4845 2731 4846 2730 4846 2728 4846 2732 4847 2730 4847 2731 4847 2732 4848 2733 4848 2730 4848 2734 4849 2735 4849 2732 4849 2732 4850 2735 4850 2733 4850 2734 4851 2736 4851 2735 4851 2737 4852 2736 4852 2734 4852 2737 4853 2738 4853 2736 4853 2739 4854 2738 4854 2737 4854 2739 4855 2740 4855 2738 4855 2739 4856 2741 4856 2740 4856 2742 4857 2741 4857 2739 4857 2742 4858 2743 4858 2741 4858 2744 4859 2743 4859 2742 4859 2744 4860 2745 4860 2743 4860 2746 4861 2745 4861 2744 4861 2746 4862 2747 4862 2745 4862 2748 4863 2747 4863 2746 4863 2748 4864 2749 4864 2747 4864 2748 4865 2750 4865 2749 4865 2751 4866 2750 4866 2748 4866 2751 4867 2752 4867 2750 4867 2751 4868 2753 4868 2752 4868 2751 4869 2754 4869 2753 4869 2755 4870 2754 4870 2751 4870 2755 4871 2756 4871 2754 4871 2755 4872 2757 4872 2756 4872 2758 4873 2757 4873 2755 4873 2758 4874 2759 4874 2757 4874 2758 4875 2760 4875 2759 4875 2761 4876 2760 4876 2758 4876 2761 4877 2762 4877 2760 4877 2763 4878 2762 4878 2761 4878 2763 4879 2764 4879 2762 4879 2763 4880 2765 4880 2764 4880 2766 4881 2765 4881 2763 4881 2766 4882 2767 4882 2765 4882 2768 4883 2767 4883 2766 4883 2768 4884 2769 4884 2767 4884 2770 4885 2769 4885 2768 4885 2770 4886 2771 4886 2769 4886 2772 4887 2771 4887 2770 4887 2772 4888 2773 4888 2771 4888 2772 4889 2774 4889 2773 4889 2775 4890 2774 4890 2772 4890 2775 4891 2776 4891 2774 4891 2777 4892 2776 4892 2775 4892 2777 4893 2778 4893 2776 4893 2779 4894 2778 4894 2777 4894 2779 4895 2780 4895 2778 4895 2779 4896 2781 4896 2780 4896 2782 4897 2781 4897 2779 4897 2782 4898 2783 4898 2781 4898 2782 4899 2784 4899 2783 4899 2785 4900 2784 4900 2782 4900 2785 4901 2786 4901 2784 4901 2787 4902 2786 4902 2785 4902 2787 4903 2788 4903 2786 4903 2789 4904 2788 4904 2787 4904 2789 4905 2790 4905 2788 4905 2789 4906 2791 4906 2790 4906 2792 4907 2791 4907 2789 4907 2792 4908 2793 4908 2791 4908 2794 4909 2793 4909 2792 4909 2794 4910 2795 4910 2793 4910 2794 4911 2796 4911 2795 4911 2797 4912 2796 4912 2794 4912 2797 4913 2798 4913 2796 4913 2799 4914 2798 4914 2797 4914 2799 4915 2800 4915 2798 4915 2801 4916 2800 4916 2799 4916 2801 4917 2802 4917 2800 4917 2801 4918 2803 4918 2802 4918 2804 4919 2803 4919 2801 4919 2805 4920 2806 4920 2804 4920 2804 4921 2806 4921 2803 4921 2805 4922 2807 4922 2806 4922 2805 4923 2808 4923 2807 4923 2809 4924 2808 4924 2805 4924 2809 4925 2810 4925 2808 4925 2811 4926 2810 4926 2809 4926 2811 4927 2812 4927 2810 4927 2813 4928 2812 4928 2811 4928 2813 4929 2814 4929 2812 4929 2815 4930 2814 4930 2813 4930 2815 4931 2816 4931 2814 4931 2815 4932 2817 4932 2816 4932 2818 4933 2817 4933 2815 4933 2818 4934 2819 4934 2817 4934 2820 4935 2819 4935 2818 4935 2820 4936 2821 4936 2819 4936 2820 4937 2822 4937 2821 4937 2823 4938 2822 4938 2820 4938 2823 4939 2824 4939 2822 4939 2825 4940 2824 4940 2823 4940 2825 4941 2826 4941 2824 4941 2827 4942 2826 4942 2825 4942 2827 4943 2828 4943 2826 4943 2827 4944 2829 4944 2828 4944 2830 4945 2829 4945 2827 4945 2830 4946 2831 4946 2829 4946 2832 4947 2831 4947 2830 4947 2832 4948 3098 4948 2831 4948 2832 4949 2348 4949 3098 4949 2833 4950 2348 4950 2832 4950 2833 4951 2346 4951 2348 4951 2834 4952 2346 4952 2833 4952 2834 4953 2339 4953 2346 4953 2835 4954 2339 4954 2834 4954 2337 4955 2339 4955 2835 4955 2836 4956 2367 4956 2364 4956 2837 4957 2367 4957 2836 4957 2369 4958 2367 4958 2837 4958 2838 4959 2369 4959 2837 4959 2372 4960 2369 4960 2838 4960 2374 4961 2372 4961 2838 4961 2839 4962 2374 4962 2838 4962 2374 4963 2839 4963 2840 4963 2377 4964 2374 4964 2840 4964 2841 4965 2377 4965 2840 4965 2379 4966 2377 4966 2841 4966 2381 4967 2379 4967 2841 4967 2383 4968 2381 4968 2842 4968 2385 4969 2383 4969 2842 4969 2843 4970 2385 4970 2842 4970 2388 4971 2385 4971 2843 4971 2844 4972 2388 4972 2843 4972 2390 4973 2388 4973 2844 4973 2845 4974 2392 4974 2390 4974 2846 4975 2392 4975 2845 4975 2395 4976 2392 4976 2846 4976 2847 4977 2395 4977 2846 4977 2397 4978 2395 4978 2847 4978 2399 4979 2397 4979 2847 4979 2848 4980 2399 4980 2847 4980 2402 4981 2399 4981 2848 4981 2402 4982 2848 4982 2849 4982 2404 4983 2402 4983 2849 4983 2850 4984 2404 4984 2849 4984 2407 4985 2404 4985 2850 4985 2851 4986 2407 4986 2850 4986 2409 4987 2407 4987 2851 4987 2852 4988 2409 4988 2851 4988 2412 4989 2409 4989 2852 4989 2853 4990 2412 4990 2852 4990 2854 4991 2412 4991 2853 4991 2415 4992 2412 4992 2854 4992 2855 4993 2415 4993 2854 4993 2417 4994 2415 4994 2855 4994 2856 4995 2417 4995 2855 4995 2420 4996 2417 4996 2856 4996 2857 4997 2420 4997 2856 4997 2423 4998 2420 4998 2857 4998 2858 4999 2423 4999 2857 4999 2859 5000 2423 5000 2858 5000 2425 5001 2423 5001 2859 5001 2860 5002 2425 5002 2859 5002 2427 5003 2425 5003 2860 5003 2861 5004 2427 5004 2860 5004 2429 5005 2427 5005 2861 5005 2862 5006 2429 5006 2861 5006 2432 5007 2429 5007 2862 5007 2434 5008 2432 5008 2862 5008 2863 5009 2434 5009 2862 5009 2436 5010 2434 5010 2863 5010 2864 5011 2436 5011 2863 5011 2865 5012 2436 5012 2864 5012 2439 5013 2436 5013 2865 5013 2441 5014 2439 5014 2865 5014 2866 5015 2441 5015 2865 5015 2444 5016 2441 5016 2866 5016 2867 5017 2444 5017 2866 5017 2868 5018 2444 5018 2867 5018 2447 5019 2444 5019 2868 5019 2449 5020 2447 5020 2868 5020 2869 5021 2449 5021 2868 5021 2451 5022 2449 5022 2869 5022 2870 5023 2451 5023 2869 5023 2454 5024 2451 5024 2870 5024 2456 5025 2454 5025 2871 5025 2872 5026 2456 5026 2871 5026 2458 5027 2456 5027 2872 5027 2873 5028 2458 5028 2872 5028 2461 5029 2458 5029 2873 5029 2463 5030 2461 5030 2873 5030 2874 5031 2463 5031 2873 5031 2465 5032 2463 5032 2874 5032 2875 5033 2465 5033 2874 5033 2468 5034 2465 5034 2875 5034 2876 5035 2468 5035 2875 5035 2470 5036 2468 5036 2876 5036 2877 5037 2470 5037 2876 5037 2472 5038 2470 5038 2877 5038 2878 5039 2472 5039 2877 5039 2474 5040 2472 5040 2878 5040 2879 5041 2474 5041 2878 5041 2477 5042 2474 5042 2879 5042 2880 5043 2477 5043 2879 5043 2881 5044 2477 5044 2880 5044 2479 5045 2477 5045 2881 5045 2481 5046 2479 5046 2881 5046 2882 5047 2481 5047 2881 5047 2484 5048 2481 5048 2882 5048 2883 5049 2486 5049 2484 5049 2488 5050 2486 5050 2883 5050 2490 5051 2488 5051 2884 5051 2885 5052 2490 5052 2884 5052 2493 5053 2490 5053 2885 5053 2494 5054 2493 5054 2885 5054 2886 5055 2494 5055 2885 5055 2496 5056 2494 5056 2886 5056 2887 5057 2499 5057 2496 5057 2501 5058 2499 5058 2887 5058 2888 5059 2501 5059 2887 5059 2889 5060 2501 5060 2888 5060 2503 5061 2501 5061 2889 5061 2890 5062 2503 5062 2889 5062 2506 5063 2503 5063 2890 5063 2891 5064 2506 5064 2890 5064 2508 5065 2506 5065 2891 5065 2511 5066 2508 5066 2891 5066 2892 5067 2513 5067 2511 5067 2515 5068 2513 5068 2892 5068 2893 5069 2515 5069 2892 5069 2894 5070 2515 5070 2893 5070 2518 5071 2515 5071 2894 5071 2895 5072 2518 5072 2894 5072 2520 5073 2518 5073 2895 5073 2896 5074 2520 5074 2895 5074 2523 5075 2520 5075 2896 5075 2897 5076 2523 5076 2896 5076 2898 5077 2523 5077 2897 5077 2526 5078 2523 5078 2898 5078 2899 5079 2526 5079 2898 5079 2528 5080 2526 5080 2899 5080 2900 5081 2528 5081 2899 5081 2530 5082 2528 5082 2900 5082 2533 5083 2530 5083 2900 5083 2901 5084 2535 5084 2533 5084 2538 5085 2535 5085 2901 5085 2902 5086 2538 5086 2901 5086 2540 5087 2538 5087 2902 5087 2542 5088 2540 5088 2902 5088 2903 5089 2542 5089 2902 5089 2904 5090 2542 5090 2903 5090 2544 5091 2542 5091 2904 5091 2905 5092 2544 5092 2904 5092 2546 5093 2544 5093 2905 5093 2548 5094 2546 5094 2905 5094 2906 5095 2548 5095 2905 5095 2551 5096 2548 5096 2906 5096 2907 5097 2551 5097 2906 5097 2908 5098 2551 5098 2907 5098 2554 5099 2551 5099 2908 5099 2555 5100 2554 5100 2908 5100 2909 5101 2555 5101 2908 5101 2910 5102 2555 5102 2909 5102 2558 5103 2555 5103 2910 5103 2911 5104 2558 5104 2910 5104 2561 5105 2558 5105 2911 5105 2912 5106 2561 5106 2911 5106 2564 5107 2561 5107 2912 5107 2913 5108 2564 5108 2912 5108 2567 5109 2564 5109 2913 5109 2914 5110 2567 5110 2913 5110 2569 5111 2567 5111 2914 5111 2915 5112 2569 5112 2914 5112 2916 5113 2569 5113 2915 5113 2571 5114 2569 5114 2916 5114 2574 5115 2571 5115 2916 5115 2576 5116 2574 5116 2917 5116 2578 5117 2576 5117 2917 5117 2918 5118 2578 5118 2917 5118 2919 5119 2578 5119 2918 5119 2580 5120 2578 5120 2919 5120 2920 5121 2580 5121 2919 5121 2583 5122 2580 5122 2920 5122 2921 5123 2583 5123 2920 5123 2585 5124 2583 5124 2921 5124 2922 5125 2585 5125 2921 5125 2587 5126 2585 5126 2922 5126 2589 5127 2587 5127 2922 5127 2591 5128 2589 5128 2923 5128 2924 5129 2591 5129 2923 5129 2594 5130 2591 5130 2924 5130 2925 5131 2594 5131 2924 5131 2596 5132 2594 5132 2925 5132 2926 5133 2596 5133 2925 5133 2599 5134 2596 5134 2926 5134 2601 5135 2599 5135 2926 5135 2927 5136 2601 5136 2926 5136 2603 5137 2601 5137 2927 5137 2928 5138 2603 5138 2927 5138 2605 5139 2603 5139 2928 5139 2929 5140 2605 5140 2928 5140 2607 5141 2605 5141 2929 5141 2930 5142 2607 5142 2929 5142 2610 5143 2607 5143 2930 5143 2931 5144 2612 5144 2610 5144 2614 5145 2612 5145 2931 5145 2932 5146 2614 5146 2931 5146 2933 5147 2614 5147 2932 5147 2617 5148 2614 5148 2933 5148 2619 5149 2617 5149 2933 5149 2934 5150 2619 5150 2933 5150 2621 5151 2619 5151 2934 5151 2935 5152 2621 5152 2934 5152 2623 5153 2621 5153 2935 5153 2936 5154 2623 5154 2935 5154 2625 5155 2623 5155 2936 5155 2937 5156 2625 5156 2936 5156 2627 5157 2625 5157 2937 5157 2630 5158 2627 5158 2937 5158 2938 5159 2630 5159 2937 5159 2632 5160 2630 5160 2938 5160 2939 5161 2632 5161 2938 5161 2634 5162 2632 5162 2939 5162 2940 5163 2634 5163 2939 5163 2636 5164 2634 5164 2940 5164 2941 5165 2636 5165 2940 5165 2639 5166 2636 5166 2941 5166 2942 5167 2639 5167 2941 5167 2641 5168 2639 5168 2942 5168 2943 5169 2641 5169 2942 5169 2643 5170 2641 5170 2943 5170 2944 5171 2643 5171 2943 5171 2646 5172 2643 5172 2944 5172 2945 5173 2646 5173 2944 5173 2946 5174 2646 5174 2945 5174 2649 5175 2646 5175 2946 5175 2947 5176 2649 5176 2946 5176 2652 5177 2649 5177 2947 5177 2654 5178 2947 5178 2948 5178 2654 5179 2652 5179 2947 5179 2949 5180 2654 5180 2948 5180 2657 5181 2654 5181 2949 5181 2950 5182 2657 5182 2949 5182 2659 5183 2657 5183 2950 5183 2661 5184 2659 5184 2950 5184 2951 5185 2661 5185 2950 5185 2663 5186 2661 5186 2951 5186 2666 5187 2663 5187 2951 5187 2952 5188 2666 5188 2951 5188 2669 5189 2666 5189 2952 5189 2953 5190 2669 5190 2952 5190 2671 5191 2669 5191 2953 5191 2954 5192 2671 5192 2953 5192 2673 5193 2671 5193 2954 5193 2955 5194 2673 5194 2954 5194 2676 5195 2673 5195 2955 5195 2956 5196 2676 5196 2955 5196 2678 5197 2676 5197 2956 5197 2957 5198 2678 5198 2956 5198 2681 5199 2678 5199 2957 5199 2958 5200 2681 5200 2957 5200 2683 5201 2681 5201 2958 5201 2685 5202 2683 5202 2958 5202 2687 5203 2685 5203 2959 5203 2960 5204 2687 5204 2959 5204 2690 5205 2687 5205 2960 5205 2961 5206 2690 5206 2960 5206 2692 5207 2690 5207 2961 5207 2694 5208 2692 5208 2961 5208 2694 5209 2961 5209 2962 5209 2696 5210 2694 5210 2962 5210 2963 5211 2696 5211 2962 5211 2964 5212 2696 5212 2963 5212 2698 5213 2696 5213 2964 5213 2965 5214 2698 5214 2964 5214 2700 5215 2698 5215 2965 5215 2702 5216 2700 5216 2965 5216 2966 5217 2702 5217 2965 5217 2704 5218 2702 5218 2966 5218 2967 5219 2704 5219 2966 5219 2707 5220 2704 5220 2967 5220 2968 5221 2707 5221 2967 5221 2709 5222 2707 5222 2968 5222 2969 5223 2709 5223 2968 5223 2711 5224 2709 5224 2969 5224 2970 5225 2711 5225 2969 5225 2714 5226 2711 5226 2970 5226 2971 5227 2714 5227 2970 5227 2972 5228 2714 5228 2971 5228 2716 5229 2714 5229 2972 5229 2718 5230 2716 5230 2972 5230 2718 5231 2972 5231 2973 5231 2720 5232 2718 5232 2973 5232 2974 5233 2720 5233 2973 5233 2723 5234 2720 5234 2974 5234 2975 5235 2723 5235 2974 5235 2726 5236 2723 5236 2975 5236 2976 5237 2726 5237 2975 5237 2728 5238 2726 5238 2976 5238 2977 5239 2728 5239 2976 5239 2731 5240 2728 5240 2977 5240 2732 5241 2731 5241 2977 5241 2978 5242 2732 5242 2977 5242 2734 5243 2732 5243 2978 5243 2979 5244 2734 5244 2978 5244 2737 5245 2734 5245 2979 5245 2980 5246 2737 5246 2979 5246 2739 5247 2737 5247 2980 5247 2981 5248 2739 5248 2980 5248 2742 5249 2739 5249 2981 5249 2982 5250 2742 5250 2981 5250 2744 5251 2742 5251 2982 5251 2746 5252 2744 5252 2982 5252 2983 5253 2746 5253 2982 5253 2748 5254 2746 5254 2983 5254 2984 5255 2748 5255 2983 5255 2751 5256 2748 5256 2984 5256 2985 5257 2751 5257 2984 5257 2755 5258 2751 5258 2985 5258 2986 5259 2755 5259 2985 5259 2987 5260 2755 5260 2986 5260 2758 5261 2755 5261 2987 5261 2988 5262 2758 5262 2987 5262 2761 5263 2758 5263 2988 5263 2989 5264 2761 5264 2988 5264 2763 5265 2761 5265 2989 5265 2990 5266 2763 5266 2989 5266 2766 5267 2763 5267 2990 5267 2991 5268 2766 5268 2990 5268 2768 5269 2766 5269 2991 5269 2770 5270 2768 5270 2991 5270 2992 5271 2770 5271 2991 5271 2993 5272 2770 5272 2992 5272 2772 5273 2770 5273 2993 5273 2994 5274 2772 5274 2993 5274 2775 5275 2772 5275 2994 5275 2777 5276 2775 5276 2995 5276 2996 5277 2777 5277 2995 5277 2779 5278 2777 5278 2996 5278 2997 5279 2779 5279 2996 5279 2782 5280 2779 5280 2997 5280 2998 5281 2782 5281 2997 5281 2785 5282 2782 5282 2998 5282 2999 5283 2785 5283 2998 5283 2787 5284 2785 5284 2999 5284 3000 5285 2787 5285 2999 5285 2789 5286 2787 5286 3000 5286 2792 5287 2789 5287 3000 5287 3001 5288 2792 5288 3000 5288 2794 5289 2792 5289 3001 5289 3002 5290 2794 5290 3001 5290 2797 5291 2794 5291 3002 5291 3003 5292 2797 5292 3002 5292 2799 5293 2797 5293 3003 5293 2801 5294 2799 5294 3004 5294 3005 5295 2801 5295 3004 5295 2804 5296 2801 5296 3005 5296 2805 5297 2804 5297 3005 5297 3006 5298 2805 5298 3005 5298 3007 5299 2805 5299 3006 5299 2809 5300 2805 5300 3007 5300 2811 5301 2809 5301 3007 5301 3008 5302 2811 5302 3007 5302 3009 5303 2811 5303 3008 5303 2813 5304 2811 5304 3009 5304 3010 5305 2813 5305 3009 5305 2815 5306 2813 5306 3010 5306 3011 5307 2815 5307 3010 5307 2818 5308 2815 5308 3011 5308 2820 5309 2818 5309 3011 5309 3012 5310 2820 5310 3011 5310 2823 5311 2820 5311 3012 5311 3013 5312 2823 5312 3012 5312 2825 5313 2823 5313 3013 5313 3014 5314 2825 5314 3013 5314 2827 5315 2825 5315 3014 5315 2827 5316 3014 5316 3015 5316 2830 5317 2827 5317 3015 5317 3016 5318 2830 5318 3015 5318 2832 5319 2830 5319 3016 5319 3017 5320 2832 5320 3016 5320 2833 5321 2832 5321 3017 5321 3018 5322 2833 5322 3017 5322 2834 5323 2833 5323 3018 5323 3019 5324 2834 5324 3018 5324 2835 5325 2834 5325 3019 5325 3020 5326 2835 5326 3019 5326 2337 5327 2835 5327 3020 5327 3021 5328 2337 5328 3020 5328 2341 5329 2337 5329 3021 5329 3022 5330 2838 5330 2837 5330 3024 5331 2838 5331 3022 5331 3024 5332 2839 5332 2838 5332 3024 5333 2840 5333 2839 5333 3023 5334 2840 5334 3024 5334 3023 5335 2841 5335 2840 5335 3025 5336 2841 5336 3023 5336 3025 5337 2381 5337 2841 5337 2353 5338 2381 5338 3025 5338 2353 5339 2842 5339 2381 5339 3026 5340 2842 5340 2353 5340 2355 5341 2843 5341 3026 5341 3026 5342 2843 5342 2842 5342 2357 5343 2843 5343 2355 5343 2357 5344 2844 5344 2843 5344 2359 5345 2844 5345 2357 5345 3027 5346 2390 5346 2359 5346 2359 5347 2390 5347 2844 5347 3027 5348 2845 5348 2390 5348 2363 5349 2845 5349 3027 5349 2363 5350 2846 5350 2845 5350 2365 5351 2846 5351 2363 5351 2365 5352 2847 5352 2846 5352 2366 5353 2847 5353 2365 5353 2368 5354 2847 5354 2366 5354 2368 5355 2848 5355 2847 5355 2370 5356 2848 5356 2368 5356 2371 5357 2848 5357 2370 5357 2371 5358 2849 5358 2848 5358 2373 5359 2849 5359 2371 5359 2373 5360 2850 5360 2849 5360 2375 5361 2850 5361 2373 5361 2376 5362 2850 5362 2375 5362 2376 5363 2851 5363 2850 5363 2378 5364 2851 5364 2376 5364 2378 5365 2852 5365 2851 5365 2380 5366 2852 5366 2378 5366 2380 5367 2853 5367 2852 5367 2382 5368 2853 5368 2380 5368 2382 5369 2854 5369 2853 5369 2384 5370 2854 5370 2382 5370 2386 5371 2854 5371 2384 5371 2386 5372 2855 5372 2854 5372 2387 5373 2855 5373 2386 5373 2387 5374 2856 5374 2855 5374 2389 5375 2856 5375 2387 5375 2391 5376 2856 5376 2389 5376 2391 5377 2857 5377 2856 5377 2393 5378 2857 5378 2391 5378 2393 5379 2858 5379 2857 5379 3028 5380 2858 5380 2393 5380 3028 5381 2859 5381 2858 5381 2396 5382 2859 5382 3028 5382 2396 5383 2860 5383 2859 5383 2398 5384 2860 5384 2396 5384 2398 5385 2861 5385 2860 5385 2400 5386 2861 5386 2398 5386 2401 5387 2861 5387 2400 5387 2401 5388 2862 5388 2861 5388 2405 5389 2862 5389 2401 5389 2405 5390 2863 5390 2862 5390 2406 5391 2863 5391 2405 5391 2408 5392 2863 5392 2406 5392 2408 5393 2864 5393 2863 5393 2410 5394 2864 5394 2408 5394 2410 5395 2865 5395 2864 5395 2411 5396 2865 5396 2410 5396 2413 5397 2865 5397 2411 5397 2413 5398 2866 5398 2865 5398 2414 5399 2866 5399 2413 5399 2414 5400 2867 5400 2866 5400 2416 5401 2867 5401 2414 5401 2416 5402 2868 5402 2867 5402 2418 5403 2868 5403 2416 5403 2419 5404 2868 5404 2418 5404 2419 5405 2869 5405 2868 5405 2421 5406 2869 5406 2419 5406 2421 5407 2870 5407 2869 5407 2422 5408 2870 5408 2421 5408 2422 5409 2454 5409 2870 5409 2424 5410 2454 5410 2422 5410 2424 5411 2871 5411 2454 5411 2426 5412 2871 5412 2424 5412 2426 5413 2872 5413 2871 5413 2428 5414 2872 5414 2426 5414 2430 5415 2872 5415 2428 5415 2430 5416 2873 5416 2872 5416 2431 5417 2873 5417 2430 5417 2433 5418 2873 5418 2431 5418 2433 5419 2874 5419 2873 5419 2435 5420 2874 5420 2433 5420 2435 5421 2875 5421 2874 5421 2437 5422 2875 5422 2435 5422 2437 5423 2876 5423 2875 5423 2438 5424 2876 5424 2437 5424 2438 5425 2877 5425 2876 5425 2440 5426 2877 5426 2438 5426 2442 5427 2877 5427 2440 5427 2442 5428 2878 5428 2877 5428 2443 5429 2878 5429 2442 5429 2443 5430 2879 5430 2878 5430 2445 5431 2879 5431 2443 5431 2446 5432 2879 5432 2445 5432 2446 5433 2880 5433 2879 5433 2448 5434 2880 5434 2446 5434 2448 5435 2881 5435 2880 5435 2450 5436 2881 5436 2448 5436 2452 5437 2881 5437 2450 5437 2452 5438 2882 5438 2881 5438 2453 5439 2882 5439 2452 5439 2455 5440 2882 5440 2453 5440 2455 5441 2484 5441 2882 5441 2457 5442 2484 5442 2455 5442 2457 5443 2883 5443 2484 5443 2459 5444 2883 5444 2457 5444 2459 5445 2488 5445 2883 5445 2460 5446 2488 5446 2459 5446 2460 5447 2884 5447 2488 5447 2462 5448 2884 5448 2460 5448 2462 5449 2885 5449 2884 5449 2464 5450 2885 5450 2462 5450 2466 5451 2885 5451 2464 5451 2466 5452 2886 5452 2885 5452 3029 5453 2886 5453 2466 5453 3029 5454 2496 5454 2886 5454 2471 5455 2496 5455 3029 5455 2471 5456 2887 5456 2496 5456 2473 5457 2887 5457 2471 5457 2473 5458 2888 5458 2887 5458 3030 5459 2888 5459 2473 5459 3030 5460 2889 5460 2888 5460 2476 5461 2889 5461 3030 5461 2476 5462 2890 5462 2889 5462 3031 5463 2890 5463 2476 5463 2480 5464 2890 5464 3031 5464 2480 5465 2891 5465 2890 5465 2482 5466 2891 5466 2480 5466 2482 5467 2511 5467 2891 5467 2483 5468 2511 5468 2482 5468 2483 5469 2892 5469 2511 5469 2485 5470 2892 5470 2483 5470 2485 5471 2893 5471 2892 5471 2487 5472 2893 5472 2485 5472 2487 5473 2894 5473 2893 5473 2489 5474 2894 5474 2487 5474 2489 5475 2895 5475 2894 5475 2491 5476 2895 5476 2489 5476 3032 5477 2895 5477 2491 5477 3032 5478 2896 5478 2895 5478 2495 5479 2896 5479 3032 5479 2495 5480 2897 5480 2896 5480 2497 5481 2897 5481 2495 5481 2497 5482 2898 5482 2897 5482 2498 5483 2898 5483 2497 5483 2498 5484 2899 5484 2898 5484 3033 5485 2899 5485 2498 5485 3033 5486 2900 5486 2899 5486 3034 5487 2900 5487 3033 5487 2502 5488 2900 5488 3034 5488 2502 5489 2533 5489 2900 5489 2504 5490 2533 5490 2502 5490 2504 5491 2901 5491 2533 5491 2505 5492 2901 5492 2504 5492 2507 5493 2901 5493 2505 5493 2507 5494 2902 5494 2901 5494 2509 5495 2902 5495 2507 5495 2510 5496 2902 5496 2509 5496 2510 5497 2903 5497 2902 5497 2512 5498 2903 5498 2510 5498 2512 5499 2904 5499 2903 5499 2514 5500 2904 5500 2512 5500 2514 5501 2905 5501 2904 5501 2516 5502 2905 5502 2514 5502 2517 5503 2905 5503 2516 5503 2519 5504 2905 5504 2517 5504 2519 5505 2906 5505 2905 5505 2521 5506 2906 5506 2519 5506 2521 5507 2907 5507 2906 5507 2522 5508 2907 5508 2521 5508 2522 5509 2908 5509 2907 5509 2524 5510 2908 5510 2522 5510 2524 5511 2909 5511 2908 5511 2525 5512 2909 5512 2524 5512 2527 5513 2910 5513 2525 5513 2525 5514 2910 5514 2909 5514 2529 5515 2910 5515 2527 5515 2529 5516 2911 5516 2910 5516 2531 5517 2911 5517 2529 5517 2531 5518 2912 5518 2911 5518 2532 5519 2912 5519 2531 5519 2534 5520 2912 5520 2532 5520 2534 5521 2913 5521 2912 5521 2536 5522 2913 5522 2534 5522 2537 5523 2913 5523 2536 5523 2539 5524 2913 5524 2537 5524 2539 5525 2914 5525 2913 5525 2541 5526 2914 5526 2539 5526 2541 5527 2915 5527 2914 5527 2543 5528 2915 5528 2541 5528 2543 5529 2916 5529 2915 5529 2545 5530 2916 5530 2543 5530 2545 5531 2574 5531 2916 5531 2547 5532 2574 5532 2545 5532 2547 5533 2917 5533 2574 5533 2549 5534 2917 5534 2547 5534 2550 5535 2917 5535 2549 5535 2550 5536 2918 5536 2917 5536 2552 5537 2918 5537 2550 5537 2552 5538 2919 5538 2918 5538 2553 5539 2919 5539 2552 5539 2553 5540 2920 5540 2919 5540 2556 5541 2920 5541 2553 5541 3035 5542 2921 5542 2556 5542 2556 5543 2921 5543 2920 5543 3036 5544 2921 5544 3035 5544 3036 5545 2922 5545 2921 5545 2559 5546 2922 5546 3036 5546 2559 5547 2589 5547 2922 5547 2560 5548 2589 5548 2559 5548 2560 5549 2923 5549 2589 5549 2563 5550 2923 5550 2560 5550 2563 5551 2924 5551 2923 5551 2565 5552 2924 5552 2563 5552 2566 5553 2924 5553 2565 5553 2566 5554 2925 5554 2924 5554 2568 5555 2925 5555 2566 5555 2570 5556 2925 5556 2568 5556 2570 5557 2926 5557 2925 5557 2572 5558 2926 5558 2570 5558 2572 5559 2927 5559 2926 5559 2573 5560 2927 5560 2572 5560 2573 5561 2928 5561 2927 5561 2575 5562 2928 5562 2573 5562 2577 5563 2928 5563 2575 5563 2577 5564 2929 5564 2928 5564 3037 5565 2929 5565 2577 5565 3037 5566 2930 5566 2929 5566 2581 5567 2930 5567 3037 5567 2581 5568 2610 5568 2930 5568 3038 5569 2610 5569 2581 5569 3038 5570 2931 5570 2610 5570 2584 5571 2931 5571 3038 5571 2584 5572 2932 5572 2931 5572 2586 5573 2932 5573 2584 5573 2586 5574 2933 5574 2932 5574 2588 5575 2933 5575 2586 5575 2590 5576 2933 5576 2588 5576 2590 5577 2934 5577 2933 5577 2592 5578 2934 5578 2590 5578 2592 5579 2935 5579 2934 5579 2593 5580 2935 5580 2592 5580 2595 5581 2935 5581 2593 5581 2595 5582 2936 5582 2935 5582 2597 5583 2936 5583 2595 5583 2597 5584 2937 5584 2936 5584 2598 5585 2937 5585 2597 5585 2600 5586 2937 5586 2598 5586 2600 5587 2938 5587 2937 5587 2602 5588 2938 5588 2600 5588 2602 5589 2939 5589 2938 5589 2604 5590 2939 5590 2602 5590 2606 5591 2940 5591 2604 5591 2604 5592 2940 5592 2939 5592 2608 5593 2940 5593 2606 5593 2608 5594 2941 5594 2940 5594 2609 5595 2941 5595 2608 5595 2609 5596 2942 5596 2941 5596 2611 5597 2942 5597 2609 5597 2611 5598 2943 5598 2942 5598 2613 5599 2943 5599 2611 5599 2615 5600 2943 5600 2613 5600 2615 5601 2944 5601 2943 5601 3039 5602 2944 5602 2615 5602 3039 5603 2945 5603 2944 5603 2618 5604 2945 5604 3039 5604 2618 5605 2946 5605 2945 5605 2620 5606 2946 5606 2618 5606 2622 5607 2947 5607 2620 5607 2620 5608 2947 5608 2946 5608 3040 5609 2947 5609 2622 5609 3040 5610 2948 5610 2947 5610 2626 5611 2948 5611 3040 5611 2628 5612 2948 5612 2626 5612 2628 5613 2949 5613 2948 5613 2629 5614 2949 5614 2628 5614 2629 5615 2950 5615 2949 5615 2631 5616 2950 5616 2629 5616 2633 5617 2950 5617 2631 5617 2633 5618 2951 5618 2950 5618 2635 5619 2951 5619 2633 5619 2637 5620 2951 5620 2635 5620 2637 5621 2952 5621 2951 5621 2638 5622 2952 5622 2637 5622 2640 5623 2952 5623 2638 5623 2640 5624 2953 5624 2952 5624 2642 5625 2953 5625 2640 5625 2642 5626 2954 5626 2953 5626 2644 5627 2954 5627 2642 5627 2644 5628 2955 5628 2954 5628 2645 5629 2955 5629 2644 5629 2647 5630 2955 5630 2645 5630 2647 5631 2956 5631 2955 5631 2648 5632 2956 5632 2647 5632 2650 5633 2956 5633 2648 5633 2650 5634 2957 5634 2956 5634 2651 5635 2957 5635 2650 5635 3041 5636 2957 5636 2651 5636 3041 5637 2958 5637 2957 5637 2655 5638 2958 5638 3041 5638 2655 5639 2685 5639 2958 5639 2656 5640 2685 5640 2655 5640 2656 5641 2959 5641 2685 5641 2658 5642 2959 5642 2656 5642 2658 5643 2960 5643 2959 5643 2660 5644 2960 5644 2658 5644 2660 5645 2961 5645 2960 5645 2664 5646 2961 5646 2660 5646 2664 5647 2962 5647 2961 5647 2665 5648 2962 5648 2664 5648 2665 5649 2963 5649 2962 5649 2667 5650 2963 5650 2665 5650 2667 5651 2964 5651 2963 5651 2668 5652 2964 5652 2667 5652 2670 5653 2964 5653 2668 5653 2670 5654 2965 5654 2964 5654 2672 5655 2965 5655 2670 5655 2674 5656 2965 5656 2672 5656 2674 5657 2966 5657 2965 5657 2675 5658 2966 5658 2674 5658 2675 5659 2967 5659 2966 5659 2677 5660 2967 5660 2675 5660 2677 5661 2968 5661 2967 5661 2679 5662 2968 5662 2677 5662 2680 5663 2968 5663 2679 5663 2680 5664 2969 5664 2968 5664 2682 5665 2969 5665 2680 5665 2682 5666 2970 5666 2969 5666 2684 5667 2970 5667 2682 5667 2686 5668 2971 5668 2684 5668 2684 5669 2971 5669 2970 5669 2686 5670 2972 5670 2971 5670 2688 5671 2972 5671 2686 5671 2689 5672 2972 5672 2688 5672 2689 5673 2973 5673 2972 5673 2691 5674 2973 5674 2689 5674 2691 5675 2974 5675 2973 5675 2693 5676 2974 5676 2691 5676 3042 5677 2974 5677 2693 5677 3042 5678 2975 5678 2974 5678 2697 5679 2975 5679 3042 5679 2697 5680 2976 5680 2975 5680 2699 5681 2976 5681 2697 5681 2699 5682 2977 5682 2976 5682 2701 5683 2977 5683 2699 5683 2703 5684 2977 5684 2701 5684 2703 5685 2978 5685 2977 5685 3043 5686 2978 5686 2703 5686 2705 5687 2978 5687 3043 5687 2705 5688 2979 5688 2978 5688 2706 5689 2979 5689 2705 5689 2706 5690 2980 5690 2979 5690 2710 5691 2980 5691 2706 5691 2710 5692 2981 5692 2980 5692 2712 5693 2981 5693 2710 5693 2712 5694 2982 5694 2981 5694 2713 5695 2982 5695 2712 5695 2713 5696 2983 5696 2982 5696 2715 5697 2983 5697 2713 5697 2717 5698 2983 5698 2715 5698 2717 5699 2984 5699 2983 5699 2719 5700 2984 5700 2717 5700 2721 5701 2984 5701 2719 5701 2721 5702 2985 5702 2984 5702 2722 5703 2985 5703 2721 5703 2724 5704 2985 5704 2722 5704 2724 5705 2986 5705 2985 5705 2725 5706 2986 5706 2724 5706 2725 5707 2987 5707 2986 5707 2727 5708 2987 5708 2725 5708 2729 5709 2987 5709 2727 5709 2729 5710 2988 5710 2987 5710 2730 5711 2988 5711 2729 5711 2730 5712 2989 5712 2988 5712 2733 5713 2989 5713 2730 5713 2735 5714 2989 5714 2733 5714 2735 5715 2990 5715 2989 5715 2736 5716 2990 5716 2735 5716 2736 5717 2991 5717 2990 5717 2738 5718 2991 5718 2736 5718 2738 5719 2992 5719 2991 5719 2740 5720 2992 5720 2738 5720 2740 5721 2993 5721 2992 5721 2741 5722 2993 5722 2740 5722 2743 5723 2993 5723 2741 5723 2743 5724 2994 5724 2993 5724 2745 5725 2994 5725 2743 5725 2747 5726 2775 5726 2745 5726 2745 5727 2775 5727 2994 5727 2747 5728 2995 5728 2775 5728 2749 5729 2995 5729 2747 5729 2750 5730 2995 5730 2749 5730 2750 5731 2996 5731 2995 5731 2752 5732 2996 5732 2750 5732 2753 5733 2996 5733 2752 5733 2753 5734 2997 5734 2996 5734 2754 5735 2997 5735 2753 5735 2754 5736 2998 5736 2997 5736 2756 5737 2998 5737 2754 5737 2757 5738 2998 5738 2756 5738 2757 5739 2999 5739 2998 5739 2759 5740 2999 5740 2757 5740 2759 5741 3000 5741 2999 5741 2760 5742 3000 5742 2759 5742 2762 5743 3000 5743 2760 5743 2762 5744 3001 5744 3000 5744 2764 5745 3001 5745 2762 5745 2764 5746 3002 5746 3001 5746 2767 5747 3002 5747 2764 5747 2767 5748 3003 5748 3002 5748 3044 5749 3003 5749 2767 5749 2769 5750 3003 5750 3044 5750 2769 5751 2799 5751 3003 5751 2771 5752 2799 5752 2769 5752 2771 5753 3004 5753 2799 5753 2773 5754 3004 5754 2771 5754 2773 5755 3005 5755 3004 5755 2774 5756 3005 5756 2773 5756 2776 5757 3005 5757 2774 5757 2776 5758 3006 5758 3005 5758 2778 5759 3006 5759 2776 5759 2778 5760 3007 5760 3006 5760 2780 5761 3007 5761 2778 5761 2781 5762 3007 5762 2780 5762 2781 5763 3008 5763 3007 5763 2781 5764 3009 5764 3008 5764 2783 5765 3009 5765 2781 5765 2784 5766 3009 5766 2783 5766 2784 5767 3010 5767 3009 5767 2786 5768 3010 5768 2784 5768 2786 5769 3011 5769 3010 5769 2790 5770 3011 5770 2786 5770 2791 5771 3012 5771 2790 5771 2790 5772 3012 5772 3011 5772 2793 5773 3012 5773 2791 5773 2795 5774 3013 5774 2793 5774 2793 5775 3013 5775 3012 5775 3045 5776 3013 5776 2795 5776 3045 5777 3014 5777 3013 5777 2796 5778 3014 5778 3045 5778 2796 5779 3015 5779 3014 5779 2798 5780 3015 5780 2796 5780 2800 5781 3015 5781 2798 5781 2802 5782 3016 5782 2800 5782 2800 5783 3016 5783 3015 5783 2802 5784 3017 5784 3016 5784 2803 5785 3017 5785 2802 5785 2806 5786 3017 5786 2803 5786 2806 5787 3018 5787 3017 5787 2807 5788 3018 5788 2806 5788 2807 5789 3019 5789 3018 5789 2808 5790 3019 5790 2807 5790 3046 5791 3019 5791 2808 5791 3046 5792 3020 5792 3019 5792 2812 5793 3021 5793 3046 5793 3046 5794 3021 5794 3020 5794 2814 5795 3021 5795 2812 5795 2814 5796 2341 5796 3021 5796 2816 5797 2341 5797 2814 5797 2817 5798 2341 5798 2816 5798 2817 5799 2343 5799 2341 5799 2819 5800 2343 5800 2817 5800 2819 5801 2347 5801 2343 5801 2821 5802 2347 5802 2819 5802 2822 5803 2347 5803 2821 5803 2822 5804 2349 5804 2347 5804 2824 5805 2349 5805 2822 5805 2826 5806 2349 5806 2824 5806 2826 5807 2351 5807 2349 5807 2828 5808 2351 5808 2826 5808 2828 5809 2352 5809 2351 5809 2829 5810 2352 5810 2828 5810 2354 5811 3026 5811 2353 5811 2355 5812 3026 5812 2354 5812 2361 5813 3027 5813 2359 5813 2363 5814 3027 5814 2361 5814 2394 5815 3028 5815 2393 5815 2396 5816 3028 5816 2394 5816 2405 5817 2401 5817 2403 5817 3029 5818 2466 5818 2467 5818 2469 5819 3029 5819 2467 5819 2471 5820 3029 5820 2469 5820 2475 5821 3030 5821 2473 5821 2476 5822 3030 5822 2475 5822 2478 5823 3031 5823 2476 5823 2480 5824 3031 5824 2478 5824 2492 5825 3032 5825 2491 5825 2495 5826 3032 5826 2492 5826 2500 5827 3033 5827 2498 5827 3034 5828 3033 5828 2500 5828 2502 5829 3034 5829 2500 5829 2557 5830 3035 5830 2556 5830 3036 5831 3035 5831 2557 5831 2559 5832 3036 5832 2557 5832 2563 5833 2560 5833 2562 5833 2579 5834 3037 5834 2577 5834 2581 5835 3037 5835 2579 5835 2582 5836 3038 5836 2581 5836 2584 5837 3038 5837 2582 5837 3039 5838 2615 5838 2616 5838 2618 5839 3039 5839 2616 5839 2624 5840 3040 5840 2622 5840 2626 5841 3040 5841 2624 5841 2653 5842 3041 5842 2651 5842 2655 5843 3041 5843 2653 5843 2664 5844 2660 5844 2662 5844 3042 5845 2693 5845 2695 5845 2697 5846 3042 5846 2695 5846 2705 5847 3043 5847 2703 5847 2710 5848 2706 5848 2708 5848 2767 5849 2764 5849 2765 5849 2769 5850 3044 5850 2767 5850 2790 5851 2786 5851 2788 5851 2796 5852 3045 5852 2795 5852 2810 5853 3046 5853 2808 5853 2812 5854 3046 5854 2810 5854 2831 5855 3049 5855 2829 5855 3047 5856 3096 5856 3095 5856 3047 5857 3098 5857 3096 5857 2831 5858 3098 5858 3047 5858 3048 5859 3047 5859 3095 5859 3049 5860 3047 5860 3048 5860 2831 5861 3047 5861 3049 5861 3048 5862 3095 5862 3050 5862 3051 5863 3049 5863 3048 5863 3052 5864 3048 5864 3050 5864 3051 5865 3048 5865 3052 5865 2829 5866 3049 5866 3051 5866 2352 5867 2829 5867 3051 5867 3053 5868 3052 5868 3050 5868 3054 5869 3051 5869 3052 5869 2352 5870 3051 5870 3054 5870 3055 5871 3052 5871 3053 5871 3054 5872 3052 5872 3055 5872 3057 5873 2352 5873 3054 5873 3057 5874 3054 5874 3055 5874 3056 5875 3055 5875 3053 5875 3058 5876 3057 5876 3055 5876 3060 5877 3055 5877 3056 5877 3058 5878 3055 5878 3059 5878 3059 5879 3055 5879 3060 5879 2350 5880 3057 5880 3058 5880 2350 5881 3058 5881 3059 5881 3061 5882 3060 5882 3056 5882 3062 5883 3059 5883 3060 5883 3062 5884 3060 5884 3061 5884 2350 5885 3059 5885 3062 5885 3065 5886 2350 5886 3062 5886 3064 5887 3062 5887 3061 5887 3065 5888 3062 5888 3064 5888 3061 5889 3056 5889 3063 5889 3063 5890 3064 5890 3061 5890 3066 5891 3064 5891 3063 5891 3069 5892 3065 5892 3064 5892 3066 5893 3063 5893 3067 5893 3066 5894 3069 5894 3064 5894 3067 5895 3063 5895 3068 5895 3070 5896 3066 5896 3067 5896 3068 5897 3070 5897 3067 5897 3070 5898 3069 5898 3066 5898 3071 5899 3068 5899 3063 5899 2344 5900 3069 5900 3070 5900 3072 5901 3070 5901 3068 5901 3073 5902 3072 5902 3068 5902 3072 5903 2344 5903 3070 5903 3071 5904 3073 5904 3068 5904 3074 5905 2344 5905 3072 5905 3074 5906 3072 5906 3073 5906 3075 5907 3074 5907 3073 5907 3076 5908 3073 5908 3071 5908 3076 5909 3075 5909 3073 5909 3075 5910 3077 5910 3074 5910 3077 5911 3075 5911 3076 5911 3079 5912 3077 5912 3076 5912 3080 5913 3076 5913 3071 5913 3080 5914 3071 5914 3078 5914 2338 5915 3077 5915 3079 5915 3080 5916 3079 5916 3076 5916 3081 5917 3079 5917 3080 5917 3082 5918 3079 5918 3081 5918 3082 5919 2338 5919 3079 5919 3078 5920 3081 5920 3080 5920 3083 5921 3081 5921 3078 5921 3083 5922 3082 5922 3081 5922 2340 5923 3082 5923 3083 5923 3085 5924 3083 5924 3078 5924 3084 5925 3085 5925 3078 5925 2342 5926 3083 5926 3085 5926 2340 5927 3083 5927 2342 5927 3086 5928 3085 5928 3084 5928 2342 5929 3085 5929 3086 5929 3086 5930 3084 5930 3087 5930 2345 5931 2342 5931 3086 5931 3088 5932 3086 5932 3087 5932 3088 5933 2345 5933 3086 5933 3089 5934 3088 5934 3087 5934 3088 5935 3090 5935 2345 5935 3090 5936 3088 5936 3089 5936 3091 5937 3087 5937 3092 5937 3089 5938 3087 5938 3091 5938 3093 5939 3090 5939 3089 5939 2346 5940 3090 5940 3093 5940 3093 5941 3089 5941 3091 5941 2348 5942 2346 5942 3093 5942 3094 5943 3093 5943 3091 5943 3094 5944 2348 5944 3093 5944 3094 5945 3091 5945 3092 5945 3097 5946 3094 5946 3092 5946 3097 5947 2348 5947 3094 5947 3096 5948 3097 5948 3092 5948 3095 5949 3096 5949 3092 5949 3098 5950 2348 5950 3097 5950 3096 5951 3098 5951 3097 5951 3053 5952 3050 5952 3095 5952 3053 5953 3095 5953 3092 5953 3071 5954 3084 5954 3078 5954 3056 5955 3092 5955 3087 5955 3056 5956 3053 5956 3092 5956 3063 5957 3087 5957 3084 5957 3063 5958 3084 5958 3071 5958 3063 5959 3056 5959 3087 5959 3100 5960 3166 5960 3099 5960 3100 5961 3165 5961 3166 5961 3102 5962 3165 5962 3100 5962 3101 5963 3100 5963 3099 5963 3103 5964 3100 5964 3101 5964 3102 5965 3100 5965 3103 5965 3105 5966 3102 5966 3103 5966 3104 5967 3103 5967 3101 5967 3106 5968 3103 5968 3104 5968 3105 5969 3103 5969 3106 5969 3107 5970 3106 5970 3104 5970 3108 5971 3105 5971 3106 5971 3110 5972 3106 5972 3107 5972 3110 5973 3107 5973 3109 5973 3110 5974 3108 5974 3106 5974 3111 5975 3110 5975 3109 5975 3112 5976 3110 5976 3111 5976 3108 5977 3110 5977 3112 5977 3113 5978 3108 5978 3112 5978 3114 5979 3112 5979 3111 5979 3113 5980 3112 5980 3115 5980 3115 5981 3112 5981 3114 5981 3116 5982 3113 5982 3115 5982 3117 5983 3115 5983 3114 5983 3118 5984 3115 5984 3117 5984 3116 5985 3115 5985 3118 5985 3119 5986 3116 5986 3118 5986 3120 5987 3118 5987 3117 5987 3121 5988 3118 5988 3120 5988 3121 5989 3119 5989 3118 5989 3122 5990 3121 5990 3120 5990 3123 5991 3121 5991 3122 5991 3119 5992 3121 5992 3123 5992 3124 5993 3123 5993 3122 5993 3125 5994 3119 5994 3123 5994 3126 5995 3123 5995 3124 5995 3125 5996 3123 5996 3126 5996 3127 5997 3126 5997 3124 5997 3128 5998 3126 5998 3127 5998 3128 5999 3125 5999 3126 5999 3129 6000 3128 6000 3127 6000 3128 6001 3130 6001 3125 6001 3130 6002 3128 6002 3129 6002 3130 6003 3129 6003 3131 6003 3133 6004 3130 6004 3131 6004 3133 6005 3131 6005 3132 6005 3134 6006 3130 6006 3133 6006 3135 6007 3133 6007 3132 6007 3136 6008 3135 6008 3132 6008 3130 6009 3134 6009 3138 6009 3134 6010 3133 6010 3135 6010 3137 6011 3135 6011 3136 6011 3138 6012 3134 6012 3135 6012 3139 6013 3135 6013 3137 6013 3138 6014 3135 6014 3139 6014 3141 6015 3139 6015 3137 6015 3141 6016 3138 6016 3139 6016 3141 6017 3137 6017 3140 6017 3143 6018 3141 6018 3140 6018 3143 6019 3140 6019 3142 6019 3141 6020 3144 6020 3138 6020 3144 6021 3141 6021 3143 6021 3145 6022 3143 6022 3142 6022 3144 6023 3143 6023 3145 6023 3146 6024 3144 6024 3145 6024 3146 6025 3145 6025 3147 6025 3148 6026 3146 6026 3147 6026 3148 6027 3144 6027 3146 6027 3149 6028 3148 6028 3147 6028 3150 6029 3148 6029 3149 6029 3153 6030 3148 6030 3150 6030 3152 6031 3149 6031 3151 6031 3150 6032 3149 6032 3152 6032 3153 6033 3150 6033 3152 6033 3155 6034 3153 6034 3152 6034 3155 6035 3152 6035 3154 6035 3157 6036 3153 6036 3155 6036 3157 6037 3155 6037 3154 6037 3157 6038 3154 6038 3156 6038 3159 6039 3153 6039 3157 6039 3158 6040 3157 6040 3156 6040 3159 6041 3157 6041 3158 6041 3159 6042 3158 6042 3161 6042 3161 6043 3158 6043 3160 6043 3163 6044 3159 6044 3161 6044 3162 6045 3161 6045 3160 6045 3165 6046 3159 6046 3163 6046 3163 6047 3161 6047 3162 6047 3164 6048 3163 6048 3162 6048 3166 6049 3163 6049 3164 6049 3165 6050 3163 6050 3166 6050 3166 6051 3164 6051 3099 6051 3099 6052 3188 6052 3167 6052 3101 6053 3099 6053 3167 6053 3101 6054 3167 6054 3235 6054 3104 6055 3235 6055 3168 6055 3104 6056 3101 6056 3235 6056 3104 6057 3168 6057 3232 6057 3107 6058 3104 6058 3232 6058 3107 6059 3232 6059 3169 6059 3109 6060 3107 6060 3169 6060 3109 6061 3169 6061 3170 6061 3111 6062 3109 6062 3170 6062 3111 6063 3170 6063 3227 6063 3114 6064 3227 6064 3226 6064 3114 6065 3111 6065 3227 6065 3114 6066 3226 6066 3171 6066 3117 6067 3114 6067 3171 6067 3117 6068 3171 6068 3172 6068 3120 6069 3117 6069 3172 6069 3120 6070 3172 6070 3221 6070 3120 6071 3221 6071 3220 6071 3122 6072 3120 6072 3220 6072 3122 6073 3220 6073 3173 6073 3124 6074 3122 6074 3173 6074 3124 6075 3173 6075 3174 6075 3127 6076 3124 6076 3174 6076 3129 6077 3127 6077 3174 6077 3129 6078 3174 6078 3214 6078 3129 6079 3214 6079 3175 6079 3131 6080 3129 6080 3175 6080 3132 6081 3175 6081 3176 6081 3132 6082 3131 6082 3175 6082 3136 6083 3132 6083 3176 6083 3136 6084 3176 6084 3177 6084 3136 6085 3177 6085 3178 6085 3137 6086 3136 6086 3178 6086 3137 6087 3178 6087 3179 6087 3140 6088 3137 6088 3179 6088 3140 6089 3179 6089 3180 6089 3142 6090 3180 6090 3207 6090 3142 6091 3140 6091 3180 6091 3142 6092 3207 6092 3181 6092 3145 6093 3142 6093 3181 6093 3145 6094 3181 6094 3182 6094 3147 6095 3145 6095 3182 6095 3147 6096 3182 6096 3203 6096 3147 6097 3203 6097 3183 6097 3149 6098 3147 6098 3183 6098 3151 6099 3149 6099 3183 6099 3151 6100 3183 6100 3184 6100 3152 6101 3151 6101 3184 6101 3152 6102 3184 6102 3185 6102 3154 6103 3152 6103 3185 6103 3156 6104 3185 6104 3196 6104 3156 6105 3154 6105 3185 6105 3156 6106 3196 6106 3194 6106 3158 6107 3156 6107 3194 6107 3158 6108 3194 6108 3186 6108 3160 6109 3158 6109 3186 6109 3160 6110 3186 6110 3187 6110 3162 6111 3160 6111 3187 6111 3164 6112 3187 6112 3188 6112 3164 6113 3162 6113 3187 6113 3099 6114 3164 6114 3188 6114 2364 6115 3144 6115 2836 6115 2364 6116 3138 6116 3144 6116 2837 6117 2836 6117 3144 6117 2837 6118 3144 6118 3148 6118 2362 6119 3138 6119 2364 6119 2837 6120 3148 6120 3153 6120 3022 6121 2837 6121 3153 6121 2362 6122 3130 6122 3138 6122 2358 6123 3130 6123 2362 6123 3024 6124 3022 6124 3153 6124 3024 6125 3153 6125 3159 6125 2358 6126 3125 6126 3130 6126 2360 6127 3125 6127 2358 6127 3165 6128 3024 6128 3159 6128 3119 6129 3125 6129 2360 6129 3165 6130 3023 6130 3024 6130 3119 6131 2360 6131 2356 6131 3116 6132 3119 6132 2356 6132 3116 6133 2356 6133 2354 6133 3102 6134 3023 6134 3165 6134 3113 6135 3116 6135 2354 6135 3105 6136 3023 6136 3102 6136 3105 6137 3025 6137 3023 6137 3113 6138 2354 6138 2353 6138 3108 6139 3113 6139 2353 6139 3105 6140 2353 6140 3025 6140 3108 6141 2353 6141 3105 6141 3190 6142 3237 6142 3189 6142 3191 6143 3190 6143 3189 6143 3192 6144 3189 6144 3188 6144 3191 6145 3189 6145 3192 6145 3192 6146 3188 6146 3187 6146 3193 6147 3191 6147 3192 6147 3193 6148 3192 6148 3187 6148 3186 6149 3193 6149 3187 6149 3195 6150 3191 6150 3193 6150 3194 6151 3193 6151 3186 6151 3195 6152 3193 6152 3194 6152 3195 6153 3197 6153 3191 6153 3195 6154 3194 6154 3196 6154 3198 6155 3195 6155 3196 6155 3197 6156 3195 6156 3198 6156 3198 6157 3196 6157 3185 6157 3199 6158 3197 6158 3198 6158 3200 6159 3198 6159 3185 6159 3200 6160 3199 6160 3198 6160 3184 6161 3200 6161 3185 6161 3201 6162 3200 6162 3184 6162 3199 6163 3200 6163 3201 6163 3201 6164 3184 6164 3183 6164 3202 6165 3199 6165 3201 6165 3203 6166 3201 6166 3183 6166 3202 6167 3201 6167 3204 6167 3204 6168 3201 6168 3203 6168 3182 6169 3204 6169 3203 6169 3202 6170 3204 6170 3205 6170 3205 6171 3204 6171 3182 6171 3206 6172 3205 6172 3182 6172 3206 6173 3182 6173 3181 6173 3207 6174 3206 6174 3181 6174 3208 6175 3206 6175 3207 6175 3205 6176 3206 6176 3208 6176 3208 6177 3207 6177 3180 6177 3209 6178 3205 6178 3208 6178 3179 6179 3208 6179 3180 6179 3209 6180 3208 6180 3179 6180 3210 6181 3209 6181 3179 6181 3210 6182 3179 6182 3178 6182 3211 6183 3209 6183 3210 6183 3177 6184 3210 6184 3178 6184 3211 6185 3210 6185 3177 6185 3212 6186 3177 6186 3176 6186 3211 6187 3177 6187 3212 6187 3213 6188 3211 6188 3212 6188 3212 6189 3176 6189 3175 6189 3214 6190 3212 6190 3175 6190 3214 6191 3213 6191 3212 6191 3215 6192 3211 6192 3213 6192 3215 6193 3213 6193 3214 6193 3216 6194 3214 6194 3174 6194 3215 6195 3214 6195 3216 6195 3217 6196 3216 6196 3174 6196 3218 6197 3215 6197 3216 6197 3173 6198 3217 6198 3174 6198 3218 6199 3216 6199 3217 6199 3218 6200 3217 6200 3173 6200 3219 6201 3218 6201 3173 6201 3219 6202 3173 6202 3220 6202 3222 6203 3220 6203 3221 6203 3222 6204 3219 6204 3220 6204 3172 6205 3222 6205 3221 6205 3223 6206 3219 6206 3222 6206 3224 6207 3222 6207 3172 6207 3223 6208 3222 6208 3224 6208 3224 6209 3172 6209 3171 6209 3225 6210 3223 6210 3224 6210 3225 6211 3224 6211 3171 6211 3226 6212 3225 6212 3171 6212 3228 6213 3225 6213 3226 6213 3228 6214 3226 6214 3227 6214 3229 6215 3227 6215 3170 6215 3229 6216 3228 6216 3227 6216 3230 6217 3225 6217 3228 6217 3169 6218 3229 6218 3170 6218 3231 6219 3228 6219 3229 6219 3230 6220 3228 6220 3231 6220 3231 6221 3229 6221 3169 6221 3232 6222 3231 6222 3169 6222 3168 6223 3231 6223 3232 6223 3233 6224 3231 6224 3168 6224 3233 6225 3230 6225 3231 6225 3234 6226 3230 6226 3233 6226 3233 6227 3168 6227 3235 6227 3236 6228 3235 6228 3167 6228 3236 6229 3233 6229 3235 6229 3237 6230 3233 6230 3236 6230 3237 6231 3234 6231 3233 6231 3236 6232 3167 6232 3188 6232 3236 6233 3188 6233 3189 6233 3189 6234 3237 6234 3236 6234 2326 6235 2328 6235 2333 6235 2333 6236 2328 6236 2331 6236 2324 6237 2326 6237 2334 6237 2334 6238 2326 6238 2333 6238 2322 6239 2324 6239 2335 6239 2335 6240 2324 6240 2334 6240

+
+ + + +

3238 6241 3239 6241 3240 6241 3239 6242 3241 6242 3240 6242 3239 6243 3243 6243 3241 6243 3242 6244 3243 6244 3239 6244 3244 6245 3245 6245 3242 6245 3242 6246 3245 6246 3243 6246 3244 6247 3246 6247 3245 6247 3246 6248 3247 6248 3245 6248 3248 6249 3249 6249 3246 6249 3246 6250 3249 6250 3247 6250 3238 6251 3240 6251 3248 6251 3248 6252 3240 6252 3249 6252 3247 6253 3251 6253 3250 6253 3247 6254 3249 6254 3251 6254 3249 6255 3240 6255 3251 6255 3251 6256 3240 6256 3255 6256 3240 6257 3241 6257 3255 6257 3255 6258 3241 6258 3254 6258 3238 6259 3248 6259 3239 6259 3239 6260 3244 6260 3242 6260 3246 6261 3244 6261 3248 6261 3248 6262 3244 6262 3239 6262 3253 6263 4108 6263 4110 6263 3253 6264 4106 6264 4108 6264 3254 6265 4110 6265 4114 6265 3254 6266 3253 6266 4110 6266 3254 6267 4114 6267 4117 6267 4122 6268 3254 6268 4117 6268 3252 6269 4155 6269 4106 6269 3252 6270 4150 6270 4155 6270 3252 6271 4106 6271 3253 6271 4146 6272 4150 6272 3252 6272 3255 6273 3254 6273 4122 6273 3255 6274 4122 6274 4125 6274 4128 6275 3255 6275 4125 6275 3250 6276 4144 6276 4146 6276 3250 6277 4146 6277 3252 6277 4128 6278 3251 6278 3255 6278 4142 6279 4144 6279 3250 6279 4131 6280 3251 6280 4128 6280 4133 6281 3251 6281 4131 6281 4139 6282 4142 6282 3250 6282 4139 6283 3250 6283 3251 6283 3256 6284 4139 6284 3251 6284 3256 6285 3251 6285 4133 6285 3258 6286 3257 6286 3999 6286 3257 6287 3259 6287 3999 6287 3258 6288 3999 6288 4002 6288 3257 6289 3995 6289 3259 6289 3260 6290 3995 6290 3257 6290 3258 6291 4002 6291 3261 6291 3262 6292 3258 6292 3261 6292 3260 6293 3993 6293 3995 6293 3263 6294 3993 6294 3260 6294 3262 6295 3261 6295 3264 6295 3263 6296 3265 6296 3993 6296 3266 6297 3262 6297 3264 6297 3267 6298 3265 6298 3263 6298 3985 6299 3265 6299 3267 6299 3269 6300 3985 6300 3267 6300 3269 6301 3267 6301 3270 6301 3271 6302 3269 6302 3270 6302 3271 6303 3270 6303 3272 6303 3975 6304 3271 6304 3272 6304 3975 6305 3272 6305 3273 6305 3279 6306 3276 6306 3275 6306 3279 6307 3277 6307 3276 6307 3281 6308 3277 6308 3279 6308 3281 6309 3280 6309 3277 6309 3278 6310 3280 6310 3281 6310 3278 6311 3282 6311 3280 6311 3283 6312 3282 6312 3278 6312 3283 6313 3284 6313 3282 6313 3285 6314 3284 6314 3283 6314 3285 6315 3286 6315 3284 6315 3287 6316 3286 6316 3285 6316 3287 6317 3288 6317 3286 6317 3287 6318 3289 6318 3288 6318 3290 6319 3289 6319 3287 6319 3290 6320 3291 6320 3289 6320 3290 6321 3292 6321 3291 6321 3293 6322 3292 6322 3290 6322 3293 6323 3294 6323 3292 6323 3295 6324 3294 6324 3293 6324 3295 6325 3296 6325 3294 6325 3297 6326 3296 6326 3295 6326 3297 6327 3298 6327 3296 6327 3299 6328 3298 6328 3297 6328 3299 6329 3300 6329 3298 6329 3299 6330 3301 6330 3300 6330 3302 6331 3301 6331 3299 6331 3302 6332 3303 6332 3301 6332 3302 6333 3304 6333 3303 6333 3305 6334 3304 6334 3302 6334 3305 6335 3306 6335 3304 6335 3307 6336 3306 6336 3305 6336 3307 6337 3308 6337 3306 6337 3309 6338 3308 6338 3307 6338 3309 6339 3310 6339 3308 6339 3309 6340 3311 6340 3310 6340 3312 6341 3311 6341 3309 6341 3312 6342 3313 6342 3311 6342 3312 6343 3314 6343 3313 6343 3315 6344 3314 6344 3312 6344 3315 6345 3316 6345 3314 6345 3315 6346 3317 6346 3316 6346 3318 6347 3317 6347 3315 6347 3318 6348 3319 6348 3317 6348 3320 6349 3319 6349 3318 6349 3320 6350 3321 6350 3319 6350 3320 6351 3322 6351 3321 6351 3323 6352 3322 6352 3320 6352 3323 6353 3324 6353 3322 6353 3325 6354 3324 6354 3323 6354 3325 6355 3326 6355 3324 6355 3327 6356 3326 6356 3325 6356 3327 6357 3328 6357 3326 6357 3327 6358 3329 6358 3328 6358 3330 6359 3329 6359 3327 6359 3330 6360 3331 6360 3329 6360 3332 6361 3331 6361 3330 6361 3332 6362 3333 6362 3331 6362 3332 6363 3334 6363 3333 6363 3335 6364 3334 6364 3332 6364 3335 6365 3336 6365 3334 6365 3335 6366 3337 6366 3336 6366 3338 6367 3337 6367 3335 6367 3339 6368 3340 6368 3338 6368 3338 6369 3340 6369 3337 6369 3339 6370 3341 6370 3340 6370 3342 6371 3341 6371 3339 6371 3342 6372 3343 6372 3341 6372 3344 6373 3343 6373 3342 6373 3344 6374 3345 6374 3343 6374 3344 6375 3346 6375 3345 6375 3347 6376 3346 6376 3344 6376 3347 6377 3348 6377 3346 6377 3347 6378 3349 6378 3348 6378 3350 6379 3349 6379 3347 6379 3350 6380 3351 6380 3349 6380 3350 6381 3352 6381 3351 6381 3353 6382 3352 6382 3350 6382 3353 6383 3354 6383 3352 6383 3355 6384 3354 6384 3353 6384 3355 6385 3356 6385 3354 6385 3357 6386 3356 6386 3355 6386 3357 6387 3358 6387 3356 6387 3359 6388 3358 6388 3357 6388 3359 6389 3360 6389 3358 6389 3359 6390 3361 6390 3360 6390 3362 6391 3361 6391 3359 6391 3362 6392 3363 6392 3361 6392 3364 6393 3363 6393 3362 6393 3364 6394 3365 6394 3363 6394 3366 6395 3365 6395 3364 6395 3366 6396 3367 6396 3365 6396 3368 6397 3367 6397 3366 6397 3368 6398 3369 6398 3367 6398 3370 6399 3369 6399 3368 6399 3370 6400 3371 6400 3369 6400 3372 6401 3371 6401 3370 6401 3372 6402 3373 6402 3371 6402 3372 6403 3374 6403 3373 6403 3375 6404 3374 6404 3372 6404 3375 6405 3376 6405 3374 6405 3375 6406 3377 6406 3376 6406 3378 6407 3377 6407 3375 6407 3378 6408 3379 6408 3377 6408 3380 6409 3379 6409 3378 6409 3380 6410 3381 6410 3379 6410 3382 6411 3381 6411 3380 6411 3382 6412 3383 6412 3381 6412 3382 6413 3384 6413 3383 6413 3386 6414 3385 6414 3382 6414 3382 6415 3385 6415 3384 6415 3386 6416 3387 6416 3385 6416 3388 6417 3387 6417 3386 6417 3388 6418 3389 6418 3387 6418 3388 6419 3390 6419 3389 6419 3391 6420 3390 6420 3388 6420 3391 6421 3392 6421 3390 6421 3391 6422 3393 6422 3392 6422 3394 6423 3393 6423 3391 6423 3394 6424 3395 6424 3393 6424 3396 6425 3395 6425 3394 6425 3396 6426 3397 6426 3395 6426 3396 6427 3398 6427 3397 6427 3399 6428 3398 6428 3396 6428 3399 6429 3400 6429 3398 6429 3399 6430 3401 6430 3400 6430 3402 6431 3401 6431 3399 6431 3402 6432 3403 6432 3401 6432 3404 6433 3403 6433 3402 6433 3404 6434 3405 6434 3403 6434 3406 6435 3405 6435 3404 6435 3406 6436 3407 6436 3405 6436 3408 6437 3407 6437 3406 6437 3408 6438 3409 6438 3407 6438 3410 6439 3409 6439 3408 6439 3410 6440 3411 6440 3409 6440 3412 6441 3411 6441 3410 6441 3412 6442 3413 6442 3411 6442 3414 6443 3413 6443 3412 6443 3414 6444 3415 6444 3413 6444 3414 6445 3416 6445 3415 6445 3417 6446 3416 6446 3414 6446 3417 6447 3418 6447 3416 6447 3419 6448 3418 6448 3417 6448 3419 6449 3420 6449 3418 6449 3421 6450 3422 6450 3419 6450 3419 6451 3422 6451 3420 6451 3421 6452 3423 6452 3422 6452 3424 6453 3423 6453 3421 6453 3424 6454 3425 6454 3423 6454 3426 6455 3425 6455 3424 6455 3426 6456 3427 6456 3425 6456 3426 6457 3428 6457 3427 6457 3429 6458 3428 6458 3426 6458 3429 6459 3430 6459 3428 6459 3431 6460 3430 6460 3429 6460 3431 6461 3432 6461 3430 6461 3433 6462 3432 6462 3431 6462 3433 6463 3434 6463 3432 6463 3433 6464 3435 6464 3434 6464 3436 6465 3435 6465 3433 6465 3436 6466 3437 6466 3435 6466 3438 6467 3437 6467 3436 6467 3438 6468 3439 6468 3437 6468 3438 6469 3440 6469 3439 6469 3441 6470 3440 6470 3438 6470 3441 6471 3442 6471 3440 6471 3443 6472 3442 6472 3441 6472 3443 6473 3444 6473 3442 6473 3445 6474 3446 6474 3443 6474 3443 6475 3446 6475 3444 6475 3445 6476 3447 6476 3446 6476 3448 6477 3447 6477 3445 6477 3448 6478 3449 6478 3447 6478 3450 6479 3449 6479 3448 6479 3450 6480 3451 6480 3449 6480 3450 6481 3452 6481 3451 6481 3453 6482 3452 6482 3450 6482 3453 6483 3454 6483 3452 6483 3455 6484 3454 6484 3453 6484 3455 6485 3456 6485 3454 6485 3457 6486 3456 6486 3455 6486 3457 6487 3458 6487 3456 6487 3457 6488 3459 6488 3458 6488 3460 6489 3459 6489 3457 6489 3460 6490 3461 6490 3459 6490 3463 6491 3462 6491 3460 6491 3460 6492 3462 6492 3461 6492 3463 6493 3464 6493 3462 6493 3465 6494 3464 6494 3463 6494 3465 6495 3466 6495 3464 6495 3465 6496 3467 6496 3466 6496 3468 6497 3467 6497 3465 6497 3468 6498 3469 6498 3467 6498 3470 6499 3469 6499 3468 6499 3470 6500 3471 6500 3469 6500 3470 6501 3472 6501 3471 6501 3473 6502 3472 6502 3470 6502 3473 6503 3474 6503 3472 6503 3475 6504 3474 6504 3473 6504 3475 6505 3476 6505 3474 6505 3475 6506 3477 6506 3476 6506 3478 6507 3477 6507 3475 6507 3478 6508 3479 6508 3477 6508 3480 6509 3479 6509 3478 6509 3480 6510 3481 6510 3479 6510 3480 6511 3482 6511 3481 6511 3483 6512 3482 6512 3480 6512 3483 6513 3484 6513 3482 6513 3485 6514 3484 6514 3483 6514 3485 6515 3486 6515 3484 6515 3487 6516 3486 6516 3485 6516 3487 6517 3488 6517 3486 6517 3489 6518 3488 6518 3487 6518 3489 6519 3490 6519 3488 6519 3489 6520 3491 6520 3490 6520 3492 6521 3491 6521 3489 6521 3492 6522 3493 6522 3491 6522 3494 6523 3493 6523 3492 6523 3494 6524 3495 6524 3493 6524 3496 6525 3495 6525 3494 6525 3496 6526 3497 6526 3495 6526 3496 6527 3498 6527 3497 6527 3499 6528 3498 6528 3496 6528 3499 6529 3500 6529 3498 6529 3499 6530 3501 6530 3500 6530 3502 6531 3501 6531 3499 6531 3502 6532 3503 6532 3501 6532 3504 6533 3503 6533 3502 6533 3504 6534 3505 6534 3503 6534 3504 6535 3506 6535 3505 6535 3507 6536 3506 6536 3504 6536 3507 6537 3508 6537 3506 6537 3509 6538 3508 6538 3507 6538 3509 6539 3510 6539 3508 6539 3509 6540 3511 6540 3510 6540 3512 6541 3511 6541 3509 6541 3512 6542 3513 6542 3511 6542 3512 6543 3514 6543 3513 6543 3515 6544 3514 6544 3512 6544 3515 6545 3516 6545 3514 6545 3517 6546 3516 6546 3515 6546 3517 6547 3518 6547 3516 6547 3519 6548 3518 6548 3517 6548 3519 6549 3520 6549 3518 6549 3521 6550 3520 6550 3519 6550 3521 6551 3522 6551 3520 6551 3523 6552 3524 6552 3521 6552 3521 6553 3524 6553 3522 6553 3523 6554 3525 6554 3524 6554 3526 6555 3525 6555 3523 6555 3526 6556 3527 6556 3525 6556 3528 6557 3527 6557 3526 6557 3528 6558 3529 6558 3527 6558 3530 6559 3529 6559 3528 6559 3530 6560 3531 6560 3529 6560 3532 6561 3531 6561 3530 6561 3532 6562 3533 6562 3531 6562 3532 6563 3534 6563 3533 6563 3535 6564 3534 6564 3532 6564 3535 6565 3536 6565 3534 6565 3537 6566 3536 6566 3535 6566 3537 6567 3538 6567 3536 6567 3537 6568 3539 6568 3538 6568 3540 6569 3539 6569 3537 6569 3540 6570 3541 6570 3539 6570 3540 6571 3542 6571 3541 6571 3543 6572 3542 6572 3540 6572 3543 6573 3544 6573 3542 6573 3545 6574 3544 6574 3543 6574 3545 6575 3546 6575 3544 6575 3547 6576 3546 6576 3545 6576 3548 6577 3546 6577 3547 6577 3548 6578 3549 6578 3546 6578 3548 6579 3550 6579 3549 6579 3551 6580 3550 6580 3548 6580 3551 6581 3552 6581 3550 6581 3551 6582 3553 6582 3552 6582 3554 6583 3553 6583 3551 6583 3554 6584 3555 6584 3553 6584 3554 6585 3556 6585 3555 6585 3557 6586 3556 6586 3554 6586 3557 6587 3558 6587 3556 6587 3559 6588 3558 6588 3557 6588 3559 6589 3560 6589 3558 6589 3561 6590 3560 6590 3559 6590 3561 6591 3562 6591 3560 6591 3561 6592 3563 6592 3562 6592 3564 6593 3563 6593 3561 6593 3564 6594 3565 6594 3563 6594 3566 6595 3565 6595 3564 6595 3566 6596 3567 6596 3565 6596 3568 6597 3567 6597 3566 6597 3568 6598 3569 6598 3567 6598 3568 6599 3570 6599 3569 6599 3571 6600 3570 6600 3568 6600 3571 6601 3572 6601 3570 6601 3571 6602 3573 6602 3572 6602 3574 6603 3573 6603 3571 6603 3574 6604 3575 6604 3573 6604 3576 6605 3575 6605 3574 6605 3576 6606 3577 6606 3575 6606 3576 6607 3578 6607 3577 6607 3579 6608 3578 6608 3576 6608 3579 6609 3580 6609 3578 6609 3581 6610 3580 6610 3579 6610 3581 6611 3582 6611 3580 6611 3581 6612 3583 6612 3582 6612 3584 6613 3583 6613 3581 6613 3585 6614 3583 6614 3584 6614 3585 6615 3586 6615 3583 6615 3585 6616 3587 6616 3586 6616 3588 6617 3587 6617 3585 6617 3588 6618 3589 6618 3587 6618 3588 6619 3590 6619 3589 6619 3591 6620 3590 6620 3588 6620 3591 6621 3592 6621 3590 6621 3593 6622 3592 6622 3591 6622 3593 6623 3594 6623 3592 6623 3595 6624 3594 6624 3593 6624 3595 6625 3596 6625 3594 6625 3595 6626 3597 6626 3596 6626 3598 6627 3597 6627 3595 6627 3598 6628 3599 6628 3597 6628 3600 6629 3599 6629 3598 6629 3600 6630 3601 6630 3599 6630 3602 6631 3601 6631 3600 6631 3602 6632 3603 6632 3601 6632 3604 6633 3603 6633 3602 6633 3604 6634 3605 6634 3603 6634 3606 6635 3605 6635 3604 6635 3606 6636 3607 6636 3605 6636 3606 6637 3608 6637 3607 6637 3609 6638 3608 6638 3606 6638 3609 6639 3610 6639 3608 6639 3611 6640 3610 6640 3609 6640 3611 6641 3612 6641 3610 6641 3611 6642 3613 6642 3612 6642 3614 6643 3613 6643 3611 6643 3615 6644 3616 6644 3614 6644 3614 6645 3616 6645 3613 6645 3615 6646 3617 6646 3616 6646 3618 6647 3617 6647 3615 6647 3618 6648 3619 6648 3617 6648 3618 6649 3620 6649 3619 6649 3621 6650 3620 6650 3618 6650 3621 6651 3622 6651 3620 6651 3623 6652 3622 6652 3621 6652 3623 6653 3624 6653 3622 6653 3625 6654 3624 6654 3623 6654 3625 6655 3626 6655 3624 6655 3627 6656 3626 6656 3625 6656 3627 6657 3628 6657 3626 6657 3627 6658 3629 6658 3628 6658 3630 6659 3629 6659 3627 6659 3630 6660 3631 6660 3629 6660 3632 6661 3631 6661 3630 6661 3633 6662 3631 6662 3632 6662 3633 6663 3634 6663 3631 6663 3633 6664 3635 6664 3634 6664 3636 6665 3635 6665 3633 6665 3636 6666 3637 6666 3635 6666 3638 6667 3637 6667 3636 6667 3638 6668 3639 6668 3637 6668 3640 6669 3639 6669 3638 6669 3640 6670 3641 6670 3639 6670 3640 6671 3642 6671 3641 6671 3643 6672 3642 6672 3640 6672 3643 6673 3644 6673 3642 6673 3643 6674 3645 6674 3644 6674 3646 6675 3645 6675 3643 6675 3646 6676 3647 6676 3645 6676 3648 6677 3647 6677 3646 6677 3648 6678 3649 6678 3647 6678 3650 6679 3649 6679 3648 6679 3650 6680 3651 6680 3649 6680 3652 6681 3653 6681 3650 6681 3650 6682 3653 6682 3651 6682 3652 6683 3654 6683 3653 6683 3655 6684 3654 6684 3652 6684 3655 6685 3656 6685 3654 6685 3657 6686 3656 6686 3655 6686 3657 6687 3658 6687 3656 6687 3657 6688 3659 6688 3658 6688 3660 6689 3659 6689 3657 6689 3660 6690 3661 6690 3659 6690 3660 6691 3662 6691 3661 6691 3663 6692 3662 6692 3660 6692 3663 6693 3664 6693 3662 6693 3665 6694 3664 6694 3663 6694 3665 6695 3666 6695 3664 6695 3667 6696 3666 6696 3665 6696 3667 6697 3668 6697 3666 6697 3669 6698 3668 6698 3667 6698 3669 6699 3670 6699 3668 6699 3669 6700 3671 6700 3670 6700 3672 6701 3671 6701 3669 6701 3672 6702 3673 6702 3671 6702 3674 6703 3673 6703 3672 6703 3674 6704 3675 6704 3673 6704 3676 6705 3675 6705 3674 6705 3676 6706 3677 6706 3675 6706 3678 6707 3677 6707 3676 6707 3678 6708 3679 6708 3677 6708 3680 6709 3679 6709 3678 6709 3680 6710 3681 6710 3679 6710 3682 6711 3681 6711 3680 6711 3682 6712 3683 6712 3681 6712 3684 6713 3683 6713 3682 6713 3684 6714 3685 6714 3683 6714 3684 6715 3686 6715 3685 6715 3687 6716 3686 6716 3684 6716 3687 6717 3688 6717 3686 6717 3689 6718 3688 6718 3687 6718 3689 6719 3690 6719 3688 6719 3691 6720 3690 6720 3689 6720 3691 6721 3692 6721 3690 6721 3691 6722 3693 6722 3692 6722 3694 6723 3693 6723 3691 6723 3694 6724 3695 6724 3693 6724 3694 6725 3696 6725 3695 6725 3697 6726 3696 6726 3694 6726 3697 6727 3698 6727 3696 6727 3697 6728 3699 6728 3698 6728 3700 6729 3699 6729 3697 6729 3700 6730 3701 6730 3699 6730 3700 6731 3702 6731 3701 6731 3703 6732 3702 6732 3700 6732 3703 6733 3704 6733 3702 6733 3705 6734 3704 6734 3703 6734 3705 6735 3706 6735 3704 6735 3707 6736 3706 6736 3705 6736 3709 6737 3708 6737 3707 6737 3707 6738 3708 6738 3706 6738 3710 6739 3708 6739 3709 6739 3710 6740 3711 6740 3708 6740 3710 6741 3712 6741 3711 6741 3710 6742 3713 6742 3712 6742 3714 6743 3713 6743 3710 6743 3715 6744 3713 6744 3714 6744 3715 6745 3716 6745 3713 6745 3715 6746 3717 6746 3716 6746 3718 6747 3717 6747 3715 6747 3718 6748 3719 6748 3717 6748 3720 6749 3719 6749 3718 6749 3720 6750 3721 6750 3719 6750 3722 6751 3721 6751 3720 6751 3722 6752 3723 6752 3721 6752 3722 6753 3724 6753 3723 6753 3725 6754 3724 6754 3722 6754 3725 6755 3726 6755 3724 6755 3727 6756 3726 6756 3725 6756 3727 6757 3728 6757 3726 6757 3727 6758 3729 6758 3728 6758 3730 6759 3729 6759 3727 6759 3731 6760 3732 6760 3730 6760 3730 6761 3732 6761 3729 6761 3731 6762 3733 6762 3732 6762 3734 6763 3733 6763 3731 6763 3734 6764 3735 6764 3733 6764 3736 6765 3735 6765 3734 6765 3736 6766 3737 6766 3735 6766 3736 6767 3738 6767 3737 6767 3739 6768 3738 6768 3736 6768 3739 6769 3740 6769 3738 6769 3739 6770 3741 6770 3740 6770 3742 6771 3741 6771 3739 6771 3742 6772 3743 6772 3741 6772 3742 6773 3744 6773 3743 6773 3745 6774 3744 6774 3742 6774 3745 6775 3746 6775 3744 6775 3747 6776 3746 6776 3745 6776 3747 6777 3748 6777 3746 6777 3749 6778 3748 6778 3747 6778 3749 6779 3268 6779 3748 6779 3749 6780 3266 6780 3268 6780 3750 6781 3266 6781 3749 6781 3750 6782 3262 6782 3266 6782 3751 6783 3262 6783 3750 6783 3752 6784 3262 6784 3751 6784 3752 6785 3258 6785 3262 6785 3753 6786 3287 6786 3285 6786 3754 6787 3287 6787 3753 6787 3290 6788 3287 6788 3754 6788 3755 6789 3290 6789 3754 6789 3293 6790 3290 6790 3755 6790 3295 6791 3293 6791 3755 6791 3756 6792 3295 6792 3755 6792 3297 6793 3295 6793 3756 6793 3757 6794 3297 6794 3756 6794 3299 6795 3297 6795 3757 6795 3758 6796 3299 6796 3757 6796 3302 6797 3299 6797 3758 6797 3759 6798 3302 6798 3758 6798 3305 6799 3302 6799 3759 6799 3760 6800 3305 6800 3759 6800 3307 6801 3305 6801 3760 6801 3309 6802 3307 6802 3761 6802 3762 6803 3309 6803 3761 6803 3312 6804 3309 6804 3762 6804 3763 6805 3312 6805 3762 6805 3315 6806 3312 6806 3763 6806 3764 6807 3315 6807 3763 6807 3318 6808 3315 6808 3764 6808 3765 6809 3318 6809 3764 6809 3320 6810 3318 6810 3765 6810 3766 6811 3320 6811 3765 6811 3323 6812 3320 6812 3766 6812 3767 6813 3323 6813 3766 6813 3325 6814 3323 6814 3767 6814 3327 6815 3325 6815 3767 6815 3768 6816 3327 6816 3767 6816 3330 6817 3327 6817 3768 6817 3769 6818 3330 6818 3768 6818 3332 6819 3330 6819 3769 6819 3770 6820 3332 6820 3769 6820 3771 6821 3332 6821 3770 6821 3335 6822 3332 6822 3771 6822 3338 6823 3335 6823 3771 6823 3772 6824 3338 6824 3771 6824 3339 6825 3338 6825 3772 6825 3773 6826 3339 6826 3772 6826 3342 6827 3339 6827 3773 6827 3774 6828 3342 6828 3773 6828 3344 6829 3342 6829 3774 6829 3347 6830 3344 6830 3774 6830 3775 6831 3347 6831 3774 6831 3776 6832 3347 6832 3775 6832 3350 6833 3347 6833 3776 6833 3777 6834 3350 6834 3776 6834 3353 6835 3350 6835 3777 6835 3778 6836 3353 6836 3777 6836 3355 6837 3353 6837 3778 6837 3357 6838 3355 6838 3778 6838 3779 6839 3357 6839 3778 6839 3359 6840 3357 6840 3779 6840 3780 6841 3359 6841 3779 6841 3362 6842 3359 6842 3780 6842 3364 6843 3362 6843 3781 6843 3366 6844 3364 6844 3781 6844 3782 6845 3366 6845 3781 6845 3368 6846 3366 6846 3782 6846 3783 6847 3368 6847 3782 6847 3370 6848 3368 6848 3783 6848 3372 6849 3370 6849 3783 6849 3784 6850 3372 6850 3783 6850 3785 6851 3372 6851 3784 6851 3375 6852 3372 6852 3785 6852 3786 6853 3375 6853 3785 6853 3378 6854 3375 6854 3786 6854 3787 6855 3378 6855 3786 6855 3380 6856 3378 6856 3787 6856 3788 6857 3380 6857 3787 6857 3382 6858 3380 6858 3788 6858 3789 6859 3382 6859 3788 6859 3386 6860 3382 6860 3789 6860 3790 6861 3386 6861 3789 6861 3388 6862 3386 6862 3790 6862 3791 6863 3388 6863 3790 6863 3391 6864 3388 6864 3791 6864 3792 6865 3391 6865 3791 6865 3793 6866 3391 6866 3792 6866 3394 6867 3391 6867 3793 6867 3396 6868 3394 6868 3793 6868 3794 6869 3396 6869 3793 6869 3795 6870 3396 6870 3794 6870 3399 6871 3396 6871 3795 6871 3796 6872 3399 6872 3795 6872 3402 6873 3399 6873 3796 6873 3797 6874 3402 6874 3796 6874 3404 6875 3402 6875 3797 6875 3406 6876 3404 6876 3797 6876 3798 6877 3406 6877 3797 6877 3408 6878 3406 6878 3798 6878 3799 6879 3408 6879 3798 6879 3410 6880 3408 6880 3799 6880 3800 6881 3410 6881 3799 6881 3412 6882 3410 6882 3800 6882 3801 6883 3412 6883 3800 6883 3414 6884 3412 6884 3801 6884 3417 6885 3414 6885 3801 6885 3802 6886 3417 6886 3801 6886 3419 6887 3417 6887 3802 6887 3803 6888 3419 6888 3802 6888 3421 6889 3419 6889 3803 6889 3804 6890 3421 6890 3803 6890 3424 6891 3421 6891 3804 6891 3805 6892 3424 6892 3804 6892 3426 6893 3424 6893 3805 6893 3806 6894 3426 6894 3805 6894 3429 6895 3426 6895 3806 6895 3807 6896 3429 6896 3806 6896 3431 6897 3429 6897 3807 6897 3808 6898 3431 6898 3807 6898 3433 6899 3431 6899 3808 6899 3809 6900 3433 6900 3808 6900 3436 6901 3433 6901 3809 6901 3810 6902 3436 6902 3809 6902 3811 6903 3436 6903 3810 6903 3438 6904 3436 6904 3811 6904 3441 6905 3438 6905 3811 6905 3812 6906 3441 6906 3811 6906 3813 6907 3441 6907 3812 6907 3443 6908 3441 6908 3813 6908 3814 6909 3443 6909 3813 6909 3445 6910 3443 6910 3814 6910 3815 6911 3445 6911 3814 6911 3448 6912 3445 6912 3815 6912 3450 6913 3448 6913 3815 6913 3816 6914 3450 6914 3815 6914 3817 6915 3450 6915 3816 6915 3453 6916 3450 6916 3817 6916 3818 6917 3453 6917 3817 6917 3455 6918 3453 6918 3818 6918 3819 6919 3455 6919 3818 6919 3457 6920 3455 6920 3819 6920 3820 6921 3457 6921 3819 6921 3460 6922 3457 6922 3820 6922 3821 6923 3460 6923 3820 6923 3463 6924 3460 6924 3821 6924 3822 6925 3463 6925 3821 6925 3465 6926 3463 6926 3822 6926 3823 6927 3465 6927 3822 6927 3468 6928 3465 6928 3823 6928 3824 6929 3468 6929 3823 6929 3470 6930 3468 6930 3824 6930 3825 6931 3470 6931 3824 6931 3826 6932 3470 6932 3825 6932 3473 6933 3470 6933 3826 6933 3827 6934 3473 6934 3826 6934 3475 6935 3473 6935 3827 6935 3828 6936 3475 6936 3827 6936 3478 6937 3475 6937 3828 6937 3829 6938 3478 6938 3828 6938 3830 6939 3478 6939 3829 6939 3480 6940 3478 6940 3830 6940 3483 6941 3480 6941 3830 6941 3487 6942 3485 6942 3831 6942 3832 6943 3487 6943 3831 6943 3489 6944 3487 6944 3832 6944 3833 6945 3489 6945 3832 6945 3492 6946 3489 6946 3833 6946 3834 6947 3492 6947 3833 6947 3494 6948 3492 6948 3834 6948 3496 6949 3494 6949 3834 6949 3496 6950 3834 6950 3835 6950 3836 6951 3496 6951 3835 6951 3499 6952 3496 6952 3836 6952 3837 6953 3499 6953 3836 6953 3502 6954 3499 6954 3837 6954 3838 6955 3502 6955 3837 6955 3839 6956 3502 6956 3838 6956 3504 6957 3502 6957 3839 6957 3840 6958 3504 6958 3839 6958 3507 6959 3504 6959 3840 6959 3841 6960 3507 6960 3840 6960 3509 6961 3507 6961 3841 6961 3842 6962 3509 6962 3841 6962 3512 6963 3509 6963 3842 6963 3843 6964 3512 6964 3842 6964 3515 6965 3512 6965 3843 6965 3844 6966 3515 6966 3843 6966 3517 6967 3515 6967 3844 6967 3845 6968 3517 6968 3844 6968 3846 6969 3517 6969 3845 6969 3519 6970 3517 6970 3846 6970 3521 6971 3519 6971 3846 6971 3847 6972 3521 6972 3846 6972 3523 6973 3521 6973 3847 6973 3526 6974 3523 6974 3847 6974 3848 6975 3526 6975 3847 6975 3528 6976 3526 6976 3848 6976 3849 6977 3528 6977 3848 6977 3530 6978 3528 6978 3849 6978 3850 6979 3530 6979 3849 6979 3851 6980 3530 6980 3850 6980 3532 6981 3530 6981 3851 6981 3852 6982 3532 6982 3851 6982 3535 6983 3532 6983 3852 6983 3537 6984 3535 6984 3852 6984 3853 6985 3537 6985 3852 6985 3854 6986 3537 6986 3853 6986 3540 6987 3537 6987 3854 6987 3855 6988 3540 6988 3854 6988 3543 6989 3540 6989 3855 6989 3545 6990 3543 6990 3855 6990 3547 6991 3545 6991 3856 6991 3548 6992 3856 6992 3857 6992 3548 6993 3547 6993 3856 6993 3551 6994 3548 6994 3857 6994 3858 6995 3551 6995 3857 6995 3554 6996 3551 6996 3858 6996 3859 6997 3554 6997 3858 6997 3557 6998 3554 6998 3859 6998 3860 6999 3559 6999 3557 6999 3861 7000 3559 7000 3860 7000 3561 7001 3559 7001 3861 7001 3862 7002 3561 7002 3861 7002 3564 7003 3561 7003 3862 7003 3566 7004 3564 7004 3862 7004 3863 7005 3566 7005 3862 7005 3864 7006 3566 7006 3863 7006 3568 7007 3566 7007 3864 7007 3865 7008 3568 7008 3864 7008 3571 7009 3568 7009 3865 7009 3866 7010 3571 7010 3865 7010 3574 7011 3571 7011 3866 7011 3867 7012 3574 7012 3866 7012 3576 7013 3574 7013 3867 7013 3868 7014 3576 7014 3867 7014 3579 7015 3576 7015 3868 7015 3869 7016 3579 7016 3868 7016 3870 7017 3579 7017 3869 7017 3581 7018 3579 7018 3870 7018 3871 7019 3581 7019 3870 7019 3584 7020 3581 7020 3871 7020 3872 7021 3584 7021 3871 7021 3585 7022 3584 7022 3872 7022 3873 7023 3585 7023 3872 7023 3588 7024 3585 7024 3873 7024 3874 7025 3588 7025 3873 7025 3591 7026 3588 7026 3874 7026 3875 7027 3591 7027 3874 7027 3876 7028 3591 7028 3875 7028 3593 7029 3591 7029 3876 7029 3595 7030 3593 7030 3876 7030 3877 7031 3595 7031 3876 7031 3878 7032 3595 7032 3877 7032 3598 7033 3595 7033 3878 7033 3879 7034 3598 7034 3878 7034 3600 7035 3598 7035 3879 7035 3602 7036 3600 7036 3879 7036 3880 7037 3602 7037 3879 7037 3604 7038 3602 7038 3880 7038 3881 7039 3604 7039 3880 7039 3606 7040 3604 7040 3881 7040 3882 7041 3606 7041 3881 7041 3883 7042 3606 7042 3882 7042 3609 7043 3606 7043 3883 7043 3884 7044 3609 7044 3883 7044 3611 7045 3609 7045 3884 7045 3885 7046 3611 7046 3884 7046 3614 7047 3611 7047 3885 7047 3615 7048 3614 7048 3885 7048 3886 7049 3615 7049 3885 7049 3618 7050 3615 7050 3886 7050 3887 7051 3618 7051 3886 7051 3621 7052 3618 7052 3887 7052 3888 7053 3621 7053 3887 7053 3623 7054 3621 7054 3888 7054 3889 7055 3623 7055 3888 7055 3625 7056 3623 7056 3889 7056 3890 7057 3625 7057 3889 7057 3627 7058 3625 7058 3890 7058 3891 7059 3627 7059 3890 7059 3630 7060 3627 7060 3891 7060 3892 7061 3632 7061 3630 7061 3633 7062 3632 7062 3892 7062 3893 7063 3633 7063 3892 7063 3636 7064 3633 7064 3893 7064 3894 7065 3636 7065 3893 7065 3638 7066 3636 7066 3894 7066 3895 7067 3638 7067 3894 7067 3640 7068 3638 7068 3895 7068 3896 7069 3640 7069 3895 7069 3643 7070 3640 7070 3896 7070 3897 7071 3643 7071 3896 7071 3646 7072 3643 7072 3897 7072 3898 7073 3646 7073 3897 7073 3648 7074 3646 7074 3898 7074 3899 7075 3650 7075 3648 7075 3652 7076 3650 7076 3899 7076 3652 7077 3899 7077 3900 7077 3655 7078 3652 7078 3900 7078 3901 7079 3655 7079 3900 7079 3657 7080 3655 7080 3901 7080 3902 7081 3657 7081 3901 7081 3660 7082 3657 7082 3902 7082 3903 7083 3660 7083 3902 7083 3663 7084 3660 7084 3903 7084 3904 7085 3663 7085 3903 7085 3905 7086 3663 7086 3904 7086 3665 7087 3663 7087 3905 7087 3906 7088 3665 7088 3905 7088 3667 7089 3665 7089 3906 7089 3907 7090 3667 7090 3906 7090 3669 7091 3667 7091 3907 7091 3908 7092 3669 7092 3907 7092 3672 7093 3669 7093 3908 7093 3909 7094 3672 7094 3908 7094 3674 7095 3672 7095 3909 7095 3910 7096 3674 7096 3909 7096 3676 7097 3674 7097 3910 7097 3911 7098 3676 7098 3910 7098 3678 7099 3676 7099 3911 7099 3912 7100 3678 7100 3911 7100 3680 7101 3678 7101 3912 7101 3682 7102 3680 7102 3912 7102 3913 7103 3682 7103 3912 7103 3684 7104 3682 7104 3913 7104 3914 7105 3684 7105 3913 7105 3687 7106 3684 7106 3914 7106 3915 7107 3687 7107 3914 7107 3689 7108 3687 7108 3915 7108 3691 7109 3689 7109 3915 7109 3916 7110 3691 7110 3915 7110 3917 7111 3691 7111 3916 7111 3694 7112 3691 7112 3917 7112 3697 7113 3694 7113 3917 7113 3918 7114 3697 7114 3917 7114 3919 7115 3697 7115 3918 7115 3700 7116 3697 7116 3919 7116 3920 7117 3700 7117 3919 7117 3703 7118 3700 7118 3920 7118 3921 7119 3703 7119 3920 7119 3705 7120 3703 7120 3921 7120 3922 7121 3705 7121 3921 7121 3707 7122 3705 7122 3922 7122 3923 7123 3707 7123 3922 7123 3709 7124 3707 7124 3923 7124 3710 7125 3709 7125 3923 7125 3924 7126 3710 7126 3923 7126 3925 7127 3710 7127 3924 7127 3714 7128 3710 7128 3925 7128 3715 7129 3714 7129 3925 7129 3926 7130 3715 7130 3925 7130 3927 7131 3715 7131 3926 7131 3718 7132 3715 7132 3927 7132 3720 7133 3718 7133 3927 7133 3928 7134 3720 7134 3927 7134 3929 7135 3720 7135 3928 7135 3722 7136 3720 7136 3929 7136 3930 7137 3722 7137 3929 7137 3725 7138 3722 7138 3930 7138 3931 7139 3725 7139 3930 7139 3727 7140 3725 7140 3931 7140 3932 7141 3727 7141 3931 7141 3730 7142 3727 7142 3932 7142 3731 7143 3730 7143 3932 7143 3933 7144 3731 7144 3932 7144 3734 7145 3731 7145 3933 7145 3934 7146 3734 7146 3933 7146 3736 7147 3734 7147 3934 7147 3739 7148 3736 7148 3934 7148 3935 7149 3739 7149 3934 7149 3742 7150 3739 7150 3935 7150 3936 7151 3742 7151 3935 7151 3742 7152 3936 7152 3937 7152 3745 7153 3742 7153 3937 7153 3938 7154 3745 7154 3937 7154 3747 7155 3745 7155 3938 7155 3939 7156 3747 7156 3938 7156 3749 7157 3747 7157 3939 7157 3940 7158 3749 7158 3939 7158 3750 7159 3749 7159 3940 7159 3941 7160 3750 7160 3940 7160 3751 7161 3750 7161 3941 7161 3752 7162 3751 7162 3941 7162 3942 7163 3752 7163 3941 7163 3258 7164 3752 7164 3942 7164 3943 7165 3258 7165 3942 7165 3257 7166 3258 7166 3943 7166 3257 7167 3943 7167 3260 7167 3945 7168 3755 7168 3754 7168 3945 7169 3756 7169 3755 7169 3946 7170 3756 7170 3945 7170 3946 7171 3757 7171 3756 7171 3944 7172 3757 7172 3946 7172 3944 7173 3758 7173 3757 7173 3947 7174 3758 7174 3944 7174 3948 7175 3758 7175 3947 7175 3948 7176 3759 7176 3758 7176 3949 7177 3759 7177 3948 7177 3949 7178 3760 7178 3759 7178 3276 7179 3760 7179 3949 7179 3276 7180 3307 7180 3760 7180 3277 7181 3307 7181 3276 7181 3277 7182 3761 7182 3307 7182 3280 7183 3761 7183 3277 7183 3280 7184 3762 7184 3761 7184 3282 7185 3762 7185 3280 7185 3284 7186 3762 7186 3282 7186 3284 7187 3763 7187 3762 7187 3286 7188 3763 7188 3284 7188 3286 7189 3764 7189 3763 7189 3288 7190 3764 7190 3286 7190 3288 7191 3765 7191 3764 7191 3289 7192 3765 7192 3288 7192 3291 7193 3765 7193 3289 7193 3291 7194 3766 7194 3765 7194 3292 7195 3766 7195 3291 7195 3294 7196 3766 7196 3292 7196 3294 7197 3767 7197 3766 7197 3296 7198 3767 7198 3294 7198 3298 7199 3767 7199 3296 7199 3298 7200 3768 7200 3767 7200 3300 7201 3768 7201 3298 7201 3300 7202 3769 7202 3768 7202 3301 7203 3769 7203 3300 7203 3301 7204 3770 7204 3769 7204 3303 7205 3770 7205 3301 7205 3304 7206 3770 7206 3303 7206 3304 7207 3771 7207 3770 7207 3306 7208 3771 7208 3304 7208 3308 7209 3771 7209 3306 7209 3308 7210 3772 7210 3771 7210 3310 7211 3772 7211 3308 7211 3311 7212 3772 7212 3310 7212 3311 7213 3773 7213 3772 7213 3313 7214 3773 7214 3311 7214 3313 7215 3774 7215 3773 7215 3316 7216 3774 7216 3313 7216 3316 7217 3775 7217 3774 7217 3317 7218 3775 7218 3316 7218 3317 7219 3776 7219 3775 7219 3319 7220 3776 7220 3317 7220 3319 7221 3777 7221 3776 7221 3322 7222 3777 7222 3319 7222 3322 7223 3778 7223 3777 7223 3324 7224 3778 7224 3322 7224 3326 7225 3778 7225 3324 7225 3326 7226 3779 7226 3778 7226 3328 7227 3779 7227 3326 7227 3328 7228 3780 7228 3779 7228 3329 7229 3780 7229 3328 7229 3329 7230 3362 7230 3780 7230 3331 7231 3362 7231 3329 7231 3331 7232 3781 7232 3362 7232 3333 7233 3781 7233 3331 7233 3334 7234 3781 7234 3333 7234 3334 7235 3782 7235 3781 7235 3336 7236 3782 7236 3334 7236 3336 7237 3783 7237 3782 7237 3340 7238 3783 7238 3336 7238 3341 7239 3784 7239 3340 7239 3340 7240 3784 7240 3783 7240 3343 7241 3785 7241 3341 7241 3341 7242 3785 7242 3784 7242 3345 7243 3785 7243 3343 7243 3345 7244 3786 7244 3785 7244 3346 7245 3786 7245 3345 7245 3348 7246 3787 7246 3346 7246 3346 7247 3787 7247 3786 7247 3349 7248 3787 7248 3348 7248 3349 7249 3788 7249 3787 7249 3351 7250 3788 7250 3349 7250 3352 7251 3788 7251 3351 7251 3352 7252 3789 7252 3788 7252 3354 7253 3789 7253 3352 7253 3354 7254 3790 7254 3789 7254 3356 7255 3790 7255 3354 7255 3358 7256 3790 7256 3356 7256 3358 7257 3791 7257 3790 7257 3360 7258 3791 7258 3358 7258 3950 7259 3791 7259 3360 7259 3950 7260 3792 7260 3791 7260 3950 7261 3793 7261 3792 7261 3363 7262 3793 7262 3950 7262 3365 7263 3793 7263 3363 7263 3365 7264 3794 7264 3793 7264 3367 7265 3794 7265 3365 7265 3367 7266 3795 7266 3794 7266 3369 7267 3795 7267 3367 7267 3371 7268 3796 7268 3369 7268 3369 7269 3796 7269 3795 7269 3373 7270 3796 7270 3371 7270 3373 7271 3797 7271 3796 7271 3374 7272 3797 7272 3373 7272 3376 7273 3797 7273 3374 7273 3376 7274 3798 7274 3797 7274 3377 7275 3798 7275 3376 7275 3379 7276 3798 7276 3377 7276 3379 7277 3799 7277 3798 7277 3381 7278 3799 7278 3379 7278 3383 7279 3799 7279 3381 7279 3383 7280 3800 7280 3799 7280 3384 7281 3800 7281 3383 7281 3384 7282 3801 7282 3800 7282 3385 7283 3801 7283 3384 7283 3387 7284 3801 7284 3385 7284 3387 7285 3802 7285 3801 7285 3389 7286 3802 7286 3387 7286 3390 7287 3802 7287 3389 7287 3390 7288 3803 7288 3802 7288 3392 7289 3803 7289 3390 7289 3392 7290 3804 7290 3803 7290 3393 7291 3804 7291 3392 7291 3393 7292 3805 7292 3804 7292 3397 7293 3805 7293 3393 7293 3397 7294 3806 7294 3805 7294 3398 7295 3806 7295 3397 7295 3400 7296 3806 7296 3398 7296 3400 7297 3807 7297 3806 7297 3401 7298 3807 7298 3400 7298 3401 7299 3808 7299 3807 7299 3403 7300 3808 7300 3401 7300 3403 7301 3809 7301 3808 7301 3405 7302 3809 7302 3403 7302 3407 7303 3809 7303 3405 7303 3407 7304 3810 7304 3809 7304 3951 7305 3810 7305 3407 7305 3951 7306 3811 7306 3810 7306 3952 7307 3811 7307 3951 7307 3413 7308 3811 7308 3952 7308 3413 7309 3812 7309 3811 7309 3415 7310 3812 7310 3413 7310 3415 7311 3813 7311 3812 7311 3416 7312 3813 7312 3415 7312 3416 7313 3814 7313 3813 7313 3418 7314 3814 7314 3416 7314 3418 7315 3815 7315 3814 7315 3420 7316 3815 7316 3418 7316 3422 7317 3815 7317 3420 7317 3422 7318 3816 7318 3815 7318 3423 7319 3816 7319 3422 7319 3423 7320 3817 7320 3816 7320 3425 7321 3817 7321 3423 7321 3425 7322 3818 7322 3817 7322 3427 7323 3818 7323 3425 7323 3428 7324 3818 7324 3427 7324 3428 7325 3819 7325 3818 7325 3430 7326 3819 7326 3428 7326 3430 7327 3820 7327 3819 7327 3432 7328 3820 7328 3430 7328 3432 7329 3821 7329 3820 7329 3434 7330 3821 7330 3432 7330 3435 7331 3821 7331 3434 7331 3435 7332 3822 7332 3821 7332 3437 7333 3822 7333 3435 7333 3437 7334 3823 7334 3822 7334 3439 7335 3823 7335 3437 7335 3440 7336 3824 7336 3439 7336 3439 7337 3824 7337 3823 7337 3953 7338 3824 7338 3440 7338 3953 7339 3825 7339 3824 7339 3442 7340 3825 7340 3953 7340 3442 7341 3826 7341 3825 7341 3444 7342 3826 7342 3442 7342 3446 7343 3826 7343 3444 7343 3446 7344 3827 7344 3826 7344 3447 7345 3827 7345 3446 7345 3447 7346 3828 7346 3827 7346 3449 7347 3828 7347 3447 7347 3449 7348 3829 7348 3828 7348 3451 7349 3829 7349 3449 7349 3451 7350 3830 7350 3829 7350 3452 7351 3830 7351 3451 7351 3454 7352 3830 7352 3452 7352 3454 7353 3483 7353 3830 7353 3456 7354 3483 7354 3454 7354 3456 7355 3485 7355 3483 7355 3954 7356 3485 7356 3456 7356 3954 7357 3831 7357 3485 7357 3458 7358 3831 7358 3954 7358 3459 7359 3831 7359 3458 7359 3459 7360 3832 7360 3831 7360 3461 7361 3832 7361 3459 7361 3461 7362 3833 7362 3832 7362 3462 7363 3833 7363 3461 7363 3464 7364 3833 7364 3462 7364 3464 7365 3834 7365 3833 7365 3466 7366 3834 7366 3464 7366 3467 7367 3834 7367 3466 7367 3467 7368 3835 7368 3834 7368 3467 7369 3836 7369 3835 7369 3469 7370 3836 7370 3467 7370 3471 7371 3836 7371 3469 7371 3471 7372 3837 7372 3836 7372 3472 7373 3837 7373 3471 7373 3472 7374 3838 7374 3837 7374 3474 7375 3838 7375 3472 7375 3474 7376 3839 7376 3838 7376 3476 7377 3839 7377 3474 7377 3476 7378 3840 7378 3839 7378 3477 7379 3840 7379 3476 7379 3481 7380 3840 7380 3477 7380 3481 7381 3841 7381 3840 7381 3482 7382 3841 7382 3481 7382 3482 7383 3842 7383 3841 7383 3484 7384 3842 7384 3482 7384 3484 7385 3843 7385 3842 7385 3486 7386 3843 7386 3484 7386 3486 7387 3844 7387 3843 7387 3488 7388 3844 7388 3486 7388 3488 7389 3845 7389 3844 7389 3490 7390 3845 7390 3488 7390 3491 7391 3845 7391 3490 7391 3491 7392 3846 7392 3845 7392 3493 7393 3846 7393 3491 7393 3495 7394 3846 7394 3493 7394 3495 7395 3847 7395 3846 7395 3497 7396 3847 7396 3495 7396 3498 7397 3847 7397 3497 7397 3498 7398 3848 7398 3847 7398 3500 7399 3848 7399 3498 7399 3500 7400 3849 7400 3848 7400 3501 7401 3849 7401 3500 7401 3501 7402 3850 7402 3849 7402 3503 7403 3850 7403 3501 7403 3503 7404 3851 7404 3850 7404 3505 7405 3851 7405 3503 7405 3506 7406 3851 7406 3505 7406 3506 7407 3852 7407 3851 7407 3508 7408 3852 7408 3506 7408 3508 7409 3853 7409 3852 7409 3510 7410 3853 7410 3508 7410 3511 7411 3853 7411 3510 7411 3511 7412 3854 7412 3853 7412 3511 7413 3855 7413 3854 7413 3513 7414 3855 7414 3511 7414 3514 7415 3855 7415 3513 7415 3514 7416 3545 7416 3855 7416 3516 7417 3545 7417 3514 7417 3516 7418 3856 7418 3545 7418 3518 7419 3856 7419 3516 7419 3955 7420 3856 7420 3518 7420 3955 7421 3857 7421 3856 7421 3520 7422 3857 7422 3955 7422 3520 7423 3858 7423 3857 7423 3524 7424 3858 7424 3520 7424 3525 7425 3858 7425 3524 7425 3525 7426 3859 7426 3858 7426 3527 7427 3859 7427 3525 7427 3527 7428 3557 7428 3859 7428 3529 7429 3557 7429 3527 7429 3529 7430 3860 7430 3557 7430 3956 7431 3860 7431 3529 7431 3956 7432 3861 7432 3860 7432 3533 7433 3861 7433 3956 7433 3534 7434 3861 7434 3533 7434 3534 7435 3862 7435 3861 7435 3536 7436 3862 7436 3534 7436 3536 7437 3863 7437 3862 7437 3538 7438 3863 7438 3536 7438 3538 7439 3864 7439 3863 7439 3539 7440 3864 7440 3538 7440 3541 7441 3864 7441 3539 7441 3541 7442 3865 7442 3864 7442 3542 7443 3865 7443 3541 7443 3542 7444 3866 7444 3865 7444 3544 7445 3866 7445 3542 7445 3544 7446 3867 7446 3866 7446 3957 7447 3867 7447 3544 7447 3957 7448 3868 7448 3867 7448 3549 7449 3868 7449 3957 7449 3549 7450 3869 7450 3868 7450 3550 7451 3869 7451 3549 7451 3550 7452 3870 7452 3869 7452 3552 7453 3870 7453 3550 7453 3553 7454 3870 7454 3552 7454 3553 7455 3871 7455 3870 7455 3555 7456 3871 7456 3553 7456 3555 7457 3872 7457 3871 7457 3556 7458 3872 7458 3555 7458 3556 7459 3873 7459 3872 7459 3558 7460 3873 7460 3556 7460 3558 7461 3874 7461 3873 7461 3560 7462 3874 7462 3558 7462 3562 7463 3874 7463 3560 7463 3562 7464 3875 7464 3874 7464 3563 7465 3875 7465 3562 7465 3563 7466 3876 7466 3875 7466 3565 7467 3876 7467 3563 7467 3567 7468 3876 7468 3565 7468 3567 7469 3877 7469 3876 7469 3569 7470 3877 7470 3567 7470 3570 7471 3877 7471 3569 7471 3570 7472 3878 7472 3877 7472 3572 7473 3878 7473 3570 7473 3572 7474 3879 7474 3878 7474 3573 7475 3879 7475 3572 7475 3575 7476 3879 7476 3573 7476 3575 7477 3880 7477 3879 7477 3577 7478 3880 7478 3575 7478 3578 7479 3880 7479 3577 7479 3578 7480 3881 7480 3880 7480 3580 7481 3881 7481 3578 7481 3580 7482 3882 7482 3881 7482 3582 7483 3882 7483 3580 7483 3582 7484 3883 7484 3882 7484 3958 7485 3883 7485 3582 7485 3958 7486 3884 7486 3883 7486 3586 7487 3884 7487 3958 7487 3586 7488 3885 7488 3884 7488 3587 7489 3885 7489 3586 7489 3959 7490 3885 7490 3587 7490 3959 7491 3886 7491 3885 7491 3589 7492 3886 7492 3959 7492 3589 7493 3887 7493 3886 7493 3590 7494 3887 7494 3589 7494 3592 7495 3887 7495 3590 7495 3592 7496 3888 7496 3887 7496 3594 7497 3888 7497 3592 7497 3594 7498 3889 7498 3888 7498 3596 7499 3889 7499 3594 7499 3596 7500 3890 7500 3889 7500 3597 7501 3890 7501 3596 7501 3597 7502 3891 7502 3890 7502 3599 7503 3891 7503 3597 7503 3601 7504 3891 7504 3599 7504 3601 7505 3630 7505 3891 7505 3603 7506 3892 7506 3601 7506 3601 7507 3892 7507 3630 7507 3605 7508 3892 7508 3603 7508 3605 7509 3893 7509 3892 7509 3607 7510 3893 7510 3605 7510 3607 7511 3894 7511 3893 7511 3960 7512 3894 7512 3607 7512 3608 7513 3894 7513 3960 7513 3608 7514 3895 7514 3894 7514 3610 7515 3895 7515 3608 7515 3610 7516 3896 7516 3895 7516 3612 7517 3896 7517 3610 7517 3613 7518 3896 7518 3612 7518 3613 7519 3897 7519 3896 7519 3616 7520 3897 7520 3613 7520 3617 7521 3897 7521 3616 7521 3617 7522 3898 7522 3897 7522 3619 7523 3898 7523 3617 7523 3619 7524 3648 7524 3898 7524 3620 7525 3648 7525 3619 7525 3620 7526 3899 7526 3648 7526 3622 7527 3899 7527 3620 7527 3622 7528 3900 7528 3899 7528 3624 7529 3900 7529 3622 7529 3626 7530 3900 7530 3624 7530 3626 7531 3901 7531 3900 7531 3628 7532 3901 7532 3626 7532 3628 7533 3902 7533 3901 7533 3629 7534 3902 7534 3628 7534 3631 7535 3903 7535 3629 7535 3629 7536 3903 7536 3902 7536 3634 7537 3903 7537 3631 7537 3634 7538 3904 7538 3903 7538 3634 7539 3905 7539 3904 7539 3635 7540 3905 7540 3634 7540 3637 7541 3905 7541 3635 7541 3637 7542 3906 7542 3905 7542 3639 7543 3906 7543 3637 7543 3639 7544 3907 7544 3906 7544 3641 7545 3907 7545 3639 7545 3641 7546 3908 7546 3907 7546 3642 7547 3908 7547 3641 7547 3644 7548 3908 7548 3642 7548 3644 7549 3909 7549 3908 7549 3645 7550 3909 7550 3644 7550 3645 7551 3910 7551 3909 7551 3647 7552 3910 7552 3645 7552 3647 7553 3911 7553 3910 7553 3649 7554 3911 7554 3647 7554 3649 7555 3912 7555 3911 7555 3651 7556 3912 7556 3649 7556 3653 7557 3912 7557 3651 7557 3653 7558 3913 7558 3912 7558 3654 7559 3913 7559 3653 7559 3656 7560 3913 7560 3654 7560 3656 7561 3914 7561 3913 7561 3658 7562 3914 7562 3656 7562 3659 7563 3914 7563 3658 7563 3659 7564 3915 7564 3914 7564 3661 7565 3915 7565 3659 7565 3662 7566 3915 7566 3661 7566 3662 7567 3916 7567 3915 7567 3664 7568 3916 7568 3662 7568 3664 7569 3917 7569 3916 7569 3961 7570 3917 7570 3664 7570 3668 7571 3917 7571 3961 7571 3668 7572 3918 7572 3917 7572 3670 7573 3918 7573 3668 7573 3670 7574 3919 7574 3918 7574 3671 7575 3919 7575 3670 7575 3671 7576 3920 7576 3919 7576 3673 7577 3920 7577 3671 7577 3673 7578 3921 7578 3920 7578 3675 7579 3921 7579 3673 7579 3675 7580 3922 7580 3921 7580 3677 7581 3922 7581 3675 7581 3677 7582 3923 7582 3922 7582 3679 7583 3923 7583 3677 7583 3679 7584 3924 7584 3923 7584 3681 7585 3924 7585 3679 7585 3683 7586 3925 7586 3681 7586 3681 7587 3925 7587 3924 7587 3685 7588 3925 7588 3683 7588 3685 7589 3926 7589 3925 7589 3686 7590 3926 7590 3685 7590 3686 7591 3927 7591 3926 7591 3690 7592 3927 7592 3686 7592 3692 7593 3927 7593 3690 7593 3692 7594 3928 7594 3927 7594 3693 7595 3928 7595 3692 7595 3695 7596 3928 7596 3693 7596 3695 7597 3929 7597 3928 7597 3696 7598 3929 7598 3695 7598 3696 7599 3930 7599 3929 7599 3698 7600 3930 7600 3696 7600 3698 7601 3931 7601 3930 7601 3699 7602 3931 7602 3698 7602 3701 7603 3931 7603 3699 7603 3702 7604 3931 7604 3701 7604 3702 7605 3932 7605 3931 7605 3704 7606 3932 7606 3702 7606 3704 7607 3933 7607 3932 7607 3706 7608 3933 7608 3704 7608 3706 7609 3934 7609 3933 7609 3708 7610 3934 7610 3706 7610 3711 7611 3934 7611 3708 7611 3711 7612 3935 7612 3934 7612 3712 7613 3935 7613 3711 7613 3962 7614 3935 7614 3712 7614 3962 7615 3936 7615 3935 7615 3963 7616 3936 7616 3962 7616 3963 7617 3937 7617 3936 7617 3716 7618 3937 7618 3963 7618 3717 7619 3937 7619 3716 7619 3717 7620 3938 7620 3937 7620 3719 7621 3938 7621 3717 7621 3719 7622 3939 7622 3938 7622 3721 7623 3939 7623 3719 7623 3721 7624 3940 7624 3939 7624 3723 7625 3940 7625 3721 7625 3724 7626 3940 7626 3723 7626 3724 7627 3941 7627 3940 7627 3726 7628 3941 7628 3724 7628 3728 7629 3941 7629 3726 7629 3728 7630 3942 7630 3941 7630 3729 7631 3942 7631 3728 7631 3729 7632 3943 7632 3942 7632 3732 7633 3943 7633 3729 7633 3732 7634 3260 7634 3943 7634 3733 7635 3260 7635 3732 7635 3735 7636 3260 7636 3733 7636 3735 7637 3263 7637 3260 7637 3737 7638 3263 7638 3735 7638 3737 7639 3267 7639 3263 7639 3738 7640 3267 7640 3737 7640 3740 7641 3267 7641 3738 7641 3740 7642 3270 7642 3267 7642 3741 7643 3270 7643 3740 7643 3743 7644 3270 7644 3741 7644 3743 7645 3272 7645 3270 7645 3273 7646 3272 7646 3743 7646 3274 7647 3948 7647 3947 7647 3949 7648 3948 7648 3274 7648 3275 7649 3949 7649 3274 7649 3276 7650 3949 7650 3275 7650 3316 7651 3313 7651 3314 7651 3322 7652 3319 7652 3321 7652 3340 7653 3336 7653 3337 7653 3950 7654 3360 7654 3361 7654 3363 7655 3950 7655 3361 7655 3397 7656 3393 7656 3395 7656 3409 7657 3951 7657 3407 7657 3952 7658 3951 7658 3409 7658 3411 7659 3952 7659 3409 7659 3413 7660 3952 7660 3411 7660 3442 7661 3953 7661 3440 7661 3458 7662 3954 7662 3456 7662 3481 7663 3477 7663 3479 7663 3520 7664 3955 7664 3518 7664 3524 7665 3520 7665 3522 7665 3531 7666 3956 7666 3529 7666 3533 7667 3956 7667 3531 7667 3957 7668 3544 7668 3546 7668 3549 7669 3957 7669 3546 7669 3583 7670 3958 7670 3582 7670 3586 7671 3958 7671 3583 7671 3589 7672 3959 7672 3587 7672 3608 7673 3960 7673 3607 7673 3666 7674 3961 7674 3664 7674 3668 7675 3961 7675 3666 7675 3690 7676 3686 7676 3688 7676 3713 7677 3962 7677 3712 7677 3963 7678 3962 7678 3713 7678 3716 7679 3963 7679 3713 7679 3744 7680 3273 7680 3743 7680 3969 7681 3273 7681 3744 7681 3746 7682 3969 7682 3744 7682 3965 7683 4013 7683 3964 7683 3967 7684 3966 7684 3965 7684 3746 7685 3748 7685 3966 7685 3967 7686 3965 7686 3964 7686 3746 7687 3966 7687 3967 7687 3969 7688 3746 7688 3967 7688 3971 7689 3968 7689 3964 7689 3970 7690 3964 7690 3968 7690 3970 7691 3967 7691 3964 7691 3969 7692 3967 7692 3970 7692 3972 7693 3970 7693 3968 7693 3972 7694 3968 7694 3973 7694 3273 7695 3970 7695 3972 7695 3273 7696 3969 7696 3970 7696 3973 7697 3968 7697 3971 7697 3975 7698 3972 7698 3973 7698 3975 7699 3273 7699 3972 7699 3973 7700 3971 7700 3974 7700 3976 7701 3975 7701 3973 7701 3976 7702 3973 7702 3974 7702 3978 7703 3976 7703 3974 7703 3271 7704 3975 7704 3976 7704 3977 7705 3978 7705 3974 7705 3978 7706 3271 7706 3976 7706 3980 7707 3977 7707 3979 7707 3980 7708 3978 7708 3977 7708 3269 7709 3271 7709 3978 7709 3980 7710 3269 7710 3978 7710 3981 7711 3979 7711 3977 7711 3982 7712 3269 7712 3980 7712 3982 7713 3980 7713 3979 7713 3982 7714 3979 7714 3984 7714 3984 7715 3979 7715 3981 7715 3985 7716 3269 7716 3982 7716 3986 7717 3982 7717 3984 7717 3986 7718 3985 7718 3982 7718 3986 7719 3984 7719 3981 7719 3987 7720 3981 7720 3983 7720 3265 7721 3985 7721 3986 7721 3987 7722 3986 7722 3981 7722 3265 7723 3986 7723 3988 7723 3988 7724 3986 7724 3987 7724 3989 7725 3988 7725 3987 7725 3989 7726 3265 7726 3988 7726 3992 7727 3987 7727 3983 7727 3992 7728 3990 7728 3987 7728 3990 7729 3989 7729 3987 7729 3993 7730 3265 7730 3989 7730 3990 7731 3993 7731 3989 7731 3991 7732 3992 7732 3983 7732 3994 7733 3990 7733 3992 7733 3994 7734 3992 7734 3991 7734 3995 7735 3993 7735 3990 7735 3995 7736 3990 7736 3994 7736 3997 7737 3994 7737 3991 7737 3259 7738 3995 7738 3994 7738 3997 7739 3991 7739 3998 7739 3997 7740 3259 7740 3994 7740 3998 7741 3991 7741 3996 7741 4000 7742 3997 7742 3998 7742 3999 7743 3259 7743 3997 7743 4000 7744 3999 7744 3997 7744 4001 7745 3998 7745 3996 7745 4002 7746 3999 7746 4000 7746 4001 7747 4000 7747 3998 7747 4003 7748 4002 7748 4000 7748 4003 7749 4000 7749 4001 7749 4005 7750 4003 7750 4001 7750 4006 7751 4001 7751 3996 7751 3261 7752 4002 7752 4003 7752 4005 7753 4001 7753 4006 7753 3261 7754 4003 7754 4005 7754 4004 7755 4006 7755 3996 7755 4007 7756 4005 7756 4006 7756 3261 7757 4005 7757 4007 7757 4008 7758 4006 7758 4004 7758 3264 7759 3261 7759 4007 7759 4007 7760 4006 7760 4008 7760 4009 7761 4007 7761 4008 7761 4009 7762 3264 7762 4007 7762 4011 7763 4008 7763 4004 7763 4009 7764 4008 7764 4010 7764 4010 7765 4008 7765 4011 7765 4009 7766 3266 7766 3264 7766 4010 7767 3266 7767 4009 7767 4013 7768 4011 7768 4004 7768 4012 7769 4010 7769 4011 7769 4013 7770 4012 7770 4011 7770 3266 7771 4010 7771 4012 7771 3268 7772 3266 7772 4012 7772 4015 7773 4012 7773 4013 7773 4014 7774 3268 7774 4012 7774 4014 7775 4012 7775 4015 7775 3965 7776 4015 7776 4013 7776 3966 7777 4014 7777 4015 7777 3966 7778 3268 7778 4014 7778 4015 7779 3965 7779 3966 7779 3748 7780 3268 7780 3966 7780 3964 7781 4013 7781 4004 7781 3983 7782 3996 7782 3991 7782 3981 7783 4004 7783 3996 7783 3981 7784 3977 7784 3974 7784 3981 7785 3996 7785 3983 7785 3981 7786 3974 7786 3971 7786 3981 7787 3971 7787 3964 7787 3981 7788 3964 7788 4004 7788 4020 7789 4017 7789 4016 7789 4020 7790 4016 7790 4018 7790 4019 7791 4017 7791 4020 7791 4022 7792 4019 7792 4020 7792 4021 7793 4020 7793 4018 7793 4022 7794 4020 7794 4021 7794 4024 7795 4021 7795 4023 7795 4022 7796 4021 7796 4024 7796 4026 7797 4019 7797 4022 7797 4026 7798 4022 7798 4024 7798 4025 7799 4024 7799 4023 7799 4026 7800 4024 7800 4025 7800 4027 7801 4026 7801 4025 7801 4028 7802 4026 7802 4027 7802 4030 7803 4027 7803 4029 7803 4030 7804 4028 7804 4027 7804 4031 7805 4030 7805 4029 7805 4032 7806 4028 7806 4030 7806 4036 7807 4030 7807 4031 7807 4036 7808 4031 7808 4033 7808 4032 7809 4030 7809 4036 7809 4035 7810 4032 7810 4036 7810 4036 7811 4033 7811 4034 7811 4038 7812 4036 7812 4034 7812 4035 7813 4036 7813 4038 7813 4038 7814 4034 7814 4037 7814 4040 7815 4035 7815 4038 7815 4038 7816 4037 7816 4039 7816 4041 7817 4038 7817 4039 7817 4040 7818 4038 7818 4041 7818 4042 7819 4041 7819 4039 7819 4043 7820 4041 7820 4042 7820 4044 7821 4041 7821 4043 7821 4044 7822 4040 7822 4041 7822 4046 7823 4043 7823 4045 7823 4046 7824 4044 7824 4043 7824 4046 7825 4040 7825 4044 7825 4048 7826 4046 7826 4045 7826 4048 7827 4045 7827 4047 7827 4049 7828 4046 7828 4048 7828 4048 7829 4047 7829 4050 7829 4051 7830 4048 7830 4050 7830 4051 7831 4049 7831 4048 7831 4052 7832 4051 7832 4050 7832 4053 7833 4051 7833 4052 7833 4053 7834 4049 7834 4051 7834 4054 7835 4053 7835 4052 7835 4056 7836 4049 7836 4053 7836 4055 7837 4053 7837 4054 7837 4057 7838 4053 7838 4055 7838 4056 7839 4053 7839 4057 7839 4059 7840 4056 7840 4057 7840 4058 7841 4059 7841 4057 7841 4061 7842 4058 7842 4060 7842 4061 7843 4059 7843 4058 7843 4062 7844 4059 7844 4061 7844 4056 7845 4059 7845 4062 7845 4061 7846 4060 7846 4063 7846 4064 7847 4061 7847 4063 7847 4062 7848 4061 7848 4064 7848 4064 7849 4063 7849 4065 7849 4062 7850 4064 7850 4066 7850 4066 7851 4064 7851 4065 7851 4067 7852 4066 7852 4065 7852 4068 7853 4062 7853 4066 7853 4069 7854 4066 7854 4067 7854 4069 7855 4068 7855 4066 7855 4069 7856 4067 7856 4070 7856 4072 7857 4070 7857 4071 7857 4069 7858 4070 7858 4072 7858 4073 7859 4068 7859 4069 7859 4073 7860 4069 7860 4072 7860 4074 7861 4072 7861 4071 7861 4075 7862 4073 7862 4072 7862 4075 7863 4072 7863 4074 7863 4077 7864 4073 7864 4075 7864 4076 7865 4075 7865 4074 7865 4077 7866 4075 7866 4076 7866 4079 7867 4076 7867 4078 7867 4077 7868 4076 7868 4079 7868 4082 7869 4077 7869 4079 7869 4080 7870 4079 7870 4078 7870 4082 7871 4079 7871 4080 7871 4083 7872 4080 7872 4081 7872 4082 7873 4080 7873 4083 7873 4084 7874 4083 7874 4081 7874 4085 7875 4082 7875 4083 7875 4017 7876 4083 7876 4084 7876 4017 7877 4085 7877 4083 7877 4017 7878 4084 7878 4016 7878 4019 7879 4085 7879 4017 7879 4018 7880 4016 7880 4086 7880 4021 7881 4086 7881 4152 7881 4021 7882 4018 7882 4086 7882 4023 7883 4021 7883 4152 7883 4023 7884 4152 7884 4087 7884 4023 7885 4087 7885 4149 7885 4025 7886 4023 7886 4149 7886 4025 7887 4149 7887 4147 7887 4027 7888 4025 7888 4147 7888 4029 7889 4147 7889 4088 7889 4029 7890 4027 7890 4147 7890 4029 7891 4088 7891 4089 7891 4031 7892 4029 7892 4089 7892 4031 7893 4089 7893 4145 7893 4033 7894 4031 7894 4145 7894 4033 7895 4145 7895 4143 7895 4033 7896 4143 7896 4141 7896 4034 7897 4033 7897 4141 7897 4034 7898 4141 7898 4140 7898 4037 7899 4034 7899 4140 7899 4037 7900 4140 7900 4090 7900 4039 7901 4037 7901 4090 7901 4042 7902 4039 7902 4090 7902 4042 7903 4090 7903 4137 7903 4043 7904 4042 7904 4137 7904 4043 7905 4137 7905 4135 7905 4045 7906 4043 7906 4135 7906 4045 7907 4135 7907 4091 7907 4047 7908 4045 7908 4091 7908 4047 7909 4091 7909 4092 7909 4050 7910 4047 7910 4092 7910 4050 7911 4092 7911 4093 7911 4052 7912 4050 7912 4093 7912 4052 7913 4093 7913 4094 7913 4054 7914 4052 7914 4094 7914 4054 7915 4094 7915 4095 7915 4055 7916 4054 7916 4095 7916 4057 7917 4055 7917 4095 7917 4057 7918 4095 7918 4096 7918 4057 7919 4096 7919 4097 7919 4058 7920 4057 7920 4097 7920 4060 7921 4058 7921 4097 7921 4060 7922 4097 7922 4124 7922 4063 7923 4124 7923 4121 7923 4063 7924 4060 7924 4124 7924 4065 7925 4121 7925 4098 7925 4065 7926 4063 7926 4121 7926 4067 7927 4065 7927 4098 7927 4067 7928 4098 7928 4118 7928 4070 7929 4067 7929 4118 7929 4070 7930 4118 7930 4099 7930 4071 7931 4070 7931 4099 7931 4071 7932 4099 7932 4115 7932 4074 7933 4115 7933 4100 7933 4074 7934 4071 7934 4115 7934 4074 7935 4100 7935 4111 7935 4076 7936 4074 7936 4111 7936 4076 7937 4111 7937 4101 7937 4078 7938 4076 7938 4101 7938 4080 7939 4078 7939 4101 7939 4080 7940 4101 7940 4102 7940 4081 7941 4080 7941 4102 7941 4081 7942 4102 7942 4103 7942 4084 7943 4103 7943 4104 7943 4084 7944 4081 7944 4103 7944 4084 7945 4104 7945 4105 7945 4016 7946 4084 7946 4105 7946 4016 7947 4105 7947 4086 7947 3285 7948 4062 7948 3753 7948 3285 7949 4056 7949 4062 7949 3753 7950 4062 7950 4068 7950 3283 7951 4056 7951 3285 7951 3754 7952 3753 7952 4068 7952 3278 7953 4056 7953 3283 7953 3278 7954 4049 7954 4056 7954 3754 7955 4068 7955 4073 7955 3945 7956 3754 7956 4073 7956 3945 7957 4073 7957 4077 7957 3278 7958 4046 7958 4049 7958 3281 7959 4046 7959 3278 7959 3281 7960 4040 7960 4046 7960 4082 7961 3945 7961 4077 7961 3946 7962 3945 7962 4082 7962 4040 7963 3281 7963 3279 7963 4085 7964 3946 7964 4082 7964 4019 7965 3944 7965 3946 7965 4019 7966 3946 7966 4085 7966 4035 7967 4040 7967 3279 7967 4035 7968 3279 7968 3275 7968 4032 7969 4035 7969 3275 7969 4032 7970 3275 7970 3274 7970 4026 7971 3944 7971 4019 7971 4026 7972 3947 7972 3944 7972 4028 7973 4032 7973 3274 7973 4026 7974 3274 7974 3947 7974 4026 7975 4028 7975 3274 7975 4107 7976 4105 7976 4104 7976 4107 7977 4106 7977 4105 7977 4103 7978 4107 7978 4104 7978 4108 7979 4106 7979 4107 7979 4108 7980 4107 7980 4103 7980 4102 7981 4108 7981 4103 7981 4109 7982 4108 7982 4102 7982 4110 7983 4108 7983 4109 7983 4101 7984 4109 7984 4102 7984 4111 7985 4109 7985 4101 7985 4112 7986 4109 7986 4111 7986 4110 7987 4109 7987 4112 7987 4112 7988 4111 7988 4100 7988 4113 7989 4110 7989 4112 7989 4113 7990 4112 7990 4100 7990 4114 7991 4110 7991 4113 7991 4115 7992 4113 7992 4100 7992 4114 7993 4113 7993 4115 7993 4116 7994 4115 7994 4099 7994 4116 7995 4114 7995 4115 7995 4117 7996 4114 7996 4116 7996 4116 7997 4099 7997 4118 7997 4098 7998 4116 7998 4118 7998 4119 7999 4117 7999 4116 7999 4119 8000 4116 8000 4098 8000 4120 8001 4119 8001 4098 8001 4121 8002 4120 8002 4098 8002 4122 8003 4117 8003 4119 8003 4123 8004 4119 8004 4120 8004 4123 8005 4120 8005 4121 8005 4122 8006 4119 8006 4123 8006 4124 8007 4123 8007 4121 8007 4123 8008 4124 8008 4097 8008 4125 8009 4122 8009 4123 8009 4126 8010 4123 8010 4097 8010 4125 8011 4123 8011 4126 8011 4096 8012 4126 8012 4097 8012 4095 8013 4126 8013 4096 8013 4127 8014 4125 8014 4126 8014 4127 8015 4126 8015 4095 8015 4128 8016 4125 8016 4127 8016 4129 8017 4095 8017 4094 8017 4129 8018 4127 8018 4095 8018 4093 8019 4129 8019 4094 8019 4128 8020 4127 8020 4129 8020 4130 8021 4129 8021 4093 8021 4131 8022 4128 8022 4129 8022 4092 8023 4130 8023 4093 8023 4131 8024 4129 8024 4130 8024 4132 8025 4130 8025 4092 8025 4132 8026 4131 8026 4130 8026 4133 8027 4131 8027 4132 8027 4091 8028 4132 8028 4092 8028 4134 8029 4132 8029 4091 8029 4134 8030 4133 8030 4132 8030 4134 8031 4091 8031 4135 8031 4136 8032 4134 8032 4135 8032 3256 8033 4133 8033 4134 8033 4137 8034 4136 8034 4135 8034 3256 8035 4134 8035 4136 8035 4138 8036 4136 8036 4137 8036 4138 8037 4137 8037 4090 8037 3256 8038 4136 8038 4138 8038 4139 8039 3256 8039 4138 8039 4139 8040 4138 8040 4140 8040 4140 8041 4138 8041 4090 8041 4142 8042 4139 8042 4140 8042 4142 8043 4140 8043 4141 8043 4142 8044 4141 8044 4143 8044 4144 8045 4142 8045 4143 8045 4144 8046 4143 8046 4145 8046 4144 8047 4145 8047 4089 8047 4146 8048 4144 8048 4089 8048 4146 8049 4089 8049 4088 8049 4146 8050 4088 8050 4147 8050 4148 8051 4146 8051 4147 8051 4148 8052 4147 8052 4149 8052 4150 8053 4146 8053 4148 8053 4151 8054 4148 8054 4149 8054 4150 8055 4148 8055 4151 8055 4087 8056 4151 8056 4149 8056 4152 8057 4151 8057 4087 8057 4153 8058 4150 8058 4151 8058 4153 8059 4151 8059 4152 8059 4154 8060 4153 8060 4152 8060 4155 8061 4150 8061 4153 8061 4154 8062 4152 8062 4086 8062 4155 8063 4153 8063 4154 8063 4154 8064 4086 8064 4105 8064 4154 8065 4105 8065 4106 8065 4106 8066 4155 8066 4154 8066 3245 8067 3247 8067 3252 8067 3252 8068 3247 8068 3250 8068 3243 8069 3245 8069 3253 8069 3253 8070 3245 8070 3252 8070 3241 8071 3243 8071 3254 8071 3254 8072 3243 8072 3253 8072

+
+ + + +

4156 8073 4157 8073 4158 8073 4157 8074 4159 8074 4158 8074 4160 8075 4161 8075 4157 8075 4157 8076 4161 8076 4159 8076 4162 8077 4163 8077 4160 8077 4160 8078 4163 8078 4161 8078 4162 8079 4164 8079 4163 8079 4164 8080 4165 8080 4163 8080 4166 8081 4167 8081 4164 8081 4164 8082 4167 8082 4165 8082 4156 8083 4158 8083 4166 8083 4166 8084 4158 8084 4167 8084 4165 8085 4167 8085 4168 8085 4168 8086 4167 8086 4169 8086 4167 8087 4173 8087 4169 8087 4167 8088 4158 8088 4173 8088 4158 8089 4159 8089 4173 8089 4173 8090 4159 8090 4172 8090 4157 8091 4164 8091 4160 8091 4166 8092 4164 8092 4156 8092 4156 8093 4164 8093 4157 8093 4164 8094 4162 8094 4160 8094 4171 8095 5032 8095 5036 8095 4171 8096 5030 8096 5032 8096 4171 8097 5073 8097 5030 8097 4172 8098 5036 8098 5039 8098 4172 8099 4171 8099 5036 8099 4172 8100 5039 8100 5042 8100 4170 8101 5070 8101 5073 8101 4170 8102 5073 8102 4171 8102 5066 8103 5070 8103 4170 8103 4173 8104 4172 8104 5042 8104 4173 8105 5042 8105 5048 8105 4168 8106 5062 8106 5066 8106 4168 8107 5066 8107 4170 8107 5050 8108 4173 8108 5048 8108 5050 8109 4169 8109 4173 8109 5060 8110 5062 8110 4168 8110 5053 8111 4169 8111 5050 8111 5060 8112 4168 8112 4169 8112 5056 8113 5060 8113 4169 8113 5056 8114 4169 8114 5053 8114 4174 8115 4920 8115 4922 8115 4175 8116 4920 8116 4174 8116 4174 8117 4922 8117 4176 8117 4175 8118 4177 8118 4920 8118 4178 8119 4174 8119 4176 8119 4179 8120 4177 8120 4175 8120 4179 8121 4915 8121 4177 8121 4178 8122 4176 8122 4180 8122 4179 8123 4911 8123 4915 8123 4181 8124 4911 8124 4179 8124 4182 8125 4178 8125 4180 8125 4181 8126 4908 8126 4911 8126 4183 8127 4908 8127 4181 8127 4904 8128 4908 8128 4183 8128 4904 8129 4183 8129 4185 8129 4901 8130 4904 8130 4185 8130 4901 8131 4185 8131 4186 8131 4192 8132 4189 8132 4188 8132 4192 8133 4190 8133 4189 8133 4194 8134 4190 8134 4192 8134 4194 8135 4193 8135 4190 8135 4191 8136 4193 8136 4194 8136 4191 8137 4195 8137 4193 8137 4196 8138 4195 8138 4191 8138 4196 8139 4197 8139 4195 8139 4198 8140 4197 8140 4196 8140 4198 8141 4199 8141 4197 8141 4200 8142 4199 8142 4198 8142 4200 8143 4201 8143 4199 8143 4202 8144 4201 8144 4200 8144 4202 8145 4203 8145 4201 8145 4202 8146 4204 8146 4203 8146 4205 8147 4204 8147 4202 8147 4205 8148 4206 8148 4204 8148 4207 8149 4206 8149 4205 8149 4207 8150 4208 8150 4206 8150 4209 8151 4208 8151 4207 8151 4209 8152 4210 8152 4208 8152 4209 8153 4211 8153 4210 8153 4212 8154 4211 8154 4209 8154 4212 8155 4213 8155 4211 8155 4214 8156 4213 8156 4212 8156 4214 8157 4215 8157 4213 8157 4216 8158 4215 8158 4214 8158 4216 8159 4217 8159 4215 8159 4218 8160 4217 8160 4216 8160 4218 8161 4219 8161 4217 8161 4220 8162 4219 8162 4218 8162 4220 8163 4221 8163 4219 8163 4222 8164 4221 8164 4220 8164 4222 8165 4223 8165 4221 8165 4222 8166 4224 8166 4223 8166 4225 8167 4224 8167 4222 8167 4225 8168 4226 8168 4224 8168 4227 8169 4226 8169 4225 8169 4227 8170 4228 8170 4226 8170 4229 8171 4228 8171 4227 8171 4229 8172 4230 8172 4228 8172 4229 8173 4231 8173 4230 8173 4232 8174 4231 8174 4229 8174 4232 8175 4233 8175 4231 8175 4234 8176 4233 8176 4232 8176 4234 8177 4235 8177 4233 8177 4236 8178 4235 8178 4234 8178 4236 8179 4237 8179 4235 8179 4238 8180 4237 8180 4236 8180 4238 8181 4239 8181 4237 8181 4238 8182 4240 8182 4239 8182 4241 8183 4240 8183 4238 8183 4241 8184 4242 8184 4240 8184 4243 8185 4242 8185 4241 8185 4243 8186 4244 8186 4242 8186 4243 8187 4245 8187 4244 8187 4246 8188 4245 8188 4243 8188 4246 8189 4247 8189 4245 8189 4246 8190 4248 8190 4247 8190 4249 8191 4248 8191 4246 8191 4249 8192 4250 8192 4248 8192 4251 8193 4250 8193 4249 8193 4251 8194 4252 8194 4250 8194 4251 8195 4253 8195 4252 8195 4254 8196 4253 8196 4251 8196 4254 8197 4255 8197 4253 8197 4254 8198 4256 8198 4255 8198 4257 8199 4256 8199 4254 8199 4257 8200 4258 8200 4256 8200 4259 8201 4258 8201 4257 8201 4259 8202 4260 8202 4258 8202 4261 8203 4260 8203 4259 8203 4261 8204 4262 8204 4260 8204 4263 8205 4262 8205 4261 8205 4263 8206 4264 8206 4262 8206 4265 8207 4266 8207 4263 8207 4263 8208 4266 8208 4264 8208 4265 8209 4267 8209 4266 8209 4268 8210 4267 8210 4265 8210 4268 8211 4269 8211 4267 8211 4270 8212 4269 8212 4268 8212 4270 8213 4271 8213 4269 8213 4272 8214 4271 8214 4270 8214 4272 8215 4273 8215 4271 8215 4274 8216 4273 8216 4272 8216 4274 8217 4275 8217 4273 8217 4276 8218 4275 8218 4274 8218 4276 8219 4277 8219 4275 8219 4278 8220 4277 8220 4276 8220 4278 8221 4279 8221 4277 8221 4278 8222 4280 8222 4279 8222 4281 8223 4280 8223 4278 8223 4281 8224 4282 8224 4280 8224 4283 8225 4282 8225 4281 8225 4283 8226 4284 8226 4282 8226 4285 8227 4284 8227 4283 8227 4285 8228 4286 8228 4284 8228 4287 8229 4286 8229 4285 8229 4287 8230 4288 8230 4286 8230 4289 8231 4288 8231 4287 8231 4289 8232 4290 8232 4288 8232 4291 8233 4290 8233 4289 8233 4291 8234 4292 8234 4290 8234 4294 8235 4293 8235 4291 8235 4291 8236 4293 8236 4292 8236 4294 8237 4295 8237 4293 8237 4296 8238 4295 8238 4294 8238 4296 8239 4297 8239 4295 8239 4298 8240 4297 8240 4296 8240 4298 8241 4299 8241 4297 8241 4298 8242 4300 8242 4299 8242 4301 8243 4300 8243 4298 8243 4301 8244 4302 8244 4300 8244 4303 8245 4302 8245 4301 8245 4303 8246 4304 8246 4302 8246 4303 8247 4305 8247 4304 8247 4306 8248 4305 8248 4303 8248 4306 8249 4307 8249 4305 8249 4308 8250 4307 8250 4306 8250 4308 8251 4309 8251 4307 8251 4310 8252 4309 8252 4308 8252 4310 8253 4311 8253 4309 8253 4310 8254 4312 8254 4311 8254 4313 8255 4312 8255 4310 8255 4313 8256 4314 8256 4312 8256 4315 8257 4314 8257 4313 8257 4315 8258 4316 8258 4314 8258 4317 8259 4316 8259 4315 8259 4317 8260 4318 8260 4316 8260 4317 8261 4319 8261 4318 8261 4320 8262 4319 8262 4317 8262 4320 8263 4321 8263 4319 8263 4320 8264 4322 8264 4321 8264 4323 8265 4322 8265 4320 8265 4323 8266 4324 8266 4322 8266 4325 8267 4324 8267 4323 8267 4325 8268 4326 8268 4324 8268 4327 8269 4326 8269 4325 8269 4327 8270 4328 8270 4326 8270 4329 8271 4328 8271 4327 8271 4329 8272 4330 8272 4328 8272 4331 8273 4330 8273 4329 8273 4331 8274 4332 8274 4330 8274 4333 8275 4334 8275 4331 8275 4331 8276 4334 8276 4332 8276 4333 8277 4335 8277 4334 8277 4336 8278 4335 8278 4333 8278 4336 8279 4337 8279 4335 8279 4338 8280 4337 8280 4336 8280 4338 8281 4339 8281 4337 8281 4338 8282 4340 8282 4339 8282 4341 8283 4340 8283 4338 8283 4341 8284 4342 8284 4340 8284 4343 8285 4342 8285 4341 8285 4343 8286 4344 8286 4342 8286 4343 8287 4345 8287 4344 8287 4346 8288 4345 8288 4343 8288 4346 8289 4347 8289 4345 8289 4348 8290 4347 8290 4346 8290 4348 8291 4349 8291 4347 8291 4348 8292 4350 8292 4349 8292 4351 8293 4350 8293 4348 8293 4351 8294 4352 8294 4350 8294 4353 8295 4352 8295 4351 8295 4353 8296 4354 8296 4352 8296 4355 8297 4354 8297 4353 8297 4355 8298 4356 8298 4354 8298 4357 8299 4356 8299 4355 8299 4357 8300 4358 8300 4356 8300 4357 8301 4359 8301 4358 8301 4360 8302 4359 8302 4357 8302 4360 8303 4361 8303 4359 8303 4362 8304 4361 8304 4360 8304 4362 8305 4363 8305 4361 8305 4362 8306 4364 8306 4363 8306 4365 8307 4364 8307 4362 8307 4365 8308 4366 8308 4364 8308 4367 8309 4366 8309 4365 8309 4368 8310 4366 8310 4367 8310 4368 8311 4369 8311 4366 8311 4370 8312 4369 8312 4368 8312 4370 8313 4371 8313 4369 8313 4372 8314 4373 8314 4370 8314 4370 8315 4373 8315 4371 8315 4372 8316 4374 8316 4373 8316 4375 8317 4376 8317 4372 8317 4372 8318 4376 8318 4374 8318 4375 8319 4377 8319 4376 8319 4378 8320 4377 8320 4375 8320 4378 8321 4379 8321 4377 8321 4378 8322 4380 8322 4379 8322 4381 8323 4380 8323 4378 8323 4381 8324 4382 8324 4380 8324 4383 8325 4382 8325 4381 8325 4383 8326 4384 8326 4382 8326 4385 8327 4384 8327 4383 8327 4385 8328 4386 8328 4384 8328 4387 8329 4386 8329 4385 8329 4387 8330 4388 8330 4386 8330 4389 8331 4388 8331 4387 8331 4389 8332 4390 8332 4388 8332 4389 8333 4391 8333 4390 8333 4392 8334 4391 8334 4389 8334 4392 8335 4393 8335 4391 8335 4394 8336 4393 8336 4392 8336 4394 8337 4395 8337 4393 8337 4396 8338 4395 8338 4394 8338 4396 8339 4397 8339 4395 8339 4398 8340 4397 8340 4396 8340 4398 8341 4399 8341 4397 8341 4398 8342 4400 8342 4399 8342 4401 8343 4400 8343 4398 8343 4401 8344 4402 8344 4400 8344 4401 8345 4403 8345 4402 8345 4404 8346 4403 8346 4401 8346 4404 8347 4405 8347 4403 8347 4406 8348 4405 8348 4404 8348 4406 8349 4407 8349 4405 8349 4408 8350 4407 8350 4406 8350 4408 8351 4409 8351 4407 8351 4410 8352 4409 8352 4408 8352 4410 8353 4411 8353 4409 8353 4410 8354 4412 8354 4411 8354 4413 8355 4412 8355 4410 8355 4414 8356 4412 8356 4413 8356 4414 8357 4415 8357 4412 8357 4416 8358 4415 8358 4414 8358 4416 8359 4417 8359 4415 8359 4418 8360 4417 8360 4416 8360 4418 8361 4419 8361 4417 8361 4420 8362 4419 8362 4418 8362 4420 8363 4421 8363 4419 8363 4420 8364 4422 8364 4421 8364 4423 8365 4422 8365 4420 8365 4423 8366 4424 8366 4422 8366 4425 8367 4424 8367 4423 8367 4425 8368 4426 8368 4424 8368 4425 8369 4427 8369 4426 8369 4428 8370 4427 8370 4425 8370 4428 8371 4429 8371 4427 8371 4430 8372 4429 8372 4428 8372 4430 8373 4431 8373 4429 8373 4432 8374 4431 8374 4430 8374 4432 8375 4433 8375 4431 8375 4434 8376 4433 8376 4432 8376 4434 8377 4435 8377 4433 8377 4436 8378 4435 8378 4434 8378 4436 8379 4437 8379 4435 8379 4436 8380 4438 8380 4437 8380 4439 8381 4438 8381 4436 8381 4439 8382 4440 8382 4438 8382 4441 8383 4440 8383 4439 8383 4441 8384 4442 8384 4440 8384 4443 8385 4442 8385 4441 8385 4443 8386 4444 8386 4442 8386 4443 8387 4445 8387 4444 8387 4446 8388 4445 8388 4443 8388 4446 8389 4447 8389 4445 8389 4448 8390 4447 8390 4446 8390 4448 8391 4449 8391 4447 8391 4450 8392 4449 8392 4448 8392 4450 8393 4451 8393 4449 8393 4452 8394 4453 8394 4450 8394 4450 8395 4453 8395 4451 8395 4452 8396 4454 8396 4453 8396 4455 8397 4454 8397 4452 8397 4455 8398 4456 8398 4454 8398 4455 8399 4457 8399 4456 8399 4458 8400 4457 8400 4455 8400 4458 8401 4459 8401 4457 8401 4460 8402 4459 8402 4458 8402 4460 8403 4461 8403 4459 8403 4462 8404 4461 8404 4460 8404 4462 8405 4463 8405 4461 8405 4462 8406 4464 8406 4463 8406 4465 8407 4464 8407 4462 8407 4467 8408 4466 8408 4465 8408 4465 8409 4466 8409 4464 8409 4467 8410 4468 8410 4466 8410 4467 8411 4469 8411 4468 8411 4470 8412 4469 8412 4467 8412 4470 8413 4471 8413 4469 8413 4470 8414 4472 8414 4471 8414 4473 8415 4472 8415 4470 8415 4473 8416 4474 8416 4472 8416 4475 8417 4474 8417 4473 8417 4475 8418 4476 8418 4474 8418 4477 8419 4476 8419 4475 8419 4477 8420 4478 8420 4476 8420 4479 8421 4478 8421 4477 8421 4479 8422 4480 8422 4478 8422 4481 8423 4480 8423 4479 8423 4481 8424 4482 8424 4480 8424 4483 8425 4482 8425 4481 8425 4483 8426 4484 8426 4482 8426 4485 8427 4484 8427 4483 8427 4485 8428 4486 8428 4484 8428 4485 8429 4487 8429 4486 8429 4488 8430 4489 8430 4485 8430 4485 8431 4489 8431 4487 8431 4488 8432 4490 8432 4489 8432 4491 8433 4490 8433 4488 8433 4491 8434 4492 8434 4490 8434 4491 8435 4493 8435 4492 8435 4494 8436 4493 8436 4491 8436 4494 8437 4495 8437 4493 8437 4496 8438 4495 8438 4494 8438 4496 8439 4497 8439 4495 8439 4498 8440 4497 8440 4496 8440 4498 8441 4499 8441 4497 8441 4500 8442 4499 8442 4498 8442 4500 8443 4501 8443 4499 8443 4502 8444 4501 8444 4500 8444 4502 8445 4503 8445 4501 8445 4504 8446 4503 8446 4502 8446 4504 8447 4505 8447 4503 8447 4504 8448 4506 8448 4505 8448 4507 8449 4506 8449 4504 8449 4507 8450 4508 8450 4506 8450 4507 8451 4509 8451 4508 8451 4510 8452 4509 8452 4507 8452 4510 8453 4511 8453 4509 8453 4512 8454 4511 8454 4510 8454 4512 8455 4513 8455 4511 8455 4514 8456 4513 8456 4512 8456 4514 8457 4515 8457 4513 8457 4514 8458 4516 8458 4515 8458 4517 8459 4516 8459 4514 8459 4517 8460 4518 8460 4516 8460 4519 8461 4518 8461 4517 8461 4519 8462 4520 8462 4518 8462 4521 8463 4520 8463 4519 8463 4521 8464 4522 8464 4520 8464 4521 8465 4523 8465 4522 8465 4524 8466 4523 8466 4521 8466 4524 8467 4525 8467 4523 8467 4526 8468 4525 8468 4524 8468 4526 8469 4527 8469 4525 8469 4528 8470 4527 8470 4526 8470 4528 8471 4529 8471 4527 8471 4528 8472 4530 8472 4529 8472 4531 8473 4530 8473 4528 8473 4531 8474 4532 8474 4530 8474 4533 8475 4532 8475 4531 8475 4533 8476 4534 8476 4532 8476 4535 8477 4534 8477 4533 8477 4535 8478 4536 8478 4534 8478 4537 8479 4536 8479 4535 8479 4537 8480 4538 8480 4536 8480 4539 8481 4538 8481 4537 8481 4539 8482 4540 8482 4538 8482 4539 8483 4541 8483 4540 8483 4542 8484 4541 8484 4539 8484 4542 8485 4543 8485 4541 8485 4544 8486 4543 8486 4542 8486 4544 8487 4545 8487 4543 8487 4546 8488 4545 8488 4544 8488 4546 8489 4547 8489 4545 8489 4546 8490 4548 8490 4547 8490 4546 8491 4549 8491 4548 8491 4550 8492 4549 8492 4546 8492 4550 8493 4551 8493 4549 8493 4552 8494 4551 8494 4550 8494 4552 8495 4553 8495 4551 8495 4554 8496 4553 8496 4552 8496 4554 8497 4555 8497 4553 8497 4556 8498 4555 8498 4554 8498 4556 8499 4557 8499 4555 8499 4558 8500 4557 8500 4556 8500 4558 8501 4559 8501 4557 8501 4560 8502 4559 8502 4558 8502 4560 8503 4561 8503 4559 8503 4562 8504 4561 8504 4560 8504 4562 8505 4563 8505 4561 8505 4564 8506 4563 8506 4562 8506 4564 8507 4565 8507 4563 8507 4566 8508 4565 8508 4564 8508 4566 8509 4567 8509 4565 8509 4568 8510 4567 8510 4566 8510 4568 8511 4569 8511 4567 8511 4568 8512 4570 8512 4569 8512 4571 8513 4570 8513 4568 8513 4571 8514 4572 8514 4570 8514 4571 8515 4573 8515 4572 8515 4574 8516 4573 8516 4571 8516 4575 8517 4573 8517 4574 8517 4575 8518 4576 8518 4573 8518 4577 8519 4576 8519 4575 8519 4577 8520 4578 8520 4576 8520 4579 8521 4578 8521 4577 8521 4579 8522 4580 8522 4578 8522 4579 8523 4581 8523 4580 8523 4582 8524 4581 8524 4579 8524 4582 8525 4583 8525 4581 8525 4584 8526 4583 8526 4582 8526 4584 8527 4585 8527 4583 8527 4586 8528 4585 8528 4584 8528 4586 8529 4587 8529 4585 8529 4588 8530 4587 8530 4586 8530 4588 8531 4589 8531 4587 8531 4588 8532 4590 8532 4589 8532 4591 8533 4590 8533 4588 8533 4591 8534 4592 8534 4590 8534 4593 8535 4592 8535 4591 8535 4593 8536 4594 8536 4592 8536 4595 8537 4594 8537 4593 8537 4595 8538 4596 8538 4594 8538 4595 8539 4597 8539 4596 8539 4598 8540 4597 8540 4595 8540 4598 8541 4599 8541 4597 8541 4598 8542 4600 8542 4599 8542 4601 8543 4600 8543 4598 8543 4602 8544 4600 8544 4601 8544 4602 8545 4603 8545 4600 8545 4602 8546 4604 8546 4603 8546 4605 8547 4604 8547 4602 8547 4605 8548 4606 8548 4604 8548 4607 8549 4606 8549 4605 8549 4607 8550 4608 8550 4606 8550 4609 8551 4610 8551 4607 8551 4607 8552 4610 8552 4608 8552 4609 8553 4611 8553 4610 8553 4612 8554 4611 8554 4609 8554 4612 8555 4613 8555 4611 8555 4614 8556 4613 8556 4612 8556 4614 8557 4615 8557 4613 8557 4616 8558 4615 8558 4614 8558 4616 8559 4617 8559 4615 8559 4618 8560 4617 8560 4616 8560 4618 8561 4619 8561 4617 8561 4618 8562 4620 8562 4619 8562 4621 8563 4620 8563 4618 8563 4621 8564 4622 8564 4620 8564 4623 8565 4622 8565 4621 8565 4623 8566 4624 8566 4622 8566 4625 8567 4624 8567 4623 8567 4625 8568 4626 8568 4624 8568 4627 8569 4626 8569 4625 8569 4627 8570 4628 8570 4626 8570 4629 8571 4628 8571 4627 8571 4630 8572 4631 8572 4629 8572 4629 8573 4631 8573 4628 8573 4630 8574 4632 8574 4631 8574 4633 8575 4632 8575 4630 8575 4633 8576 4634 8576 4632 8576 4635 8577 4634 8577 4633 8577 4635 8578 4636 8578 4634 8578 4635 8579 4637 8579 4636 8579 4635 8580 4638 8580 4637 8580 4639 8581 4638 8581 4635 8581 4639 8582 4640 8582 4638 8582 4641 8583 4640 8583 4639 8583 4641 8584 4642 8584 4640 8584 4641 8585 4643 8585 4642 8585 4644 8586 4643 8586 4641 8586 4644 8587 4645 8587 4643 8587 4646 8588 4645 8588 4644 8588 4646 8589 4647 8589 4645 8589 4648 8590 4647 8590 4646 8590 4648 8591 4649 8591 4647 8591 4650 8592 4649 8592 4648 8592 4650 8593 4651 8593 4649 8593 4652 8594 4651 8594 4650 8594 4652 8595 4653 8595 4651 8595 4652 8596 4654 8596 4653 8596 4655 8597 4654 8597 4652 8597 4655 8598 4656 8598 4654 8598 4657 8599 4656 8599 4655 8599 4657 8600 4658 8600 4656 8600 4657 8601 4659 8601 4658 8601 4660 8602 4659 8602 4657 8602 4660 8603 4661 8603 4659 8603 4662 8604 4661 8604 4660 8604 4662 8605 4663 8605 4661 8605 4662 8606 4664 8606 4663 8606 4665 8607 4664 8607 4662 8607 4665 8608 4666 8608 4664 8608 4667 8609 4666 8609 4665 8609 4667 8610 4668 8610 4666 8610 4667 8611 4184 8611 4668 8611 4667 8612 4182 8612 4184 8612 4669 8613 4182 8613 4667 8613 4669 8614 4178 8614 4182 8614 4670 8615 4178 8615 4669 8615 4671 8616 4178 8616 4670 8616 4671 8617 4174 8617 4178 8617 4672 8618 4200 8618 4198 8618 4673 8619 4200 8619 4672 8619 4202 8620 4200 8620 4673 8620 4674 8621 4202 8621 4673 8621 4205 8622 4202 8622 4674 8622 4675 8623 4205 8623 4674 8623 4207 8624 4205 8624 4675 8624 4676 8625 4207 8625 4675 8625 4209 8626 4207 8626 4676 8626 4677 8627 4209 8627 4676 8627 4212 8628 4209 8628 4677 8628 4678 8629 4212 8629 4677 8629 4214 8630 4212 8630 4678 8630 4679 8631 4214 8631 4678 8631 4216 8632 4214 8632 4679 8632 4680 8633 4216 8633 4679 8633 4218 8634 4216 8634 4680 8634 4681 8635 4218 8635 4680 8635 4220 8636 4218 8636 4681 8636 4222 8637 4220 8637 4681 8637 4682 8638 4222 8638 4681 8638 4225 8639 4222 8639 4682 8639 4227 8640 4225 8640 4683 8640 4684 8641 4227 8641 4683 8641 4229 8642 4227 8642 4684 8642 4232 8643 4229 8643 4684 8643 4685 8644 4232 8644 4684 8644 4234 8645 4232 8645 4685 8645 4686 8646 4234 8646 4685 8646 4236 8647 4234 8647 4686 8647 4687 8648 4236 8648 4686 8648 4238 8649 4236 8649 4687 8649 4241 8650 4238 8650 4687 8650 4688 8651 4241 8651 4687 8651 4689 8652 4241 8652 4688 8652 4243 8653 4241 8653 4689 8653 4690 8654 4243 8654 4689 8654 4246 8655 4243 8655 4690 8655 4691 8656 4246 8656 4690 8656 4249 8657 4246 8657 4691 8657 4692 8658 4249 8658 4691 8658 4251 8659 4249 8659 4692 8659 4693 8660 4251 8660 4692 8660 4254 8661 4251 8661 4693 8661 4694 8662 4254 8662 4693 8662 4257 8663 4254 8663 4694 8663 4695 8664 4257 8664 4694 8664 4259 8665 4257 8665 4695 8665 4696 8666 4259 8666 4695 8666 4259 8667 4696 8667 4697 8667 4261 8668 4259 8668 4697 8668 4263 8669 4261 8669 4697 8669 4698 8670 4263 8670 4697 8670 4699 8671 4263 8671 4698 8671 4265 8672 4263 8672 4699 8672 4700 8673 4265 8673 4699 8673 4268 8674 4265 8674 4700 8674 4270 8675 4268 8675 4700 8675 4272 8676 4270 8676 4701 8676 4274 8677 4272 8677 4701 8677 4702 8678 4274 8678 4701 8678 4276 8679 4274 8679 4702 8679 4703 8680 4276 8680 4702 8680 4278 8681 4276 8681 4703 8681 4704 8682 4278 8682 4703 8682 4281 8683 4278 8683 4704 8683 4283 8684 4281 8684 4704 8684 4705 8685 4283 8685 4704 8685 4285 8686 4283 8686 4705 8686 4706 8687 4287 8687 4285 8687 4289 8688 4287 8688 4706 8688 4707 8689 4289 8689 4706 8689 4291 8690 4289 8690 4707 8690 4708 8691 4291 8691 4707 8691 4294 8692 4291 8692 4708 8692 4709 8693 4294 8693 4708 8693 4296 8694 4294 8694 4709 8694 4710 8695 4296 8695 4709 8695 4298 8696 4296 8696 4710 8696 4711 8697 4298 8697 4710 8697 4301 8698 4298 8698 4711 8698 4712 8699 4301 8699 4711 8699 4303 8700 4301 8700 4712 8700 4713 8701 4303 8701 4712 8701 4306 8702 4303 8702 4713 8702 4714 8703 4306 8703 4713 8703 4308 8704 4306 8704 4714 8704 4715 8705 4308 8705 4714 8705 4310 8706 4308 8706 4715 8706 4716 8707 4310 8707 4715 8707 4313 8708 4310 8708 4716 8708 4717 8709 4313 8709 4716 8709 4315 8710 4313 8710 4717 8710 4718 8711 4315 8711 4717 8711 4317 8712 4315 8712 4718 8712 4320 8713 4317 8713 4718 8713 4719 8714 4320 8714 4718 8714 4323 8715 4320 8715 4719 8715 4720 8716 4323 8716 4719 8716 4325 8717 4323 8717 4720 8717 4721 8718 4325 8718 4720 8718 4327 8719 4325 8719 4721 8719 4722 8720 4327 8720 4721 8720 4329 8721 4327 8721 4722 8721 4331 8722 4329 8722 4722 8722 4723 8723 4331 8723 4722 8723 4333 8724 4331 8724 4723 8724 4724 8725 4333 8725 4723 8725 4336 8726 4333 8726 4724 8726 4725 8727 4336 8727 4724 8727 4338 8728 4336 8728 4725 8728 4341 8729 4338 8729 4725 8729 4726 8730 4341 8730 4725 8730 4343 8731 4341 8731 4726 8731 4727 8732 4343 8732 4726 8732 4346 8733 4343 8733 4727 8733 4728 8734 4346 8734 4727 8734 4348 8735 4346 8735 4728 8735 4729 8736 4348 8736 4728 8736 4351 8737 4348 8737 4729 8737 4353 8738 4351 8738 4729 8738 4730 8739 4353 8739 4729 8739 4731 8740 4353 8740 4730 8740 4355 8741 4353 8741 4731 8741 4732 8742 4355 8742 4731 8742 4357 8743 4355 8743 4732 8743 4733 8744 4357 8744 4732 8744 4360 8745 4357 8745 4733 8745 4734 8746 4360 8746 4733 8746 4362 8747 4360 8747 4734 8747 4735 8748 4362 8748 4734 8748 4736 8749 4362 8749 4735 8749 4365 8750 4362 8750 4736 8750 4367 8751 4365 8751 4736 8751 4737 8752 4367 8752 4736 8752 4368 8753 4367 8753 4737 8753 4738 8754 4368 8754 4737 8754 4370 8755 4368 8755 4738 8755 4739 8756 4370 8756 4738 8756 4372 8757 4370 8757 4739 8757 4740 8758 4372 8758 4739 8758 4375 8759 4372 8759 4740 8759 4741 8760 4375 8760 4740 8760 4378 8761 4375 8761 4741 8761 4742 8762 4378 8762 4741 8762 4381 8763 4378 8763 4742 8763 4743 8764 4381 8764 4742 8764 4383 8765 4381 8765 4743 8765 4385 8766 4383 8766 4743 8766 4744 8767 4387 8767 4385 8767 4389 8768 4387 8768 4744 8768 4745 8769 4389 8769 4744 8769 4392 8770 4389 8770 4745 8770 4746 8771 4392 8771 4745 8771 4394 8772 4392 8772 4746 8772 4396 8773 4394 8773 4746 8773 4747 8774 4396 8774 4746 8774 4398 8775 4396 8775 4747 8775 4748 8776 4398 8776 4747 8776 4749 8777 4398 8777 4748 8777 4401 8778 4398 8778 4749 8778 4750 8779 4401 8779 4749 8779 4404 8780 4401 8780 4750 8780 4406 8781 4404 8781 4750 8781 4751 8782 4406 8782 4750 8782 4408 8783 4406 8783 4751 8783 4410 8784 4408 8784 4752 8784 4413 8785 4410 8785 4752 8785 4753 8786 4414 8786 4413 8786 4416 8787 4414 8787 4753 8787 4754 8788 4416 8788 4753 8788 4418 8789 4416 8789 4754 8789 4755 8790 4418 8790 4754 8790 4420 8791 4418 8791 4755 8791 4756 8792 4420 8792 4755 8792 4423 8793 4420 8793 4756 8793 4757 8794 4423 8794 4756 8794 4425 8795 4423 8795 4757 8795 4758 8796 4425 8796 4757 8796 4428 8797 4425 8797 4758 8797 4759 8798 4428 8798 4758 8798 4430 8799 4428 8799 4759 8799 4432 8800 4430 8800 4759 8800 4760 8801 4432 8801 4759 8801 4761 8802 4432 8802 4760 8802 4434 8803 4432 8803 4761 8803 4762 8804 4434 8804 4761 8804 4436 8805 4434 8805 4762 8805 4763 8806 4436 8806 4762 8806 4439 8807 4436 8807 4763 8807 4764 8808 4439 8808 4763 8808 4441 8809 4439 8809 4764 8809 4765 8810 4441 8810 4764 8810 4443 8811 4441 8811 4765 8811 4446 8812 4443 8812 4765 8812 4766 8813 4446 8813 4765 8813 4448 8814 4446 8814 4766 8814 4767 8815 4448 8815 4766 8815 4450 8816 4448 8816 4767 8816 4768 8817 4450 8817 4767 8817 4452 8818 4450 8818 4768 8818 4769 8819 4452 8819 4768 8819 4455 8820 4452 8820 4769 8820 4770 8821 4455 8821 4769 8821 4458 8822 4455 8822 4770 8822 4771 8823 4458 8823 4770 8823 4460 8824 4458 8824 4771 8824 4772 8825 4460 8825 4771 8825 4462 8826 4460 8826 4772 8826 4773 8827 4462 8827 4772 8827 4465 8828 4462 8828 4773 8828 4467 8829 4465 8829 4773 8829 4774 8830 4467 8830 4773 8830 4775 8831 4467 8831 4774 8831 4470 8832 4467 8832 4775 8832 4776 8833 4470 8833 4775 8833 4473 8834 4470 8834 4776 8834 4473 8835 4776 8835 4777 8835 4475 8836 4473 8836 4777 8836 4477 8837 4475 8837 4777 8837 4778 8838 4479 8838 4477 8838 4481 8839 4479 8839 4778 8839 4779 8840 4481 8840 4778 8840 4483 8841 4481 8841 4779 8841 4780 8842 4483 8842 4779 8842 4485 8843 4483 8843 4780 8843 4781 8844 4485 8844 4780 8844 4488 8845 4485 8845 4781 8845 4782 8846 4488 8846 4781 8846 4491 8847 4488 8847 4782 8847 4783 8848 4491 8848 4782 8848 4494 8849 4491 8849 4783 8849 4784 8850 4494 8850 4783 8850 4496 8851 4494 8851 4784 8851 4785 8852 4496 8852 4784 8852 4498 8853 4496 8853 4785 8853 4786 8854 4498 8854 4785 8854 4500 8855 4498 8855 4786 8855 4787 8856 4500 8856 4786 8856 4502 8857 4500 8857 4787 8857 4788 8858 4502 8858 4787 8858 4504 8859 4502 8859 4788 8859 4507 8860 4504 8860 4788 8860 4789 8861 4507 8861 4788 8861 4790 8862 4507 8862 4789 8862 4510 8863 4507 8863 4790 8863 4791 8864 4510 8864 4790 8864 4512 8865 4510 8865 4791 8865 4792 8866 4512 8866 4791 8866 4514 8867 4512 8867 4792 8867 4793 8868 4514 8868 4792 8868 4517 8869 4514 8869 4793 8869 4794 8870 4517 8870 4793 8870 4519 8871 4517 8871 4794 8871 4521 8872 4519 8872 4794 8872 4795 8873 4521 8873 4794 8873 4796 8874 4521 8874 4795 8874 4524 8875 4521 8875 4796 8875 4526 8876 4524 8876 4796 8876 4797 8877 4526 8877 4796 8877 4798 8878 4526 8878 4797 8878 4528 8879 4526 8879 4798 8879 4799 8880 4528 8880 4798 8880 4531 8881 4528 8881 4799 8881 4800 8882 4531 8882 4799 8882 4533 8883 4531 8883 4800 8883 4801 8884 4533 8884 4800 8884 4535 8885 4533 8885 4801 8885 4802 8886 4535 8886 4801 8886 4537 8887 4535 8887 4802 8887 4803 8888 4537 8888 4802 8888 4539 8889 4537 8889 4803 8889 4804 8890 4539 8890 4803 8890 4542 8891 4539 8891 4804 8891 4805 8892 4542 8892 4804 8892 4544 8893 4542 8893 4805 8893 4806 8894 4544 8894 4805 8894 4546 8895 4544 8895 4806 8895 4807 8896 4546 8896 4806 8896 4550 8897 4546 8897 4807 8897 4552 8898 4550 8898 4807 8898 4554 8899 4552 8899 4808 8899 4556 8900 4554 8900 4808 8900 4809 8901 4556 8901 4808 8901 4558 8902 4556 8902 4809 8902 4810 8903 4558 8903 4809 8903 4560 8904 4558 8904 4810 8904 4562 8905 4560 8905 4810 8905 4811 8906 4562 8906 4810 8906 4564 8907 4562 8907 4811 8907 4812 8908 4564 8908 4811 8908 4813 8909 4564 8909 4812 8909 4566 8910 4564 8910 4813 8910 4814 8911 4566 8911 4813 8911 4568 8912 4566 8912 4814 8912 4815 8913 4568 8913 4814 8913 4571 8914 4568 8914 4815 8914 4816 8915 4571 8915 4815 8915 4574 8916 4571 8916 4816 8916 4817 8917 4574 8917 4816 8917 4575 8918 4574 8918 4817 8918 4818 8919 4575 8919 4817 8919 4577 8920 4575 8920 4818 8920 4819 8921 4577 8921 4818 8921 4579 8922 4577 8922 4819 8922 4820 8923 4579 8923 4819 8923 4582 8924 4579 8924 4820 8924 4584 8925 4582 8925 4820 8925 4821 8926 4584 8926 4820 8926 4822 8927 4584 8927 4821 8927 4586 8928 4584 8928 4822 8928 4588 8929 4586 8929 4822 8929 4823 8930 4588 8930 4822 8930 4591 8931 4588 8931 4823 8931 4824 8932 4591 8932 4823 8932 4593 8933 4591 8933 4824 8933 4825 8934 4593 8934 4824 8934 4595 8935 4593 8935 4825 8935 4826 8936 4595 8936 4825 8936 4598 8937 4595 8937 4826 8937 4827 8938 4598 8938 4826 8938 4601 8939 4598 8939 4827 8939 4602 8940 4601 8940 4827 8940 4828 8941 4602 8941 4827 8941 4829 8942 4602 8942 4828 8942 4605 8943 4602 8943 4829 8943 4605 8944 4829 8944 4830 8944 4607 8945 4605 8945 4830 8945 4609 8946 4607 8946 4830 8946 4831 8947 4609 8947 4830 8947 4612 8948 4609 8948 4831 8948 4614 8949 4612 8949 4831 8949 4616 8950 4614 8950 4832 8950 4833 8951 4616 8951 4832 8951 4618 8952 4616 8952 4833 8952 4621 8953 4618 8953 4833 8953 4834 8954 4621 8954 4833 8954 4623 8955 4621 8955 4834 8955 4835 8956 4623 8956 4834 8956 4625 8957 4623 8957 4835 8957 4627 8958 4625 8958 4835 8958 4629 8959 4627 8959 4836 8959 4630 8960 4629 8960 4836 8960 4837 8961 4630 8961 4836 8961 4838 8962 4630 8962 4837 8962 4633 8963 4630 8963 4838 8963 4839 8964 4633 8964 4838 8964 4635 8965 4633 8965 4839 8965 4840 8966 4635 8966 4839 8966 4639 8967 4635 8967 4840 8967 4841 8968 4639 8968 4840 8968 4641 8969 4639 8969 4841 8969 4842 8970 4641 8970 4841 8970 4644 8971 4641 8971 4842 8971 4843 8972 4644 8972 4842 8972 4646 8973 4644 8973 4843 8973 4648 8974 4843 8974 4844 8974 4648 8975 4646 8975 4843 8975 4650 8976 4648 8976 4844 8976 4845 8977 4650 8977 4844 8977 4652 8978 4650 8978 4845 8978 4846 8979 4652 8979 4845 8979 4655 8980 4652 8980 4846 8980 4847 8981 4655 8981 4846 8981 4657 8982 4655 8982 4847 8982 4660 8983 4657 8983 4847 8983 4848 8984 4660 8984 4847 8984 4662 8985 4660 8985 4848 8985 4849 8986 4662 8986 4848 8986 4665 8987 4662 8987 4849 8987 4850 8988 4665 8988 4849 8988 4667 8989 4665 8989 4850 8989 4851 8990 4667 8990 4850 8990 4852 8991 4667 8991 4851 8991 4669 8992 4667 8992 4852 8992 4853 8993 4669 8993 4852 8993 4670 8994 4669 8994 4853 8994 4671 8995 4670 8995 4853 8995 4854 8996 4671 8996 4853 8996 4855 8997 4671 8997 4854 8997 4174 8998 4671 8998 4855 8998 4175 8999 4174 8999 4855 8999 4856 9000 4175 9000 4855 9000 4179 9001 4175 9001 4856 9001 4857 9002 4674 9002 4673 9002 4859 9003 4674 9003 4857 9003 4859 9004 4675 9004 4674 9004 4859 9005 4676 9005 4675 9005 4858 9006 4676 9006 4859 9006 4860 9007 4676 9007 4858 9007 4860 9008 4677 9008 4676 9008 4861 9009 4677 9009 4860 9009 4861 9010 4678 9010 4677 9010 4862 9011 4678 9011 4861 9011 4189 9012 4679 9012 4862 9012 4862 9013 4679 9013 4678 9013 4190 9014 4679 9014 4189 9014 4190 9015 4680 9015 4679 9015 4193 9016 4680 9016 4190 9016 4193 9017 4681 9017 4680 9017 4195 9018 4681 9018 4193 9018 4195 9019 4682 9019 4681 9019 4863 9020 4682 9020 4195 9020 4863 9021 4225 9021 4682 9021 4199 9022 4225 9022 4863 9022 4199 9023 4683 9023 4225 9023 4199 9024 4684 9024 4683 9024 4201 9025 4684 9025 4199 9025 4203 9026 4684 9026 4201 9026 4203 9027 4685 9027 4684 9027 4204 9028 4685 9028 4203 9028 4204 9029 4686 9029 4685 9029 4206 9030 4686 9030 4204 9030 4206 9031 4687 9031 4686 9031 4208 9032 4687 9032 4206 9032 4210 9033 4687 9033 4208 9033 4210 9034 4688 9034 4687 9034 4211 9035 4688 9035 4210 9035 4211 9036 4689 9036 4688 9036 4864 9037 4689 9037 4211 9037 4213 9038 4689 9038 4864 9038 4213 9039 4690 9039 4689 9039 4865 9040 4690 9040 4213 9040 4865 9041 4691 9041 4690 9041 4217 9042 4691 9042 4865 9042 4217 9043 4692 9043 4691 9043 4219 9044 4692 9044 4217 9044 4221 9045 4692 9045 4219 9045 4221 9046 4693 9046 4692 9046 4223 9047 4693 9047 4221 9047 4223 9048 4694 9048 4693 9048 4226 9049 4694 9049 4223 9049 4226 9050 4695 9050 4694 9050 4228 9051 4695 9051 4226 9051 4228 9052 4696 9052 4695 9052 4230 9053 4696 9053 4228 9053 4230 9054 4697 9054 4696 9054 4233 9055 4697 9055 4230 9055 4235 9056 4697 9056 4233 9056 4235 9057 4698 9057 4697 9057 4237 9058 4698 9058 4235 9058 4237 9059 4699 9059 4698 9059 4239 9060 4699 9060 4237 9060 4239 9061 4700 9061 4699 9061 4240 9062 4700 9062 4239 9062 4240 9063 4270 9063 4700 9063 4242 9064 4270 9064 4240 9064 4242 9065 4701 9065 4270 9065 4245 9066 4701 9066 4242 9066 4245 9067 4702 9067 4701 9067 4247 9068 4702 9068 4245 9068 4248 9069 4702 9069 4247 9069 4248 9070 4703 9070 4702 9070 4250 9071 4703 9071 4248 9071 4252 9072 4704 9072 4250 9072 4250 9073 4704 9073 4703 9073 4253 9074 4704 9074 4252 9074 4253 9075 4705 9075 4704 9075 4255 9076 4705 9076 4253 9076 4255 9077 4285 9077 4705 9077 4256 9078 4285 9078 4255 9078 4258 9079 4706 9079 4256 9079 4256 9080 4706 9080 4285 9080 4866 9081 4706 9081 4258 9081 4866 9082 4707 9082 4706 9082 4867 9083 4707 9083 4866 9083 4868 9084 4707 9084 4867 9084 4868 9085 4708 9085 4707 9085 4868 9086 4709 9086 4708 9086 4264 9087 4709 9087 4868 9087 4266 9088 4709 9088 4264 9088 4266 9089 4710 9089 4709 9089 4267 9090 4710 9090 4266 9090 4267 9091 4711 9091 4710 9091 4269 9092 4711 9092 4267 9092 4869 9093 4711 9093 4269 9093 4869 9094 4712 9094 4711 9094 4869 9095 4713 9095 4712 9095 4275 9096 4713 9096 4869 9096 4275 9097 4714 9097 4713 9097 4277 9098 4714 9098 4275 9098 4279 9099 4715 9099 4277 9099 4277 9100 4715 9100 4714 9100 4280 9101 4715 9101 4279 9101 4280 9102 4716 9102 4715 9102 4282 9103 4716 9103 4280 9103 4284 9104 4716 9104 4282 9104 4284 9105 4717 9105 4716 9105 4286 9106 4717 9106 4284 9106 4286 9107 4718 9107 4717 9107 4288 9108 4718 9108 4286 9108 4290 9109 4718 9109 4288 9109 4290 9110 4719 9110 4718 9110 4870 9111 4719 9111 4290 9111 4870 9112 4720 9112 4719 9112 4293 9113 4720 9113 4870 9113 4295 9114 4720 9114 4293 9114 4295 9115 4721 9115 4720 9115 4297 9116 4721 9116 4295 9116 4299 9117 4721 9117 4297 9117 4299 9118 4722 9118 4721 9118 4300 9119 4722 9119 4299 9119 4302 9120 4722 9120 4300 9120 4302 9121 4723 9121 4722 9121 4304 9122 4723 9122 4302 9122 4304 9123 4724 9123 4723 9123 4305 9124 4724 9124 4304 9124 4305 9125 4725 9125 4724 9125 4307 9126 4725 9126 4305 9126 4309 9127 4725 9127 4307 9127 4309 9128 4726 9128 4725 9128 4311 9129 4726 9129 4309 9129 4312 9130 4726 9130 4311 9130 4312 9131 4727 9131 4726 9131 4314 9132 4727 9132 4312 9132 4316 9133 4727 9133 4314 9133 4316 9134 4728 9134 4727 9134 4318 9135 4728 9135 4316 9135 4318 9136 4729 9136 4728 9136 4319 9137 4729 9137 4318 9137 4321 9138 4729 9138 4319 9138 4321 9139 4730 9139 4729 9139 4871 9140 4730 9140 4321 9140 4871 9141 4731 9141 4730 9141 4324 9142 4731 9142 4871 9142 4326 9143 4731 9143 4324 9143 4326 9144 4732 9144 4731 9144 4328 9145 4732 9145 4326 9145 4328 9146 4733 9146 4732 9146 4330 9147 4733 9147 4328 9147 4330 9148 4734 9148 4733 9148 4332 9149 4734 9149 4330 9149 4332 9150 4735 9150 4734 9150 4334 9151 4735 9151 4332 9151 4335 9152 4735 9152 4334 9152 4335 9153 4736 9153 4735 9153 4337 9154 4736 9154 4335 9154 4339 9155 4736 9155 4337 9155 4339 9156 4737 9156 4736 9156 4340 9157 4737 9157 4339 9157 4340 9158 4738 9158 4737 9158 4344 9159 4738 9159 4340 9159 4345 9160 4739 9160 4344 9160 4344 9161 4739 9161 4738 9161 4347 9162 4739 9162 4345 9162 4347 9163 4740 9163 4739 9163 4349 9164 4740 9164 4347 9164 4349 9165 4741 9165 4740 9165 4350 9166 4741 9166 4349 9166 4350 9167 4742 9167 4741 9167 4352 9168 4742 9168 4350 9168 4354 9169 4742 9169 4352 9169 4354 9170 4743 9170 4742 9170 4356 9171 4743 9171 4354 9171 4358 9172 4743 9172 4356 9172 4358 9173 4385 9173 4743 9173 4358 9174 4744 9174 4385 9174 4359 9175 4744 9175 4358 9175 4361 9176 4744 9176 4359 9176 4361 9177 4745 9177 4744 9177 4363 9178 4745 9178 4361 9178 4363 9179 4746 9179 4745 9179 4364 9180 4746 9180 4363 9180 4872 9181 4746 9181 4364 9181 4872 9182 4747 9182 4746 9182 4873 9183 4747 9183 4872 9183 4873 9184 4748 9184 4747 9184 4371 9185 4748 9185 4873 9185 4371 9186 4749 9186 4748 9186 4373 9187 4749 9187 4371 9187 4373 9188 4750 9188 4749 9188 4374 9189 4750 9189 4373 9189 4376 9190 4750 9190 4374 9190 4376 9191 4751 9191 4750 9191 4377 9192 4751 9192 4376 9192 4377 9193 4408 9193 4751 9193 4379 9194 4408 9194 4377 9194 4379 9195 4752 9195 4408 9195 4380 9196 4752 9196 4379 9196 4382 9197 4752 9197 4380 9197 4382 9198 4413 9198 4752 9198 4384 9199 4413 9199 4382 9199 4384 9200 4753 9200 4413 9200 4386 9201 4753 9201 4384 9201 4386 9202 4754 9202 4753 9202 4388 9203 4754 9203 4386 9203 4388 9204 4755 9204 4754 9204 4390 9205 4755 9205 4388 9205 4391 9206 4755 9206 4390 9206 4391 9207 4756 9207 4755 9207 4393 9208 4756 9208 4391 9208 4395 9209 4756 9209 4393 9209 4395 9210 4757 9210 4756 9210 4397 9211 4757 9211 4395 9211 4397 9212 4758 9212 4757 9212 4399 9213 4758 9213 4397 9213 4399 9214 4759 9214 4758 9214 4400 9215 4759 9215 4399 9215 4402 9216 4759 9216 4400 9216 4402 9217 4760 9217 4759 9217 4403 9218 4760 9218 4402 9218 4403 9219 4761 9219 4760 9219 4405 9220 4761 9220 4403 9220 4405 9221 4762 9221 4761 9221 4407 9222 4762 9222 4405 9222 4407 9223 4763 9223 4762 9223 4409 9224 4763 9224 4407 9224 4411 9225 4763 9225 4409 9225 4411 9226 4764 9226 4763 9226 4412 9227 4764 9227 4411 9227 4412 9228 4765 9228 4764 9228 4415 9229 4765 9229 4412 9229 4415 9230 4766 9230 4765 9230 4874 9231 4766 9231 4415 9231 4417 9232 4766 9232 4874 9232 4417 9233 4767 9233 4766 9233 4419 9234 4767 9234 4417 9234 4419 9235 4768 9235 4767 9235 4421 9236 4768 9236 4419 9236 4424 9237 4768 9237 4421 9237 4424 9238 4769 9238 4768 9238 4426 9239 4769 9239 4424 9239 4426 9240 4770 9240 4769 9240 4427 9241 4770 9241 4426 9241 4429 9242 4770 9242 4427 9242 4429 9243 4771 9243 4770 9243 4431 9244 4771 9244 4429 9244 4431 9245 4772 9245 4771 9245 4433 9246 4772 9246 4431 9246 4435 9247 4772 9247 4433 9247 4435 9248 4773 9248 4772 9248 4437 9249 4773 9249 4435 9249 4438 9250 4773 9250 4437 9250 4438 9251 4774 9251 4773 9251 4440 9252 4774 9252 4438 9252 4440 9253 4775 9253 4774 9253 4442 9254 4775 9254 4440 9254 4442 9255 4776 9255 4775 9255 4875 9256 4776 9256 4442 9256 4875 9257 4777 9257 4776 9257 4876 9258 4777 9258 4875 9258 4877 9259 4777 9259 4876 9259 4877 9260 4477 9260 4777 9260 4449 9261 4477 9261 4877 9261 4449 9262 4778 9262 4477 9262 4451 9263 4778 9263 4449 9263 4451 9264 4779 9264 4778 9264 4453 9265 4779 9265 4451 9265 4454 9266 4779 9266 4453 9266 4456 9267 4779 9267 4454 9267 4456 9268 4780 9268 4779 9268 4457 9269 4780 9269 4456 9269 4457 9270 4781 9270 4780 9270 4459 9271 4781 9271 4457 9271 4459 9272 4782 9272 4781 9272 4461 9273 4782 9273 4459 9273 4461 9274 4783 9274 4782 9274 4463 9275 4783 9275 4461 9275 4464 9276 4783 9276 4463 9276 4464 9277 4784 9277 4783 9277 4466 9278 4784 9278 4464 9278 4466 9279 4785 9279 4784 9279 4468 9280 4785 9280 4466 9280 4468 9281 4786 9281 4785 9281 4469 9282 4786 9282 4468 9282 4471 9283 4786 9283 4469 9283 4471 9284 4787 9284 4786 9284 4878 9285 4787 9285 4471 9285 4878 9286 4788 9286 4787 9286 4472 9287 4788 9287 4878 9287 4474 9288 4788 9288 4472 9288 4474 9289 4789 9289 4788 9289 4476 9290 4789 9290 4474 9290 4476 9291 4790 9291 4789 9291 4478 9292 4790 9292 4476 9292 4480 9293 4790 9293 4478 9293 4480 9294 4791 9294 4790 9294 4482 9295 4791 9295 4480 9295 4484 9296 4791 9296 4482 9296 4484 9297 4792 9297 4791 9297 4486 9298 4792 9298 4484 9298 4486 9299 4793 9299 4792 9299 4487 9300 4793 9300 4486 9300 4487 9301 4794 9301 4793 9301 4489 9302 4794 9302 4487 9302 4490 9303 4794 9303 4489 9303 4490 9304 4795 9304 4794 9304 4492 9305 4795 9305 4490 9305 4492 9306 4796 9306 4795 9306 4495 9307 4796 9307 4492 9307 4879 9308 4797 9308 4495 9308 4495 9309 4797 9309 4796 9309 4879 9310 4798 9310 4797 9310 4497 9311 4798 9311 4879 9311 4499 9312 4798 9312 4497 9312 4499 9313 4799 9313 4798 9313 4501 9314 4799 9314 4499 9314 4503 9315 4799 9315 4501 9315 4503 9316 4800 9316 4799 9316 4505 9317 4800 9317 4503 9317 4505 9318 4801 9318 4800 9318 4506 9319 4801 9319 4505 9319 4506 9320 4802 9320 4801 9320 4509 9321 4802 9321 4506 9321 4509 9322 4803 9322 4802 9322 4880 9323 4803 9323 4509 9323 4511 9324 4803 9324 4880 9324 4511 9325 4804 9325 4803 9325 4513 9326 4804 9326 4511 9326 4513 9327 4805 9327 4804 9327 4515 9328 4805 9328 4513 9328 4518 9329 4805 9329 4515 9329 4518 9330 4806 9330 4805 9330 4520 9331 4806 9331 4518 9331 4520 9332 4807 9332 4806 9332 4522 9333 4807 9333 4520 9333 4522 9334 4552 9334 4807 9334 4523 9335 4552 9335 4522 9335 4525 9336 4552 9336 4523 9336 4525 9337 4808 9337 4552 9337 4527 9338 4808 9338 4525 9338 4527 9339 4809 9339 4808 9339 4529 9340 4809 9340 4527 9340 4529 9341 4810 9341 4809 9341 4530 9342 4810 9342 4529 9342 4532 9343 4810 9343 4530 9343 4532 9344 4811 9344 4810 9344 4534 9345 4811 9345 4532 9345 4534 9346 4812 9346 4811 9346 4534 9347 4813 9347 4812 9347 4536 9348 4813 9348 4534 9348 4538 9349 4813 9349 4536 9349 4538 9350 4814 9350 4813 9350 4540 9351 4814 9351 4538 9351 4540 9352 4815 9352 4814 9352 4541 9353 4815 9353 4540 9353 4541 9354 4816 9354 4815 9354 4543 9355 4816 9355 4541 9355 4545 9356 4816 9356 4543 9356 4545 9357 4817 9357 4816 9357 4547 9358 4817 9358 4545 9358 4547 9359 4818 9359 4817 9359 4548 9360 4818 9360 4547 9360 4548 9361 4819 9361 4818 9361 4549 9362 4819 9362 4548 9362 4549 9363 4820 9363 4819 9363 4551 9364 4820 9364 4549 9364 4553 9365 4820 9365 4551 9365 4553 9366 4821 9366 4820 9366 4555 9367 4821 9367 4553 9367 4555 9368 4822 9368 4821 9368 4557 9369 4822 9369 4555 9369 4559 9370 4822 9370 4557 9370 4559 9371 4823 9371 4822 9371 4881 9372 4823 9372 4559 9372 4881 9373 4824 9373 4823 9373 4563 9374 4824 9374 4881 9374 4563 9375 4825 9375 4824 9375 4882 9376 4825 9376 4563 9376 4567 9377 4825 9377 4882 9377 4567 9378 4826 9378 4825 9378 4569 9379 4826 9379 4567 9379 4569 9380 4827 9380 4826 9380 4570 9381 4827 9381 4569 9381 4570 9382 4828 9382 4827 9382 4572 9383 4828 9383 4570 9383 4572 9384 4829 9384 4828 9384 4573 9385 4829 9385 4572 9385 4576 9386 4829 9386 4573 9386 4576 9387 4830 9387 4829 9387 4578 9388 4830 9388 4576 9388 4580 9389 4830 9389 4578 9389 4580 9390 4831 9390 4830 9390 4581 9391 4831 9391 4580 9391 4583 9392 4614 9392 4581 9392 4581 9393 4614 9393 4831 9393 4585 9394 4832 9394 4583 9394 4583 9395 4832 9395 4614 9395 4587 9396 4832 9396 4585 9396 4587 9397 4833 9397 4832 9397 4589 9398 4833 9398 4587 9398 4590 9399 4833 9399 4589 9399 4590 9400 4834 9400 4833 9400 4592 9401 4834 9401 4590 9401 4592 9402 4835 9402 4834 9402 4594 9403 4835 9403 4592 9403 4596 9404 4835 9404 4594 9404 4596 9405 4627 9405 4835 9405 4597 9406 4627 9406 4596 9406 4597 9407 4836 9407 4627 9407 4599 9408 4836 9408 4597 9408 4600 9409 4836 9409 4599 9409 4600 9410 4837 9410 4836 9410 4603 9411 4837 9411 4600 9411 4603 9412 4838 9412 4837 9412 4604 9413 4838 9413 4603 9413 4604 9414 4839 9414 4838 9414 4606 9415 4839 9415 4604 9415 4608 9416 4839 9416 4606 9416 4608 9417 4840 9417 4839 9417 4610 9418 4840 9418 4608 9418 4610 9419 4841 9419 4840 9419 4611 9420 4841 9420 4610 9420 4611 9421 4842 9421 4841 9421 4613 9422 4842 9422 4611 9422 4615 9423 4842 9423 4613 9423 4883 9424 4843 9424 4615 9424 4615 9425 4843 9425 4842 9425 4619 9426 4843 9426 4883 9426 4619 9427 4844 9427 4843 9427 4620 9428 4844 9428 4619 9428 4622 9429 4844 9429 4620 9429 4622 9430 4845 9430 4844 9430 4624 9431 4845 9431 4622 9431 4624 9432 4846 9432 4845 9432 4626 9433 4846 9433 4624 9433 4884 9434 4846 9434 4626 9434 4884 9435 4847 9435 4846 9435 4885 9436 4847 9436 4884 9436 4885 9437 4848 9437 4847 9437 4632 9438 4848 9438 4885 9438 4632 9439 4849 9439 4848 9439 4634 9440 4849 9440 4632 9440 4634 9441 4850 9441 4849 9441 4636 9442 4850 9442 4634 9442 4637 9443 4850 9443 4636 9443 4637 9444 4851 9444 4850 9444 4640 9445 4851 9445 4637 9445 4640 9446 4852 9446 4851 9446 4642 9447 4852 9447 4640 9447 4642 9448 4853 9448 4852 9448 4643 9449 4853 9449 4642 9449 4886 9450 4853 9450 4643 9450 4886 9451 4854 9451 4853 9451 4645 9452 4854 9452 4886 9452 4645 9453 4855 9453 4854 9453 4647 9454 4855 9454 4645 9454 4649 9455 4855 9455 4647 9455 4649 9456 4856 9456 4855 9456 4651 9457 4856 9457 4649 9457 4651 9458 4179 9458 4856 9458 4653 9459 4179 9459 4651 9459 4653 9460 4181 9460 4179 9460 4654 9461 4181 9461 4653 9461 4654 9462 4183 9462 4181 9462 4656 9463 4183 9463 4654 9463 4658 9464 4183 9464 4656 9464 4658 9465 4185 9465 4183 9465 4659 9466 4185 9466 4658 9466 4661 9467 4185 9467 4659 9467 4661 9468 4186 9468 4185 9468 4663 9469 4186 9469 4661 9469 4663 9470 4187 9470 4186 9470 4861 9471 4860 9471 4887 9471 4862 9472 4861 9472 4887 9472 4188 9473 4862 9473 4887 9473 4189 9474 4862 9474 4188 9474 4197 9475 4863 9475 4195 9475 4199 9476 4863 9476 4197 9476 4213 9477 4864 9477 4211 9477 4865 9478 4213 9478 4215 9478 4217 9479 4865 9479 4215 9479 4226 9480 4223 9480 4224 9480 4233 9481 4230 9481 4231 9481 4245 9482 4242 9482 4244 9482 4260 9483 4866 9483 4258 9483 4867 9484 4866 9484 4260 9484 4262 9485 4867 9485 4260 9485 4868 9486 4867 9486 4262 9486 4264 9487 4868 9487 4262 9487 4869 9488 4269 9488 4271 9488 4273 9489 4869 9489 4271 9489 4275 9490 4869 9490 4273 9490 4292 9491 4870 9491 4290 9491 4293 9492 4870 9492 4292 9492 4322 9493 4871 9493 4321 9493 4324 9494 4871 9494 4322 9494 4344 9495 4340 9495 4342 9495 4872 9496 4364 9496 4366 9496 4873 9497 4872 9497 4366 9497 4369 9498 4873 9498 4366 9498 4371 9499 4873 9499 4369 9499 4417 9500 4874 9500 4415 9500 4424 9501 4421 9501 4422 9501 4875 9502 4442 9502 4444 9502 4445 9503 4875 9503 4444 9503 4876 9504 4875 9504 4445 9504 4447 9505 4876 9505 4445 9505 4877 9506 4876 9506 4447 9506 4449 9507 4877 9507 4447 9507 4472 9508 4878 9508 4471 9508 4495 9509 4492 9509 4493 9509 4497 9510 4879 9510 4495 9510 4509 9511 4506 9511 4508 9511 4511 9512 4880 9512 4509 9512 4518 9513 4515 9513 4516 9513 4881 9514 4559 9514 4561 9514 4563 9515 4881 9515 4561 9515 4882 9516 4563 9516 4565 9516 4567 9517 4882 9517 4565 9517 4617 9518 4883 9518 4615 9518 4619 9519 4883 9519 4617 9519 4628 9520 4884 9520 4626 9520 4885 9521 4884 9521 4628 9521 4631 9522 4885 9522 4628 9522 4632 9523 4885 9523 4631 9523 4640 9524 4637 9524 4638 9524 4645 9525 4886 9525 4643 9525 4664 9526 4187 9526 4663 9526 4892 9527 4187 9527 4664 9527 4666 9528 4892 9528 4664 9528 4668 9529 4937 9529 4666 9529 4888 9530 4933 9530 4889 9530 4890 9531 4888 9531 4889 9531 4891 9532 4888 9532 4890 9532 4666 9533 4937 9533 4891 9533 4892 9534 4666 9534 4891 9534 4892 9535 4891 9535 4890 9535 4893 9536 4892 9536 4890 9536 4893 9537 4187 9537 4892 9537 4895 9538 4890 9538 4889 9538 4893 9539 4890 9539 4894 9539 4894 9540 4890 9540 4895 9540 4894 9541 4187 9541 4893 9541 4895 9542 4889 9542 4896 9542 4897 9543 4894 9543 4895 9543 4186 9544 4187 9544 4894 9544 4186 9545 4894 9545 4897 9545 4897 9546 4895 9546 4896 9546 4898 9547 4897 9547 4896 9547 4186 9548 4897 9548 4898 9548 4898 9549 4896 9549 4899 9549 4899 9550 4896 9550 4900 9550 4901 9551 4898 9551 4899 9551 4901 9552 4186 9552 4898 9552 4902 9553 4901 9553 4899 9553 4903 9554 4902 9554 4899 9554 4903 9555 4899 9555 4900 9555 4904 9556 4902 9556 4903 9556 4904 9557 4901 9557 4902 9557 4906 9558 4903 9558 4900 9558 4906 9559 4900 9559 4905 9559 4906 9560 4904 9560 4903 9560 4908 9561 4904 9561 4906 9561 4907 9562 4906 9562 4905 9562 4908 9563 4906 9563 4907 9563 4910 9564 4907 9564 4905 9564 4910 9565 4905 9565 4909 9565 4911 9566 4908 9566 4907 9566 4912 9567 4907 9567 4910 9567 4911 9568 4907 9568 4912 9568 4913 9569 4912 9569 4910 9569 4913 9570 4910 9570 4909 9570 4915 9571 4911 9571 4912 9571 4915 9572 4912 9572 4913 9572 4916 9573 4913 9573 4909 9573 4916 9574 4915 9574 4913 9574 4917 9575 4916 9575 4909 9575 4917 9576 4909 9576 4914 9576 4177 9577 4915 9577 4916 9577 4917 9578 4914 9578 4918 9578 4919 9579 4916 9579 4917 9579 4919 9580 4177 9580 4916 9580 4919 9581 4917 9581 4918 9581 4920 9582 4177 9582 4919 9582 4921 9583 4919 9583 4918 9583 4921 9584 4920 9584 4919 9584 4922 9585 4920 9585 4921 9585 4923 9586 4918 9586 4914 9586 4923 9587 4921 9587 4918 9587 4922 9588 4921 9588 4924 9588 4924 9589 4921 9589 4923 9589 4176 9590 4922 9590 4924 9590 4925 9591 4924 9591 4923 9591 4926 9592 4924 9592 4925 9592 4176 9593 4924 9593 4926 9593 4927 9594 4925 9594 4923 9594 4928 9595 4926 9595 4925 9595 4928 9596 4925 9596 4927 9596 4928 9597 4176 9597 4926 9597 4930 9598 4928 9598 4927 9598 4180 9599 4176 9599 4928 9599 4180 9600 4928 9600 4930 9600 4931 9601 4930 9601 4927 9601 4931 9602 4927 9602 4929 9602 4180 9603 4930 9603 4931 9603 4932 9604 4180 9604 4931 9604 4929 9605 4932 9605 4931 9605 4182 9606 4180 9606 4932 9606 4934 9607 4932 9607 4929 9607 4934 9608 4929 9608 4933 9608 4182 9609 4932 9609 4934 9609 4184 9610 4182 9610 4934 9610 4935 9611 4934 9611 4933 9611 4184 9612 4934 9612 4935 9612 4936 9613 4184 9613 4935 9613 4888 9614 4935 9614 4933 9614 4937 9615 4936 9615 4935 9615 4668 9616 4184 9616 4936 9616 4668 9617 4936 9617 4937 9617 4937 9618 4935 9618 4888 9618 4937 9619 4888 9619 4891 9619 4909 9620 4923 9620 4914 9620 4909 9621 4929 9621 4927 9621 4909 9622 4927 9622 4923 9622 4909 9623 4933 9623 4929 9623 4905 9624 4900 9624 4896 9624 4905 9625 4933 9625 4909 9625 4905 9626 4896 9626 4889 9626 4905 9627 4889 9627 4933 9627 4940 9628 4939 9628 4938 9628 4941 9629 4939 9629 4940 9629 4941 9630 4940 9630 4943 9630 4943 9631 4940 9631 4942 9631 4943 9632 4942 9632 4944 9632 4946 9633 4943 9633 4944 9633 4945 9634 4946 9634 4944 9634 4947 9635 4943 9635 4946 9635 4949 9636 4946 9636 4945 9636 4948 9637 4946 9637 4949 9637 4947 9638 4946 9638 4948 9638 4950 9639 4948 9639 4949 9639 4951 9640 4948 9640 4950 9640 4951 9641 4947 9641 4948 9641 4951 9642 4950 9642 4952 9642 4953 9643 4951 9643 4952 9643 4954 9644 4951 9644 4953 9644 4956 9645 4953 9645 4955 9645 4956 9646 4954 9646 4953 9646 4957 9647 4956 9647 4955 9647 4958 9648 4956 9648 4957 9648 4960 9649 4954 9649 4956 9649 4959 9650 4958 9650 4957 9650 4960 9651 4956 9651 4958 9651 4962 9652 4960 9652 4958 9652 4961 9653 4958 9653 4959 9653 4962 9654 4958 9654 4961 9654 4964 9655 4961 9655 4963 9655 4962 9656 4961 9656 4964 9656 4965 9657 4964 9657 4963 9657 4965 9658 4962 9658 4964 9658 4965 9659 4963 9659 4966 9659 4968 9660 4962 9660 4965 9660 4967 9661 4965 9661 4966 9661 4968 9662 4965 9662 4967 9662 4970 9663 4967 9663 4969 9663 4970 9664 4968 9664 4967 9664 4971 9665 4968 9665 4970 9665 4970 9666 4969 9666 4972 9666 4970 9667 4972 9667 4973 9667 4974 9668 4970 9668 4973 9668 4974 9669 4971 9669 4970 9669 4974 9670 4973 9670 4975 9670 4976 9671 4971 9671 4974 9671 4977 9672 4974 9672 4975 9672 4976 9673 4974 9673 4977 9673 4979 9674 4977 9674 4978 9674 4976 9675 4977 9675 4979 9675 4980 9676 4976 9676 4979 9676 4982 9677 4980 9677 4979 9677 4982 9678 4979 9678 4981 9678 4980 9679 4982 9679 4983 9679 4984 9680 4982 9680 4981 9680 4984 9681 4983 9681 4982 9681 4986 9682 4983 9682 4984 9682 4986 9683 4984 9683 4985 9683 4989 9684 4983 9684 4986 9684 4988 9685 4986 9685 4985 9685 4988 9686 4985 9686 4987 9686 4989 9687 4986 9687 4988 9687 4990 9688 4988 9688 4987 9688 4991 9689 4988 9689 4990 9689 4989 9690 4988 9690 4991 9690 4992 9691 4991 9691 4990 9691 4994 9692 4991 9692 4992 9692 4993 9693 4989 9693 4991 9693 4993 9694 4991 9694 4994 9694 4996 9695 4993 9695 4994 9695 4996 9696 4994 9696 4995 9696 4998 9697 4995 9697 4997 9697 4998 9698 4996 9698 4995 9698 4998 9699 4993 9699 4996 9699 5000 9700 4993 9700 4998 9700 4999 9701 4998 9701 4997 9701 5001 9702 4998 9702 4999 9702 5000 9703 4998 9703 5001 9703 5002 9704 5001 9704 4999 9704 5003 9705 5001 9705 5002 9705 5004 9706 5001 9706 5003 9706 5004 9707 5000 9707 5001 9707 5003 9708 5002 9708 5005 9708 4939 9709 5003 9709 5005 9709 5005 9710 4938 9710 4939 9710 5004 9711 5003 9711 4939 9711 5004 9712 4939 9712 4941 9712 4938 9713 5074 9713 5006 9713 4940 9714 4938 9714 5006 9714 4942 9715 5006 9715 5007 9715 4942 9716 4940 9716 5006 9716 4944 9717 5007 9717 5008 9717 4944 9718 4942 9718 5007 9718 4945 9719 4944 9719 5008 9719 4945 9720 5008 9720 5009 9720 4949 9721 5009 9721 5068 9721 4949 9722 4945 9722 5009 9722 4949 9723 5068 9723 5010 9723 4950 9724 4949 9724 5010 9724 4952 9725 4950 9725 5010 9725 4952 9726 5010 9726 5065 9726 4953 9727 5065 9727 5011 9727 4953 9728 4952 9728 5065 9728 4955 9729 4953 9729 5011 9729 4955 9730 5011 9730 5063 9730 4957 9731 4955 9731 5063 9731 4957 9732 5063 9732 5012 9732 4959 9733 4957 9733 5012 9733 4959 9734 5012 9734 5058 9734 4961 9735 4959 9735 5058 9735 4961 9736 5058 9736 5055 9736 4963 9737 4961 9737 5055 9737 4963 9738 5055 9738 5054 9738 4963 9739 5054 9739 5013 9739 4966 9740 4963 9740 5013 9740 4966 9741 5013 9741 5014 9741 4967 9742 4966 9742 5014 9742 4967 9743 5014 9743 5015 9743 4969 9744 4967 9744 5015 9744 4969 9745 5015 9745 5051 9745 4972 9746 4969 9746 5051 9746 4973 9747 5051 9747 5016 9747 4973 9748 4972 9748 5051 9748 4973 9749 5016 9749 5017 9749 4975 9750 4973 9750 5017 9750 4975 9751 5017 9751 5018 9751 4977 9752 4975 9752 5018 9752 4978 9753 4977 9753 5018 9753 4978 9754 5018 9754 5046 9754 4978 9755 5046 9755 5019 9755 4979 9756 4978 9756 5019 9756 4981 9757 4979 9757 5019 9757 4981 9758 5019 9758 5020 9758 4984 9759 4981 9759 5020 9759 4984 9760 5020 9760 5021 9760 4985 9761 4984 9761 5021 9761 4985 9762 5021 9762 5040 9762 4987 9763 4985 9763 5040 9763 4987 9764 5040 9764 5038 9764 4990 9765 4987 9765 5038 9765 4990 9766 5038 9766 5022 9766 4992 9767 4990 9767 5022 9767 4994 9768 4992 9768 5022 9768 4994 9769 5022 9769 5034 9769 4995 9770 4994 9770 5034 9770 4995 9771 5034 9771 5023 9771 4997 9772 4995 9772 5023 9772 4999 9773 4997 9773 5023 9773 4999 9774 5023 9774 5024 9774 5002 9775 5024 9775 5025 9775 5002 9776 4999 9776 5024 9776 5002 9777 5025 9777 5026 9777 5005 9778 5002 9778 5026 9778 4938 9779 5026 9779 5074 9779 4938 9780 5005 9780 5026 9780 4672 9781 4198 9781 4980 9781 4672 9782 4980 9782 4983 9782 4198 9783 4976 9783 4980 9783 4196 9784 4976 9784 4198 9784 4672 9785 4983 9785 4989 9785 4673 9786 4672 9786 4989 9786 4196 9787 4971 9787 4976 9787 4673 9788 4989 9788 4993 9788 4191 9789 4971 9789 4196 9789 4857 9790 4673 9790 4993 9790 4191 9791 4968 9791 4971 9791 4859 9792 4857 9792 4993 9792 4194 9793 4968 9793 4191 9793 4194 9794 4962 9794 4968 9794 5000 9795 4859 9795 4993 9795 4962 9796 4194 9796 4192 9796 5004 9797 4859 9797 5000 9797 4960 9798 4962 9798 4192 9798 5004 9799 4858 9799 4859 9799 4954 9800 4960 9800 4192 9800 4954 9801 4192 9801 4188 9801 4941 9802 4858 9802 5004 9802 4941 9803 4860 9803 4858 9803 4943 9804 4860 9804 4941 9804 4951 9805 4954 9805 4188 9805 4951 9806 4188 9806 4887 9806 4943 9807 4887 9807 4860 9807 4947 9808 4887 9808 4943 9808 4951 9809 4887 9809 4947 9809 5026 9810 5027 9810 5074 9810 5029 9811 5026 9811 5025 9811 5029 9812 5027 9812 5026 9812 5030 9813 5073 9813 5028 9813 5028 9814 5027 9814 5029 9814 5030 9815 5028 9815 5029 9815 5030 9816 5029 9816 5025 9816 5030 9817 5025 9817 5024 9817 5031 9818 5030 9818 5024 9818 5031 9819 5024 9819 5023 9819 5032 9820 5030 9820 5031 9820 5033 9821 5031 9821 5023 9821 5032 9822 5031 9822 5033 9822 5033 9823 5023 9823 5034 9823 5035 9824 5033 9824 5034 9824 5035 9825 5032 9825 5033 9825 5036 9826 5032 9826 5035 9826 5022 9827 5035 9827 5034 9827 5037 9828 5035 9828 5022 9828 5037 9829 5036 9829 5035 9829 5037 9830 5039 9830 5036 9830 5038 9831 5037 9831 5022 9831 5039 9832 5037 9832 5041 9832 5040 9833 5037 9833 5038 9833 5041 9834 5037 9834 5040 9834 5043 9835 5040 9835 5021 9835 5042 9836 5039 9836 5041 9836 5043 9837 5041 9837 5040 9837 5043 9838 5021 9838 5020 9838 5042 9839 5041 9839 5043 9839 5019 9840 5043 9840 5020 9840 5044 9841 5043 9841 5019 9841 5044 9842 5042 9842 5043 9842 5045 9843 5042 9843 5044 9843 5046 9844 5044 9844 5019 9844 5047 9845 5044 9845 5046 9845 5045 9846 5044 9846 5047 9846 5047 9847 5046 9847 5018 9847 5048 9848 5045 9848 5047 9848 5048 9849 5042 9849 5045 9849 5017 9850 5047 9850 5018 9850 5048 9851 5047 9851 5017 9851 5049 9852 5048 9852 5017 9852 5049 9853 5017 9853 5016 9853 5050 9854 5048 9854 5049 9854 5051 9855 5049 9855 5016 9855 5050 9856 5049 9856 5051 9856 5050 9857 5051 9857 5052 9857 5052 9858 5051 9858 5015 9858 5053 9859 5050 9859 5052 9859 5052 9860 5015 9860 5014 9860 5053 9861 5052 9861 5014 9861 5054 9862 5014 9862 5013 9862 5053 9863 5014 9863 5054 9863 5056 9864 5053 9864 5054 9864 5055 9865 5056 9865 5054 9865 5057 9866 5056 9866 5055 9866 5057 9867 5055 9867 5058 9867 5059 9868 5057 9868 5058 9868 5060 9869 5056 9869 5057 9869 5059 9870 5058 9870 5012 9870 5060 9871 5057 9871 5059 9871 5061 9872 5059 9872 5012 9872 5060 9873 5059 9873 5061 9873 5063 9874 5061 9874 5012 9874 5062 9875 5060 9875 5061 9875 5062 9876 5061 9876 5063 9876 5064 9877 5062 9877 5063 9877 5064 9878 5063 9878 5011 9878 5064 9879 5011 9879 5065 9879 5066 9880 5062 9880 5064 9880 5066 9881 5064 9881 5065 9881 5067 9882 5066 9882 5065 9882 5067 9883 5065 9883 5010 9883 5068 9884 5067 9884 5010 9884 5069 9885 5066 9885 5067 9885 5069 9886 5067 9886 5068 9886 5069 9887 5068 9887 5009 9887 5070 9888 5069 9888 5009 9888 5070 9889 5066 9889 5069 9889 5071 9890 5009 9890 5008 9890 5070 9891 5009 9891 5071 9891 5071 9892 5008 9892 5007 9892 5006 9893 5071 9893 5007 9893 5072 9894 5071 9894 5006 9894 5073 9895 5070 9895 5071 9895 5073 9896 5071 9896 5072 9896 5072 9897 5006 9897 5074 9897 5027 9898 5072 9898 5074 9898 5072 9899 5027 9899 5028 9899 5028 9900 5073 9900 5072 9900 4163 9901 4168 9901 4170 9901 4163 9902 4165 9902 4168 9902 4161 9903 4163 9903 4171 9903 4171 9904 4163 9904 4170 9904 4159 9905 4171 9905 4172 9905 4159 9906 4161 9906 4171 9906

+
+ + + +

5075 9907 5076 9907 5077 9907 5076 9908 5078 9908 5077 9908 5076 9909 5080 9909 5078 9909 5079 9910 5080 9910 5076 9910 5081 9911 5082 9911 5079 9911 5079 9912 5082 9912 5080 9912 5081 9913 5083 9913 5082 9913 5083 9914 5084 9914 5082 9914 5083 9915 5085 9915 5084 9915 5085 9916 5086 9916 5084 9916 5075 9917 5077 9917 5085 9917 5085 9918 5077 9918 5086 9918 5084 9919 5086 9919 5087 9919 5087 9920 5086 9920 5088 9920 5086 9921 5092 9921 5088 9921 5086 9922 5077 9922 5092 9922 5077 9923 5091 9923 5092 9923 5077 9924 5078 9924 5091 9924 5076 9925 5081 9925 5079 9925 5083 9926 5081 9926 5085 9926 5085 9927 5081 9927 5075 9927 5075 9928 5081 9928 5076 9928 5090 9929 5946 9929 5949 9929 5090 9930 5945 9930 5946 9930 5090 9931 5943 9931 5945 9931 5091 9932 5090 9932 5949 9932 5091 9933 5954 9933 5956 9933 5091 9934 5949 9934 5954 9934 5959 9935 5091 9935 5956 9935 5089 9936 5986 9936 5943 9936 5089 9937 5943 9937 5090 9937 5983 9938 5986 9938 5089 9938 5092 9939 5091 9939 5959 9939 5092 9940 5959 9940 5963 9940 5087 9941 5980 9941 5983 9941 5087 9942 5983 9942 5089 9942 5977 9943 5980 9943 5087 9943 5965 9944 5092 9944 5963 9944 5965 9945 5088 9945 5092 9945 5971 9946 5088 9946 5965 9946 5977 9947 5087 9947 5088 9947 5974 9948 5977 9948 5088 9948 5974 9949 5088 9949 5971 9949 5094 9950 5093 9950 5839 9950 5094 9951 5839 9951 5095 9951 5093 9952 5096 9952 5839 9952 5097 9953 5094 9953 5095 9953 5098 9954 5096 9954 5093 9954 5097 9955 5095 9955 5099 9955 5098 9956 5100 9956 5096 9956 5098 9957 5831 9957 5100 9957 5097 9958 5099 9958 5101 9958 5102 9959 5831 9959 5098 9959 5102 9960 5829 9960 5831 9960 5103 9961 5097 9961 5101 9961 5827 9962 5829 9962 5102 9962 5104 9963 5827 9963 5102 9963 5106 9964 5827 9964 5104 9964 5106 9965 5104 9965 5107 9965 5108 9966 5106 9966 5107 9966 5818 9967 5108 9967 5107 9967 5818 9968 5107 9968 5109 9968 5114 9969 5112 9969 5111 9969 5114 9970 5113 9970 5112 9970 5117 9971 5113 9971 5114 9971 5117 9972 5115 9972 5113 9972 5119 9973 5115 9973 5117 9973 5119 9974 5118 9974 5115 9974 5116 9975 5118 9975 5119 9975 5116 9976 5120 9976 5118 9976 5121 9977 5120 9977 5116 9977 5121 9978 5122 9978 5120 9978 5123 9979 5122 9979 5121 9979 5123 9980 5124 9980 5122 9980 5125 9981 5124 9981 5123 9981 5125 9982 5126 9982 5124 9982 5127 9983 5126 9983 5125 9983 5127 9984 5128 9984 5126 9984 5127 9985 5129 9985 5128 9985 5130 9986 5129 9986 5127 9986 5130 9987 5131 9987 5129 9987 5132 9988 5131 9988 5130 9988 5132 9989 5133 9989 5131 9989 5132 9990 5134 9990 5133 9990 5135 9991 5134 9991 5132 9991 5135 9992 5136 9992 5134 9992 5137 9993 5136 9993 5135 9993 5137 9994 5138 9994 5136 9994 5137 9995 5139 9995 5138 9995 5140 9996 5139 9996 5137 9996 5141 9997 5139 9997 5140 9997 5141 9998 5142 9998 5139 9998 5141 9999 5143 9999 5142 9999 5144 10000 5143 10000 5141 10000 5144 10001 5145 10001 5143 10001 5146 10002 5145 10002 5144 10002 5146 10003 5147 10003 5145 10003 5148 10004 5147 10004 5146 10004 5148 10005 5149 10005 5147 10005 5150 10006 5149 10006 5148 10006 5150 10007 5151 10007 5149 10007 5150 10008 5152 10008 5151 10008 5153 10009 5152 10009 5150 10009 5153 10010 5154 10010 5152 10010 5155 10011 5154 10011 5153 10011 5155 10012 5156 10012 5154 10012 5155 10013 5157 10013 5156 10013 5158 10014 5157 10014 5155 10014 5158 10015 5159 10015 5157 10015 5160 10016 5159 10016 5158 10016 5160 10017 5161 10017 5159 10017 5162 10018 5163 10018 5160 10018 5160 10019 5163 10019 5161 10019 5162 10020 5164 10020 5163 10020 5165 10021 5164 10021 5162 10021 5165 10022 5166 10022 5164 10022 5167 10023 5166 10023 5165 10023 5167 10024 5168 10024 5166 10024 5169 10025 5168 10025 5167 10025 5169 10026 5170 10026 5168 10026 5169 10027 5171 10027 5170 10027 5172 10028 5171 10028 5169 10028 5172 10029 5173 10029 5171 10029 5174 10030 5173 10030 5172 10030 5174 10031 5175 10031 5173 10031 5174 10032 5176 10032 5175 10032 5177 10033 5176 10033 5174 10033 5177 10034 5178 10034 5176 10034 5177 10035 5179 10035 5178 10035 5180 10036 5179 10036 5177 10036 5181 10037 5182 10037 5180 10037 5180 10038 5182 10038 5179 10038 5181 10039 5183 10039 5182 10039 5184 10040 5183 10040 5181 10040 5184 10041 5185 10041 5183 10041 5186 10042 5185 10042 5184 10042 5186 10043 5187 10043 5185 10043 5186 10044 5188 10044 5187 10044 5189 10045 5188 10045 5186 10045 5189 10046 5190 10046 5188 10046 5191 10047 5190 10047 5189 10047 5191 10048 5192 10048 5190 10048 5193 10049 5192 10049 5191 10049 5193 10050 5194 10050 5192 10050 5193 10051 5195 10051 5194 10051 5196 10052 5195 10052 5193 10052 5196 10053 5197 10053 5195 10053 5198 10054 5197 10054 5196 10054 5198 10055 5199 10055 5197 10055 5198 10056 5200 10056 5199 10056 5201 10057 5200 10057 5198 10057 5201 10058 5202 10058 5200 10058 5203 10059 5202 10059 5201 10059 5203 10060 5204 10060 5202 10060 5205 10061 5204 10061 5203 10061 5205 10062 5206 10062 5204 10062 5207 10063 5206 10063 5205 10063 5207 10064 5208 10064 5206 10064 5207 10065 5209 10065 5208 10065 5210 10066 5209 10066 5207 10066 5210 10067 5211 10067 5209 10067 5210 10068 5212 10068 5211 10068 5213 10069 5212 10069 5210 10069 5213 10070 5214 10070 5212 10070 5213 10071 5215 10071 5214 10071 5216 10072 5215 10072 5213 10072 5216 10073 5217 10073 5215 10073 5218 10074 5217 10074 5216 10074 5218 10075 5219 10075 5217 10075 5220 10076 5219 10076 5218 10076 5220 10077 5221 10077 5219 10077 5220 10078 5222 10078 5221 10078 5223 10079 5222 10079 5220 10079 5223 10080 5224 10080 5222 10080 5225 10081 5224 10081 5223 10081 5225 10082 5226 10082 5224 10082 5227 10083 5226 10083 5225 10083 5227 10084 5228 10084 5226 10084 5227 10085 5229 10085 5228 10085 5230 10086 5229 10086 5227 10086 5230 10087 5231 10087 5229 10087 5232 10088 5231 10088 5230 10088 5232 10089 5233 10089 5231 10089 5234 10090 5233 10090 5232 10090 5234 10091 5235 10091 5233 10091 5234 10092 5236 10092 5235 10092 5237 10093 5236 10093 5234 10093 5237 10094 5238 10094 5236 10094 5239 10095 5238 10095 5237 10095 5239 10096 5240 10096 5238 10096 5241 10097 5240 10097 5239 10097 5241 10098 5242 10098 5240 10098 5243 10099 5242 10099 5241 10099 5243 10100 5244 10100 5242 10100 5243 10101 5245 10101 5244 10101 5246 10102 5245 10102 5243 10102 5246 10103 5247 10103 5245 10103 5248 10104 5247 10104 5246 10104 5248 10105 5249 10105 5247 10105 5250 10106 5249 10106 5248 10106 5250 10107 5251 10107 5249 10107 5250 10108 5252 10108 5251 10108 5253 10109 5252 10109 5250 10109 5254 10110 5255 10110 5253 10110 5253 10111 5255 10111 5252 10111 5254 10112 5256 10112 5255 10112 5257 10113 5256 10113 5254 10113 5257 10114 5258 10114 5256 10114 5259 10115 5258 10115 5257 10115 5259 10116 5260 10116 5258 10116 5259 10117 5261 10117 5260 10117 5262 10118 5261 10118 5259 10118 5262 10119 5263 10119 5261 10119 5264 10120 5263 10120 5262 10120 5264 10121 5265 10121 5263 10121 5264 10122 5266 10122 5265 10122 5267 10123 5266 10123 5264 10123 5267 10124 5268 10124 5266 10124 5267 10125 5269 10125 5268 10125 5270 10126 5269 10126 5267 10126 5270 10127 5271 10127 5269 10127 5272 10128 5271 10128 5270 10128 5272 10129 5273 10129 5271 10129 5274 10130 5273 10130 5272 10130 5274 10131 5275 10131 5273 10131 5276 10132 5275 10132 5274 10132 5276 10133 5277 10133 5275 10133 5276 10134 5278 10134 5277 10134 5279 10135 5278 10135 5276 10135 5279 10136 5280 10136 5278 10136 5281 10137 5280 10137 5279 10137 5281 10138 5282 10138 5280 10138 5281 10139 5283 10139 5282 10139 5284 10140 5283 10140 5281 10140 5284 10141 5285 10141 5283 10141 5284 10142 5286 10142 5285 10142 5287 10143 5286 10143 5284 10143 5287 10144 5288 10144 5286 10144 5289 10145 5288 10145 5287 10145 5289 10146 5290 10146 5288 10146 5291 10147 5290 10147 5289 10147 5291 10148 5292 10148 5290 10148 5291 10149 5293 10149 5292 10149 5294 10150 5293 10150 5291 10150 5294 10151 5295 10151 5293 10151 5297 10152 5296 10152 5294 10152 5294 10153 5296 10153 5295 10153 5297 10154 5298 10154 5296 10154 5299 10155 5298 10155 5297 10155 5299 10156 5300 10156 5298 10156 5299 10157 5301 10157 5300 10157 5302 10158 5301 10158 5299 10158 5302 10159 5303 10159 5301 10159 5304 10160 5303 10160 5302 10160 5304 10161 5305 10161 5303 10161 5306 10162 5305 10162 5304 10162 5306 10163 5307 10163 5305 10163 5308 10164 5307 10164 5306 10164 5308 10165 5309 10165 5307 10165 5310 10166 5309 10166 5308 10166 5310 10167 5311 10167 5309 10167 5312 10168 5311 10168 5310 10168 5312 10169 5313 10169 5311 10169 5314 10170 5313 10170 5312 10170 5314 10171 5315 10171 5313 10171 5316 10172 5315 10172 5314 10172 5316 10173 5317 10173 5315 10173 5318 10174 5317 10174 5316 10174 5318 10175 5319 10175 5317 10175 5320 10176 5319 10176 5318 10176 5320 10177 5321 10177 5319 10177 5322 10178 5321 10178 5320 10178 5322 10179 5323 10179 5321 10179 5322 10180 5324 10180 5323 10180 5325 10181 5324 10181 5322 10181 5325 10182 5326 10182 5324 10182 5327 10183 5326 10183 5325 10183 5327 10184 5328 10184 5326 10184 5329 10185 5328 10185 5327 10185 5329 10186 5330 10186 5328 10186 5331 10187 5330 10187 5329 10187 5331 10188 5332 10188 5330 10188 5331 10189 5333 10189 5332 10189 5334 10190 5333 10190 5331 10190 5334 10191 5335 10191 5333 10191 5336 10192 5335 10192 5334 10192 5336 10193 5337 10193 5335 10193 5338 10194 5337 10194 5336 10194 5339 10195 5337 10195 5338 10195 5339 10196 5340 10196 5337 10196 5339 10197 5341 10197 5340 10197 5342 10198 5341 10198 5339 10198 5343 10199 5344 10199 5342 10199 5342 10200 5344 10200 5341 10200 5343 10201 5345 10201 5344 10201 5346 10202 5345 10202 5343 10202 5346 10203 5347 10203 5345 10203 5348 10204 5347 10204 5346 10204 5348 10205 5349 10205 5347 10205 5350 10206 5349 10206 5348 10206 5350 10207 5351 10207 5349 10207 5352 10208 5351 10208 5350 10208 5352 10209 5353 10209 5351 10209 5352 10210 5354 10210 5353 10210 5355 10211 5354 10211 5352 10211 5355 10212 5356 10212 5354 10212 5355 10213 5357 10213 5356 10213 5358 10214 5357 10214 5355 10214 5358 10215 5359 10215 5357 10215 5360 10216 5361 10216 5358 10216 5358 10217 5361 10217 5359 10217 5362 10218 5363 10218 5360 10218 5360 10219 5363 10219 5361 10219 5362 10220 5364 10220 5363 10220 5362 10221 5365 10221 5364 10221 5366 10222 5365 10222 5362 10222 5366 10223 5367 10223 5365 10223 5368 10224 5367 10224 5366 10224 5368 10225 5369 10225 5367 10225 5370 10226 5369 10226 5368 10226 5370 10227 5371 10227 5369 10227 5370 10228 5372 10228 5371 10228 5373 10229 5372 10229 5370 10229 5373 10230 5374 10230 5372 10230 5376 10231 5375 10231 5373 10231 5373 10232 5375 10232 5374 10232 5376 10233 5377 10233 5375 10233 5378 10234 5377 10234 5376 10234 5378 10235 5379 10235 5377 10235 5380 10236 5379 10236 5378 10236 5380 10237 5381 10237 5379 10237 5382 10238 5383 10238 5380 10238 5380 10239 5383 10239 5381 10239 5382 10240 5384 10240 5383 10240 5385 10241 5384 10241 5382 10241 5385 10242 5386 10242 5384 10242 5387 10243 5386 10243 5385 10243 5387 10244 5388 10244 5386 10244 5387 10245 5389 10245 5388 10245 5390 10246 5389 10246 5387 10246 5390 10247 5391 10247 5389 10247 5390 10248 5392 10248 5391 10248 5393 10249 5392 10249 5390 10249 5393 10250 5394 10250 5392 10250 5395 10251 5394 10251 5393 10251 5395 10252 5396 10252 5394 10252 5397 10253 5396 10253 5395 10253 5397 10254 5398 10254 5396 10254 5399 10255 5398 10255 5397 10255 5399 10256 5400 10256 5398 10256 5401 10257 5400 10257 5399 10257 5401 10258 5402 10258 5400 10258 5403 10259 5402 10259 5401 10259 5403 10260 5404 10260 5402 10260 5403 10261 5405 10261 5404 10261 5406 10262 5405 10262 5403 10262 5406 10263 5407 10263 5405 10263 5406 10264 5408 10264 5407 10264 5409 10265 5408 10265 5406 10265 5409 10266 5410 10266 5408 10266 5411 10267 5410 10267 5409 10267 5411 10268 5412 10268 5410 10268 5413 10269 5412 10269 5411 10269 5413 10270 5414 10270 5412 10270 5415 10271 5414 10271 5413 10271 5415 10272 5416 10272 5414 10272 5415 10273 5417 10273 5416 10273 5418 10274 5417 10274 5415 10274 5418 10275 5419 10275 5417 10275 5420 10276 5419 10276 5418 10276 5420 10277 5421 10277 5419 10277 5420 10278 5422 10278 5421 10278 5423 10279 5422 10279 5420 10279 5424 10280 5425 10280 5423 10280 5423 10281 5425 10281 5422 10281 5426 10282 5427 10282 5424 10282 5424 10283 5427 10283 5425 10283 5428 10284 5429 10284 5426 10284 5426 10285 5429 10285 5427 10285 5430 10286 5429 10286 5428 10286 5430 10287 5431 10287 5429 10287 5430 10288 5432 10288 5431 10288 5433 10289 5432 10289 5430 10289 5433 10290 5434 10290 5432 10290 5435 10291 5434 10291 5433 10291 5435 10292 5436 10292 5434 10292 5437 10293 5436 10293 5435 10293 5437 10294 5438 10294 5436 10294 5437 10295 5439 10295 5438 10295 5440 10296 5439 10296 5437 10296 5440 10297 5441 10297 5439 10297 5440 10298 5442 10298 5441 10298 5443 10299 5442 10299 5440 10299 5443 10300 5444 10300 5442 10300 5443 10301 5445 10301 5444 10301 5446 10302 5445 10302 5443 10302 5446 10303 5447 10303 5445 10303 5448 10304 5447 10304 5446 10304 5448 10305 5449 10305 5447 10305 5450 10306 5449 10306 5448 10306 5450 10307 5451 10307 5449 10307 5452 10308 5451 10308 5450 10308 5452 10309 5453 10309 5451 10309 5452 10310 5454 10310 5453 10310 5455 10311 5454 10311 5452 10311 5455 10312 5456 10312 5454 10312 5455 10313 5457 10313 5456 10313 5458 10314 5457 10314 5455 10314 5459 10315 5460 10315 5458 10315 5458 10316 5460 10316 5457 10316 5459 10317 5461 10317 5460 10317 5462 10318 5461 10318 5459 10318 5462 10319 5463 10319 5461 10319 5464 10320 5463 10320 5462 10320 5464 10321 5465 10321 5463 10321 5466 10322 5465 10322 5464 10322 5466 10323 5467 10323 5465 10323 5468 10324 5469 10324 5466 10324 5466 10325 5469 10325 5467 10325 5470 10326 5469 10326 5468 10326 5470 10327 5471 10327 5469 10327 5470 10328 5472 10328 5471 10328 5473 10329 5472 10329 5470 10329 5473 10330 5474 10330 5472 10330 5475 10331 5474 10331 5473 10331 5475 10332 5476 10332 5474 10332 5477 10333 5476 10333 5475 10333 5477 10334 5478 10334 5476 10334 5479 10335 5478 10335 5477 10335 5479 10336 5480 10336 5478 10336 5481 10337 5480 10337 5479 10337 5481 10338 5482 10338 5480 10338 5481 10339 5483 10339 5482 10339 5484 10340 5483 10340 5481 10340 5484 10341 5485 10341 5483 10341 5486 10342 5485 10342 5484 10342 5486 10343 5487 10343 5485 10343 5488 10344 5487 10344 5486 10344 5488 10345 5489 10345 5487 10345 5490 10346 5489 10346 5488 10346 5490 10347 5491 10347 5489 10347 5490 10348 5492 10348 5491 10348 5493 10349 5492 10349 5490 10349 5493 10350 5494 10350 5492 10350 5495 10351 5494 10351 5493 10351 5495 10352 5496 10352 5494 10352 5497 10353 5496 10353 5495 10353 5497 10354 5498 10354 5496 10354 5497 10355 5499 10355 5498 10355 5500 10356 5499 10356 5497 10356 5500 10357 5501 10357 5499 10357 5502 10358 5501 10358 5500 10358 5502 10359 5503 10359 5501 10359 5502 10360 5504 10360 5503 10360 5505 10361 5504 10361 5502 10361 5505 10362 5506 10362 5504 10362 5507 10363 5508 10363 5505 10363 5505 10364 5508 10364 5506 10364 5507 10365 5509 10365 5508 10365 5510 10366 5509 10366 5507 10366 5510 10367 5511 10367 5509 10367 5512 10368 5511 10368 5510 10368 5512 10369 5513 10369 5511 10369 5512 10370 5514 10370 5513 10370 5515 10371 5514 10371 5512 10371 5515 10372 5516 10372 5514 10372 5517 10373 5516 10373 5515 10373 5517 10374 5518 10374 5516 10374 5517 10375 5519 10375 5518 10375 5520 10376 5519 10376 5517 10376 5520 10377 5521 10377 5519 10377 5522 10378 5521 10378 5520 10378 5522 10379 5523 10379 5521 10379 5524 10380 5523 10380 5522 10380 5524 10381 5525 10381 5523 10381 5524 10382 5526 10382 5525 10382 5527 10383 5526 10383 5524 10383 5527 10384 5528 10384 5526 10384 5527 10385 5529 10385 5528 10385 5530 10386 5529 10386 5527 10386 5530 10387 5531 10387 5529 10387 5532 10388 5531 10388 5530 10388 5532 10389 5533 10389 5531 10389 5534 10390 5533 10390 5532 10390 5534 10391 5535 10391 5533 10391 5536 10392 5535 10392 5534 10392 5536 10393 5537 10393 5535 10393 5538 10394 5537 10394 5536 10394 5538 10395 5539 10395 5537 10395 5538 10396 5540 10396 5539 10396 5541 10397 5540 10397 5538 10397 5541 10398 5542 10398 5540 10398 5543 10399 5542 10399 5541 10399 5543 10400 5544 10400 5542 10400 5545 10401 5544 10401 5543 10401 5545 10402 5546 10402 5544 10402 5545 10403 5547 10403 5546 10403 5548 10404 5547 10404 5545 10404 5548 10405 5549 10405 5547 10405 5550 10406 5549 10406 5548 10406 5550 10407 5551 10407 5549 10407 5552 10408 5551 10408 5550 10408 5553 10409 5551 10409 5552 10409 5553 10410 5554 10410 5551 10410 5553 10411 5555 10411 5554 10411 5556 10412 5555 10412 5553 10412 5556 10413 5557 10413 5555 10413 5558 10414 5559 10414 5556 10414 5556 10415 5559 10415 5557 10415 5558 10416 5560 10416 5559 10416 5558 10417 5561 10417 5560 10417 5562 10418 5561 10418 5558 10418 5562 10419 5563 10419 5561 10419 5564 10420 5563 10420 5562 10420 5564 10421 5565 10421 5563 10421 5566 10422 5565 10422 5564 10422 5566 10423 5567 10423 5565 10423 5566 10424 5568 10424 5567 10424 5569 10425 5568 10425 5566 10425 5569 10426 5570 10426 5568 10426 5571 10427 5570 10427 5569 10427 5571 10428 5572 10428 5570 10428 5573 10429 5574 10429 5571 10429 5571 10430 5574 10430 5572 10430 5573 10431 5575 10431 5574 10431 5576 10432 5575 10432 5573 10432 5576 10433 5577 10433 5575 10433 5578 10434 5577 10434 5576 10434 5578 10435 5579 10435 5577 10435 5580 10436 5579 10436 5578 10436 5580 10437 5581 10437 5579 10437 5580 10438 5582 10438 5581 10438 5583 10439 5582 10439 5580 10439 5584 10440 5582 10440 5583 10440 5584 10441 5585 10441 5582 10441 5584 10442 5586 10442 5585 10442 5587 10443 5586 10443 5584 10443 5587 10444 5588 10444 5586 10444 5589 10445 5588 10445 5587 10445 5589 10446 5590 10446 5588 10446 5589 10447 5105 10447 5590 10447 5591 10448 5105 10448 5589 10448 5591 10449 5103 10449 5105 10449 5591 10450 5097 10450 5103 10450 5592 10451 5097 10451 5591 10451 5593 10452 5097 10452 5592 10452 5593 10453 5094 10453 5097 10453 5594 10454 5125 10454 5123 10454 5595 10455 5125 10455 5594 10455 5127 10456 5125 10456 5595 10456 5596 10457 5127 10457 5595 10457 5130 10458 5127 10458 5596 10458 5132 10459 5130 10459 5596 10459 5597 10460 5132 10460 5596 10460 5598 10461 5132 10461 5597 10461 5135 10462 5132 10462 5598 10462 5137 10463 5135 10463 5598 10463 5599 10464 5137 10464 5598 10464 5140 10465 5137 10465 5599 10465 5600 10466 5140 10466 5599 10466 5141 10467 5140 10467 5600 10467 5601 10468 5141 10468 5600 10468 5144 10469 5141 10469 5601 10469 5146 10470 5144 10470 5601 10470 5602 10471 5146 10471 5601 10471 5148 10472 5146 10472 5602 10472 5603 10473 5148 10473 5602 10473 5150 10474 5148 10474 5603 10474 5604 10475 5150 10475 5603 10475 5153 10476 5150 10476 5604 10476 5605 10477 5153 10477 5604 10477 5155 10478 5153 10478 5605 10478 5606 10479 5155 10479 5605 10479 5158 10480 5155 10480 5606 10480 5607 10481 5158 10481 5606 10481 5160 10482 5158 10482 5607 10482 5608 10483 5160 10483 5607 10483 5162 10484 5160 10484 5608 10484 5165 10485 5162 10485 5608 10485 5609 10486 5165 10486 5608 10486 5167 10487 5165 10487 5609 10487 5610 10488 5167 10488 5609 10488 5169 10489 5167 10489 5610 10489 5611 10490 5169 10490 5610 10490 5612 10491 5169 10491 5611 10491 5172 10492 5169 10492 5612 10492 5613 10493 5172 10493 5612 10493 5174 10494 5172 10494 5613 10494 5614 10495 5174 10495 5613 10495 5615 10496 5174 10496 5614 10496 5177 10497 5174 10497 5615 10497 5180 10498 5177 10498 5615 10498 5616 10499 5180 10499 5615 10499 5617 10500 5180 10500 5616 10500 5181 10501 5180 10501 5617 10501 5618 10502 5181 10502 5617 10502 5184 10503 5181 10503 5618 10503 5186 10504 5184 10504 5618 10504 5619 10505 5186 10505 5618 10505 5189 10506 5186 10506 5619 10506 5620 10507 5189 10507 5619 10507 5191 10508 5189 10508 5620 10508 5621 10509 5191 10509 5620 10509 5193 10510 5191 10510 5621 10510 5622 10511 5193 10511 5621 10511 5623 10512 5193 10512 5622 10512 5196 10513 5193 10513 5623 10513 5198 10514 5196 10514 5623 10514 5624 10515 5198 10515 5623 10515 5201 10516 5198 10516 5624 10516 5625 10517 5201 10517 5624 10517 5203 10518 5201 10518 5625 10518 5626 10519 5203 10519 5625 10519 5205 10520 5203 10520 5626 10520 5207 10521 5205 10521 5626 10521 5627 10522 5207 10522 5626 10522 5628 10523 5207 10523 5627 10523 5210 10524 5207 10524 5628 10524 5629 10525 5210 10525 5628 10525 5213 10526 5210 10526 5629 10526 5630 10527 5213 10527 5629 10527 5216 10528 5213 10528 5630 10528 5218 10529 5216 10529 5631 10529 5220 10530 5218 10530 5631 10530 5632 10531 5220 10531 5631 10531 5633 10532 5220 10532 5632 10532 5223 10533 5220 10533 5633 10533 5225 10534 5223 10534 5633 10534 5227 10535 5225 10535 5634 10535 5230 10536 5227 10536 5634 10536 5635 10537 5230 10537 5634 10537 5232 10538 5230 10538 5635 10538 5636 10539 5232 10539 5635 10539 5234 10540 5232 10540 5636 10540 5637 10541 5234 10541 5636 10541 5237 10542 5234 10542 5637 10542 5638 10543 5237 10543 5637 10543 5239 10544 5237 10544 5638 10544 5241 10545 5239 10545 5638 10545 5241 10546 5638 10546 5639 10546 5640 10547 5241 10547 5639 10547 5243 10548 5241 10548 5640 10548 5641 10549 5243 10549 5640 10549 5246 10550 5243 10550 5641 10550 5642 10551 5246 10551 5641 10551 5248 10552 5246 10552 5642 10552 5643 10553 5248 10553 5642 10553 5644 10554 5248 10554 5643 10554 5250 10555 5248 10555 5644 10555 5645 10556 5250 10556 5644 10556 5253 10557 5250 10557 5645 10557 5254 10558 5253 10558 5645 10558 5646 10559 5254 10559 5645 10559 5647 10560 5254 10560 5646 10560 5257 10561 5254 10561 5647 10561 5648 10562 5257 10562 5647 10562 5649 10563 5257 10563 5648 10563 5259 10564 5257 10564 5649 10564 5650 10565 5259 10565 5649 10565 5262 10566 5259 10566 5650 10566 5262 10567 5650 10567 5651 10567 5264 10568 5262 10568 5651 10568 5652 10569 5264 10569 5651 10569 5267 10570 5264 10570 5652 10570 5270 10571 5267 10571 5652 10571 5272 10572 5270 10572 5653 10572 5274 10573 5272 10573 5653 10573 5654 10574 5276 10574 5274 10574 5655 10575 5276 10575 5654 10575 5279 10576 5276 10576 5655 10576 5656 10577 5279 10577 5655 10577 5281 10578 5279 10578 5656 10578 5284 10579 5281 10579 5656 10579 5657 10580 5284 10580 5656 10580 5658 10581 5284 10581 5657 10581 5287 10582 5284 10582 5658 10582 5659 10583 5287 10583 5658 10583 5289 10584 5287 10584 5659 10584 5660 10585 5289 10585 5659 10585 5291 10586 5289 10586 5660 10586 5661 10587 5291 10587 5660 10587 5294 10588 5291 10588 5661 10588 5662 10589 5294 10589 5661 10589 5297 10590 5294 10590 5662 10590 5663 10591 5297 10591 5662 10591 5299 10592 5297 10592 5663 10592 5664 10593 5299 10593 5663 10593 5302 10594 5299 10594 5664 10594 5665 10595 5304 10595 5302 10595 5306 10596 5304 10596 5665 10596 5666 10597 5306 10597 5665 10597 5308 10598 5306 10598 5666 10598 5667 10599 5308 10599 5666 10599 5310 10600 5308 10600 5667 10600 5668 10601 5310 10601 5667 10601 5312 10602 5310 10602 5668 10602 5669 10603 5312 10603 5668 10603 5314 10604 5312 10604 5669 10604 5670 10605 5314 10605 5669 10605 5316 10606 5314 10606 5670 10606 5671 10607 5316 10607 5670 10607 5318 10608 5316 10608 5671 10608 5672 10609 5318 10609 5671 10609 5320 10610 5318 10610 5672 10610 5322 10611 5320 10611 5672 10611 5673 10612 5322 10612 5672 10612 5325 10613 5322 10613 5673 10613 5674 10614 5325 10614 5673 10614 5327 10615 5325 10615 5674 10615 5329 10616 5327 10616 5674 10616 5331 10617 5329 10617 5675 10617 5334 10618 5331 10618 5675 10618 5336 10619 5334 10619 5676 10619 5338 10620 5336 10620 5676 10620 5677 10621 5338 10621 5676 10621 5339 10622 5338 10622 5677 10622 5678 10623 5339 10623 5677 10623 5342 10624 5339 10624 5678 10624 5679 10625 5342 10625 5678 10625 5343 10626 5342 10626 5679 10626 5346 10627 5343 10627 5679 10627 5680 10628 5346 10628 5679 10628 5681 10629 5346 10629 5680 10629 5348 10630 5346 10630 5681 10630 5350 10631 5348 10631 5681 10631 5682 10632 5350 10632 5681 10632 5352 10633 5350 10633 5682 10633 5683 10634 5352 10634 5682 10634 5355 10635 5352 10635 5683 10635 5684 10636 5355 10636 5683 10636 5358 10637 5355 10637 5684 10637 5685 10638 5358 10638 5684 10638 5360 10639 5358 10639 5685 10639 5686 10640 5360 10640 5685 10640 5362 10641 5360 10641 5686 10641 5687 10642 5362 10642 5686 10642 5688 10643 5362 10643 5687 10643 5366 10644 5362 10644 5688 10644 5368 10645 5366 10645 5688 10645 5689 10646 5368 10646 5688 10646 5690 10647 5368 10647 5689 10647 5370 10648 5368 10648 5690 10648 5691 10649 5370 10649 5690 10649 5373 10650 5370 10650 5691 10650 5692 10651 5373 10651 5691 10651 5376 10652 5373 10652 5692 10652 5693 10653 5376 10653 5692 10653 5378 10654 5376 10654 5693 10654 5694 10655 5378 10655 5693 10655 5380 10656 5378 10656 5694 10656 5695 10657 5380 10657 5694 10657 5382 10658 5380 10658 5695 10658 5696 10659 5382 10659 5695 10659 5385 10660 5382 10660 5696 10660 5697 10661 5385 10661 5696 10661 5387 10662 5385 10662 5697 10662 5698 10663 5387 10663 5697 10663 5390 10664 5387 10664 5698 10664 5699 10665 5390 10665 5698 10665 5393 10666 5390 10666 5699 10666 5700 10667 5393 10667 5699 10667 5395 10668 5393 10668 5700 10668 5701 10669 5395 10669 5700 10669 5397 10670 5395 10670 5701 10670 5399 10671 5397 10671 5701 10671 5399 10672 5701 10672 5702 10672 5401 10673 5399 10673 5702 10673 5703 10674 5401 10674 5702 10674 5403 10675 5401 10675 5703 10675 5704 10676 5403 10676 5703 10676 5705 10677 5403 10677 5704 10677 5406 10678 5403 10678 5705 10678 5706 10679 5406 10679 5705 10679 5409 10680 5406 10680 5706 10680 5707 10681 5409 10681 5706 10681 5411 10682 5409 10682 5707 10682 5708 10683 5411 10683 5707 10683 5413 10684 5411 10684 5708 10684 5709 10685 5413 10685 5708 10685 5415 10686 5413 10686 5709 10686 5710 10687 5415 10687 5709 10687 5418 10688 5415 10688 5710 10688 5711 10689 5418 10689 5710 10689 5420 10690 5418 10690 5711 10690 5712 10691 5420 10691 5711 10691 5713 10692 5420 10692 5712 10692 5423 10693 5420 10693 5713 10693 5424 10694 5423 10694 5713 10694 5714 10695 5424 10695 5713 10695 5426 10696 5424 10696 5714 10696 5715 10697 5426 10697 5714 10697 5428 10698 5426 10698 5715 10698 5430 10699 5428 10699 5715 10699 5716 10700 5430 10700 5715 10700 5433 10701 5430 10701 5716 10701 5717 10702 5433 10702 5716 10702 5435 10703 5433 10703 5717 10703 5437 10704 5435 10704 5718 10704 5719 10705 5437 10705 5718 10705 5440 10706 5437 10706 5719 10706 5443 10707 5440 10707 5719 10707 5720 10708 5443 10708 5719 10708 5721 10709 5443 10709 5720 10709 5446 10710 5443 10710 5721 10710 5722 10711 5446 10711 5721 10711 5448 10712 5446 10712 5722 10712 5723 10713 5448 10713 5722 10713 5450 10714 5448 10714 5723 10714 5452 10715 5450 10715 5723 10715 5724 10716 5452 10716 5723 10716 5455 10717 5452 10717 5724 10717 5725 10718 5455 10718 5724 10718 5726 10719 5455 10719 5725 10719 5458 10720 5455 10720 5726 10720 5459 10721 5458 10721 5726 10721 5727 10722 5459 10722 5726 10722 5728 10723 5459 10723 5727 10723 5462 10724 5459 10724 5728 10724 5729 10725 5462 10725 5728 10725 5464 10726 5462 10726 5729 10726 5730 10727 5464 10727 5729 10727 5466 10728 5464 10728 5730 10728 5468 10729 5466 10729 5730 10729 5470 10730 5468 10730 5731 10730 5473 10731 5470 10731 5731 10731 5732 10732 5473 10732 5731 10732 5733 10733 5473 10733 5732 10733 5475 10734 5473 10734 5733 10734 5734 10735 5475 10735 5733 10735 5477 10736 5475 10736 5734 10736 5735 10737 5477 10737 5734 10737 5479 10738 5477 10738 5735 10738 5481 10739 5479 10739 5735 10739 5736 10740 5481 10740 5735 10740 5484 10741 5481 10741 5736 10741 5737 10742 5484 10742 5736 10742 5486 10743 5484 10743 5737 10743 5738 10744 5486 10744 5737 10744 5488 10745 5486 10745 5738 10745 5490 10746 5488 10746 5738 10746 5739 10747 5490 10747 5738 10747 5493 10748 5490 10748 5739 10748 5740 10749 5493 10749 5739 10749 5495 10750 5493 10750 5740 10750 5741 10751 5495 10751 5740 10751 5497 10752 5495 10752 5741 10752 5742 10753 5497 10753 5741 10753 5500 10754 5497 10754 5742 10754 5502 10755 5500 10755 5743 10755 5744 10756 5502 10756 5743 10756 5505 10757 5502 10757 5744 10757 5745 10758 5505 10758 5744 10758 5507 10759 5505 10759 5745 10759 5510 10760 5507 10760 5745 10760 5746 10761 5510 10761 5745 10761 5512 10762 5510 10762 5746 10762 5747 10763 5512 10763 5746 10763 5515 10764 5512 10764 5747 10764 5748 10765 5517 10765 5515 10765 5749 10766 5517 10766 5748 10766 5520 10767 5517 10767 5749 10767 5522 10768 5520 10768 5749 10768 5750 10769 5524 10769 5522 10769 5527 10770 5524 10770 5750 10770 5751 10771 5527 10771 5750 10771 5530 10772 5527 10772 5751 10772 5532 10773 5530 10773 5752 10773 5753 10774 5532 10774 5752 10774 5534 10775 5532 10775 5753 10775 5754 10776 5534 10776 5753 10776 5536 10777 5534 10777 5754 10777 5538 10778 5536 10778 5754 10778 5755 10779 5538 10779 5754 10779 5756 10780 5538 10780 5755 10780 5541 10781 5538 10781 5756 10781 5757 10782 5541 10782 5756 10782 5543 10783 5541 10783 5757 10783 5758 10784 5543 10784 5757 10784 5545 10785 5543 10785 5758 10785 5759 10786 5545 10786 5758 10786 5548 10787 5545 10787 5759 10787 5550 10788 5548 10788 5759 10788 5760 10789 5550 10789 5759 10789 5552 10790 5550 10790 5760 10790 5761 10791 5553 10791 5552 10791 5556 10792 5553 10792 5761 10792 5762 10793 5556 10793 5761 10793 5763 10794 5556 10794 5762 10794 5558 10795 5556 10795 5763 10795 5764 10796 5558 10796 5763 10796 5562 10797 5558 10797 5764 10797 5765 10798 5562 10798 5764 10798 5564 10799 5562 10799 5765 10799 5766 10800 5564 10800 5765 10800 5566 10801 5564 10801 5766 10801 5767 10802 5566 10802 5766 10802 5569 10803 5566 10803 5767 10803 5768 10804 5569 10804 5767 10804 5571 10805 5569 10805 5768 10805 5769 10806 5571 10806 5768 10806 5573 10807 5571 10807 5769 10807 5770 10808 5573 10808 5769 10808 5576 10809 5573 10809 5770 10809 5578 10810 5576 10810 5770 10810 5580 10811 5578 10811 5771 10811 5583 10812 5580 10812 5771 10812 5772 10813 5583 10813 5771 10813 5584 10814 5583 10814 5772 10814 5773 10815 5584 10815 5772 10815 5587 10816 5584 10816 5773 10816 5774 10817 5587 10817 5773 10817 5589 10818 5587 10818 5774 10818 5775 10819 5589 10819 5774 10819 5591 10820 5589 10820 5775 10820 5776 10821 5591 10821 5775 10821 5592 10822 5591 10822 5776 10822 5777 10823 5592 10823 5776 10823 5593 10824 5592 10824 5777 10824 5094 10825 5593 10825 5777 10825 5778 10826 5094 10826 5777 10826 5093 10827 5094 10827 5778 10827 5779 10828 5093 10828 5778 10828 5098 10829 5093 10829 5779 10829 5781 10830 5596 10830 5595 10830 5781 10831 5597 10831 5596 10831 5782 10832 5597 10832 5781 10832 5782 10833 5598 10833 5597 10833 5780 10834 5598 10834 5782 10834 5780 10835 5599 10835 5598 10835 5783 10836 5599 10836 5780 10836 5111 10837 5599 10837 5783 10837 5111 10838 5600 10838 5599 10838 5112 10839 5600 10839 5111 10839 5112 10840 5601 10840 5600 10840 5113 10841 5601 10841 5112 10841 5115 10842 5601 10842 5113 10842 5115 10843 5602 10843 5601 10843 5118 10844 5602 10844 5115 10844 5120 10845 5603 10845 5118 10845 5118 10846 5603 10846 5602 10846 5122 10847 5603 10847 5120 10847 5122 10848 5604 10848 5603 10848 5784 10849 5604 10849 5122 10849 5784 10850 5605 10850 5604 10850 5785 10851 5605 10851 5784 10851 5785 10852 5606 10852 5605 10852 5126 10853 5606 10853 5785 10853 5128 10854 5606 10854 5126 10854 5128 10855 5607 10855 5606 10855 5129 10856 5607 10856 5128 10856 5131 10857 5607 10857 5129 10857 5131 10858 5608 10858 5607 10858 5133 10859 5608 10859 5131 10859 5134 10860 5608 10860 5133 10860 5134 10861 5609 10861 5608 10861 5136 10862 5609 10862 5134 10862 5138 10863 5609 10863 5136 10863 5138 10864 5610 10864 5609 10864 5138 10865 5611 10865 5610 10865 5139 10866 5611 10866 5138 10866 5139 10867 5612 10867 5611 10867 5142 10868 5612 10868 5139 10868 5143 10869 5612 10869 5142 10869 5143 10870 5613 10870 5612 10870 5145 10871 5613 10871 5143 10871 5145 10872 5614 10872 5613 10872 5147 10873 5614 10873 5145 10873 5147 10874 5615 10874 5614 10874 5149 10875 5615 10875 5147 10875 5151 10876 5615 10876 5149 10876 5151 10877 5616 10877 5615 10877 5152 10878 5616 10878 5151 10878 5152 10879 5617 10879 5616 10879 5154 10880 5617 10880 5152 10880 5156 10881 5617 10881 5154 10881 5156 10882 5618 10882 5617 10882 5786 10883 5618 10883 5156 10883 5787 10884 5618 10884 5786 10884 5787 10885 5619 10885 5618 10885 5159 10886 5619 10886 5787 10886 5159 10887 5620 10887 5619 10887 5161 10888 5620 10888 5159 10888 5163 10889 5620 10889 5161 10889 5163 10890 5621 10890 5620 10890 5164 10891 5621 10891 5163 10891 5164 10892 5622 10892 5621 10892 5166 10893 5622 10893 5164 10893 5166 10894 5623 10894 5622 10894 5168 10895 5623 10895 5166 10895 5168 10896 5624 10896 5623 10896 5170 10897 5624 10897 5168 10897 5171 10898 5624 10898 5170 10898 5171 10899 5625 10899 5624 10899 5173 10900 5625 10900 5171 10900 5173 10901 5626 10901 5625 10901 5175 10902 5626 10902 5173 10902 5176 10903 5626 10903 5175 10903 5176 10904 5627 10904 5626 10904 5178 10905 5627 10905 5176 10905 5178 10906 5628 10906 5627 10906 5179 10907 5628 10907 5178 10907 5179 10908 5629 10908 5628 10908 5182 10909 5629 10909 5179 10909 5183 10910 5629 10910 5182 10910 5183 10911 5630 10911 5629 10911 5185 10912 5630 10912 5183 10912 5185 10913 5216 10913 5630 10913 5187 10914 5216 10914 5185 10914 5187 10915 5631 10915 5216 10915 5188 10916 5631 10916 5187 10916 5190 10917 5631 10917 5188 10917 5190 10918 5632 10918 5631 10918 5192 10919 5632 10919 5190 10919 5192 10920 5633 10920 5632 10920 5194 10921 5633 10921 5192 10921 5194 10922 5225 10922 5633 10922 5195 10923 5225 10923 5194 10923 5195 10924 5634 10924 5225 10924 5197 10925 5634 10925 5195 10925 5199 10926 5634 10926 5197 10926 5200 10927 5634 10927 5199 10927 5200 10928 5635 10928 5634 10928 5202 10929 5635 10929 5200 10929 5202 10930 5636 10930 5635 10930 5204 10931 5636 10931 5202 10931 5204 10932 5637 10932 5636 10932 5206 10933 5637 10933 5204 10933 5208 10934 5637 10934 5206 10934 5208 10935 5638 10935 5637 10935 5209 10936 5638 10936 5208 10936 5211 10937 5638 10937 5209 10937 5211 10938 5639 10938 5638 10938 5212 10939 5639 10939 5211 10939 5212 10940 5640 10940 5639 10940 5214 10941 5640 10941 5212 10941 5214 10942 5641 10942 5640 10942 5215 10943 5641 10943 5214 10943 5215 10944 5642 10944 5641 10944 5217 10945 5642 10945 5215 10945 5217 10946 5643 10946 5642 10946 5219 10947 5643 10947 5217 10947 5219 10948 5644 10948 5643 10948 5221 10949 5644 10949 5219 10949 5222 10950 5644 10950 5221 10950 5222 10951 5645 10951 5644 10951 5224 10952 5645 10952 5222 10952 5224 10953 5646 10953 5645 10953 5226 10954 5646 10954 5224 10954 5226 10955 5647 10955 5646 10955 5229 10956 5647 10956 5226 10956 5229 10957 5648 10957 5647 10957 5231 10958 5648 10958 5229 10958 5231 10959 5649 10959 5648 10959 5233 10960 5649 10960 5231 10960 5235 10961 5649 10961 5233 10961 5235 10962 5650 10962 5649 10962 5236 10963 5650 10963 5235 10963 5236 10964 5651 10964 5650 10964 5238 10965 5651 10965 5236 10965 5240 10966 5651 10966 5238 10966 5240 10967 5652 10967 5651 10967 5242 10968 5652 10968 5240 10968 5242 10969 5270 10969 5652 10969 5244 10970 5270 10970 5242 10970 5244 10971 5653 10971 5270 10971 5788 10972 5653 10972 5244 10972 5788 10973 5274 10973 5653 10973 5247 10974 5274 10974 5788 10974 5247 10975 5654 10975 5274 10975 5789 10976 5654 10976 5247 10976 5249 10977 5655 10977 5789 10977 5789 10978 5655 10978 5654 10978 5251 10979 5655 10979 5249 10979 5251 10980 5656 10980 5655 10980 5252 10981 5656 10981 5251 10981 5255 10982 5656 10982 5252 10982 5255 10983 5657 10983 5656 10983 5256 10984 5657 10984 5255 10984 5256 10985 5658 10985 5657 10985 5790 10986 5658 10986 5256 10986 5790 10987 5659 10987 5658 10987 5260 10988 5659 10988 5790 10988 5791 10989 5659 10989 5260 10989 5791 10990 5660 10990 5659 10990 5261 10991 5660 10991 5791 10991 5263 10992 5660 10992 5261 10992 5263 10993 5661 10993 5660 10993 5265 10994 5661 10994 5263 10994 5265 10995 5662 10995 5661 10995 5266 10996 5662 10996 5265 10996 5268 10997 5662 10997 5266 10997 5268 10998 5663 10998 5662 10998 5269 10999 5663 10999 5268 10999 5269 11000 5664 11000 5663 11000 5271 11001 5664 11001 5269 11001 5273 11002 5664 11002 5271 11002 5273 11003 5302 11003 5664 11003 5275 11004 5302 11004 5273 11004 5275 11005 5665 11005 5302 11005 5277 11006 5665 11006 5275 11006 5278 11007 5665 11007 5277 11007 5278 11008 5666 11008 5665 11008 5280 11009 5666 11009 5278 11009 5280 11010 5667 11010 5666 11010 5282 11011 5667 11011 5280 11011 5283 11012 5668 11012 5282 11012 5282 11013 5668 11013 5667 11013 5285 11014 5668 11014 5283 11014 5285 11015 5669 11015 5668 11015 5285 11016 5670 11016 5669 11016 5286 11017 5670 11017 5285 11017 5288 11018 5670 11018 5286 11018 5288 11019 5671 11019 5670 11019 5792 11020 5671 11020 5288 11020 5290 11021 5672 11021 5792 11021 5792 11022 5672 11022 5671 11022 5292 11023 5672 11023 5290 11023 5292 11024 5673 11024 5672 11024 5293 11025 5673 11025 5292 11025 5295 11026 5673 11026 5293 11026 5295 11027 5674 11027 5673 11027 5296 11028 5674 11028 5295 11028 5298 11029 5674 11029 5296 11029 5298 11030 5329 11030 5674 11030 5300 11031 5329 11031 5298 11031 5300 11032 5675 11032 5329 11032 5301 11033 5675 11033 5300 11033 5303 11034 5675 11034 5301 11034 5303 11035 5334 11035 5675 11035 5305 11036 5334 11036 5303 11036 5305 11037 5676 11037 5334 11037 5307 11038 5676 11038 5305 11038 5307 11039 5677 11039 5676 11039 5309 11040 5677 11040 5307 11040 5309 11041 5678 11041 5677 11041 5311 11042 5678 11042 5309 11042 5793 11043 5678 11043 5311 11043 5793 11044 5679 11044 5678 11044 5315 11045 5679 11045 5793 11045 5315 11046 5680 11046 5679 11046 5317 11047 5680 11047 5315 11047 5317 11048 5681 11048 5680 11048 5319 11049 5681 11049 5317 11049 5321 11050 5681 11050 5319 11050 5321 11051 5682 11051 5681 11051 5323 11052 5682 11052 5321 11052 5324 11053 5682 11053 5323 11053 5324 11054 5683 11054 5682 11054 5326 11055 5683 11055 5324 11055 5328 11056 5683 11056 5326 11056 5328 11057 5684 11057 5683 11057 5330 11058 5684 11058 5328 11058 5330 11059 5685 11059 5684 11059 5332 11060 5685 11060 5330 11060 5332 11061 5686 11061 5685 11061 5333 11062 5686 11062 5332 11062 5794 11063 5686 11063 5333 11063 5794 11064 5687 11064 5686 11064 5794 11065 5688 11065 5687 11065 5335 11066 5688 11066 5794 11066 5337 11067 5688 11067 5335 11067 5337 11068 5689 11068 5688 11068 5340 11069 5689 11069 5337 11069 5340 11070 5690 11070 5689 11070 5795 11071 5690 11071 5340 11071 5341 11072 5691 11072 5795 11072 5795 11073 5691 11073 5690 11073 5344 11074 5691 11074 5341 11074 5344 11075 5692 11075 5691 11075 5345 11076 5692 11076 5344 11076 5347 11077 5692 11077 5345 11077 5347 11078 5693 11078 5692 11078 5349 11079 5693 11079 5347 11079 5349 11080 5694 11080 5693 11080 5796 11081 5694 11081 5349 11081 5351 11082 5694 11082 5796 11082 5351 11083 5695 11083 5694 11083 5353 11084 5695 11084 5351 11084 5353 11085 5696 11085 5695 11085 5354 11086 5696 11086 5353 11086 5357 11087 5696 11087 5354 11087 5357 11088 5697 11088 5696 11088 5359 11089 5697 11089 5357 11089 5359 11090 5698 11090 5697 11090 5361 11091 5698 11091 5359 11091 5361 11092 5699 11092 5698 11092 5363 11093 5699 11093 5361 11093 5364 11094 5700 11094 5363 11094 5363 11095 5700 11095 5699 11095 5365 11096 5700 11096 5364 11096 5365 11097 5701 11097 5700 11097 5367 11098 5701 11098 5365 11098 5797 11099 5701 11099 5367 11099 5369 11100 5701 11100 5797 11100 5369 11101 5702 11101 5701 11101 5371 11102 5702 11102 5369 11102 5371 11103 5703 11103 5702 11103 5372 11104 5703 11104 5371 11104 5374 11105 5703 11105 5372 11105 5374 11106 5704 11106 5703 11106 5375 11107 5704 11107 5374 11107 5377 11108 5705 11108 5375 11108 5375 11109 5705 11109 5704 11109 5379 11110 5705 11110 5377 11110 5379 11111 5706 11111 5705 11111 5381 11112 5706 11112 5379 11112 5381 11113 5707 11113 5706 11113 5383 11114 5707 11114 5381 11114 5384 11115 5707 11115 5383 11115 5384 11116 5708 11116 5707 11116 5386 11117 5708 11117 5384 11117 5386 11118 5709 11118 5708 11118 5389 11119 5709 11119 5386 11119 5389 11120 5710 11120 5709 11120 5391 11121 5710 11121 5389 11121 5391 11122 5711 11122 5710 11122 5798 11123 5711 11123 5391 11123 5799 11124 5711 11124 5798 11124 5799 11125 5712 11125 5711 11125 5394 11126 5712 11126 5799 11126 5394 11127 5713 11127 5712 11127 5396 11128 5713 11128 5394 11128 5396 11129 5714 11129 5713 11129 5398 11130 5714 11130 5396 11130 5400 11131 5714 11131 5398 11131 5400 11132 5715 11132 5714 11132 5402 11133 5715 11133 5400 11133 5402 11134 5716 11134 5715 11134 5404 11135 5716 11135 5402 11135 5404 11136 5717 11136 5716 11136 5405 11137 5717 11137 5404 11137 5405 11138 5435 11138 5717 11138 5407 11139 5435 11139 5405 11139 5407 11140 5718 11140 5435 11140 5408 11141 5718 11141 5407 11141 5410 11142 5719 11142 5408 11142 5408 11143 5719 11143 5718 11143 5412 11144 5719 11144 5410 11144 5412 11145 5720 11145 5719 11145 5414 11146 5720 11146 5412 11146 5414 11147 5721 11147 5720 11147 5416 11148 5721 11148 5414 11148 5416 11149 5722 11149 5721 11149 5417 11150 5722 11150 5416 11150 5419 11151 5722 11151 5417 11151 5419 11152 5723 11152 5722 11152 5421 11153 5723 11153 5419 11153 5800 11154 5723 11154 5421 11154 5800 11155 5724 11155 5723 11155 5422 11156 5724 11156 5800 11156 5425 11157 5724 11157 5422 11157 5425 11158 5725 11158 5724 11158 5427 11159 5725 11159 5425 11159 5429 11160 5725 11160 5427 11160 5429 11161 5726 11161 5725 11161 5431 11162 5726 11162 5429 11162 5431 11163 5727 11163 5726 11163 5432 11164 5727 11164 5431 11164 5432 11165 5728 11165 5727 11165 5434 11166 5728 11166 5432 11166 5434 11167 5729 11167 5728 11167 5436 11168 5729 11168 5434 11168 5438 11169 5730 11169 5436 11169 5436 11170 5730 11170 5729 11170 5439 11171 5730 11171 5438 11171 5439 11172 5468 11172 5730 11172 5441 11173 5468 11173 5439 11173 5441 11174 5731 11174 5468 11174 5442 11175 5731 11175 5441 11175 5444 11176 5731 11176 5442 11176 5444 11177 5732 11177 5731 11177 5801 11178 5732 11178 5444 11178 5801 11179 5733 11179 5732 11179 5447 11180 5733 11180 5801 11180 5447 11181 5734 11181 5733 11181 5449 11182 5734 11182 5447 11182 5451 11183 5734 11183 5449 11183 5451 11184 5735 11184 5734 11184 5453 11185 5735 11185 5451 11185 5453 11186 5736 11186 5735 11186 5454 11187 5736 11187 5453 11187 5454 11188 5737 11188 5736 11188 5456 11189 5737 11189 5454 11189 5457 11190 5737 11190 5456 11190 5457 11191 5738 11191 5737 11191 5460 11192 5738 11192 5457 11192 5461 11193 5738 11193 5460 11193 5461 11194 5739 11194 5738 11194 5463 11195 5739 11195 5461 11195 5463 11196 5740 11196 5739 11196 5465 11197 5740 11197 5463 11197 5465 11198 5741 11198 5740 11198 5467 11199 5741 11199 5465 11199 5469 11200 5742 11200 5467 11200 5467 11201 5742 11201 5741 11201 5471 11202 5742 11202 5469 11202 5471 11203 5500 11203 5742 11203 5472 11204 5500 11204 5471 11204 5472 11205 5743 11205 5500 11205 5802 11206 5743 11206 5472 11206 5802 11207 5744 11207 5743 11207 5474 11208 5744 11208 5802 11208 5476 11209 5744 11209 5474 11209 5476 11210 5745 11210 5744 11210 5478 11211 5745 11211 5476 11211 5478 11212 5746 11212 5745 11212 5480 11213 5746 11213 5478 11213 5482 11214 5746 11214 5480 11214 5482 11215 5747 11215 5746 11215 5483 11216 5747 11216 5482 11216 5483 11217 5515 11217 5747 11217 5485 11218 5515 11218 5483 11218 5485 11219 5748 11219 5515 11219 5803 11220 5748 11220 5485 11220 5803 11221 5749 11221 5748 11221 5489 11222 5749 11222 5803 11222 5489 11223 5522 11223 5749 11223 5491 11224 5522 11224 5489 11224 5492 11225 5522 11225 5491 11225 5492 11226 5750 11226 5522 11226 5494 11227 5750 11227 5492 11227 5494 11228 5751 11228 5750 11228 5496 11229 5751 11229 5494 11229 5498 11230 5751 11230 5496 11230 5498 11231 5530 11231 5751 11231 5499 11232 5530 11232 5498 11232 5499 11233 5752 11233 5530 11233 5501 11234 5752 11234 5499 11234 5501 11235 5753 11235 5752 11235 5503 11236 5753 11236 5501 11236 5504 11237 5753 11237 5503 11237 5504 11238 5754 11238 5753 11238 5506 11239 5754 11239 5504 11239 5506 11240 5755 11240 5754 11240 5508 11241 5755 11241 5506 11241 5509 11242 5755 11242 5508 11242 5509 11243 5756 11243 5755 11243 5511 11244 5756 11244 5509 11244 5511 11245 5757 11245 5756 11245 5513 11246 5757 11246 5511 11246 5513 11247 5758 11247 5757 11247 5514 11248 5758 11248 5513 11248 5516 11249 5758 11249 5514 11249 5516 11250 5759 11250 5758 11250 5518 11251 5759 11251 5516 11251 5519 11252 5760 11252 5518 11252 5518 11253 5760 11253 5759 11253 5521 11254 5552 11254 5519 11254 5519 11255 5552 11255 5760 11255 5525 11256 5761 11256 5521 11256 5521 11257 5761 11257 5552 11257 5526 11258 5761 11258 5525 11258 5526 11259 5762 11259 5761 11259 5528 11260 5762 11260 5526 11260 5528 11261 5763 11261 5762 11261 5529 11262 5763 11262 5528 11262 5531 11263 5764 11263 5529 11263 5529 11264 5764 11264 5763 11264 5533 11265 5764 11265 5531 11265 5533 11266 5765 11266 5764 11266 5535 11267 5765 11267 5533 11267 5535 11268 5766 11268 5765 11268 5537 11269 5766 11269 5535 11269 5537 11270 5767 11270 5766 11270 5539 11271 5767 11271 5537 11271 5540 11272 5767 11272 5539 11272 5540 11273 5768 11273 5767 11273 5542 11274 5768 11274 5540 11274 5542 11275 5769 11275 5768 11275 5544 11276 5769 11276 5542 11276 5544 11277 5770 11277 5769 11277 5546 11278 5770 11278 5544 11278 5547 11279 5770 11279 5546 11279 5547 11280 5578 11280 5770 11280 5549 11281 5578 11281 5547 11281 5549 11282 5771 11282 5578 11282 5551 11283 5771 11283 5549 11283 5554 11284 5771 11284 5551 11284 5554 11285 5772 11285 5771 11285 5555 11286 5772 11286 5554 11286 5555 11287 5773 11287 5772 11287 5557 11288 5773 11288 5555 11288 5559 11289 5773 11289 5557 11289 5559 11290 5774 11290 5773 11290 5560 11291 5774 11291 5559 11291 5560 11292 5775 11292 5774 11292 5561 11293 5775 11293 5560 11293 5563 11294 5775 11294 5561 11294 5563 11295 5776 11295 5775 11295 5565 11296 5776 11296 5563 11296 5567 11297 5776 11297 5565 11297 5567 11298 5777 11298 5776 11298 5568 11299 5777 11299 5567 11299 5570 11300 5777 11300 5568 11300 5570 11301 5778 11301 5777 11301 5572 11302 5778 11302 5570 11302 5572 11303 5779 11303 5778 11303 5574 11304 5779 11304 5572 11304 5574 11305 5098 11305 5779 11305 5575 11306 5098 11306 5574 11306 5575 11307 5102 11307 5098 11307 5577 11308 5102 11308 5575 11308 5577 11309 5104 11309 5102 11309 5579 11310 5104 11310 5577 11310 5581 11311 5104 11311 5579 11311 5581 11312 5107 11312 5104 11312 5582 11313 5107 11313 5581 11313 5585 11314 5107 11314 5582 11314 5585 11315 5109 11315 5107 11315 5804 11316 5109 11316 5585 11316 5804 11317 5110 11317 5109 11317 5124 11318 5784 11318 5122 11318 5785 11319 5784 11319 5124 11319 5126 11320 5785 11320 5124 11320 5157 11321 5786 11321 5156 11321 5787 11322 5786 11322 5157 11322 5159 11323 5787 11323 5157 11323 5229 11324 5226 11324 5228 11324 5245 11325 5788 11325 5244 11325 5247 11326 5788 11326 5245 11326 5249 11327 5789 11327 5247 11327 5258 11328 5790 11328 5256 11328 5260 11329 5790 11329 5258 11329 5261 11330 5791 11330 5260 11330 5290 11331 5792 11331 5288 11331 5313 11332 5793 11332 5311 11332 5315 11333 5793 11333 5313 11333 5335 11334 5794 11334 5333 11334 5341 11335 5795 11335 5340 11335 5351 11336 5796 11336 5349 11336 5357 11337 5354 11337 5356 11337 5369 11338 5797 11338 5367 11338 5389 11339 5386 11339 5388 11339 5392 11340 5798 11340 5391 11340 5799 11341 5798 11341 5392 11341 5394 11342 5799 11342 5392 11342 5422 11343 5800 11343 5421 11343 5801 11344 5444 11344 5445 11344 5447 11345 5801 11345 5445 11345 5474 11346 5802 11346 5472 11346 5803 11347 5485 11347 5487 11347 5489 11348 5803 11348 5487 11348 5525 11349 5521 11349 5523 11349 5586 11350 5804 11350 5585 11350 5110 11351 5804 11351 5586 11351 5588 11352 5110 11352 5586 11352 5811 11353 5110 11353 5588 11353 5590 11354 5808 11354 5588 11354 5807 11355 5806 11355 5805 11355 5810 11356 5807 11356 5805 11356 5811 11357 5808 11357 5807 11357 5588 11358 5808 11358 5811 11358 5810 11359 5805 11359 5809 11359 5811 11360 5807 11360 5810 11360 5812 11361 5811 11361 5810 11361 5812 11362 5810 11362 5809 11362 5110 11363 5811 11363 5812 11363 5814 11364 5812 11364 5809 11364 5110 11365 5812 11365 5814 11365 5814 11366 5809 11366 5813 11366 5815 11367 5814 11367 5813 11367 5109 11368 5110 11368 5814 11368 5815 11369 5109 11369 5814 11369 5817 11370 5815 11370 5813 11370 5816 11371 5817 11371 5813 11371 5818 11372 5109 11372 5815 11372 5818 11373 5815 11373 5817 11373 5819 11374 5817 11374 5816 11374 5820 11375 5817 11375 5819 11375 5820 11376 5818 11376 5817 11376 5108 11377 5818 11377 5820 11377 5822 11378 5816 11378 5821 11378 5819 11379 5816 11379 5822 11379 5823 11380 5819 11380 5822 11380 5823 11381 5820 11381 5819 11381 5108 11382 5820 11382 5823 11382 5825 11383 5823 11383 5822 11383 5106 11384 5108 11384 5823 11384 5821 11385 5825 11385 5822 11385 5106 11386 5823 11386 5825 11386 5826 11387 5821 11387 5824 11387 5826 11388 5825 11388 5821 11388 5827 11389 5106 11389 5825 11389 5827 11390 5825 11390 5826 11390 5828 11391 5826 11391 5824 11391 5829 11392 5827 11392 5826 11392 5830 11393 5826 11393 5828 11393 5829 11394 5826 11394 5830 11394 5831 11395 5829 11395 5830 11395 5833 11396 5828 11396 5824 11396 5832 11397 5830 11397 5828 11397 5832 11398 5828 11398 5833 11398 5834 11399 5830 11399 5832 11399 5831 11400 5830 11400 5834 11400 5100 11401 5831 11401 5834 11401 5833 11402 5834 11402 5832 11402 5835 11403 5834 11403 5833 11403 5096 11404 5100 11404 5834 11404 5835 11405 5096 11405 5834 11405 5836 11406 5833 11406 5837 11406 5835 11407 5833 11407 5836 11407 5838 11408 5835 11408 5836 11408 5839 11409 5096 11409 5835 11409 5838 11410 5839 11410 5835 11410 5838 11411 5836 11411 5837 11411 5840 11412 5838 11412 5837 11412 5840 11413 5839 11413 5838 11413 5841 11414 5840 11414 5837 11414 5095 11415 5839 11415 5840 11415 5842 11416 5840 11416 5841 11416 5095 11417 5840 11417 5842 11417 5841 11418 5837 11418 5843 11418 5844 11419 5842 11419 5841 11419 5844 11420 5095 11420 5842 11420 5843 11421 5844 11421 5841 11421 5845 11422 5844 11422 5843 11422 5099 11423 5095 11423 5844 11423 5099 11424 5844 11424 5845 11424 5846 11425 5845 11425 5843 11425 5846 11426 5843 11426 5847 11426 5101 11427 5099 11427 5845 11427 5848 11428 5846 11428 5847 11428 5101 11429 5845 11429 5846 11429 5101 11430 5846 11430 5848 11430 5849 11431 5848 11431 5847 11431 5103 11432 5101 11432 5848 11432 5103 11433 5848 11433 5849 11433 5849 11434 5847 11434 5850 11434 5850 11435 5847 11435 5806 11435 5851 11436 5103 11436 5849 11436 5851 11437 5105 11437 5103 11437 5852 11438 5849 11438 5850 11438 5851 11439 5849 11439 5852 11439 5105 11440 5851 11440 5852 11440 5852 11441 5850 11441 5806 11441 5853 11442 5105 11442 5852 11442 5853 11443 5590 11443 5105 11443 5852 11444 5806 11444 5807 11444 5853 11445 5852 11445 5807 11445 5853 11446 5807 11446 5808 11446 5590 11447 5853 11447 5808 11447 5821 11448 5816 11448 5813 11448 5824 11449 5847 11449 5843 11449 5824 11450 5837 11450 5833 11450 5824 11451 5843 11451 5837 11451 5824 11452 5821 11452 5813 11452 5824 11453 5806 11453 5847 11453 5824 11454 5809 11454 5805 11454 5824 11455 5813 11455 5809 11455 5824 11456 5805 11456 5806 11456 5855 11457 5856 11457 5854 11457 5856 11458 5855 11458 5858 11458 5860 11459 5857 11459 5856 11459 5860 11460 5856 11460 5858 11460 5860 11461 5858 11461 5861 11461 5861 11462 5858 11462 5859 11462 5864 11463 5860 11463 5861 11463 5863 11464 5861 11464 5859 11464 5863 11465 5859 11465 5862 11465 5864 11466 5861 11466 5863 11466 5863 11467 5862 11467 5865 11467 5866 11468 5863 11468 5865 11468 5864 11469 5863 11469 5866 11469 5868 11470 5864 11470 5866 11470 5867 11471 5866 11471 5865 11471 5866 11472 5867 11472 5869 11472 5868 11473 5866 11473 5869 11473 5869 11474 5867 11474 5870 11474 5868 11475 5869 11475 5871 11475 5871 11476 5869 11476 5870 11476 5873 11477 5871 11477 5870 11477 5873 11478 5870 11478 5872 11478 5874 11479 5871 11479 5873 11479 5873 11480 5872 11480 5875 11480 5876 11481 5873 11481 5875 11481 5874 11482 5873 11482 5876 11482 5878 11483 5876 11483 5875 11483 5877 11484 5874 11484 5876 11484 5877 11485 5876 11485 5878 11485 5879 11486 5877 11486 5878 11486 5882 11487 5877 11487 5879 11487 5882 11488 5879 11488 5880 11488 5880 11489 5879 11489 5881 11489 5883 11490 5880 11490 5881 11490 5884 11491 5880 11491 5883 11491 5884 11492 5882 11492 5880 11492 5884 11493 5883 11493 5885 11493 5886 11494 5882 11494 5884 11494 5888 11495 5884 11495 5885 11495 5886 11496 5884 11496 5888 11496 5887 11497 5888 11497 5885 11497 5890 11498 5886 11498 5888 11498 5889 11499 5888 11499 5887 11499 5890 11500 5888 11500 5889 11500 5892 11501 5889 11501 5891 11501 5890 11502 5889 11502 5892 11502 5893 11503 5892 11503 5891 11503 5894 11504 5890 11504 5892 11504 5894 11505 5892 11505 5893 11505 5896 11506 5893 11506 5895 11506 5894 11507 5893 11507 5896 11507 5897 11508 5896 11508 5895 11508 5898 11509 5894 11509 5896 11509 5898 11510 5896 11510 5897 11510 5900 11511 5898 11511 5897 11511 5900 11512 5897 11512 5899 11512 5901 11513 5894 11513 5898 11513 5901 11514 5898 11514 5900 11514 5902 11515 5900 11515 5899 11515 5903 11516 5900 11516 5902 11516 5903 11517 5901 11517 5900 11517 5904 11518 5903 11518 5902 11518 5905 11519 5903 11519 5904 11519 5901 11520 5903 11520 5905 11520 5905 11521 5904 11521 5906 11521 5909 11522 5901 11522 5905 11522 5910 11523 5905 11523 5906 11523 5907 11524 5901 11524 5909 11524 5910 11525 5906 11525 5908 11525 5909 11526 5905 11526 5910 11526 5911 11527 5910 11527 5908 11527 5907 11528 5909 11528 5910 11528 5912 11529 5910 11529 5911 11529 5912 11530 5907 11530 5910 11530 5915 11531 5907 11531 5912 11531 5915 11532 5912 11532 5913 11532 5914 11533 5907 11533 5915 11533 5915 11534 5913 11534 5916 11534 5914 11535 5915 11535 5916 11535 5914 11536 5916 11536 5917 11536 5918 11537 5917 11537 5916 11537 5919 11538 5914 11538 5917 11538 5919 11539 5917 11539 5918 11539 5919 11540 5918 11540 5920 11540 5857 11541 5919 11541 5920 11541 5857 11542 5920 11542 5854 11542 5857 11543 5854 11543 5856 11543 5855 11544 5854 11544 5921 11544 5855 11545 5921 11545 5989 11545 5858 11546 5855 11546 5989 11546 5859 11547 5989 11547 5987 11547 5859 11548 5858 11548 5989 11548 5859 11549 5987 11549 5985 11549 5862 11550 5859 11550 5985 11550 5865 11551 5985 11551 5922 11551 5865 11552 5862 11552 5985 11552 5867 11553 5922 11553 5981 11553 5867 11554 5865 11554 5922 11554 5867 11555 5981 11555 5979 11555 5870 11556 5867 11556 5979 11556 5870 11557 5979 11557 5923 11557 5872 11558 5870 11558 5923 11558 5872 11559 5923 11559 5924 11559 5872 11560 5924 11560 5925 11560 5875 11561 5872 11561 5925 11561 5875 11562 5925 11562 5926 11562 5878 11563 5875 11563 5926 11563 5878 11564 5926 11564 5927 11564 5878 11565 5927 11565 5928 11565 5879 11566 5878 11566 5928 11566 5881 11567 5879 11567 5928 11567 5881 11568 5928 11568 5973 11568 5881 11569 5973 11569 5929 11569 5883 11570 5881 11570 5929 11570 5885 11571 5883 11571 5929 11571 5885 11572 5929 11572 5930 11572 5885 11573 5930 11573 5968 11573 5887 11574 5885 11574 5968 11574 5889 11575 5968 11575 5966 11575 5889 11576 5887 11576 5968 11576 5891 11577 5889 11577 5966 11577 5891 11578 5966 11578 5964 11578 5893 11579 5891 11579 5964 11579 5893 11580 5964 11580 5931 11580 5893 11581 5931 11581 5962 11581 5895 11582 5893 11582 5962 11582 5895 11583 5962 11583 5932 11583 5897 11584 5932 11584 5958 11584 5897 11585 5895 11585 5932 11585 5899 11586 5958 11586 5933 11586 5899 11587 5897 11587 5958 11587 5899 11588 5933 11588 5934 11588 5902 11589 5899 11589 5934 11589 5904 11590 5902 11590 5934 11590 5904 11591 5934 11591 5935 11591 5906 11592 5904 11592 5935 11592 5906 11593 5935 11593 5936 11593 5906 11594 5936 11594 5951 11594 5908 11595 5906 11595 5951 11595 5911 11596 5951 11596 5937 11596 5911 11597 5908 11597 5951 11597 5912 11598 5937 11598 5938 11598 5912 11599 5911 11599 5937 11599 5913 11600 5912 11600 5938 11600 5913 11601 5938 11601 5939 11601 5916 11602 5913 11602 5939 11602 5918 11603 5916 11603 5939 11603 5918 11604 5939 11604 5940 11604 5920 11605 5918 11605 5940 11605 5854 11606 5940 11606 5941 11606 5854 11607 5920 11607 5940 11607 5854 11608 5941 11608 5921 11608 5123 11609 5894 11609 5594 11609 5594 11610 5894 11610 5901 11610 5595 11611 5594 11611 5901 11611 5121 11612 5894 11612 5123 11612 5781 11613 5595 11613 5901 11613 5121 11614 5890 11614 5894 11614 5781 11615 5901 11615 5907 11615 5116 11616 5890 11616 5121 11616 5116 11617 5886 11617 5890 11617 5116 11618 5882 11618 5886 11618 5781 11619 5907 11619 5914 11619 5119 11620 5882 11620 5116 11620 5782 11621 5781 11621 5914 11621 5919 11622 5782 11622 5914 11622 5882 11623 5119 11623 5117 11623 5877 11624 5882 11624 5117 11624 5857 11625 5782 11625 5919 11625 5857 11626 5780 11626 5782 11626 5874 11627 5877 11627 5117 11627 5874 11628 5117 11628 5114 11628 5860 11629 5780 11629 5857 11629 5871 11630 5874 11630 5114 11630 5860 11631 5783 11631 5780 11631 5871 11632 5114 11632 5111 11632 5868 11633 5871 11633 5111 11633 5864 11634 5783 11634 5860 11634 5864 11635 5111 11635 5783 11635 5864 11636 5868 11636 5111 11636 5942 11637 5921 11637 5941 11637 5943 11638 5942 11638 5941 11638 5944 11639 5943 11639 5941 11639 5944 11640 5941 11640 5940 11640 5939 11641 5944 11641 5940 11641 5945 11642 5943 11642 5944 11642 5945 11643 5944 11643 5939 11643 5947 11644 5945 11644 5939 11644 5946 11645 5945 11645 5947 11645 5947 11646 5939 11646 5938 11646 5948 11647 5938 11647 5937 11647 5948 11648 5947 11648 5938 11648 5949 11649 5946 11649 5947 11649 5949 11650 5947 11650 5948 11650 5951 11651 5948 11651 5937 11651 5950 11652 5948 11652 5951 11652 5949 11653 5948 11653 5950 11653 5950 11654 5951 11654 5936 11654 5952 11655 5949 11655 5950 11655 5952 11656 5950 11656 5936 11656 5954 11657 5949 11657 5952 11657 5953 11658 5936 11658 5935 11658 5953 11659 5952 11659 5936 11659 5934 11660 5953 11660 5935 11660 5954 11661 5952 11661 5953 11661 5955 11662 5953 11662 5934 11662 5956 11663 5953 11663 5955 11663 5956 11664 5954 11664 5953 11664 5933 11665 5955 11665 5934 11665 5957 11666 5955 11666 5933 11666 5956 11667 5955 11667 5957 11667 5957 11668 5933 11668 5958 11668 5959 11669 5956 11669 5957 11669 5960 11670 5959 11670 5957 11670 5960 11671 5957 11671 5958 11671 5960 11672 5958 11672 5932 11672 5961 11673 5959 11673 5960 11673 5962 11674 5960 11674 5932 11674 5961 11675 5960 11675 5962 11675 5963 11676 5959 11676 5961 11676 5931 11677 5961 11677 5962 11677 5963 11678 5961 11678 5931 11678 5963 11679 5931 11679 5964 11679 5965 11680 5963 11680 5964 11680 5965 11681 5964 11681 5966 11681 5965 11682 5966 11682 5967 11682 5967 11683 5966 11683 5968 11683 5930 11684 5967 11684 5968 11684 5969 11685 5965 11685 5967 11685 5970 11686 5967 11686 5930 11686 5971 11687 5965 11687 5969 11687 5969 11688 5967 11688 5970 11688 5970 11689 5930 11689 5929 11689 5972 11690 5970 11690 5929 11690 5972 11691 5969 11691 5970 11691 5972 11692 5929 11692 5973 11692 5971 11693 5969 11693 5972 11693 5974 11694 5971 11694 5972 11694 5974 11695 5973 11695 5928 11695 5974 11696 5972 11696 5973 11696 5974 11697 5928 11697 5927 11697 5926 11698 5974 11698 5927 11698 5977 11699 5974 11699 5975 11699 5975 11700 5974 11700 5926 11700 5976 11701 5926 11701 5925 11701 5975 11702 5926 11702 5976 11702 5977 11703 5975 11703 5976 11703 5976 11704 5925 11704 5924 11704 5978 11705 5976 11705 5924 11705 5978 11706 5977 11706 5976 11706 5978 11707 5924 11707 5923 11707 5980 11708 5977 11708 5978 11708 5979 11709 5978 11709 5923 11709 5980 11710 5978 11710 5979 11710 5982 11711 5980 11711 5979 11711 5982 11712 5979 11712 5981 11712 5982 11713 5983 11713 5980 11713 5982 11714 5981 11714 5922 11714 5984 11715 5982 11715 5922 11715 5984 11716 5983 11716 5982 11716 5984 11717 5922 11717 5985 11717 5987 11718 5984 11718 5985 11718 5986 11719 5983 11719 5984 11719 5988 11720 5984 11720 5987 11720 5988 11721 5986 11721 5984 11721 5988 11722 5987 11722 5989 11722 5921 11723 5988 11723 5989 11723 5942 11724 5986 11724 5988 11724 5942 11725 5988 11725 5921 11725 5943 11726 5986 11726 5942 11726 5082 11727 5084 11727 5089 11727 5089 11728 5084 11728 5087 11728 5080 11729 5082 11729 5090 11729 5090 11730 5082 11730 5089 11730 5078 11731 5080 11731 5091 11731 5091 11732 5080 11732 5090 11732

+
+ + + +

6056 11733 5990 11733 5991 11733 5991 11734 5990 11734 5992 11734 5990 11735 5993 11735 5992 11735 5992 11736 5993 11736 5994 11736 5993 11737 5995 11737 5994 11737 5994 11738 5995 11738 5996 11738 5995 11739 5997 11739 5996 11739 5996 11740 5997 11740 5998 11740 5997 11741 5999 11741 5998 11741 5998 11742 5999 11742 6000 11742 5999 11743 6001 11743 6000 11743 6000 11744 6001 11744 6002 11744 6001 11745 6003 11745 6002 11745 6002 11746 6003 11746 6004 11746 6003 11747 6005 11747 6004 11747 6004 11748 6005 11748 6006 11748 6005 11749 6007 11749 6006 11749 6006 11750 6007 11750 6008 11750 6007 11751 6009 11751 6008 11751 6008 11752 6009 11752 6010 11752 6009 11753 6011 11753 6010 11753 6010 11754 6011 11754 6012 11754 6011 11755 6013 11755 6012 11755 6012 11756 6013 11756 6014 11756 6014 11757 6013 11757 6015 11757 6013 11758 6016 11758 6015 11758 6016 11759 6017 11759 6015 11759 6015 11760 6017 11760 6018 11760 6017 11761 6019 11761 6018 11761 6018 11762 6019 11762 6020 11762 6019 11763 6021 11763 6020 11763 6020 11764 6021 11764 6022 11764 6021 11765 6023 11765 6022 11765 6022 11766 6023 11766 6024 11766 6024 11767 6023 11767 6025 11767 6023 11768 6026 11768 6025 11768 6026 11769 6027 11769 6025 11769 6025 11770 6027 11770 6028 11770 6028 11771 6027 11771 6029 11771 6027 11772 6030 11772 6029 11772 6029 11773 6030 11773 6031 11773 6030 11774 6032 11774 6031 11774 6031 11775 6033 11775 6034 11775 6032 11776 6033 11776 6031 11776 6034 11777 6033 11777 6035 11777 6033 11778 6036 11778 6035 11778 6036 11779 6037 11779 6035 11779 6035 11780 6037 11780 6038 11780 6037 11781 6039 11781 6038 11781 6038 11782 6039 11782 6040 11782 6039 11783 6041 11783 6040 11783 6040 11784 6041 11784 6042 11784 6041 11785 6043 11785 6042 11785 6042 11786 6043 11786 6044 11786 6043 11787 6045 11787 6044 11787 6044 11788 6045 11788 6046 11788 6046 11789 6047 11789 6048 11789 6045 11790 6047 11790 6046 11790 6048 11791 6049 11791 6050 11791 6047 11792 6049 11792 6048 11792 6050 11793 6049 11793 6051 11793 6049 11794 6052 11794 6051 11794 6051 11795 6052 11795 6053 11795 6052 11796 6054 11796 6053 11796 6053 11797 6054 11797 6055 11797 6054 11798 6056 11798 6055 11798 6055 11799 6056 11799 5991 11799 6073 11800 5991 11800 6057 11800 5991 11801 5992 11801 6057 11801 5992 11802 5994 11802 6057 11802 6057 11803 5994 11803 6058 11803 6058 11804 5996 11804 6059 11804 5994 11805 5996 11805 6058 11805 5998 11806 6059 11806 5996 11806 5998 11807 6000 11807 6059 11807 6059 11808 6000 11808 6060 11808 6000 11809 6002 11809 6060 11809 6060 11810 6004 11810 6061 11810 6002 11811 6004 11811 6060 11811 6061 11812 6006 11812 6062 11812 6004 11813 6006 11813 6061 11813 6006 11814 6008 11814 6062 11814 6008 11815 6010 11815 6062 11815 6010 11816 6012 11816 6062 11816 6062 11817 6012 11817 6063 11817 6012 11818 6014 11818 6063 11818 6014 11819 6015 11819 6063 11819 6063 11820 6015 11820 6064 11820 6015 11821 6018 11821 6064 11821 6018 11822 6020 11822 6064 11822 6064 11823 6020 11823 6065 11823 6022 11824 6065 11824 6020 11824 6065 11825 6024 11825 6066 11825 6022 11826 6024 11826 6065 11826 6024 11827 6025 11827 6066 11827 6028 11828 6066 11828 6025 11828 6066 11829 6028 11829 6067 11829 6028 11830 6029 11830 6067 11830 6029 11831 6031 11831 6067 11831 6031 11832 6034 11832 6067 11832 6067 11833 6034 11833 6068 11833 6068 11834 6035 11834 6069 11834 6034 11835 6035 11835 6068 11835 6035 11836 6038 11836 6069 11836 6040 11837 6069 11837 6038 11837 6069 11838 6040 11838 6070 11838 6040 11839 6042 11839 6070 11839 6070 11840 6044 11840 6071 11840 6042 11841 6044 11841 6070 11841 6046 11842 6071 11842 6044 11842 6046 11843 6048 11843 6071 11843 6071 11844 6048 11844 6072 11844 6050 11845 6072 11845 6048 11845 6050 11846 6051 11846 6072 11846 6072 11847 6051 11847 6073 11847 6051 11848 6053 11848 6073 11848 6053 11849 6055 11849 6073 11849 6073 11850 6055 11850 5991 11850 6064 11851 6067 11851 6063 11851 6063 11852 6067 11852 6062 11852 6065 11853 6067 11853 6064 11853 6066 11854 6067 11854 6065 11854 6062 11855 6060 11855 6061 11855 6068 11856 6069 11856 6067 11856 6059 11857 6057 11857 6058 11857 6067 11858 6069 11858 6062 11858 6070 11859 6071 11859 6069 11859 6062 11860 6071 11860 6060 11860 6060 11861 6071 11861 6059 11861 6069 11862 6071 11862 6062 11862 6057 11863 6072 11863 6073 11863 6059 11864 6072 11864 6057 11864 6071 11865 6072 11865 6059 11865 6075 11866 5997 11866 6074 11866 6074 67 5997 67 6076 67 6075 67 5999 67 5997 67 5997 11867 5995 11867 6076 11867 6075 11868 6001 11868 5999 11868 6076 67 5995 67 6077 67 6078 67 6001 67 6075 67 5995 67 5993 67 6077 67 6078 67 6003 67 6001 67 6077 67 5993 67 6079 67 6080 11869 6003 11869 6078 11869 5993 67 5990 67 6079 67 6080 67 6005 67 6003 67 6079 67 5990 67 6081 67 6082 11870 6005 11870 6080 11870 5990 11871 6056 11871 6081 11871 6081 67 6056 67 6083 67 6082 67 6007 67 6005 67 6084 67 6007 67 6082 67 6056 67 6054 67 6083 67 6054 67 6085 67 6083 67 6084 67 6009 67 6007 67 6086 11872 6009 11872 6084 11872 6054 67 6052 67 6085 67 6052 67 6087 67 6085 67 6086 11873 6011 11873 6009 11873 6088 67 6011 67 6086 67 6052 67 6049 67 6087 67 6089 11874 6011 11874 6088 11874 6087 11875 6049 11875 6090 11875 6089 67 6013 67 6011 67 6090 11876 6049 11876 6091 11876 6092 11877 6013 11877 6089 11877 6047 11878 6091 11878 6049 11878 6047 11879 6093 11879 6091 11879 6092 67 6016 67 6013 67 6045 11880 6093 11880 6047 11880 6092 67 6094 67 6016 67 6045 11881 6095 11881 6093 11881 6094 67 6017 67 6016 67 6094 67 6096 67 6017 67 6043 11882 6095 11882 6045 11882 6096 67 6019 67 6017 67 6043 11883 6097 11883 6095 11883 6096 11884 6098 11884 6019 11884 6098 11885 6021 11885 6019 11885 6041 11886 6097 11886 6043 11886 6041 67 6099 67 6097 67 6021 11887 6098 11887 6023 11887 6098 11888 6100 11888 6023 11888 6039 67 6099 67 6041 67 6039 67 6101 67 6099 67 6100 11889 6102 11889 6023 11889 6037 11890 6101 11890 6039 11890 6023 67 6102 67 6026 67 6036 11891 6103 11891 6037 11891 6037 67 6103 67 6101 67 6102 11892 6104 11892 6026 11892 6036 11893 6105 11893 6103 11893 6026 11894 6104 11894 6027 11894 6033 11895 6105 11895 6036 11895 6104 11896 6106 11896 6027 11896 6033 11897 6107 11897 6105 11897 6027 67 6106 67 6030 67 6032 67 6107 67 6033 67 6106 11898 6108 11898 6030 11898 6032 67 6108 67 6107 67 6030 11899 6108 11899 6032 11899 6100 11900 6109 11900 6110 11900 6102 11901 6100 11901 6110 11901 6102 11902 6110 11902 6111 11902 6104 11903 6102 11903 6111 11903 6104 11904 6111 11904 6112 11904 6106 11905 6104 11905 6112 11905 6108 11906 6106 11906 6112 11906 6108 11907 6112 11907 6113 11907 6108 11908 6113 11908 6114 11908 6107 11909 6108 11909 6114 11909 6105 11910 6107 11910 6114 11910 6105 11911 6114 11911 6115 11911 6103 11912 6105 11912 6115 11912 6103 11913 6115 11913 6116 11913 6101 11914 6103 11914 6116 11914 6101 11915 6116 11915 6117 11915 6099 11916 6101 11916 6117 11916 6099 11917 6117 11917 6118 11917 6097 11918 6099 11918 6118 11918 6097 11919 6118 11919 6119 11919 6095 11920 6097 11920 6119 11920 6095 11921 6119 11921 6120 11921 6093 11922 6095 11922 6120 11922 6093 11923 6120 11923 6121 11923 6091 11924 6093 11924 6121 11924 6090 11925 6121 11925 6122 11925 6090 11926 6091 11926 6121 11926 6087 11927 6090 11927 6122 11927 6087 11928 6122 11928 6123 11928 6087 11929 6123 11929 6124 11929 6085 11930 6087 11930 6124 11930 6083 11931 6085 11931 6124 11931 6083 11932 6124 11932 6125 11932 6083 11933 6125 11933 6126 11933 6081 11934 6083 11934 6126 11934 6079 11935 6081 11935 6126 11935 6079 11936 6126 11936 6127 11936 6079 11937 6127 11937 6128 11937 6077 11938 6079 11938 6128 11938 6076 11939 6128 11939 6129 11939 6076 11940 6077 11940 6128 11940 6074 11941 6129 11941 6130 11941 6074 11942 6076 11942 6129 11942 6075 11943 6074 11943 6130 11943 6075 11944 6130 11944 6131 11944 6075 11945 6131 11945 6132 11945 6078 11946 6075 11946 6132 11946 6078 11947 6132 11947 6133 11947 6080 11948 6078 11948 6133 11948 6080 11949 6133 11949 6134 11949 6082 11950 6080 11950 6134 11950 6082 11951 6134 11951 6135 11951 6084 11952 6082 11952 6135 11952 6084 11953 6135 11953 6136 11953 6086 11954 6084 11954 6136 11954 6086 11955 6136 11955 6137 11955 6086 11956 6137 11956 6138 11956 6088 11957 6086 11957 6138 11957 6089 11958 6088 11958 6138 11958 6089 11959 6138 11959 6139 11959 6092 11960 6089 11960 6139 11960 6092 11961 6139 11961 6140 11961 6092 11962 6140 11962 6141 11962 6094 11963 6092 11963 6141 11963 6096 11964 6094 11964 6141 11964 6096 11965 6141 11965 6142 11965 6098 11966 6096 11966 6142 11966 6098 11967 6142 11967 6143 11967 6098 11968 6143 11968 6109 11968 6100 11969 6098 11969 6109 11969 6110 11970 6144 11970 6145 11970 6110 11971 6109 11971 6144 11971 6111 11972 6110 11972 6145 11972 6112 11973 6111 11973 6145 11973 6112 11974 6145 11974 6146 11974 6113 11975 6112 11975 6146 11975 6114 11976 6113 11976 6146 11976 6114 11977 6146 11977 6147 11977 6115 11978 6114 11978 6147 11978 6116 11979 6115 11979 6147 11979 6117 11980 6116 11980 6147 11980 6117 11981 6147 11981 6148 11981 6118 11982 6117 11982 6148 11982 6119 11983 6118 11983 6148 11983 6119 11984 6148 11984 6149 11984 6120 11985 6119 11985 6149 11985 6120 11986 6149 11986 6150 11986 6121 11987 6120 11987 6150 11987 6122 11988 6121 11988 6150 11988 6123 11989 6122 11989 6150 11989 6123 11990 6150 11990 6151 11990 6124 11991 6123 11991 6151 11991 6125 11992 6124 11992 6151 11992 6126 11993 6125 11993 6151 11993 6126 11994 6151 11994 6152 11994 6127 11995 6126 11995 6152 11995 6128 11996 6127 11996 6152 11996 6128 11997 6152 11997 6153 11997 6129 11998 6128 11998 6153 11998 6130 11999 6129 11999 6153 11999 6131 12000 6153 12000 6154 12000 6131 12001 6130 12001 6153 12001 6132 12002 6131 12002 6154 12002 6133 12003 6132 12003 6154 12003 6133 12004 6154 12004 6155 12004 6134 12005 6133 12005 6155 12005 6135 12006 6134 12006 6155 12006 6136 12007 6155 12007 6156 12007 6136 12008 6135 12008 6155 12008 6137 12009 6156 12009 6157 12009 6137 12010 6136 12010 6156 12010 6138 12011 6137 12011 6157 12011 6139 12012 6138 12012 6157 12012 6139 12013 6157 12013 6158 12013 6140 12014 6139 12014 6158 12014 6141 12015 6140 12015 6158 12015 6141 12016 6158 12016 6159 12016 6142 12017 6141 12017 6159 12017 6143 12018 6159 12018 6144 12018 6143 12019 6142 12019 6159 12019 6143 12020 6144 12020 6109 12020 6156 12021 6158 12021 6157 12021 6145 12022 6144 12022 6159 12022 6153 12023 6155 12023 6154 12023 6153 12024 6158 12024 6156 12024 6153 12025 6156 12025 6155 12025 6152 12026 6158 12026 6153 12026 6147 12027 6146 12027 6145 12027 6152 12028 6159 12028 6158 12028 6151 12029 6159 12029 6152 12029 6150 12030 6149 12030 6148 12030 6150 12031 6148 12031 6147 12031 6150 12032 6145 12032 6159 12032 6150 12033 6159 12033 6151 12033 6150 12034 6147 12034 6145 12034

+
+ + + +

6226 11733 6160 11733 6161 11733 6161 11734 6160 11734 6162 11734 6160 11735 6163 11735 6162 11735 6162 11736 6163 11736 6164 11736 6163 11737 6165 11737 6164 11737 6164 11738 6165 11738 6166 11738 6165 11739 6167 11739 6166 11739 6166 11740 6167 11740 6168 11740 6167 11741 6169 11741 6168 11741 6168 11742 6169 11742 6170 11742 6169 11743 6171 11743 6170 11743 6170 11744 6171 11744 6172 11744 6171 11745 6173 11745 6172 11745 6172 11746 6173 11746 6174 11746 6173 11747 6175 11747 6174 11747 6174 11748 6175 11748 6176 11748 6175 11749 6177 11749 6176 11749 6176 11750 6177 11750 6178 11750 6177 11751 6179 11751 6178 11751 6178 11752 6179 11752 6180 11752 6179 11753 6181 11753 6180 11753 6180 11754 6181 11754 6182 11754 6181 11755 6183 11755 6182 11755 6182 11756 6183 11756 6184 11756 6184 11757 6183 11757 6185 11757 6183 11758 6186 11758 6185 11758 6186 11759 6187 11759 6185 11759 6185 11760 6187 11760 6188 11760 6187 11761 6189 11761 6188 11761 6188 11762 6189 11762 6190 11762 6189 11763 6191 11763 6190 11763 6190 11764 6191 11764 6192 11764 6191 11765 6193 11765 6192 11765 6192 11766 6193 11766 6194 11766 6194 11767 6193 11767 6195 11767 6193 11768 6196 11768 6195 11768 6196 11769 6197 11769 6195 11769 6195 11770 6197 11770 6198 11770 6198 11771 6197 11771 6199 11771 6197 11772 6200 11772 6199 11772 6199 11773 6200 11773 6201 11773 6200 11774 6202 11774 6201 11774 6201 11775 6203 11775 6204 11775 6202 11776 6203 11776 6201 11776 6204 11777 6203 11777 6205 11777 6203 11778 6206 11778 6205 11778 6206 11779 6207 11779 6205 11779 6205 11780 6207 11780 6208 11780 6207 11781 6209 11781 6208 11781 6208 11782 6209 11782 6210 11782 6209 11783 6211 11783 6210 11783 6210 11784 6211 11784 6212 11784 6211 11785 6213 11785 6212 11785 6212 11786 6213 11786 6214 11786 6213 11787 6215 11787 6214 11787 6214 11788 6215 11788 6216 11788 6216 11789 6217 11789 6218 11789 6215 11790 6217 11790 6216 11790 6218 11791 6219 11791 6220 11791 6217 11792 6219 11792 6218 11792 6220 11793 6219 11793 6221 11793 6219 11794 6222 11794 6221 11794 6221 11795 6222 11795 6223 11795 6222 11796 6224 11796 6223 11796 6223 11797 6224 11797 6225 11797 6224 11798 6226 11798 6225 11798 6225 11799 6226 11799 6161 11799 6243 11800 6161 11800 6227 11800 6161 11801 6162 11801 6227 11801 6162 11802 6164 11802 6227 11802 6227 11803 6164 11803 6228 11803 6228 11804 6166 11804 6229 11804 6164 11805 6166 11805 6228 11805 6168 11806 6229 11806 6166 11806 6168 11807 6170 11807 6229 11807 6229 11808 6170 11808 6230 11808 6170 11809 6172 11809 6230 11809 6230 11810 6174 11810 6231 11810 6172 11811 6174 11811 6230 11811 6231 11812 6176 11812 6232 11812 6174 11813 6176 11813 6231 11813 6176 11814 6178 11814 6232 11814 6178 11815 6180 11815 6232 11815 6180 11816 6182 11816 6232 11816 6232 11817 6182 11817 6233 11817 6182 11818 6184 11818 6233 11818 6184 11819 6185 11819 6233 11819 6233 11820 6185 11820 6234 11820 6185 11821 6188 11821 6234 11821 6188 11822 6190 11822 6234 11822 6234 11823 6190 11823 6235 11823 6192 11824 6235 11824 6190 11824 6235 11825 6194 11825 6236 11825 6192 11826 6194 11826 6235 11826 6194 11827 6195 11827 6236 11827 6198 11828 6236 11828 6195 11828 6236 11829 6198 11829 6237 11829 6198 11830 6199 11830 6237 11830 6199 11831 6201 11831 6237 11831 6201 11832 6204 11832 6237 11832 6237 11833 6204 11833 6238 11833 6238 11834 6205 11834 6239 11834 6204 11835 6205 11835 6238 11835 6205 11836 6208 11836 6239 11836 6210 11837 6239 11837 6208 11837 6239 11838 6210 11838 6240 11838 6210 11839 6212 11839 6240 11839 6240 11840 6214 11840 6241 11840 6212 11841 6214 11841 6240 11841 6216 11842 6241 11842 6214 11842 6216 11843 6218 11843 6241 11843 6241 11844 6218 11844 6242 11844 6220 11845 6242 11845 6218 11845 6220 11846 6221 11846 6242 11846 6242 11847 6221 11847 6243 11847 6221 11848 6223 11848 6243 11848 6223 11849 6225 11849 6243 11849 6243 11850 6225 11850 6161 11850 6234 11851 6237 11851 6233 11851 6233 11852 6237 11852 6232 11852 6235 11853 6237 11853 6234 11853 6236 11854 6237 11854 6235 11854 6232 11855 6230 11855 6231 11855 6238 11856 6239 11856 6237 11856 6229 11857 6227 11857 6228 11857 6237 11858 6239 11858 6232 11858 6240 11859 6241 11859 6239 11859 6232 11860 6241 11860 6230 11860 6230 11861 6241 11861 6229 11861 6239 11862 6241 11862 6232 11862 6227 11863 6242 11863 6243 11863 6229 11864 6242 11864 6227 11864 6241 11865 6242 11865 6229 11865 6245 11866 6167 11866 6244 11866 6244 67 6167 67 6246 67 6245 67 6169 67 6167 67 6167 11867 6165 11867 6246 11867 6245 11868 6171 11868 6169 11868 6246 67 6165 67 6247 67 6248 67 6171 67 6245 67 6165 67 6163 67 6247 67 6248 67 6173 67 6171 67 6247 67 6163 67 6249 67 6250 11869 6173 11869 6248 11869 6163 67 6160 67 6249 67 6250 67 6175 67 6173 67 6249 67 6160 67 6251 67 6252 11870 6175 11870 6250 11870 6160 11871 6226 11871 6251 11871 6251 67 6226 67 6253 67 6252 67 6177 67 6175 67 6254 67 6177 67 6252 67 6226 67 6224 67 6253 67 6224 67 6255 67 6253 67 6254 67 6179 67 6177 67 6256 11872 6179 11872 6254 11872 6224 67 6222 67 6255 67 6222 67 6257 67 6255 67 6256 11873 6181 11873 6179 11873 6258 67 6181 67 6256 67 6222 67 6219 67 6257 67 6259 11874 6181 11874 6258 11874 6257 11875 6219 11875 6260 11875 6259 67 6183 67 6181 67 6260 11876 6219 11876 6261 11876 6262 11877 6183 11877 6259 11877 6217 11878 6261 11878 6219 11878 6217 11879 6263 11879 6261 11879 6262 67 6186 67 6183 67 6215 11880 6263 11880 6217 11880 6262 67 6264 67 6186 67 6215 11881 6265 11881 6263 11881 6264 67 6187 67 6186 67 6264 67 6266 67 6187 67 6213 11882 6265 11882 6215 11882 6266 67 6189 67 6187 67 6213 11883 6267 11883 6265 11883 6266 11884 6268 11884 6189 11884 6268 11885 6191 11885 6189 11885 6211 11886 6267 11886 6213 11886 6211 67 6269 67 6267 67 6191 11887 6268 11887 6193 11887 6268 11888 6270 11888 6193 11888 6209 67 6269 67 6211 67 6209 67 6271 67 6269 67 6270 11889 6272 11889 6193 11889 6207 11890 6271 11890 6209 11890 6193 67 6272 67 6196 67 6206 11891 6273 11891 6207 11891 6207 67 6273 67 6271 67 6272 11892 6274 11892 6196 11892 6206 11893 6275 11893 6273 11893 6196 11894 6274 11894 6197 11894 6203 11895 6275 11895 6206 11895 6274 11896 6276 11896 6197 11896 6203 11897 6277 11897 6275 11897 6197 67 6276 67 6200 67 6202 67 6277 67 6203 67 6276 11898 6278 11898 6200 11898 6202 67 6278 67 6277 67 6200 11899 6278 11899 6202 11899 6270 11900 6279 11900 6280 11900 6272 11901 6270 11901 6280 11901 6272 11902 6280 11902 6281 11902 6274 11903 6272 11903 6281 11903 6274 11904 6281 11904 6282 11904 6276 11905 6274 11905 6282 11905 6278 11906 6276 11906 6282 11906 6278 11907 6282 11907 6283 11907 6278 11908 6283 11908 6284 11908 6277 11909 6278 11909 6284 11909 6275 11910 6277 11910 6284 11910 6275 11911 6284 11911 6285 11911 6273 11912 6275 11912 6285 11912 6273 11913 6285 11913 6286 11913 6271 11914 6273 11914 6286 11914 6271 11915 6286 11915 6287 11915 6269 11916 6271 11916 6287 11916 6269 11917 6287 11917 6288 11917 6267 11918 6269 11918 6288 11918 6267 11919 6288 11919 6289 11919 6265 11920 6267 11920 6289 11920 6265 11921 6289 11921 6290 11921 6263 11922 6265 11922 6290 11922 6263 11923 6290 11923 6291 11923 6261 11924 6263 11924 6291 11924 6260 11925 6291 11925 6292 11925 6260 11926 6261 11926 6291 11926 6257 11927 6260 11927 6292 11927 6257 11928 6292 11928 6293 11928 6257 11929 6293 11929 6294 11929 6255 11930 6257 11930 6294 11930 6253 11931 6255 11931 6294 11931 6253 11932 6294 11932 6295 11932 6253 11933 6295 11933 6296 11933 6251 11934 6253 11934 6296 11934 6249 11935 6251 11935 6296 11935 6249 11936 6296 11936 6297 11936 6249 11937 6297 11937 6298 11937 6247 11938 6249 11938 6298 11938 6246 11939 6298 11939 6299 11939 6246 11940 6247 11940 6298 11940 6244 11941 6299 11941 6300 11941 6244 11942 6246 11942 6299 11942 6245 11943 6244 11943 6300 11943 6245 11944 6300 11944 6301 11944 6245 11945 6301 11945 6302 11945 6248 11946 6245 11946 6302 11946 6248 11947 6302 11947 6303 11947 6250 11948 6248 11948 6303 11948 6250 11949 6303 11949 6304 11949 6252 11950 6250 11950 6304 11950 6252 11951 6304 11951 6305 11951 6254 11952 6252 11952 6305 11952 6254 11953 6305 11953 6306 11953 6256 11954 6254 11954 6306 11954 6256 11955 6306 11955 6307 11955 6256 11956 6307 11956 6308 11956 6258 11957 6256 11957 6308 11957 6259 11958 6258 11958 6308 11958 6259 11959 6308 11959 6309 11959 6262 11960 6259 11960 6309 11960 6262 11961 6309 11961 6310 11961 6262 11962 6310 11962 6311 11962 6264 11963 6262 11963 6311 11963 6266 11964 6264 11964 6311 11964 6266 11965 6311 11965 6312 11965 6268 11966 6266 11966 6312 11966 6268 11967 6312 11967 6313 11967 6268 11968 6313 11968 6279 11968 6270 11969 6268 11969 6279 11969 6280 11970 6314 11970 6315 11970 6280 11971 6279 11971 6314 11971 6281 11972 6280 11972 6315 11972 6282 11973 6281 11973 6315 11973 6282 11974 6315 11974 6316 11974 6283 11975 6282 11975 6316 11975 6284 11976 6283 11976 6316 11976 6284 11977 6316 11977 6317 11977 6285 11978 6284 11978 6317 11978 6286 11979 6285 11979 6317 11979 6287 11980 6286 11980 6317 11980 6287 11981 6317 11981 6318 11981 6288 11982 6287 11982 6318 11982 6289 11983 6288 11983 6318 11983 6289 11984 6318 11984 6319 11984 6290 11985 6289 11985 6319 11985 6290 11986 6319 11986 6320 11986 6291 11987 6290 11987 6320 11987 6292 11988 6291 11988 6320 11988 6293 11989 6292 11989 6320 11989 6293 11990 6320 11990 6321 11990 6294 11991 6293 11991 6321 11991 6295 11992 6294 11992 6321 11992 6296 11993 6295 11993 6321 11993 6296 11994 6321 11994 6322 11994 6297 11995 6296 11995 6322 11995 6298 11996 6297 11996 6322 11996 6298 11997 6322 11997 6323 11997 6299 11998 6298 11998 6323 11998 6300 11999 6299 11999 6323 11999 6301 12000 6323 12000 6324 12000 6301 12001 6300 12001 6323 12001 6302 12002 6301 12002 6324 12002 6303 12003 6302 12003 6324 12003 6303 12004 6324 12004 6325 12004 6304 12005 6303 12005 6325 12005 6305 12006 6304 12006 6325 12006 6306 12007 6325 12007 6326 12007 6306 12008 6305 12008 6325 12008 6307 12009 6326 12009 6327 12009 6307 12010 6306 12010 6326 12010 6308 12011 6307 12011 6327 12011 6309 12012 6308 12012 6327 12012 6309 12013 6327 12013 6328 12013 6310 12014 6309 12014 6328 12014 6311 12015 6310 12015 6328 12015 6311 12016 6328 12016 6329 12016 6312 12017 6311 12017 6329 12017 6313 12018 6329 12018 6314 12018 6313 12019 6312 12019 6329 12019 6313 12020 6314 12020 6279 12020 6326 12021 6328 12021 6327 12021 6315 12022 6314 12022 6329 12022 6323 12023 6325 12023 6324 12023 6323 12024 6328 12024 6326 12024 6323 12025 6326 12025 6325 12025 6322 12026 6328 12026 6323 12026 6317 12027 6316 12027 6315 12027 6322 12028 6329 12028 6328 12028 6321 12029 6329 12029 6322 12029 6320 12030 6319 12030 6318 12030 6320 12031 6318 12031 6317 12031 6320 12032 6315 12032 6329 12032 6320 12033 6329 12033 6321 12033 6320 12034 6317 12034 6315 12034

+
+ + + +

6351 12035 6330 12035 6331 12035 6330 12036 6332 12036 6331 12036 6331 12037 6332 12037 6333 12037 6332 12038 6334 12038 6333 12038 6333 12039 6334 12039 6335 12039 6334 12040 6336 12040 6335 12040 6336 12041 6337 12041 6335 12041 6335 12042 6337 12042 6338 12042 6338 12043 6337 12043 6339 12043 6337 12044 6340 12044 6339 12044 6339 12045 6340 12045 6341 12045 6340 12046 6342 12046 6341 12046 6341 12047 6342 12047 6343 12047 6342 12048 6344 12048 6343 12048 6344 12049 6345 12049 6343 12049 6343 12050 6345 12050 6346 12050 6345 12051 6347 12051 6346 12051 6346 12052 6347 12052 6348 12052 6347 12053 6349 12053 6348 12053 6348 12054 6349 12054 6350 12054 6350 12055 6349 12055 6351 12055 6349 12056 6330 12056 6351 12056 6352 12057 6381 12057 6353 12057 6352 12058 6353 12058 6354 12058 6355 12059 6352 12059 6354 12059 6356 12060 6355 12060 6354 12060 6356 12061 6354 12061 6357 12061 6358 12062 6356 12062 6357 12062 6358 12063 6357 12063 6359 12063 6360 12064 6358 12064 6359 12064 6360 12065 6359 12065 6361 12065 6362 12066 6360 12066 6361 12066 6362 12067 6361 12067 6363 12067 6364 12068 6362 12068 6363 12068 6364 12069 6363 12069 6365 12069 6366 12070 6364 12070 6365 12070 6366 12071 6365 12071 6367 12071 6368 12072 6366 12072 6367 12072 6369 12073 6368 12073 6367 12073 6369 12074 6367 12074 6370 12074 6371 12075 6369 12075 6370 12075 6371 12076 6370 12076 6372 12076 6373 12077 6371 12077 6372 12077 6374 12078 6372 12078 6375 12078 6374 12079 6373 12079 6372 12079 6376 12080 6374 12080 6375 12080 6376 12081 6375 12081 6377 12081 6378 12082 6376 12082 6377 12082 6378 12083 6377 12083 6379 12083 6380 12084 6378 12084 6379 12084 6380 12085 6379 12085 6381 12085 6352 12086 6380 12086 6381 12086 6342 213 6377 213 6344 213 6342 12087 6379 12087 6377 12087 6344 12088 6377 12088 6375 12088 6345 12089 6344 12089 6375 12089 6342 213 6381 213 6379 213 6345 213 6375 213 6372 213 6347 213 6345 213 6372 213 6340 12090 6353 12090 6381 12090 6340 213 6381 213 6342 213 6340 12091 6354 12091 6353 12091 6337 213 6354 213 6340 213 6347 213 6372 213 6370 213 6349 12092 6347 12092 6370 12092 6357 213 6354 213 6337 213 6367 12093 6349 12093 6370 12093 6357 12094 6337 12094 6336 12094 6359 213 6357 213 6336 213 6367 12095 6330 12095 6349 12095 6359 213 6336 213 6334 213 6365 12096 6330 12096 6367 12096 6361 12097 6359 12097 6334 12097 6363 213 6330 213 6365 213 6363 12098 6361 12098 6334 12098 6363 12099 6332 12099 6330 12099 6363 12100 6334 12100 6332 12100 6348 67 6350 67 6369 67 6348 12101 6369 12101 6371 12101 6350 12102 6368 12102 6369 12102 6351 67 6368 67 6350 67 6348 12103 6371 12103 6373 12103 6346 12104 6348 12104 6373 12104 6351 12105 6366 12105 6368 12105 6346 67 6373 67 6374 67 6331 67 6366 67 6351 67 6331 12106 6364 12106 6366 12106 6346 67 6374 67 6376 67 6343 67 6346 67 6376 67 6333 67 6364 67 6331 67 6378 12107 6343 12107 6376 12107 6362 67 6364 67 6333 67 6378 12108 6341 12108 6343 12108 6380 12109 6341 12109 6378 12109 6362 67 6333 67 6335 67 6360 67 6362 67 6335 67 6352 67 6341 67 6380 67 6358 67 6360 67 6335 67 6352 12110 6339 12110 6341 12110 6356 12111 6358 12111 6335 12111 6355 12112 6339 12112 6352 12112 6356 67 6335 67 6338 67 6356 67 6339 67 6355 67 6356 12113 6338 12113 6339 12113

+
+ + + +

6382 12114 6383 12114 6384 12114 6385 12115 6383 12115 6382 12115 6383 12116 6386 12116 6384 12116 6385 12117 6387 12117 6383 12117 7165 12118 6387 12118 6385 12118 6384 12119 6386 12119 6388 12119 6386 12120 6389 12120 6388 12120 7165 12121 7001 12121 6387 12121 6388 12122 6389 12122 6390 12122 6391 12123 7001 12123 7165 12123 6389 12124 6392 12124 6390 12124 6391 12125 6393 12125 7001 12125 6391 12126 6394 12126 6393 12126 6393 12127 6394 12127 6395 12127 6401 12128 6399 12128 6398 12128 6401 12129 6402 12129 6399 12129 6404 12130 6402 12130 6401 12130 6404 12131 6403 12131 6402 12131 6404 12132 6405 12132 6403 12132 6400 12133 6405 12133 6404 12133 6400 12134 6406 12134 6405 12134 6407 12135 6406 12135 6400 12135 6407 12136 6408 12136 6406 12136 6409 12137 6408 12137 6407 12137 6409 12138 6410 12138 6408 12138 6409 12139 6411 12139 6410 12139 6412 12140 6411 12140 6409 12140 6412 12141 6413 12141 6411 12141 6414 12142 6413 12142 6412 12142 6414 12143 6415 12143 6413 12143 6414 12144 6416 12144 6415 12144 6417 12145 6416 12145 6414 12145 6417 12146 6418 12146 6416 12146 6419 12147 6418 12147 6417 12147 6419 12148 6420 12148 6418 12148 6419 12149 6421 12149 6420 12149 6422 12150 6421 12150 6419 12150 6422 12151 6423 12151 6421 12151 6424 12152 6423 12152 6422 12152 6424 12153 6425 12153 6423 12153 6424 12154 6426 12154 6425 12154 6427 12155 6426 12155 6424 12155 6428 12156 6426 12156 6427 12156 6428 12157 6429 12157 6426 12157 6428 12158 6430 12158 6429 12158 6431 12159 6430 12159 6428 12159 6431 12160 6432 12160 6430 12160 6433 12161 6432 12161 6431 12161 6433 12162 6434 12162 6432 12162 6435 12163 6434 12163 6433 12163 6435 12164 6436 12164 6434 12164 6437 12165 6436 12165 6435 12165 6437 12166 6438 12166 6436 12166 6437 12167 6439 12167 6438 12167 6440 12168 6439 12168 6437 12168 6440 12169 6441 12169 6439 12169 6442 12170 6441 12170 6440 12170 6442 12171 6443 12171 6441 12171 6444 12172 6443 12172 6442 12172 6444 12173 6445 12173 6443 12173 6444 12174 6446 12174 6445 12174 6447 12175 6446 12175 6444 12175 6447 12176 6448 12176 6446 12176 6449 12177 6448 12177 6447 12177 6449 12178 6450 12178 6448 12178 6451 12179 6452 12179 6449 12179 6449 12180 6452 12180 6450 12180 6451 12181 6453 12181 6452 12181 6454 12182 6453 12182 6451 12182 6454 12183 6455 12183 6453 12183 6456 12184 6455 12184 6454 12184 6456 12185 6457 12185 6455 12185 6458 12186 6457 12186 6456 12186 6458 12187 6459 12187 6457 12187 6458 12188 6460 12188 6459 12188 6461 12189 6462 12189 6458 12189 6458 12190 6462 12190 6460 12190 6461 12191 6463 12191 6462 12191 6461 12192 6464 12192 6463 12192 6465 12193 6464 12193 6461 12193 6465 12194 6466 12194 6464 12194 6467 12195 6466 12195 6465 12195 6467 12196 6468 12196 6466 12196 6467 12197 6469 12197 6468 12197 6470 12198 6469 12198 6467 12198 6470 12199 6471 12199 6469 12199 6472 12200 6473 12200 6470 12200 6470 12201 6473 12201 6471 12201 6474 12202 6473 12202 6472 12202 6474 12203 6475 12203 6473 12203 6474 12204 6476 12204 6475 12204 6477 12205 6476 12205 6474 12205 6477 12206 6478 12206 6476 12206 6479 12207 6478 12207 6477 12207 6479 12208 6480 12208 6478 12208 6481 12209 6482 12209 6479 12209 6479 12210 6482 12210 6480 12210 6481 12211 6483 12211 6482 12211 6484 12212 6483 12212 6481 12212 6484 12213 6485 12213 6483 12213 6484 12214 6486 12214 6485 12214 6487 12215 6486 12215 6484 12215 6487 12216 6488 12216 6486 12216 6489 12217 6488 12217 6487 12217 6489 12218 6490 12218 6488 12218 6491 12219 6492 12219 6489 12219 6489 12220 6492 12220 6490 12220 6491 12221 6493 12221 6492 12221 6494 12222 6493 12222 6491 12222 6494 12223 6495 12223 6493 12223 6494 12224 6496 12224 6495 12224 6497 12225 6496 12225 6494 12225 6497 12226 6498 12226 6496 12226 6499 12227 6498 12227 6497 12227 6499 12228 6500 12228 6498 12228 6501 12229 6500 12229 6499 12229 6501 12230 6502 12230 6500 12230 6503 12231 6502 12231 6501 12231 6503 12232 6504 12232 6502 12232 6505 12233 6504 12233 6503 12233 6505 12234 6506 12234 6504 12234 6507 12235 6506 12235 6505 12235 6507 12236 6508 12236 6506 12236 6509 12237 6510 12237 6507 12237 6507 12238 6510 12238 6508 12238 6509 12239 6511 12239 6510 12239 6512 12240 6511 12240 6509 12240 6512 12241 6513 12241 6511 12241 6514 12242 6513 12242 6512 12242 6514 12243 6515 12243 6513 12243 6514 12244 6516 12244 6515 12244 6517 12245 6516 12245 6514 12245 6517 12246 6518 12246 6516 12246 6519 12247 6518 12247 6517 12247 6519 12248 6520 12248 6518 12248 6521 12249 6520 12249 6519 12249 6521 12250 6522 12250 6520 12250 6523 12251 6522 12251 6521 12251 6523 12252 6524 12252 6522 12252 6525 12253 6526 12253 6523 12253 6523 12254 6526 12254 6524 12254 6525 12255 6527 12255 6526 12255 6528 12256 6527 12256 6525 12256 6528 12257 6529 12257 6527 12257 6530 12258 6529 12258 6528 12258 6530 12259 6531 12259 6529 12259 6532 12260 6531 12260 6530 12260 6532 12261 6533 12261 6531 12261 6534 12262 6533 12262 6532 12262 6534 12263 6535 12263 6533 12263 6536 12264 6535 12264 6534 12264 6536 12265 6537 12265 6535 12265 6536 12266 6538 12266 6537 12266 6539 12267 6538 12267 6536 12267 6540 12268 6538 12268 6539 12268 6540 12269 6541 12269 6538 12269 6540 12270 6542 12270 6541 12270 6543 12271 6542 12271 6540 12271 6543 12272 6544 12272 6542 12272 6545 12273 6544 12273 6543 12273 6545 12274 6546 12274 6544 12274 6547 12275 6546 12275 6545 12275 6547 12276 6548 12276 6546 12276 6549 12277 6548 12277 6547 12277 6549 12278 6550 12278 6548 12278 6551 12279 6550 12279 6549 12279 6551 12280 6552 12280 6550 12280 6553 12281 6552 12281 6551 12281 6553 12282 6554 12282 6552 12282 6553 12283 6555 12283 6554 12283 6556 12284 6555 12284 6553 12284 6556 12285 6557 12285 6555 12285 6558 12286 6557 12286 6556 12286 6558 12287 6559 12287 6557 12287 6560 12288 6559 12288 6558 12288 6560 12289 6561 12289 6559 12289 6562 12290 6561 12290 6560 12290 6562 12291 6563 12291 6561 12291 6564 12292 6563 12292 6562 12292 6564 12293 6565 12293 6563 12293 6566 12294 6565 12294 6564 12294 6566 12295 6567 12295 6565 12295 6566 12296 6568 12296 6567 12296 6569 12297 6568 12297 6566 12297 6570 12298 6568 12298 6569 12298 6570 12299 6571 12299 6568 12299 6570 12300 6572 12300 6571 12300 6573 12301 6572 12301 6570 12301 6573 12302 6574 12302 6572 12302 6575 12303 6574 12303 6573 12303 6575 12304 6576 12304 6574 12304 6577 12305 6576 12305 6575 12305 6577 12306 6578 12306 6576 12306 6579 12307 6578 12307 6577 12307 6579 12308 6580 12308 6578 12308 6579 12309 6581 12309 6580 12309 6582 12310 6581 12310 6579 12310 6582 12311 6583 12311 6581 12311 6582 12312 6584 12312 6583 12312 6585 12313 6584 12313 6582 12313 6585 12314 6586 12314 6584 12314 6587 12315 6586 12315 6585 12315 6587 12316 6588 12316 6586 12316 6587 12317 6589 12317 6588 12317 6590 12318 6589 12318 6587 12318 6590 12319 6591 12319 6589 12319 6590 12320 6592 12320 6591 12320 6593 12321 6592 12321 6590 12321 6593 12322 6594 12322 6592 12322 6595 12323 6594 12323 6593 12323 6595 12324 6596 12324 6594 12324 6597 12325 6596 12325 6595 12325 6597 12326 6598 12326 6596 12326 6599 12327 6598 12327 6597 12327 6599 12328 6600 12328 6598 12328 6601 12329 6600 12329 6599 12329 6601 12330 6602 12330 6600 12330 6603 12331 6602 12331 6601 12331 6603 12332 6604 12332 6602 12332 6603 12333 6605 12333 6604 12333 6606 12334 6605 12334 6603 12334 6606 12335 6607 12335 6605 12335 6606 12336 6608 12336 6607 12336 6609 12337 6608 12337 6606 12337 6609 12338 6610 12338 6608 12338 6611 12339 6610 12339 6609 12339 6611 12340 6612 12340 6610 12340 6613 12341 6614 12341 6611 12341 6611 12342 6614 12342 6612 12342 6613 12343 6615 12343 6614 12343 6616 12344 6615 12344 6613 12344 6616 12345 6617 12345 6615 12345 6616 12346 6618 12346 6617 12346 6619 12347 6618 12347 6616 12347 6619 12348 6620 12348 6618 12348 6621 12349 6620 12349 6619 12349 6621 12350 6622 12350 6620 12350 6623 12351 6622 12351 6621 12351 6623 12352 6624 12352 6622 12352 6625 12353 6624 12353 6623 12353 6625 12354 6626 12354 6624 12354 6625 12355 6627 12355 6626 12355 6628 12356 6627 12356 6625 12356 6628 12357 6629 12357 6627 12357 6630 12358 6629 12358 6628 12358 6630 12359 6631 12359 6629 12359 6632 12360 6631 12360 6630 12360 6632 12361 6633 12361 6631 12361 6634 12362 6633 12362 6632 12362 6634 12363 6635 12363 6633 12363 6634 12364 6636 12364 6635 12364 6637 12365 6636 12365 6634 12365 6638 12366 6636 12366 6637 12366 6638 12367 6639 12367 6636 12367 6640 12368 6639 12368 6638 12368 6640 12369 6641 12369 6639 12369 6640 12370 6642 12370 6641 12370 6643 12371 6642 12371 6640 12371 6643 12372 6644 12372 6642 12372 6645 12373 6644 12373 6643 12373 6645 12374 6646 12374 6644 12374 6645 12375 6647 12375 6646 12375 6648 12376 6647 12376 6645 12376 6648 12377 6649 12377 6647 12377 6650 12378 6651 12378 6648 12378 6648 12379 6651 12379 6649 12379 6652 12380 6651 12380 6650 12380 6652 12381 6653 12381 6651 12381 6654 12382 6653 12382 6652 12382 6654 12383 6655 12383 6653 12383 6654 12384 6656 12384 6655 12384 6657 12385 6656 12385 6654 12385 6657 12386 6658 12386 6656 12386 6659 12387 6658 12387 6657 12387 6659 12388 6660 12388 6658 12388 6661 12389 6660 12389 6659 12389 6661 12390 6662 12390 6660 12390 6661 12391 6663 12391 6662 12391 6664 12392 6663 12392 6661 12392 6665 12393 6663 12393 6664 12393 6665 12394 6666 12394 6663 12394 6667 12395 6666 12395 6665 12395 6667 12396 6668 12396 6666 12396 6669 12397 6668 12397 6667 12397 6669 12398 6670 12398 6668 12398 6669 12399 6671 12399 6670 12399 6672 12400 6671 12400 6669 12400 6672 12401 6673 12401 6671 12401 6674 12402 6673 12402 6672 12402 6674 12403 6675 12403 6673 12403 6676 12404 6675 12404 6674 12404 6676 12405 6677 12405 6675 12405 6678 12406 6677 12406 6676 12406 6678 12407 6679 12407 6677 12407 6680 12408 6679 12408 6678 12408 6680 12409 6681 12409 6679 12409 6682 12410 6681 12410 6680 12410 6682 12411 6683 12411 6681 12411 6682 12412 6684 12412 6683 12412 6685 12413 6684 12413 6682 12413 6685 12414 6686 12414 6684 12414 6687 12415 6686 12415 6685 12415 6687 12416 6688 12416 6686 12416 6689 12417 6688 12417 6687 12417 6689 12418 6690 12418 6688 12418 6689 12419 6691 12419 6690 12419 6692 12420 6691 12420 6689 12420 6692 12421 6693 12421 6691 12421 6692 12422 6694 12422 6693 12422 6695 12423 6694 12423 6692 12423 6695 12424 6696 12424 6694 12424 6697 12425 6696 12425 6695 12425 6697 12426 6698 12426 6696 12426 6699 12427 6698 12427 6697 12427 6699 12428 6700 12428 6698 12428 6699 12429 6701 12429 6700 12429 6702 12430 6701 12430 6699 12430 6702 12431 6703 12431 6701 12431 6704 12432 6703 12432 6702 12432 6704 12433 6705 12433 6703 12433 6706 12434 6705 12434 6704 12434 6706 12435 6707 12435 6705 12435 6708 12436 6707 12436 6706 12436 6708 12437 6709 12437 6707 12437 6710 12438 6711 12438 6708 12438 6708 12439 6711 12439 6709 12439 6712 12440 6711 12440 6710 12440 6712 12441 6713 12441 6711 12441 6714 12442 6713 12442 6712 12442 6714 12443 6715 12443 6713 12443 6714 12444 6716 12444 6715 12444 6717 12445 6716 12445 6714 12445 6717 12446 6718 12446 6716 12446 6719 12447 6718 12447 6717 12447 6719 12448 6720 12448 6718 12448 6719 12449 6721 12449 6720 12449 6719 12450 6722 12450 6721 12450 6723 12451 6722 12451 6719 12451 6723 12452 6724 12452 6722 12452 6725 12453 6724 12453 6723 12453 6725 12454 6726 12454 6724 12454 6725 12455 6727 12455 6726 12455 6728 12456 6727 12456 6725 12456 6729 12457 6727 12457 6728 12457 6729 12458 6730 12458 6727 12458 6729 12459 6731 12459 6730 12459 6732 12460 6731 12460 6729 12460 6733 12461 6731 12461 6732 12461 6733 12462 6734 12462 6731 12462 6733 12463 6735 12463 6734 12463 6736 12464 6735 12464 6733 12464 6736 12465 6737 12465 6735 12465 6738 12466 6737 12466 6736 12466 6738 12467 6739 12467 6737 12467 6740 12468 6741 12468 6738 12468 6738 12469 6741 12469 6739 12469 6740 12470 6742 12470 6741 12470 6743 12471 6742 12471 6740 12471 6743 12472 6744 12472 6742 12472 6743 12473 6745 12473 6744 12473 6746 12474 6745 12474 6743 12474 6746 12475 6747 12475 6745 12475 6746 12476 6748 12476 6747 12476 6749 12477 6748 12477 6746 12477 6750 12478 6748 12478 6749 12478 6750 12479 6751 12479 6748 12479 6750 12480 6752 12480 6751 12480 6753 12481 6752 12481 6750 12481 6753 12482 6754 12482 6752 12482 6755 12483 6754 12483 6753 12483 6755 12484 6756 12484 6754 12484 6757 12485 6756 12485 6755 12485 6758 12486 6756 12486 6757 12486 6758 12487 6759 12487 6756 12487 6758 12488 6760 12488 6759 12488 6761 12489 6760 12489 6758 12489 6761 12490 6762 12490 6760 12490 6763 12491 6762 12491 6761 12491 6763 12492 6764 12492 6762 12492 6765 12493 6764 12493 6763 12493 6766 12494 6764 12494 6765 12494 6766 12495 6767 12495 6764 12495 6768 12496 6767 12496 6766 12496 6768 12497 6769 12497 6767 12497 6768 12498 6770 12498 6769 12498 6768 12499 6771 12499 6770 12499 6772 12500 6771 12500 6768 12500 6772 12501 6773 12501 6771 12501 6774 12502 6773 12502 6772 12502 6774 12503 6775 12503 6773 12503 6774 12504 6776 12504 6775 12504 6777 12505 6776 12505 6774 12505 6777 12506 6778 12506 6776 12506 6777 12507 6779 12507 6778 12507 6780 12508 6779 12508 6777 12508 6780 12509 6781 12509 6779 12509 6782 12510 6781 12510 6780 12510 6782 12511 6783 12511 6781 12511 6784 12512 6783 12512 6782 12512 6784 12513 6785 12513 6783 12513 6786 12514 6785 12514 6784 12514 6786 12515 6787 12515 6785 12515 6788 12516 6787 12516 6786 12516 6788 12517 6789 12517 6787 12517 6790 12518 6791 12518 6788 12518 6788 12519 6791 12519 6789 12519 6792 12520 6791 12520 6790 12520 6792 12521 6793 12521 6791 12521 6794 12522 6795 12522 6792 12522 6792 12523 6795 12523 6793 12523 6794 12524 6796 12524 6795 12524 6797 12525 6796 12525 6794 12525 6797 12526 6798 12526 6796 12526 6799 12527 6798 12527 6797 12527 6799 12528 6800 12528 6798 12528 6799 12529 6801 12529 6800 12529 6802 12530 6801 12530 6799 12530 6802 12531 6803 12531 6801 12531 6804 12532 6803 12532 6802 12532 6804 12533 6805 12533 6803 12533 6806 12534 6807 12534 6804 12534 6804 12535 6807 12535 6805 12535 6808 12536 6807 12536 6806 12536 6808 12537 6809 12537 6807 12537 6810 12538 6809 12538 6808 12538 6810 12539 6811 12539 6809 12539 6810 12540 6812 12540 6811 12540 6813 12541 6812 12541 6810 12541 6813 12542 6814 12542 6812 12542 6813 12543 6815 12543 6814 12543 6816 12544 6815 12544 6813 12544 6816 12545 6817 12545 6815 12545 6816 12546 6818 12546 6817 12546 6819 12547 6818 12547 6816 12547 6819 12548 6820 12548 6818 12548 6821 12549 6820 12549 6819 12549 6821 12550 6822 12550 6820 12550 6821 12551 6823 12551 6822 12551 6824 12552 6823 12552 6821 12552 6824 12553 6825 12553 6823 12553 6824 12554 6826 12554 6825 12554 6827 12555 6826 12555 6824 12555 6827 12556 6828 12556 6826 12556 6829 12557 6828 12557 6827 12557 6829 12558 6830 12558 6828 12558 6829 12559 6831 12559 6830 12559 6832 12560 6831 12560 6829 12560 6832 12561 6833 12561 6831 12561 6834 12562 6833 12562 6832 12562 6834 12563 6835 12563 6833 12563 6834 12564 6836 12564 6835 12564 6837 12565 6836 12565 6834 12565 6837 12566 6838 12566 6836 12566 6839 12567 6838 12567 6837 12567 6839 12568 6840 12568 6838 12568 6841 12569 6840 12569 6839 12569 6841 12570 6842 12570 6840 12570 6843 12571 6842 12571 6841 12571 6843 12572 6844 12572 6842 12572 6843 12573 6845 12573 6844 12573 6846 12574 6845 12574 6843 12574 6846 12575 6847 12575 6845 12575 6848 12576 6847 12576 6846 12576 6848 12577 6849 12577 6847 12577 6850 12578 6849 12578 6848 12578 6850 12579 6851 12579 6849 12579 6852 12580 6851 12580 6850 12580 6852 12581 6853 12581 6851 12581 6854 12582 6853 12582 6852 12582 6854 12583 6855 12583 6853 12583 6856 12584 6855 12584 6854 12584 6856 12585 6857 12585 6855 12585 6856 12586 6858 12586 6857 12586 6859 12587 6858 12587 6856 12587 6859 12588 6860 12588 6858 12588 6861 12589 6860 12589 6859 12589 6861 12590 6862 12590 6860 12590 6863 12591 6862 12591 6861 12591 6863 12592 6864 12592 6862 12592 6863 12593 6865 12593 6864 12593 6866 12594 6865 12594 6863 12594 6866 12595 6867 12595 6865 12595 6868 12596 6867 12596 6866 12596 6868 12597 6869 12597 6867 12597 6870 12598 6869 12598 6868 12598 6870 12599 6871 12599 6869 12599 6872 12600 6871 12600 6870 12600 6872 12601 6873 12601 6871 12601 6874 12602 6873 12602 6872 12602 6874 12603 6875 12603 6873 12603 6874 12604 6876 12604 6875 12604 6877 12605 6876 12605 6874 12605 6877 12606 6878 12606 6876 12606 6877 12607 6879 12607 6878 12607 6880 12608 6879 12608 6877 12608 6881 12609 6879 12609 6880 12609 6881 12610 6882 12610 6879 12610 6883 12611 6882 12611 6881 12611 6883 12612 6884 12612 6882 12612 6883 12613 6885 12613 6884 12613 6886 12614 6885 12614 6883 12614 6886 12615 6887 12615 6885 12615 6888 12616 6887 12616 6886 12616 6888 12617 6889 12617 6887 12617 6890 12618 6889 12618 6888 12618 6890 12619 6891 12619 6889 12619 6892 12620 6891 12620 6890 12620 6892 12621 6893 12621 6891 12621 6894 12622 6893 12622 6892 12622 6894 12623 6895 12623 6893 12623 6896 12624 6895 12624 6894 12624 6896 12625 6897 12625 6895 12625 6898 12626 6897 12626 6896 12626 6898 12627 6899 12627 6897 12627 6900 12628 6899 12628 6898 12628 6900 12629 6901 12629 6899 12629 6902 12630 6901 12630 6900 12630 6902 12631 6903 12631 6901 12631 6904 12632 6903 12632 6902 12632 6904 12633 6905 12633 6903 12633 6904 12634 6906 12634 6905 12634 6907 12635 6906 12635 6904 12635 6907 12636 6908 12636 6906 12636 6907 12637 6909 12637 6908 12637 6910 12638 6909 12638 6907 12638 6910 12639 6911 12639 6909 12639 6912 12640 6911 12640 6910 12640 6912 12641 6913 12641 6911 12641 6914 12642 6915 12642 6912 12642 6912 12643 6915 12643 6913 12643 6914 12644 6916 12644 6915 12644 6917 12645 6916 12645 6914 12645 6917 12646 6918 12646 6916 12646 6919 12647 6918 12647 6917 12647 6919 12648 6920 12648 6918 12648 6919 12649 6921 12649 6920 12649 6922 12650 6921 12650 6919 12650 6922 12651 6923 12651 6921 12651 6924 12652 6923 12652 6922 12652 6924 12653 6925 12653 6923 12653 6926 12654 6925 12654 6924 12654 6926 12655 6927 12655 6925 12655 6928 12656 6927 12656 6926 12656 6928 12657 6929 12657 6927 12657 6930 12658 6929 12658 6928 12658 6930 12659 6931 12659 6929 12659 6932 12660 6931 12660 6930 12660 6932 12661 6933 12661 6931 12661 6932 12662 6934 12662 6933 12662 6935 12663 6934 12663 6932 12663 6935 12664 6936 12664 6934 12664 6937 12665 6936 12665 6935 12665 6937 12666 6938 12666 6936 12666 6939 12667 6938 12667 6937 12667 6939 12668 6940 12668 6938 12668 6939 12669 6941 12669 6940 12669 6942 12670 6941 12670 6939 12670 6942 12671 6943 12671 6941 12671 6944 12672 6943 12672 6942 12672 6944 12673 6945 12673 6943 12673 6944 12674 6946 12674 6945 12674 6947 12675 6946 12675 6944 12675 6947 12676 6948 12676 6946 12676 6949 12677 6948 12677 6947 12677 6949 12678 6950 12678 6948 12678 6951 12679 6950 12679 6949 12679 6951 12680 6952 12680 6950 12680 6951 12681 6953 12681 6952 12681 6954 12682 6953 12682 6951 12682 6955 12683 6953 12683 6954 12683 6955 12684 6956 12684 6953 12684 6957 12685 6956 12685 6955 12685 6957 12686 6958 12686 6956 12686 6957 12687 6959 12687 6958 12687 6960 12688 6959 12688 6957 12688 6960 12689 6961 12689 6959 12689 6960 12690 6962 12690 6961 12690 6963 12691 6962 12691 6960 12691 6963 12692 6964 12692 6962 12692 6963 12693 6965 12693 6964 12693 6966 12694 6965 12694 6963 12694 6966 12695 6967 12695 6965 12695 6968 12696 6967 12696 6966 12696 6969 12697 6967 12697 6968 12697 6969 12698 6970 12698 6967 12698 6971 12699 6970 12699 6969 12699 6971 12700 6972 12700 6970 12700 6971 12701 6973 12701 6972 12701 6974 12702 6973 12702 6971 12702 6974 12703 6975 12703 6973 12703 6976 12704 6975 12704 6974 12704 6976 12705 6977 12705 6975 12705 6978 12706 6977 12706 6976 12706 6978 12707 6979 12707 6977 12707 6980 12708 6979 12708 6978 12708 6980 12709 6981 12709 6979 12709 6982 12710 6981 12710 6980 12710 6982 12711 6983 12711 6981 12711 6982 12712 6984 12712 6983 12712 6985 12713 6984 12713 6982 12713 6985 12714 6986 12714 6984 12714 6987 12715 6986 12715 6985 12715 6987 12716 6988 12716 6986 12716 6987 12717 6989 12717 6988 12717 6990 12718 6989 12718 6987 12718 6990 12719 6991 12719 6989 12719 6992 12720 6991 12720 6990 12720 6992 12721 6993 12721 6991 12721 6994 12722 6993 12722 6992 12722 6994 12723 6995 12723 6993 12723 6994 12724 6996 12724 6995 12724 6997 12725 6996 12725 6994 12725 6997 12726 7184 12726 6996 12726 6998 12727 7184 12727 6997 12727 6998 12728 6397 12728 7184 12728 6998 12729 7177 12729 6397 12729 6999 12730 7177 12730 6998 12730 6999 12731 6396 12731 7177 12731 6999 12732 6395 12732 6396 12732 7000 12733 6395 12733 6999 12733 7000 12734 6393 12734 6395 12734 6409 12735 6407 12735 7002 12735 7003 12736 6409 12736 7002 12736 6412 12737 6409 12737 7003 12737 7004 12738 6412 12738 7003 12738 7005 12739 6412 12739 7004 12739 6414 12740 6412 12740 7005 12740 6417 12741 6414 12741 7005 12741 7006 12742 6417 12742 7005 12742 6419 12743 6417 12743 7006 12743 7007 12744 6419 12744 7006 12744 6422 12745 6419 12745 7007 12745 7008 12746 6422 12746 7007 12746 6424 12747 6422 12747 7008 12747 6427 12748 6424 12748 7008 12748 6428 12749 6427 12749 7009 12749 6431 12750 6428 12750 7009 12750 7010 12751 6444 12751 6442 12751 6447 12752 6444 12752 7010 12752 6454 12753 6451 12753 7011 12753 7012 12754 6454 12754 7011 12754 6456 12755 6454 12755 7012 12755 7013 12756 6458 12756 6456 12756 7014 12757 6458 12757 7013 12757 6461 12758 6458 12758 7014 12758 7015 12759 6461 12759 7014 12759 6465 12760 6461 12760 7015 12760 7016 12761 6465 12761 7015 12761 6467 12762 6465 12762 7016 12762 6470 12763 6467 12763 7016 12763 6481 12764 6479 12764 7017 12764 7018 12765 6481 12765 7017 12765 6484 12766 6481 12766 7018 12766 6487 12767 6484 12767 7018 12767 6489 12768 6487 12768 7019 12768 7020 12769 6489 12769 7019 12769 6491 12770 6489 12770 7020 12770 6494 12771 6491 12771 7020 12771 7021 12772 6494 12772 7020 12772 6497 12773 6494 12773 7021 12773 7022 12774 6497 12774 7021 12774 6499 12775 6497 12775 7022 12775 7023 12776 6503 12776 6501 12776 6505 12777 6503 12777 7023 12777 7024 12778 6505 12778 7023 12778 6507 12779 6505 12779 7024 12779 7025 12780 6507 12780 7024 12780 6509 12781 6507 12781 7025 12781 7026 12782 6509 12782 7025 12782 6512 12783 6509 12783 7026 12783 7027 12784 6512 12784 7026 12784 6514 12785 6512 12785 7027 12785 7028 12786 6514 12786 7027 12786 6517 12787 6514 12787 7028 12787 6519 12788 6517 12788 7029 12788 6521 12789 6519 12789 7029 12789 7030 12790 6521 12790 7029 12790 6523 12791 6521 12791 7030 12791 7031 12792 6525 12792 6523 12792 6528 12793 6525 12793 7031 12793 7032 12794 6540 12794 6539 12794 6543 12795 6540 12795 7032 12795 6545 12796 6543 12796 7032 12796 6547 12797 6545 12797 7033 12797 6549 12798 6547 12798 7033 12798 6558 12799 6556 12799 7034 12799 6560 12800 6558 12800 7034 12800 6562 12801 6560 12801 7035 12801 6564 12802 6562 12802 7035 12802 7036 12803 6566 12803 6564 12803 7037 12804 6566 12804 7036 12804 6569 12805 6566 12805 7037 12805 6570 12806 6569 12806 7037 12806 6573 12807 6570 12807 7037 12807 6579 12808 6577 12808 7038 12808 7039 12809 6579 12809 7038 12809 6582 12810 6579 12810 7039 12810 7040 12811 6582 12811 7039 12811 6585 12812 6582 12812 7040 12812 7041 12813 6587 12813 6585 12813 7042 12814 6587 12814 7041 12814 6590 12815 6587 12815 7042 12815 6593 12816 6590 12816 7042 12816 6595 12817 6593 12817 7043 12817 7044 12818 6595 12818 7043 12818 6597 12819 6595 12819 7044 12819 6599 12820 6597 12820 7044 12820 7045 12821 6603 12821 6601 12821 6606 12822 6603 12822 7045 12822 7046 12823 6606 12823 7045 12823 6609 12824 6606 12824 7046 12824 6613 12825 6611 12825 7047 12825 7048 12826 6613 12826 7047 12826 6616 12827 6613 12827 7048 12827 6619 12828 6616 12828 7048 12828 7049 12829 6621 12829 6619 12829 6623 12830 6621 12830 7049 12830 7050 12831 6625 12831 6623 12831 6628 12832 6625 12832 7050 12832 7051 12833 6628 12833 7050 12833 6630 12834 6628 12834 7051 12834 6630 12835 7051 12835 7052 12835 6632 12836 6630 12836 7052 12836 7053 12837 6632 12837 7052 12837 6634 12838 6632 12838 7053 12838 7054 12839 6637 12839 6634 12839 6638 12840 6637 12840 7054 12840 7055 12841 6638 12841 7054 12841 6640 12842 6638 12842 7055 12842 6640 12843 7055 12843 6643 12843 6645 12844 6643 12844 7056 12844 7057 12845 6645 12845 7056 12845 6648 12846 6645 12846 7057 12846 7058 12847 6648 12847 7057 12847 6650 12848 6648 12848 7058 12848 7059 12849 6652 12849 6650 12849 6654 12850 6652 12850 7059 12850 7060 12851 6654 12851 7059 12851 6657 12852 6654 12852 7060 12852 6659 12853 6657 12853 7060 12853 6665 12854 6664 12854 7061 12854 6667 12855 6665 12855 7061 12855 6672 12856 6669 12856 7062 12856 6674 12857 6672 12857 7062 12857 6682 12858 6680 12858 6678 12858 6685 12859 6682 12859 7063 12859 6687 12860 6685 12860 7063 12860 6692 12861 6689 12861 7064 12861 7065 12862 6692 12862 7064 12862 6695 12863 6692 12863 7065 12863 6697 12864 6695 12864 7065 12864 6699 12865 6697 12865 7066 12865 7067 12866 6699 12866 7066 12866 6702 12867 6699 12867 7067 12867 7068 12868 6702 12868 7067 12868 6704 12869 6702 12869 7068 12869 7069 12870 6704 12870 7068 12870 6706 12871 6704 12871 7069 12871 7070 12872 6706 12872 7069 12872 6708 12873 6706 12873 7070 12873 6710 12874 6708 12874 7070 12874 7071 12875 6714 12875 6712 12875 6717 12876 6714 12876 7071 12876 7072 12877 6717 12877 7071 12877 6719 12878 6717 12878 7072 12878 7073 12879 6719 12879 7072 12879 6723 12880 6719 12880 7073 12880 6725 12881 6723 12881 7074 12881 6728 12882 6725 12882 7074 12882 7075 12883 6738 12883 6736 12883 6740 12884 6738 12884 7075 12884 7076 12885 6740 12885 7075 12885 7077 12886 6740 12886 7076 12886 6743 12887 6740 12887 7077 12887 6746 12888 6743 12888 7077 12888 7078 12889 6746 12889 7077 12889 6749 12890 6746 12890 7078 12890 6750 12891 6749 12891 7079 12891 6753 12892 6750 12892 7079 12892 7080 12893 6755 12893 6753 12893 6757 12894 6755 12894 7080 12894 7081 12895 6758 12895 6757 12895 6761 12896 6758 12896 7081 12896 6763 12897 6761 12897 7081 12897 7082 12898 6768 12898 6766 12898 6768 12899 7082 12899 7083 12899 6772 12900 6768 12900 7083 12900 7084 12901 6772 12901 7083 12901 6774 12902 6772 12902 7084 12902 7085 12903 6774 12903 7084 12903 6777 12904 6774 12904 7085 12904 7086 12905 6777 12905 7085 12905 6780 12906 6777 12906 7086 12906 7087 12907 6784 12907 6782 12907 6786 12908 6784 12908 7087 12908 6794 12909 6792 12909 7088 12909 7089 12910 6794 12910 7088 12910 6797 12911 6794 12911 7089 12911 7090 12912 6797 12912 7089 12912 6799 12913 6797 12913 7090 12913 7091 12914 6799 12914 7090 12914 6802 12915 6799 12915 7091 12915 7092 12916 6802 12916 7091 12916 6804 12917 6802 12917 7092 12917 6806 12918 6804 12918 7092 12918 6808 12919 6806 12919 7093 12919 6810 12920 6808 12920 7093 12920 7094 12921 6810 12921 7093 12921 6813 12922 6810 12922 7094 12922 7095 12923 6813 12923 7094 12923 6816 12924 6813 12924 7095 12924 6816 12925 7095 12925 7096 12925 6819 12926 6816 12926 7096 12926 7097 12927 6819 12927 7096 12927 6821 12928 6819 12928 7097 12928 7098 12929 6821 12929 7097 12929 7099 12930 6821 12930 7098 12930 6824 12931 6821 12931 7099 12931 6827 12932 6824 12932 7099 12932 7100 12933 6827 12933 7099 12933 7101 12934 6827 12934 7100 12934 6829 12935 6827 12935 7101 12935 6832 12936 6829 12936 7101 12936 6839 12937 6837 12937 7102 12937 6841 12938 6839 12938 7102 12938 6843 12939 6841 12939 7103 12939 7104 12940 6843 12940 7103 12940 6846 12941 6843 12941 7104 12941 7105 12942 6846 12942 7104 12942 6848 12943 6846 12943 7105 12943 6850 12944 6848 12944 7105 12944 6854 12945 6852 12945 7106 12945 6856 12946 6854 12946 7106 12946 7107 12947 6856 12947 7106 12947 7108 12948 6856 12948 7107 12948 6859 12949 6856 12949 7108 12949 7109 12950 6859 12950 7108 12950 6861 12951 6859 12951 7109 12951 7110 12952 6861 12952 7109 12952 6863 12953 6861 12953 7110 12953 7111 12954 6870 12954 6868 12954 7112 12955 6870 12955 7111 12955 6872 12956 6870 12956 7112 12956 6874 12957 6872 12957 7112 12957 7113 12958 6874 12958 7112 12958 7114 12959 6874 12959 7113 12959 6877 12960 6874 12960 7114 12960 6880 12961 6877 12961 7114 12961 6881 12962 6880 12962 7115 12962 7116 12963 6881 12963 7115 12963 6883 12964 6881 12964 7116 12964 6886 12965 6883 12965 7116 12965 6900 12966 6898 12966 7117 12966 7118 12967 6900 12967 7117 12967 6902 12968 6900 12968 7118 12968 7119 12969 6902 12969 7118 12969 6904 12970 6902 12970 7119 12970 7120 12971 6904 12971 7119 12971 6907 12972 6904 12972 7120 12972 7121 12973 6907 12973 7120 12973 7122 12974 6907 12974 7121 12974 6910 12975 6907 12975 7122 12975 6912 12976 6910 12976 7122 12976 6914 12977 6912 12977 7123 12977 6917 12978 6914 12978 7123 12978 7124 12979 6917 12979 7123 12979 6919 12980 6917 12980 7124 12980 7125 12981 6919 12981 7124 12981 6922 12982 6919 12982 7125 12982 6926 12983 6924 12983 7126 12983 6928 12984 6926 12984 7126 12984 7127 12985 6930 12985 6928 12985 7128 12986 6930 12986 7127 12986 6932 12987 6930 12987 7128 12987 7129 12988 6932 12988 7128 12988 6935 12989 6932 12989 7129 12989 6935 12990 7129 12990 6937 12990 6939 12991 6937 12991 7130 12991 7131 12992 6939 12992 7130 12992 6942 12993 6939 12993 7131 12993 7132 12994 6942 12994 7131 12994 6944 12995 6942 12995 7132 12995 6947 12996 6944 12996 7132 12996 7133 12997 6947 12997 7132 12997 7134 12998 6947 12998 7133 12998 6949 12999 6947 12999 7134 12999 7135 13000 6949 13000 7134 13000 6951 13001 6949 13001 7135 13001 6954 13002 6951 13002 7135 13002 7136 13003 6955 13003 6954 13003 6957 13004 6955 13004 7136 13004 7137 13005 6960 13005 6957 13005 7138 13006 6960 13006 7137 13006 6963 13007 6960 13007 7138 13007 7139 13008 6963 13008 7138 13008 6966 13009 6963 13009 7139 13009 6968 13010 6966 13010 7139 13010 6971 13011 6969 13011 7140 13011 6974 13012 6971 13012 7140 13012 6976 13013 6974 13013 7141 13013 6978 13014 6976 13014 7141 13014 7142 13015 6978 13015 7141 13015 6980 13016 6978 13016 7142 13016 7143 13017 6985 13017 6982 13017 6987 13018 6985 13018 7143 13018 7144 13019 6987 13019 7143 13019 7145 13020 6987 13020 7144 13020 6990 13021 6987 13021 7145 13021 6992 13022 6990 13022 7145 13022 7146 13023 6994 13023 6992 13023 6997 13024 6994 13024 7146 13024 7147 13025 6999 13025 6998 13025 7000 13026 6999 13026 7147 13026 7148 13027 7000 13027 7147 13027 6393 13028 7000 13028 7148 13028 7149 13029 6393 13029 7148 13029 7001 13030 6393 13030 7149 13030 7150 13031 7001 13031 7149 13031 6387 13032 7001 13032 7150 13032 6383 13033 6387 13033 7150 13033 7152 13034 7005 13034 7004 13034 7152 13035 7006 13035 7005 13035 7151 13036 7006 13036 7152 13036 7151 13037 7007 13037 7006 13037 7153 13038 7007 13038 7151 13038 7153 13039 7008 13039 7007 13039 6398 13040 7008 13040 7153 13040 6399 13041 7008 13041 6398 13041 6399 13042 6427 13042 7008 13042 6402 13043 6427 13043 6399 13043 6402 13044 7009 13044 6427 13044 6403 13045 7009 13045 6402 13045 6405 13046 7009 13046 6403 13046 6405 13047 6431 13047 7009 13047 6406 13048 6431 13048 6405 13048 6406 13049 6433 13049 6431 13049 6406 13050 6435 13050 6433 13050 6408 13051 6435 13051 6406 13051 6408 13052 6437 13052 6435 13052 7154 13053 6437 13053 6408 13053 7154 13054 6440 13054 6437 13054 6413 13055 6440 13055 7154 13055 6413 13056 6442 13056 6440 13056 6415 13057 6442 13057 6413 13057 6415 13058 7010 13058 6442 13058 6416 13059 7010 13059 6415 13059 6418 13060 7010 13060 6416 13060 6418 13061 6447 13061 7010 13061 6420 13062 6447 13062 6418 13062 6420 13063 6449 13063 6447 13063 6420 13064 6451 13064 6449 13064 6423 13065 6451 13065 6420 13065 6423 13066 7011 13066 6451 13066 6425 13067 7011 13067 6423 13067 6426 13068 7011 13068 6425 13068 6426 13069 7012 13069 7011 13069 6429 13070 7012 13070 6426 13070 6429 13071 6456 13071 7012 13071 6430 13072 6456 13072 6429 13072 6430 13073 7013 13073 6456 13073 6432 13074 7013 13074 6430 13074 6432 13075 7014 13075 7013 13075 6434 13076 7014 13076 6432 13076 6436 13077 7014 13077 6434 13077 6436 13078 7015 13078 7014 13078 6438 13079 7015 13079 6436 13079 6438 13080 7016 13080 7015 13080 6439 13081 7016 13081 6438 13081 6441 13082 7016 13082 6439 13082 6441 13083 6470 13083 7016 13083 6443 13084 6470 13084 6441 13084 6443 13085 6472 13085 6470 13085 6445 13086 6472 13086 6443 13086 6445 13087 6474 13087 6472 13087 6446 13088 6474 13088 6445 13088 6448 13089 6474 13089 6446 13089 6448 13090 6477 13090 6474 13090 6450 13091 6477 13091 6448 13091 6450 13092 6479 13092 6477 13092 6452 13093 6479 13093 6450 13093 6452 13094 7017 13094 6479 13094 6453 13095 7017 13095 6452 13095 6455 13096 7017 13096 6453 13096 6455 13097 7018 13097 7017 13097 6457 13098 7018 13098 6455 13098 6459 13099 7018 13099 6457 13099 6459 13100 6487 13100 7018 13100 6460 13101 6487 13101 6459 13101 6460 13102 7019 13102 6487 13102 6462 13103 7019 13103 6460 13103 6462 13104 7020 13104 7019 13104 6463 13105 7020 13105 6462 13105 6464 13106 7020 13106 6463 13106 6466 13107 7020 13107 6464 13107 6466 13108 7021 13108 7020 13108 6468 13109 7021 13109 6466 13109 6469 13110 7021 13110 6468 13110 6469 13111 7022 13111 7021 13111 6471 13112 7022 13112 6469 13112 6471 13113 6499 13113 7022 13113 6473 13114 6499 13114 6471 13114 6475 13115 6499 13115 6473 13115 6475 13116 6501 13116 6499 13116 6476 13117 6501 13117 6475 13117 6476 13118 7023 13118 6501 13118 6478 13119 7023 13119 6476 13119 6480 13120 7023 13120 6478 13120 6480 13121 7024 13121 7023 13121 6482 13122 7024 13122 6480 13122 6483 13123 7025 13123 6482 13123 6482 13124 7025 13124 7024 13124 6485 13125 7025 13125 6483 13125 6485 13126 7026 13126 7025 13126 6486 13127 7026 13127 6485 13127 6486 13128 7027 13128 7026 13128 6488 13129 7027 13129 6486 13129 6490 13130 7027 13130 6488 13130 6490 13131 7028 13131 7027 13131 6492 13132 7028 13132 6490 13132 6492 13133 6517 13133 7028 13133 6493 13134 6517 13134 6492 13134 6493 13135 7029 13135 6517 13135 6495 13136 7029 13136 6493 13136 6496 13137 7029 13137 6495 13137 6498 13138 7029 13138 6496 13138 6498 13139 7030 13139 7029 13139 7155 13140 7030 13140 6498 13140 7155 13141 6523 13141 7030 13141 7155 13142 7031 13142 6523 13142 6502 13143 7031 13143 7155 13143 6504 13144 7031 13144 6502 13144 6504 13145 6528 13145 7031 13145 6504 13146 6530 13146 6528 13146 6506 13147 6530 13147 6504 13147 6506 13148 6532 13148 6530 13148 6508 13149 6532 13149 6506 13149 6508 13150 6534 13150 6532 13150 6510 13151 6534 13151 6508 13151 6510 13152 6536 13152 6534 13152 6511 13153 6536 13153 6510 13153 6511 13154 6539 13154 6536 13154 6513 13155 6539 13155 6511 13155 6513 13156 7032 13156 6539 13156 6515 13157 7032 13157 6513 13157 6516 13158 7032 13158 6515 13158 6516 13159 6545 13159 7032 13159 6518 13160 6545 13160 6516 13160 6518 13161 7033 13161 6545 13161 6520 13162 7033 13162 6518 13162 6520 13163 6549 13163 7033 13163 6522 13164 6549 13164 6520 13164 6522 13165 6551 13165 6549 13165 6524 13166 6551 13166 6522 13166 6524 13167 6553 13167 6551 13167 6526 13168 6553 13168 6524 13168 6526 13169 6556 13169 6553 13169 6527 13170 6556 13170 6526 13170 6527 13171 7034 13171 6556 13171 6529 13172 7034 13172 6527 13172 6529 13173 6560 13173 7034 13173 6531 13174 6560 13174 6529 13174 6531 13175 7035 13175 6560 13175 6533 13176 7035 13176 6531 13176 6535 13177 7035 13177 6533 13177 6535 13178 6564 13178 7035 13178 6537 13179 6564 13179 6535 13179 6537 13180 7036 13180 6564 13180 6538 13181 7036 13181 6537 13181 6541 13182 7036 13182 6538 13182 6541 13183 7037 13183 7036 13183 6542 13184 7037 13184 6541 13184 6544 13185 7037 13185 6542 13185 6544 13186 6573 13186 7037 13186 6546 13187 6573 13187 6544 13187 6546 13188 6575 13188 6573 13188 6548 13189 6575 13189 6546 13189 6548 13190 6577 13190 6575 13190 6550 13191 6577 13191 6548 13191 6550 13192 7038 13192 6577 13192 6554 13193 7038 13193 6550 13193 6554 13194 7039 13194 7038 13194 6555 13195 7039 13195 6554 13195 6555 13196 7040 13196 7039 13196 6557 13197 7040 13197 6555 13197 6559 13198 6585 13198 6557 13198 6557 13199 6585 13199 7040 13199 6561 13200 6585 13200 6559 13200 6561 13201 7041 13201 6585 13201 6563 13202 7041 13202 6561 13202 6563 13203 7042 13203 7041 13203 6565 13204 7042 13204 6563 13204 6565 13205 6593 13205 7042 13205 6567 13206 6593 13206 6565 13206 6567 13207 7043 13207 6593 13207 6568 13208 7043 13208 6567 13208 6568 13209 7044 13209 7043 13209 6571 13210 7044 13210 6568 13210 6571 13211 6599 13211 7044 13211 6572 13212 6599 13212 6571 13212 6574 13213 6599 13213 6572 13213 6574 13214 6601 13214 6599 13214 6576 13215 6601 13215 6574 13215 6576 13216 7045 13216 6601 13216 6578 13217 7045 13217 6576 13217 6580 13218 7045 13218 6578 13218 6580 13219 7046 13219 7045 13219 6581 13220 7046 13220 6580 13220 6583 13221 7046 13221 6581 13221 6584 13222 7046 13222 6583 13222 6584 13223 6609 13223 7046 13223 6586 13224 6609 13224 6584 13224 6586 13225 6611 13225 6609 13225 6588 13226 6611 13226 6586 13226 6588 13227 7047 13227 6611 13227 6589 13228 7047 13228 6588 13228 6591 13229 7047 13229 6589 13229 6591 13230 7048 13230 7047 13230 6592 13231 7048 13231 6591 13231 6594 13232 7048 13232 6592 13232 6594 13233 6619 13233 7048 13233 7156 13234 6619 13234 6594 13234 7156 13235 7049 13235 6619 13235 6596 13236 7049 13236 7156 13236 6598 13237 7049 13237 6596 13237 6598 13238 6623 13238 7049 13238 6600 13239 6623 13239 6598 13239 6600 13240 7050 13240 6623 13240 6602 13241 7050 13241 6600 13241 6602 13242 7051 13242 7050 13242 6604 13243 7051 13243 6602 13243 6604 13244 7052 13244 7051 13244 6605 13245 7052 13245 6604 13245 6605 13246 7053 13246 7052 13246 6607 13247 7053 13247 6605 13247 6608 13248 7053 13248 6607 13248 6608 13249 6634 13249 7053 13249 6610 13250 6634 13250 6608 13250 6610 13251 7054 13251 6634 13251 6612 13252 7054 13252 6610 13252 6614 13253 7054 13253 6612 13253 6614 13254 7055 13254 7054 13254 6615 13255 7055 13255 6614 13255 6615 13256 6643 13256 7055 13256 6617 13257 6643 13257 6615 13257 6617 13258 7056 13258 6643 13258 6618 13259 7056 13259 6617 13259 6620 13260 7056 13260 6618 13260 6620 13261 7057 13261 7056 13261 6622 13262 7057 13262 6620 13262 6622 13263 7058 13263 7057 13263 6624 13264 7058 13264 6622 13264 6624 13265 6650 13265 7058 13265 7157 13266 6650 13266 6624 13266 7157 13267 7059 13267 6650 13267 6627 13268 7059 13268 7157 13268 6629 13269 7060 13269 6627 13269 6627 13270 7060 13270 7059 13270 6631 13271 7060 13271 6629 13271 6631 13272 6659 13272 7060 13272 6633 13273 6659 13273 6631 13273 6633 13274 6661 13274 6659 13274 6635 13275 6661 13275 6633 13275 6635 13276 6664 13276 6661 13276 6636 13277 6664 13277 6635 13277 6636 13278 7061 13278 6664 13278 6639 13279 7061 13279 6636 13279 6641 13280 7061 13280 6639 13280 6641 13281 6667 13281 7061 13281 6642 13282 6667 13282 6641 13282 6642 13283 6669 13283 6667 13283 6644 13284 6669 13284 6642 13284 6644 13285 7062 13285 6669 13285 6646 13286 7062 13286 6644 13286 6646 13287 6674 13287 7062 13287 6647 13288 6674 13288 6646 13288 6647 13289 6676 13289 6674 13289 6649 13290 6676 13290 6647 13290 6651 13291 6676 13291 6649 13291 6651 13292 6678 13292 6676 13292 6653 13293 6678 13293 6651 13293 6653 13294 6682 13294 6678 13294 6653 13295 7063 13295 6682 13295 6655 13296 7063 13296 6653 13296 6656 13297 7063 13297 6655 13297 6656 13298 6687 13298 7063 13298 6658 13299 6687 13299 6656 13299 6658 13300 6689 13300 6687 13300 6660 13301 6689 13301 6658 13301 6662 13302 6689 13302 6660 13302 6662 13303 7064 13303 6689 13303 6663 13304 7064 13304 6662 13304 6663 13305 7065 13305 7064 13305 6666 13306 7065 13306 6663 13306 6668 13307 6697 13307 6666 13307 6666 13308 6697 13308 7065 13308 6670 13309 6697 13309 6668 13309 6670 13310 7066 13310 6697 13310 6671 13311 7066 13311 6670 13311 6671 13312 7067 13312 7066 13312 6673 13313 7067 13313 6671 13313 6673 13314 7068 13314 7067 13314 6675 13315 7068 13315 6673 13315 6677 13316 7068 13316 6675 13316 6677 13317 7069 13317 7068 13317 6679 13318 7069 13318 6677 13318 6681 13319 7069 13319 6679 13319 6681 13320 7070 13320 7069 13320 6683 13321 7070 13321 6681 13321 6684 13322 7070 13322 6683 13322 6684 13323 6710 13323 7070 13323 6686 13324 6710 13324 6684 13324 6686 13325 6712 13325 6710 13325 6688 13326 6712 13326 6686 13326 6688 13327 7071 13327 6712 13327 6690 13328 7071 13328 6688 13328 6691 13329 7071 13329 6690 13329 6691 13330 7072 13330 7071 13330 6693 13331 7072 13331 6691 13331 6693 13332 7073 13332 7072 13332 6694 13333 7073 13333 6693 13333 6696 13334 7073 13334 6694 13334 6696 13335 6723 13335 7073 13335 6698 13336 6723 13336 6696 13336 6698 13337 7074 13337 6723 13337 6700 13338 7074 13338 6698 13338 6700 13339 6728 13339 7074 13339 6701 13340 6728 13340 6700 13340 6703 13341 6728 13341 6701 13341 6703 13342 6729 13342 6728 13342 6703 13343 6732 13343 6729 13343 6705 13344 6732 13344 6703 13344 6707 13345 6732 13345 6705 13345 6707 13346 6733 13346 6732 13346 6709 13347 6733 13347 6707 13347 6709 13348 6736 13348 6733 13348 6711 13349 6736 13349 6709 13349 6711 13350 7075 13350 6736 13350 6713 13351 7075 13351 6711 13351 6713 13352 7076 13352 7075 13352 6715 13353 7076 13353 6713 13353 6715 13354 7077 13354 7076 13354 6716 13355 7077 13355 6715 13355 6718 13356 7077 13356 6716 13356 6718 13357 7078 13357 7077 13357 6720 13358 7078 13358 6718 13358 6721 13359 7078 13359 6720 13359 6721 13360 6749 13360 7078 13360 6722 13361 6749 13361 6721 13361 6722 13362 7079 13362 6749 13362 6724 13363 7079 13363 6722 13363 6724 13364 6753 13364 7079 13364 6726 13365 6753 13365 6724 13365 6727 13366 6753 13366 6726 13366 6727 13367 7080 13367 6753 13367 6730 13368 7080 13368 6727 13368 6731 13369 7080 13369 6730 13369 6731 13370 6757 13370 7080 13370 6734 13371 6757 13371 6731 13371 6734 13372 7081 13372 6757 13372 6735 13373 7081 13373 6734 13373 6735 13374 6763 13374 7081 13374 6737 13375 6763 13375 6735 13375 6737 13376 6765 13376 6763 13376 6739 13377 6765 13377 6737 13377 6739 13378 6766 13378 6765 13378 6741 13379 6766 13379 6739 13379 6741 13380 7082 13380 6766 13380 6742 13381 7082 13381 6741 13381 6744 13382 7082 13382 6742 13382 6744 13383 7083 13383 7082 13383 6745 13384 7083 13384 6744 13384 6745 13385 7084 13385 7083 13385 6747 13386 7084 13386 6745 13386 6748 13387 7084 13387 6747 13387 6748 13388 7085 13388 7084 13388 6751 13389 7085 13389 6748 13389 6751 13390 7086 13390 7085 13390 6752 13391 7086 13391 6751 13391 6754 13392 7086 13392 6752 13392 6754 13393 6780 13393 7086 13393 6754 13394 6782 13394 6780 13394 6756 13395 6782 13395 6754 13395 6756 13396 7087 13396 6782 13396 6759 13397 7087 13397 6756 13397 6760 13398 7087 13398 6759 13398 6760 13399 6786 13399 7087 13399 6762 13400 6786 13400 6760 13400 6762 13401 6788 13401 6786 13401 6762 13402 6790 13402 6788 13402 6764 13403 6790 13403 6762 13403 6764 13404 6792 13404 6790 13404 6767 13405 6792 13405 6764 13405 6767 13406 7088 13406 6792 13406 6769 13407 7088 13407 6767 13407 6769 13408 7089 13408 7088 13408 6770 13409 7089 13409 6769 13409 6771 13410 7089 13410 6770 13410 6771 13411 7090 13411 7089 13411 6773 13412 7090 13412 6771 13412 6773 13413 7091 13413 7090 13413 6775 13414 7091 13414 6773 13414 6776 13415 7091 13415 6775 13415 6778 13416 7092 13416 6776 13416 6776 13417 7092 13417 7091 13417 6779 13418 7092 13418 6778 13418 6781 13419 6806 13419 6779 13419 6779 13420 6806 13420 7092 13420 6783 13421 6806 13421 6781 13421 6783 13422 7093 13422 6806 13422 6785 13423 7093 13423 6783 13423 6785 13424 7094 13424 7093 13424 6787 13425 7094 13425 6785 13425 6787 13426 7095 13426 7094 13426 6789 13427 7095 13427 6787 13427 6791 13428 7095 13428 6789 13428 6791 13429 7096 13429 7095 13429 6793 13430 7096 13430 6791 13430 6793 13431 7097 13431 7096 13431 6795 13432 7097 13432 6793 13432 6796 13433 7097 13433 6795 13433 6796 13434 7098 13434 7097 13434 6798 13435 7098 13435 6796 13435 6798 13436 7099 13436 7098 13436 6800 13437 7099 13437 6798 13437 6801 13438 7099 13438 6800 13438 6801 13439 7100 13439 7099 13439 6803 13440 7100 13440 6801 13440 6803 13441 7101 13441 7100 13441 6805 13442 7101 13442 6803 13442 6805 13443 6832 13443 7101 13443 6807 13444 6832 13444 6805 13444 6807 13445 6834 13445 6832 13445 6809 13446 6834 13446 6807 13446 6809 13447 6837 13447 6834 13447 6811 13448 6837 13448 6809 13448 6811 13449 7102 13449 6837 13449 6812 13450 7102 13450 6811 13450 6814 13451 7102 13451 6812 13451 6814 13452 6841 13452 7102 13452 6815 13453 6841 13453 6814 13453 6815 13454 7103 13454 6841 13454 6817 13455 7103 13455 6815 13455 6818 13456 7103 13456 6817 13456 6818 13457 7104 13457 7103 13457 6820 13458 7104 13458 6818 13458 6820 13459 7105 13459 7104 13459 6822 13460 7105 13460 6820 13460 6822 13461 6850 13461 7105 13461 6823 13462 6850 13462 6822 13462 6823 13463 6852 13463 6850 13463 6825 13464 6852 13464 6823 13464 6826 13465 6852 13465 6825 13465 6826 13466 7106 13466 6852 13466 6828 13467 7106 13467 6826 13467 6830 13468 7106 13468 6828 13468 6831 13469 7106 13469 6830 13469 6831 13470 7107 13470 7106 13470 6831 13471 7108 13471 7107 13471 7158 13472 7108 13472 6831 13472 6835 13473 7108 13473 7158 13473 6835 13474 7109 13474 7108 13474 6836 13475 7109 13475 6835 13475 6836 13476 7110 13476 7109 13476 6838 13477 7110 13477 6836 13477 6838 13478 6863 13478 7110 13478 6840 13479 6863 13479 6838 13479 6840 13480 6866 13480 6863 13480 6842 13481 6866 13481 6840 13481 6842 13482 6868 13482 6866 13482 6844 13483 6868 13483 6842 13483 6844 13484 7111 13484 6868 13484 6845 13485 7111 13485 6844 13485 6847 13486 7112 13486 6845 13486 6845 13487 7112 13487 7111 13487 6849 13488 7112 13488 6847 13488 6851 13489 7112 13489 6849 13489 6851 13490 7113 13490 7112 13490 7159 13491 7113 13491 6851 13491 7159 13492 7114 13492 7113 13492 7160 13493 7114 13493 7159 13493 7160 13494 6880 13494 7114 13494 6857 13495 6880 13495 7160 13495 6857 13496 7115 13496 6880 13496 6858 13497 7115 13497 6857 13497 6858 13498 7116 13498 7115 13498 6860 13499 7116 13499 6858 13499 6860 13500 6886 13500 7116 13500 6862 13501 6886 13501 6860 13501 6862 13502 6888 13502 6886 13502 6864 13503 6888 13503 6862 13503 6864 13504 6890 13504 6888 13504 6865 13505 6890 13505 6864 13505 6865 13506 6892 13506 6890 13506 6867 13507 6892 13507 6865 13507 6867 13508 6894 13508 6892 13508 6869 13509 6894 13509 6867 13509 6869 13510 6896 13510 6894 13510 6871 13511 6896 13511 6869 13511 6871 13512 6898 13512 6896 13512 6873 13513 6898 13513 6871 13513 6873 13514 7117 13514 6898 13514 6875 13515 7117 13515 6873 13515 6875 13516 7118 13516 7117 13516 6876 13517 7118 13517 6875 13517 6876 13518 7119 13518 7118 13518 6878 13519 7119 13519 6876 13519 6879 13520 7119 13520 6878 13520 6879 13521 7120 13521 7119 13521 6882 13522 7120 13522 6879 13522 6882 13523 7121 13523 7120 13523 6884 13524 7121 13524 6882 13524 6884 13525 7122 13525 7121 13525 6885 13526 7122 13526 6884 13526 6887 13527 7122 13527 6885 13527 6887 13528 6912 13528 7122 13528 6889 13529 6912 13529 6887 13529 6889 13530 7123 13530 6912 13530 6891 13531 7123 13531 6889 13531 6891 13532 7124 13532 7123 13532 6893 13533 7124 13533 6891 13533 6893 13534 7125 13534 7124 13534 6895 13535 7125 13535 6893 13535 6895 13536 6922 13536 7125 13536 6897 13537 6922 13537 6895 13537 6897 13538 6924 13538 6922 13538 6899 13539 6924 13539 6897 13539 6899 13540 7126 13540 6924 13540 6901 13541 7126 13541 6899 13541 6901 13542 6928 13542 7126 13542 6903 13543 6928 13543 6901 13543 6903 13544 7127 13544 6928 13544 6905 13545 7127 13545 6903 13545 6906 13546 7127 13546 6905 13546 6906 13547 7128 13547 7127 13547 6908 13548 7128 13548 6906 13548 6908 13549 7129 13549 7128 13549 6909 13550 7129 13550 6908 13550 6909 13551 6937 13551 7129 13551 6911 13552 6937 13552 6909 13552 6911 13553 7130 13553 6937 13553 6913 13554 7130 13554 6911 13554 6913 13555 7131 13555 7130 13555 6915 13556 7131 13556 6913 13556 6916 13557 7131 13557 6915 13557 6916 13558 7132 13558 7131 13558 6918 13559 7132 13559 6916 13559 6918 13560 7133 13560 7132 13560 6920 13561 7133 13561 6918 13561 6920 13562 7134 13562 7133 13562 6921 13563 7134 13563 6920 13563 6923 13564 7134 13564 6921 13564 6923 13565 7135 13565 7134 13565 6925 13566 7135 13566 6923 13566 6927 13567 7135 13567 6925 13567 6927 13568 6954 13568 7135 13568 6929 13569 6954 13569 6927 13569 6929 13570 7136 13570 6954 13570 6931 13571 7136 13571 6929 13571 6931 13572 6957 13572 7136 13572 6933 13573 6957 13573 6931 13573 6933 13574 7137 13574 6957 13574 6934 13575 7137 13575 6933 13575 6936 13576 7138 13576 6934 13576 6934 13577 7138 13577 7137 13577 6938 13578 7138 13578 6936 13578 6938 13579 7139 13579 7138 13579 6940 13580 7139 13580 6938 13580 6941 13581 7139 13581 6940 13581 6941 13582 6968 13582 7139 13582 6941 13583 6969 13583 6968 13583 6943 13584 6969 13584 6941 13584 6945 13585 7140 13585 6943 13585 6943 13586 7140 13586 6969 13586 6946 13587 7140 13587 6945 13587 6946 13588 6974 13588 7140 13588 6948 13589 6974 13589 6946 13589 6948 13590 7141 13590 6974 13590 6950 13591 7141 13591 6948 13591 6952 13592 7141 13592 6950 13592 6952 13593 7142 13593 7141 13593 6953 13594 7142 13594 6952 13594 6953 13595 6980 13595 7142 13595 6956 13596 6980 13596 6953 13596 6956 13597 6982 13597 6980 13597 6958 13598 6982 13598 6956 13598 6958 13599 7143 13599 6982 13599 6959 13600 7143 13600 6958 13600 6961 13601 7143 13601 6959 13601 6961 13602 7144 13602 7143 13602 6962 13603 7144 13603 6961 13603 6962 13604 7145 13604 7144 13604 6964 13605 7145 13605 6962 13605 6965 13606 7145 13606 6964 13606 6965 13607 6992 13607 7145 13607 6967 13608 6992 13608 6965 13608 6967 13609 7146 13609 6992 13609 6970 13610 7146 13610 6967 13610 6970 13611 6997 13611 7146 13611 6972 13612 6997 13612 6970 13612 6972 13613 6998 13613 6997 13613 6973 13614 6998 13614 6972 13614 6973 13615 7147 13615 6998 13615 6975 13616 7147 13616 6973 13616 6977 13617 7147 13617 6975 13617 6977 13618 7148 13618 7147 13618 6979 13619 7148 13619 6977 13619 6979 13620 7149 13620 7148 13620 6981 13621 7149 13621 6979 13621 6983 13622 7149 13622 6981 13622 6983 13623 7150 13623 7149 13623 6984 13624 7150 13624 6983 13624 6984 13625 6383 13625 7150 13625 6986 13626 6383 13626 6984 13626 6988 13627 6383 13627 6986 13627 6988 13628 6386 13628 6383 13628 6989 13629 6386 13629 6988 13629 6989 13630 6389 13630 6386 13630 6991 13631 6389 13631 6989 13631 6993 13632 6389 13632 6991 13632 6993 13633 6392 13633 6389 13633 6995 13634 6392 13634 6993 13634 7154 13635 6408 13635 6410 13635 6411 13636 7154 13636 6410 13636 6413 13637 7154 13637 6411 13637 6423 13638 6420 13638 6421 13638 7155 13639 6498 13639 6500 13639 6502 13640 7155 13640 6500 13640 6554 13641 6550 13641 6552 13641 6596 13642 7156 13642 6594 13642 7157 13643 6624 13643 6626 13643 6627 13644 7157 13644 6626 13644 6833 13645 7158 13645 6831 13645 6835 13646 7158 13646 6833 13646 6853 13647 7159 13647 6851 13647 7160 13648 7159 13648 6853 13648 6855 13649 7160 13649 6853 13649 6857 13650 7160 13650 6855 13650 6996 13651 6392 13651 6995 13651 7163 13652 7162 13652 7161 13652 7166 13653 7163 13653 7161 13653 7166 13654 7165 13654 7163 13654 7166 13655 7161 13655 7167 13655 7166 13656 6391 13656 7165 13656 7167 13657 7161 13657 7164 13657 7168 13658 7166 13658 7167 13658 7169 13659 7167 13659 7164 13659 6391 13660 7166 13660 7168 13660 7168 13661 7167 13661 7169 13661 7172 13662 7169 13662 7164 13662 6394 13663 7168 13663 7169 13663 6391 13664 7168 13664 6394 13664 7171 13665 6394 13665 7169 13665 7171 13666 7169 13666 7172 13666 7172 13667 7164 13667 7170 13667 6395 13668 6394 13668 7171 13668 7172 13669 7170 13669 7173 13669 7175 13670 7171 13670 7172 13670 7175 13671 7172 13671 7173 13671 7175 13672 6395 13672 7171 13672 7174 13673 7173 13673 7170 13673 7174 13674 7176 13674 7173 13674 7176 13675 7175 13675 7173 13675 7175 13676 6396 13676 6395 13676 7177 13677 7175 13677 7176 13677 6396 13678 7175 13678 7177 13678 7178 13679 7176 13679 7174 13679 7179 13680 7177 13680 7176 13680 7179 13681 7176 13681 7178 13681 7179 13682 6397 13682 7177 13682 7180 13683 7179 13683 7178 13683 7178 13684 7174 13684 7181 13684 7180 13685 6397 13685 7179 13685 7183 13686 7180 13686 7178 13686 7183 13687 7178 13687 7181 13687 7180 13688 7184 13688 6397 13688 7181 13689 7174 13689 7182 13689 7184 13690 7180 13690 7183 13690 7185 13691 7183 13691 7181 13691 7184 13692 7183 13692 7185 13692 7185 13693 7181 13693 7182 13693 7186 13694 7184 13694 7185 13694 6996 13695 7184 13695 7186 13695 7187 13696 7186 13696 7185 13696 7187 13697 7185 13697 7182 13697 7187 13698 7182 13698 7188 13698 7186 13699 6392 13699 6996 13699 7190 13700 7186 13700 7187 13700 6392 13701 7186 13701 7190 13701 7190 13702 7187 13702 7188 13702 7191 13703 7182 13703 7189 13703 7188 13704 7182 13704 7191 13704 7192 13705 7190 13705 7188 13705 7192 13706 7188 13706 7191 13706 7193 13707 7192 13707 7191 13707 6392 13708 7190 13708 7192 13708 6390 13709 6392 13709 7192 13709 7193 13710 7191 13710 7189 13710 7194 13711 7192 13711 7193 13711 6390 13712 7192 13712 7194 13712 7195 13713 7194 13713 7193 13713 6388 13714 6390 13714 7194 13714 7197 13715 7193 13715 7189 13715 7195 13716 6388 13716 7194 13716 7195 13717 7193 13717 7197 13717 7197 13718 7189 13718 7196 13718 6384 13719 6388 13719 7195 13719 7198 13720 7195 13720 7197 13720 7198 13721 6384 13721 7195 13721 7199 13722 7197 13722 7196 13722 7199 13723 7198 13723 7197 13723 7201 13724 7198 13724 7199 13724 7200 13725 7199 13725 7196 13725 6384 13726 7198 13726 7201 13726 6382 13727 6384 13727 7201 13727 7202 13728 7199 13728 7200 13728 7202 13729 7201 13729 7199 13729 6382 13730 7201 13730 7202 13730 7162 13731 7202 13731 7200 13731 7162 13732 7200 13732 7161 13732 7202 13733 6385 13733 6382 13733 7202 13734 7162 13734 7163 13734 7163 13735 6385 13735 7202 13735 6385 13736 7163 13736 7165 13736 7174 13737 7200 13737 7196 13737 7174 13738 7161 13738 7200 13738 7174 13739 7189 13739 7182 13739 7174 13740 7170 13740 7164 13740 7174 13741 7196 13741 7189 13741 7174 13742 7164 13742 7161 13742 7204 13743 7203 13743 7212 13743 7212 13744 7203 13744 7209 13744 7203 13745 7205 13745 7209 13745 7209 13746 7205 13746 7210 13746 7205 13747 7206 13747 7210 13747 7210 13748 7206 13748 7214 13748 7206 13749 7207 13749 7214 13749 7214 13750 7207 13750 7213 13750 7207 13751 7208 13751 7213 13751 7213 13752 7208 13752 7211 13752 7208 13753 7212 13753 7211 13753 7208 13754 7204 13754 7212 13754 7210 13755 7215 13755 7216 13755 7210 13756 7216 13756 7217 13756 7214 13757 7218 13757 7215 13757 7214 13758 7219 13758 7218 13758 7214 13759 7215 13759 7210 13759 7209 13760 7217 13760 7220 13760 7209 13761 7210 13761 7217 13761 7221 13762 7209 13762 7220 13762 7213 13763 7222 13763 7219 13763 7213 13764 7219 13764 7214 13764 7223 13765 7222 13765 7213 13765 7212 13766 7209 13766 7221 13766 7224 13767 7212 13767 7221 13767 7225 13768 7223 13768 7213 13768 7225 13769 7213 13769 7211 13769 7226 13770 7212 13770 7224 13770 7226 13771 7211 13771 7212 13771 7227 13772 7225 13772 7211 13772 7227 13773 7211 13773 7226 13773 7203 13774 7206 13774 7205 13774 7208 13775 7207 13775 7204 13775 7204 13776 7207 13776 7203 13776 7203 13777 7207 13777 7206 13777 7228 13778 7241 13778 7218 13778 7228 13779 7218 13779 7219 13779 7229 13780 7228 13780 7219 13780 7229 13781 7219 13781 7222 13781 7229 13782 7222 13782 7223 13782 7230 13783 7229 13783 7223 13783 7231 13784 7230 13784 7223 13784 7231 13785 7223 13785 7225 13785 7232 13786 7231 13786 7225 13786 7232 13787 7225 13787 7227 13787 7233 13788 7232 13788 7227 13788 7233 13789 7227 13789 7226 13789 7234 13790 7233 13790 7226 13790 7234 13791 7226 13791 7224 13791 7235 13792 7234 13792 7224 13792 7236 13793 7235 13793 7224 13793 7236 13794 7224 13794 7221 13794 7237 13795 7236 13795 7221 13795 7237 13796 7221 13796 7220 13796 7237 13797 7220 13797 7217 13797 7238 13798 7237 13798 7217 13798 7239 13799 7238 13799 7217 13799 7239 13800 7217 13800 7216 13800 7239 13801 7216 13801 7215 13801 7240 13802 7239 13802 7215 13802 7241 13803 7215 13803 7218 13803 7241 13804 7240 13804 7215 13804 7002 13805 7236 13805 7237 13805 6407 13806 7236 13806 7002 13806 6407 13807 7235 13807 7236 13807 7003 13808 7002 13808 7237 13808 7003 13809 7237 13809 7238 13809 6400 13810 7235 13810 6407 13810 6400 13811 7234 13811 7235 13811 7004 13812 7003 13812 7238 13812 7004 13813 7238 13813 7239 13813 6400 13814 7233 13814 7234 13814 6404 13815 7233 13815 6400 13815 7152 13816 7004 13816 7239 13816 6404 13817 7232 13817 7233 13817 7240 13818 7152 13818 7239 13818 7232 13819 6404 13819 6401 13819 7241 13820 7152 13820 7240 13820 7231 13821 7232 13821 6401 13821 7241 13822 7151 13822 7152 13822 7231 13823 6401 13823 6398 13823 7228 13824 7151 13824 7241 13824 7230 13825 7231 13825 6398 13825 7229 13826 7151 13826 7228 13826 7229 13827 7230 13827 6398 13827 7229 13828 7153 13828 7151 13828 7229 13829 6398 13829 7153 13829

+
+ + + +

8069 13830 7242 13830 7243 13830 8069 13831 7244 13831 7242 13831 8071 13832 7244 13832 8069 13832 7242 13833 7245 13833 7243 13833 7243 13834 7245 13834 7246 13834 8072 13835 7244 13835 8071 13835 8072 13836 7247 13836 7244 13836 7245 13837 7248 13837 7246 13837 7249 13838 7247 13838 8072 13838 7246 13839 7248 13839 8062 13839 8062 13840 7248 13840 7252 13840 7249 13841 7250 13841 7247 13841 7251 13842 7250 13842 7249 13842 7248 13843 7253 13843 7252 13843 7251 13844 7254 13844 7250 13844 7251 13845 7256 13845 7254 13845 7254 13846 7256 13846 7257 13846 7256 13847 7258 13847 7257 13847 7263 13848 7261 13848 7260 13848 7263 13849 7262 13849 7261 13849 7266 13850 7262 13850 7263 13850 7266 13851 7265 13851 7262 13851 7266 13852 7267 13852 7265 13852 7268 13853 7267 13853 7266 13853 7268 13854 7269 13854 7267 13854 7264 13855 7269 13855 7268 13855 7264 13856 7270 13856 7269 13856 7264 13857 7271 13857 7270 13857 7272 13858 7271 13858 7264 13858 7273 13859 7271 13859 7272 13859 7273 13860 7274 13860 7271 13860 7273 13861 7275 13861 7274 13861 7276 13862 7275 13862 7273 13862 7276 13863 7277 13863 7275 13863 7278 13864 7277 13864 7276 13864 7278 13865 7279 13865 7277 13865 7278 13866 7280 13866 7279 13866 7281 13867 7280 13867 7278 13867 7281 13868 7282 13868 7280 13868 7283 13869 7282 13869 7281 13869 7283 13870 7284 13870 7282 13870 7285 13871 7284 13871 7283 13871 7285 13872 7286 13872 7284 13872 7287 13873 7286 13873 7285 13873 7287 13874 7288 13874 7286 13874 7289 13875 7288 13875 7287 13875 7289 13876 7290 13876 7288 13876 7289 13877 7291 13877 7290 13877 7292 13878 7291 13878 7289 13878 7292 13879 7293 13879 7291 13879 7294 13880 7293 13880 7292 13880 7294 13881 7295 13881 7293 13881 7294 13882 7296 13882 7295 13882 7297 13883 7296 13883 7294 13883 7297 13884 7298 13884 7296 13884 7299 13885 7298 13885 7297 13885 7299 13886 7300 13886 7298 13886 7301 13887 7300 13887 7299 13887 7301 13888 7302 13888 7300 13888 7303 13889 7302 13889 7301 13889 7303 13890 7304 13890 7302 13890 7303 13891 7305 13891 7304 13891 7306 13892 7305 13892 7303 13892 7306 13893 7307 13893 7305 13893 7308 13894 7307 13894 7306 13894 7308 13895 7309 13895 7307 13895 7308 13896 7310 13896 7309 13896 7311 13897 7310 13897 7308 13897 7311 13898 7312 13898 7310 13898 7311 13899 7313 13899 7312 13899 7314 13900 7313 13900 7311 13900 7314 13901 7315 13901 7313 13901 7316 13902 7315 13902 7314 13902 7316 13903 7317 13903 7315 13903 7316 13904 7318 13904 7317 13904 7319 13905 7318 13905 7316 13905 7319 13906 7320 13906 7318 13906 7321 13907 7320 13907 7319 13907 7321 13908 7322 13908 7320 13908 7323 13909 7322 13909 7321 13909 7323 13910 7324 13910 7322 13910 7325 13911 7324 13911 7323 13911 7325 13912 7326 13912 7324 13912 7327 13913 7326 13913 7325 13913 7327 13914 7328 13914 7326 13914 7329 13915 7330 13915 7327 13915 7327 13916 7330 13916 7328 13916 7329 13917 7331 13917 7330 13917 7332 13918 7331 13918 7329 13918 7333 13919 7331 13919 7332 13919 7333 13920 7334 13920 7331 13920 7333 13921 7335 13921 7334 13921 7336 13922 7335 13922 7333 13922 7337 13923 7335 13923 7336 13923 7337 13924 7338 13924 7335 13924 7339 13925 7338 13925 7337 13925 7339 13926 7340 13926 7338 13926 7339 13927 7341 13927 7340 13927 7339 13928 7342 13928 7341 13928 7343 13929 7342 13929 7339 13929 7343 13930 7344 13930 7342 13930 7345 13931 7344 13931 7343 13931 7345 13932 7346 13932 7344 13932 7347 13933 7346 13933 7345 13933 7347 13934 7348 13934 7346 13934 7347 13935 7349 13935 7348 13935 7347 13936 7350 13936 7349 13936 7351 13937 7350 13937 7347 13937 7351 13938 7352 13938 7350 13938 7353 13939 7352 13939 7351 13939 7353 13940 7354 13940 7352 13940 7355 13941 7354 13941 7353 13941 7356 13942 7354 13942 7355 13942 7356 13943 7357 13943 7354 13943 7356 13944 7358 13944 7357 13944 7356 13945 7359 13945 7358 13945 7360 13946 7359 13946 7356 13946 7360 13947 7361 13947 7359 13947 7362 13948 7361 13948 7360 13948 7362 13949 7363 13949 7361 13949 7362 13950 7364 13950 7363 13950 7365 13951 7364 13951 7362 13951 7365 13952 7366 13952 7364 13952 7365 13953 7367 13953 7366 13953 7368 13954 7367 13954 7365 13954 7368 13955 7369 13955 7367 13955 7370 13956 7369 13956 7368 13956 7370 13957 7371 13957 7369 13957 7372 13958 7371 13958 7370 13958 7372 13959 7373 13959 7371 13959 7374 13960 7373 13960 7372 13960 7374 13961 7375 13961 7373 13961 7376 13962 7375 13962 7374 13962 7376 13963 7377 13963 7375 13963 7376 13964 7378 13964 7377 13964 7379 13965 7378 13965 7376 13965 7379 13966 7380 13966 7378 13966 7381 13967 7380 13967 7379 13967 7381 13968 7382 13968 7380 13968 7381 13969 7383 13969 7382 13969 7384 13970 7383 13970 7381 13970 7384 13971 7385 13971 7383 13971 7384 13972 7386 13972 7385 13972 7387 13973 7386 13973 7384 13973 7387 13974 7388 13974 7386 13974 7389 13975 7388 13975 7387 13975 7389 13976 7390 13976 7388 13976 7391 13977 7390 13977 7389 13977 7391 13978 7392 13978 7390 13978 7391 13979 7393 13979 7392 13979 7394 13980 7393 13980 7391 13980 7395 13981 7393 13981 7394 13981 7395 13982 7396 13982 7393 13982 7395 13983 7397 13983 7396 13983 7398 13984 7397 13984 7395 13984 7398 13985 7399 13985 7397 13985 7400 13986 7399 13986 7398 13986 7400 13987 7401 13987 7399 13987 7400 13988 7402 13988 7401 13988 7403 13989 7402 13989 7400 13989 7403 13990 7404 13990 7402 13990 7405 13991 7404 13991 7403 13991 7405 13992 7406 13992 7404 13992 7407 13993 7406 13993 7405 13993 7407 13994 7408 13994 7406 13994 7409 13995 7408 13995 7407 13995 7409 13996 7410 13996 7408 13996 7409 13997 7411 13997 7410 13997 7412 13998 7411 13998 7409 13998 7413 13999 7411 13999 7412 13999 7413 14000 7414 14000 7411 14000 7413 14001 7415 14001 7414 14001 7416 14002 7415 14002 7413 14002 7416 14003 7417 14003 7415 14003 7418 14004 7417 14004 7416 14004 7418 14005 7419 14005 7417 14005 7418 14006 7420 14006 7419 14006 7421 14007 7420 14007 7418 14007 7421 14008 7422 14008 7420 14008 7423 14009 7422 14009 7421 14009 7423 14010 7424 14010 7422 14010 7423 14011 7425 14011 7424 14011 7426 14012 7425 14012 7423 14012 7426 14013 7427 14013 7425 14013 7428 14014 7427 14014 7426 14014 7428 14015 7429 14015 7427 14015 7430 14016 7429 14016 7428 14016 7430 14017 7431 14017 7429 14017 7432 14018 7431 14018 7430 14018 7432 14019 7433 14019 7431 14019 7432 14020 7434 14020 7433 14020 7435 14021 7434 14021 7432 14021 7435 14022 7436 14022 7434 14022 7437 14023 7436 14023 7435 14023 7437 14024 7438 14024 7436 14024 7439 14025 7438 14025 7437 14025 7439 14026 7440 14026 7438 14026 7441 14027 7440 14027 7439 14027 7441 14028 7442 14028 7440 14028 7441 14029 7443 14029 7442 14029 7444 14030 7443 14030 7441 14030 7444 14031 7445 14031 7443 14031 7446 14032 7445 14032 7444 14032 7446 14033 7447 14033 7445 14033 7448 14034 7447 14034 7446 14034 7448 14035 7449 14035 7447 14035 7448 14036 7450 14036 7449 14036 7451 14037 7450 14037 7448 14037 7452 14038 7450 14038 7451 14038 7452 14039 7453 14039 7450 14039 7454 14040 7455 14040 7452 14040 7452 14041 7455 14041 7453 14041 7456 14042 7455 14042 7454 14042 7456 14043 7457 14043 7455 14043 7456 14044 7458 14044 7457 14044 7459 14045 7458 14045 7456 14045 7459 14046 7460 14046 7458 14046 7461 14047 7460 14047 7459 14047 7461 14048 7462 14048 7460 14048 7463 14049 7462 14049 7461 14049 7463 14050 7464 14050 7462 14050 7463 14051 7465 14051 7464 14051 7466 14052 7465 14052 7463 14052 7466 14053 7467 14053 7465 14053 7468 14054 7467 14054 7466 14054 7468 14055 7469 14055 7467 14055 7470 14056 7469 14056 7468 14056 7470 14057 7471 14057 7469 14057 7472 14058 7471 14058 7470 14058 7472 14059 7473 14059 7471 14059 7472 14060 7474 14060 7473 14060 7475 14061 7474 14061 7472 14061 7475 14062 7476 14062 7474 14062 7477 14063 7476 14063 7475 14063 7477 14064 7478 14064 7476 14064 7479 14065 7478 14065 7477 14065 7479 14066 7480 14066 7478 14066 7481 14067 7480 14067 7479 14067 7481 14068 7482 14068 7480 14068 7481 14069 7483 14069 7482 14069 7484 14070 7483 14070 7481 14070 7484 14071 7485 14071 7483 14071 7484 14072 7486 14072 7485 14072 7487 14073 7486 14073 7484 14073 7487 14074 7488 14074 7486 14074 7487 14075 7489 14075 7488 14075 7490 14076 7489 14076 7487 14076 7490 14077 7491 14077 7489 14077 7492 14078 7491 14078 7490 14078 7492 14079 7493 14079 7491 14079 7494 14080 7495 14080 7492 14080 7492 14081 7495 14081 7493 14081 7494 14082 7496 14082 7495 14082 7497 14083 7496 14083 7494 14083 7498 14084 7496 14084 7497 14084 7498 14085 7499 14085 7496 14085 7498 14086 7500 14086 7499 14086 7501 14087 7500 14087 7498 14087 7501 14088 7502 14088 7500 14088 7503 14089 7502 14089 7501 14089 7503 14090 7504 14090 7502 14090 7503 14091 7505 14091 7504 14091 7506 14092 7505 14092 7503 14092 7506 14093 7507 14093 7505 14093 7508 14094 7507 14094 7506 14094 7508 14095 7509 14095 7507 14095 7510 14096 7509 14096 7508 14096 7510 14097 7511 14097 7509 14097 7512 14098 7511 14098 7510 14098 7512 14099 7513 14099 7511 14099 7514 14100 7513 14100 7512 14100 7514 14101 7515 14101 7513 14101 7516 14102 7515 14102 7514 14102 7516 14103 7517 14103 7515 14103 7518 14104 7517 14104 7516 14104 7518 14105 7519 14105 7517 14105 7518 14106 7520 14106 7519 14106 7521 14107 7520 14107 7518 14107 7522 14108 7520 14108 7521 14108 7522 14109 7523 14109 7520 14109 7524 14110 7523 14110 7522 14110 7524 14111 7525 14111 7523 14111 7524 14112 7526 14112 7525 14112 7527 14113 7526 14113 7524 14113 7528 14114 7526 14114 7527 14114 7528 14115 7529 14115 7526 14115 7528 14116 7530 14116 7529 14116 7531 14117 7530 14117 7528 14117 7532 14118 7530 14118 7531 14118 7532 14119 7533 14119 7530 14119 7532 14120 7534 14120 7533 14120 7535 14121 7534 14121 7532 14121 7535 14122 7536 14122 7534 14122 7537 14123 7536 14123 7535 14123 7537 14124 7538 14124 7536 14124 7539 14125 7538 14125 7537 14125 7539 14126 7540 14126 7538 14126 7541 14127 7540 14127 7539 14127 7541 14128 7542 14128 7540 14128 7543 14129 7542 14129 7541 14129 7543 14130 7544 14130 7542 14130 7545 14131 7544 14131 7543 14131 7545 14132 7546 14132 7544 14132 7545 14133 7547 14133 7546 14133 7548 14134 7547 14134 7545 14134 7548 14135 7549 14135 7547 14135 7550 14136 7549 14136 7548 14136 7550 14137 7551 14137 7549 14137 7552 14138 7553 14138 7550 14138 7550 14139 7553 14139 7551 14139 7552 14140 7554 14140 7553 14140 7552 14141 7555 14141 7554 14141 7556 14142 7555 14142 7552 14142 7556 14143 7557 14143 7555 14143 7558 14144 7557 14144 7556 14144 7558 14145 7559 14145 7557 14145 7560 14146 7559 14146 7558 14146 7560 14147 7561 14147 7559 14147 7562 14148 7561 14148 7560 14148 7562 14149 7563 14149 7561 14149 7564 14150 7563 14150 7562 14150 7564 14151 7565 14151 7563 14151 7566 14152 7565 14152 7564 14152 7566 14153 7567 14153 7565 14153 7566 14154 7568 14154 7567 14154 7569 14155 7568 14155 7566 14155 7569 14156 7570 14156 7568 14156 7571 14157 7570 14157 7569 14157 7571 14158 7572 14158 7570 14158 7571 14159 7573 14159 7572 14159 7574 14160 7573 14160 7571 14160 7574 14161 7575 14161 7573 14161 7576 14162 7575 14162 7574 14162 7576 14163 7577 14163 7575 14163 7578 14164 7577 14164 7576 14164 7578 14165 7579 14165 7577 14165 7580 14166 7579 14166 7578 14166 7580 14167 7581 14167 7579 14167 7580 14168 7582 14168 7581 14168 7583 14169 7582 14169 7580 14169 7583 14170 7584 14170 7582 14170 7585 14171 7584 14171 7583 14171 7585 14172 7586 14172 7584 14172 7587 14173 7586 14173 7585 14173 7587 14174 7588 14174 7586 14174 7589 14175 7588 14175 7587 14175 7589 14176 7590 14176 7588 14176 7589 14177 7591 14177 7590 14177 7592 14178 7591 14178 7589 14178 7592 14179 7593 14179 7591 14179 7594 14180 7593 14180 7592 14180 7594 14181 7595 14181 7593 14181 7594 14182 7596 14182 7595 14182 7597 14183 7596 14183 7594 14183 7597 14184 7598 14184 7596 14184 7599 14185 7598 14185 7597 14185 7599 14186 7600 14186 7598 14186 7599 14187 7601 14187 7600 14187 7602 14188 7601 14188 7599 14188 7602 14189 7603 14189 7601 14189 7604 14190 7603 14190 7602 14190 7604 14191 7605 14191 7603 14191 7606 14192 7605 14192 7604 14192 7606 14193 7607 14193 7605 14193 7606 14194 7608 14194 7607 14194 7609 14195 7608 14195 7606 14195 7610 14196 7608 14196 7609 14196 7610 14197 7611 14197 7608 14197 7612 14198 7611 14198 7610 14198 7612 14199 7613 14199 7611 14199 7612 14200 7614 14200 7613 14200 7615 14201 7614 14201 7612 14201 7615 14202 7616 14202 7614 14202 7617 14203 7618 14203 7615 14203 7615 14204 7618 14204 7616 14204 7617 14205 7619 14205 7618 14205 7620 14206 7619 14206 7617 14206 7620 14207 7621 14207 7619 14207 7622 14208 7621 14208 7620 14208 7622 14209 7623 14209 7621 14209 7624 14210 7623 14210 7622 14210 7624 14211 7625 14211 7623 14211 7626 14212 7625 14212 7624 14212 7626 14213 7627 14213 7625 14213 7626 14214 7628 14214 7627 14214 7629 14215 7628 14215 7626 14215 7630 14216 7628 14216 7629 14216 7630 14217 7631 14217 7628 14217 7630 14218 7632 14218 7631 14218 7633 14219 7632 14219 7630 14219 7633 14220 7634 14220 7632 14220 7635 14221 7634 14221 7633 14221 7635 14222 7636 14222 7634 14222 7637 14223 7636 14223 7635 14223 7637 14224 7638 14224 7636 14224 7639 14225 7638 14225 7637 14225 7639 14226 7640 14226 7638 14226 7639 14227 7641 14227 7640 14227 7642 14228 7641 14228 7639 14228 7642 14229 7643 14229 7641 14229 7644 14230 7643 14230 7642 14230 7645 14231 7646 14231 7644 14231 7644 14232 7646 14232 7643 14232 7645 14233 7647 14233 7646 14233 7648 14234 7647 14234 7645 14234 7648 14235 7649 14235 7647 14235 7648 14236 7650 14236 7649 14236 7651 14237 7650 14237 7648 14237 7651 14238 7652 14238 7650 14238 7653 14239 7652 14239 7651 14239 7653 14240 7654 14240 7652 14240 7655 14241 7654 14241 7653 14241 7655 14242 7656 14242 7654 14242 7655 14243 7657 14243 7656 14243 7658 14244 7657 14244 7655 14244 7658 14245 7659 14245 7657 14245 7660 14246 7659 14246 7658 14246 7660 14247 7661 14247 7659 14247 7662 14248 7661 14248 7660 14248 7662 14249 7663 14249 7661 14249 7664 14250 7663 14250 7662 14250 7664 14251 7665 14251 7663 14251 7664 14252 7666 14252 7665 14252 7667 14253 7666 14253 7664 14253 7667 14254 7668 14254 7666 14254 7669 14255 7670 14255 7667 14255 7667 14256 7670 14256 7668 14256 7669 14257 7671 14257 7670 14257 7672 14258 7671 14258 7669 14258 7672 14259 7673 14259 7671 14259 7674 14260 7673 14260 7672 14260 7674 14261 7675 14261 7673 14261 7676 14262 7675 14262 7674 14262 7676 14263 7677 14263 7675 14263 7676 14264 7678 14264 7677 14264 7679 14265 7678 14265 7676 14265 7679 14266 7680 14266 7678 14266 7681 14267 7680 14267 7679 14267 7681 14268 7682 14268 7680 14268 7683 14269 7682 14269 7681 14269 7683 14270 7684 14270 7682 14270 7685 14271 7684 14271 7683 14271 7685 14272 7686 14272 7684 14272 7687 14273 7686 14273 7685 14273 7687 14274 7688 14274 7686 14274 7689 14275 7688 14275 7687 14275 7689 14276 7690 14276 7688 14276 7691 14277 7690 14277 7689 14277 7691 14278 7692 14278 7690 14278 7693 14279 7692 14279 7691 14279 7693 14280 7694 14280 7692 14280 7693 14281 7695 14281 7694 14281 7696 14282 7695 14282 7693 14282 7697 14283 7698 14283 7696 14283 7696 14284 7698 14284 7695 14284 7697 14285 7699 14285 7698 14285 7700 14286 7699 14286 7697 14286 7700 14287 7701 14287 7699 14287 7702 14288 7701 14288 7700 14288 7702 14289 7703 14289 7701 14289 7704 14290 7703 14290 7702 14290 7704 14291 7705 14291 7703 14291 7706 14292 7705 14292 7704 14292 7706 14293 7707 14293 7705 14293 7706 14294 7708 14294 7707 14294 7709 14295 7708 14295 7706 14295 7709 14296 7710 14296 7708 14296 7711 14297 7710 14297 7709 14297 7711 14298 7712 14298 7710 14298 7713 14299 7712 14299 7711 14299 7713 14300 7714 14300 7712 14300 7715 14301 7714 14301 7713 14301 7715 14302 7716 14302 7714 14302 7715 14303 7717 14303 7716 14303 7718 14304 7717 14304 7715 14304 7719 14305 7720 14305 7718 14305 7718 14306 7720 14306 7717 14306 7721 14307 7722 14307 7719 14307 7719 14308 7722 14308 7720 14308 7723 14309 7722 14309 7721 14309 7723 14310 7724 14310 7722 14310 7723 14311 7725 14311 7724 14311 7726 14312 7725 14312 7723 14312 7726 14313 7727 14313 7725 14313 7728 14314 7727 14314 7726 14314 7728 14315 7729 14315 7727 14315 7730 14316 7729 14316 7728 14316 7730 14317 7731 14317 7729 14317 7730 14318 7732 14318 7731 14318 7733 14319 7732 14319 7730 14319 7734 14320 7732 14320 7733 14320 7734 14321 7735 14321 7732 14321 7736 14322 7735 14322 7734 14322 7736 14323 7737 14323 7735 14323 7738 14324 7737 14324 7736 14324 7738 14325 7739 14325 7737 14325 7740 14326 7739 14326 7738 14326 7740 14327 7741 14327 7739 14327 7740 14328 7742 14328 7741 14328 7743 14329 7742 14329 7740 14329 7743 14330 7744 14330 7742 14330 7743 14331 7745 14331 7744 14331 7746 14332 7745 14332 7743 14332 7746 14333 7747 14333 7745 14333 7748 14334 7747 14334 7746 14334 7748 14335 7749 14335 7747 14335 7750 14336 7749 14336 7748 14336 7750 14337 7751 14337 7749 14337 7752 14338 7751 14338 7750 14338 7752 14339 7753 14339 7751 14339 7752 14340 7754 14340 7753 14340 7755 14341 7754 14341 7752 14341 7755 14342 7756 14342 7754 14342 7757 14343 7756 14343 7755 14343 7757 14344 7758 14344 7756 14344 7759 14345 7758 14345 7757 14345 7759 14346 7760 14346 7758 14346 7761 14347 7760 14347 7759 14347 7761 14348 7762 14348 7760 14348 7763 14349 7762 14349 7761 14349 7763 14350 7764 14350 7762 14350 7763 14351 7765 14351 7764 14351 7766 14352 7765 14352 7763 14352 7766 14353 7767 14353 7765 14353 7768 14354 7767 14354 7766 14354 7768 14355 7769 14355 7767 14355 7768 14356 7770 14356 7769 14356 7771 14357 7770 14357 7768 14357 7771 14358 7772 14358 7770 14358 7771 14359 7773 14359 7772 14359 7774 14360 7773 14360 7771 14360 7774 14361 7775 14361 7773 14361 7776 14362 7775 14362 7774 14362 7776 14363 7777 14363 7775 14363 7776 14364 7778 14364 7777 14364 7779 14365 7778 14365 7776 14365 7779 14366 7780 14366 7778 14366 7781 14367 7780 14367 7779 14367 7782 14368 7780 14368 7781 14368 7782 14369 7783 14369 7780 14369 7782 14370 7784 14370 7783 14370 7785 14371 7784 14371 7782 14371 7785 14372 7786 14372 7784 14372 7787 14373 7786 14373 7785 14373 7787 14374 7788 14374 7786 14374 7787 14375 7789 14375 7788 14375 7790 14376 7789 14376 7787 14376 7790 14377 7791 14377 7789 14377 7790 14378 7792 14378 7791 14378 7793 14379 7792 14379 7790 14379 7793 14380 7794 14380 7792 14380 7795 14381 7794 14381 7793 14381 7795 14382 7796 14382 7794 14382 7797 14383 7796 14383 7795 14383 7797 14384 7798 14384 7796 14384 7799 14385 7798 14385 7797 14385 7799 14386 7800 14386 7798 14386 7801 14387 7802 14387 7799 14387 7799 14388 7802 14388 7800 14388 7801 14389 7803 14389 7802 14389 7804 14390 7803 14390 7801 14390 7804 14391 7805 14391 7803 14391 7804 14392 7806 14392 7805 14392 7807 14393 7806 14393 7804 14393 7807 14394 7808 14394 7806 14394 7809 14395 7808 14395 7807 14395 7809 14396 7810 14396 7808 14396 7811 14397 7810 14397 7809 14397 7811 14398 7812 14398 7810 14398 7813 14399 7812 14399 7811 14399 7813 14400 7814 14400 7812 14400 7815 14401 7814 14401 7813 14401 7815 14402 7816 14402 7814 14402 7817 14403 7818 14403 7815 14403 7815 14404 7818 14404 7816 14404 7817 14405 7819 14405 7818 14405 7820 14406 7819 14406 7817 14406 7820 14407 7821 14407 7819 14407 7820 14408 7822 14408 7821 14408 7823 14409 7822 14409 7820 14409 7823 14410 7824 14410 7822 14410 7825 14411 7824 14411 7823 14411 7825 14412 7826 14412 7824 14412 7827 14413 7826 14413 7825 14413 7827 14414 7828 14414 7826 14414 7829 14415 7828 14415 7827 14415 7829 14416 7830 14416 7828 14416 7831 14417 7830 14417 7829 14417 7832 14418 7833 14418 7831 14418 7831 14419 7833 14419 7830 14419 7832 14420 7834 14420 7833 14420 7835 14421 7834 14421 7832 14421 7835 14422 7836 14422 7834 14422 7835 14423 7837 14423 7836 14423 7838 14424 7837 14424 7835 14424 7838 14425 7839 14425 7837 14425 7840 14426 7839 14426 7838 14426 7840 14427 7841 14427 7839 14427 7842 14428 7841 14428 7840 14428 7842 14429 7843 14429 7841 14429 7844 14430 7843 14430 7842 14430 7844 14431 7845 14431 7843 14431 7844 14432 7846 14432 7845 14432 7847 14433 7846 14433 7844 14433 7847 14434 7848 14434 7846 14434 7849 14435 7848 14435 7847 14435 7849 14436 7850 14436 7848 14436 7851 14437 7850 14437 7849 14437 7851 14438 7852 14438 7850 14438 7853 14439 7852 14439 7851 14439 7853 14440 7854 14440 7852 14440 7853 14441 7855 14441 7854 14441 7856 14442 7855 14442 7853 14442 7856 14443 7857 14443 7855 14443 7858 14444 7857 14444 7856 14444 7858 14445 8049 14445 7857 14445 7859 14446 8049 14446 7858 14446 7859 14447 7259 14447 8049 14447 7859 14448 7258 14448 7259 14448 7860 14449 7258 14449 7859 14449 7860 14450 7257 14450 7258 14450 7861 14451 7257 14451 7860 14451 7862 14452 7257 14452 7861 14452 7862 14453 7254 14453 7257 14453 7863 14454 7273 14454 7272 14454 7864 14455 7273 14455 7863 14455 7276 14456 7273 14456 7864 14456 7865 14457 7276 14457 7864 14457 7278 14458 7276 14458 7865 14458 7281 14459 7278 14459 7865 14459 7285 14460 7283 14460 7866 14460 7867 14461 7287 14461 7285 14461 7289 14462 7287 14462 7867 14462 7868 14463 7289 14463 7867 14463 7292 14464 7289 14464 7868 14464 7869 14465 7294 14465 7292 14465 7297 14466 7294 14466 7869 14466 7870 14467 7303 14467 7301 14467 7306 14468 7303 14468 7870 14468 7871 14469 7306 14469 7870 14469 7306 14470 7871 14470 7872 14470 7308 14471 7306 14471 7872 14471 7873 14472 7308 14472 7872 14472 7311 14473 7308 14473 7873 14473 7874 14474 7311 14474 7873 14474 7314 14475 7311 14475 7874 14475 7316 14476 7314 14476 7875 14476 7876 14477 7316 14477 7875 14477 7319 14478 7316 14478 7876 14478 7877 14479 7319 14479 7876 14479 7321 14480 7319 14480 7877 14480 7878 14481 7321 14481 7877 14481 7323 14482 7321 14482 7878 14482 7879 14483 7323 14483 7878 14483 7325 14484 7323 14484 7879 14484 7332 14485 7329 14485 7327 14485 7337 14486 7336 14486 7880 14486 7339 14487 7337 14487 7880 14487 7881 14488 7339 14488 7880 14488 7343 14489 7339 14489 7881 14489 7882 14490 7343 14490 7881 14490 7345 14491 7343 14491 7882 14491 7883 14492 7345 14492 7882 14492 7884 14493 7345 14493 7883 14493 7347 14494 7345 14494 7884 14494 7351 14495 7347 14495 7884 14495 7885 14496 7356 14496 7355 14496 7360 14497 7356 14497 7885 14497 7886 14498 7360 14498 7885 14498 7362 14499 7360 14499 7886 14499 7365 14500 7362 14500 7887 14500 7368 14501 7365 14501 7887 14501 7372 14502 7370 14502 7888 14502 7374 14503 7372 14503 7888 14503 7376 14504 7374 14504 7889 14504 7890 14505 7376 14505 7889 14505 7379 14506 7376 14506 7890 14506 7891 14507 7379 14507 7890 14507 7381 14508 7379 14508 7891 14508 7892 14509 7381 14509 7891 14509 7384 14510 7381 14510 7892 14510 7384 14511 7892 14511 7893 14511 7387 14512 7384 14512 7893 14512 7894 14513 7387 14513 7893 14513 7389 14514 7387 14514 7894 14514 7895 14515 7389 14515 7894 14515 7391 14516 7389 14516 7895 14516 7896 14517 7391 14517 7895 14517 7394 14518 7391 14518 7896 14518 7897 14519 7394 14519 7896 14519 7395 14520 7394 14520 7897 14520 7398 14521 7395 14521 7897 14521 7400 14522 7398 14522 7898 14522 7899 14523 7400 14523 7898 14523 7403 14524 7400 14524 7899 14524 7900 14525 7403 14525 7899 14525 7405 14526 7403 14526 7900 14526 7407 14527 7405 14527 7900 14527 7409 14528 7407 14528 7901 14528 7412 14529 7409 14529 7901 14529 7413 14530 7412 14530 7902 14530 7416 14531 7413 14531 7902 14531 7903 14532 7418 14532 7416 14532 7421 14533 7418 14533 7903 14533 7423 14534 7421 14534 7903 14534 7426 14535 7423 14535 7904 14535 7428 14536 7426 14536 7904 14536 7430 14537 7428 14537 7905 14537 7432 14538 7430 14538 7905 14538 7906 14539 7432 14539 7905 14539 7435 14540 7432 14540 7906 14540 7907 14541 7435 14541 7906 14541 7437 14542 7435 14542 7907 14542 7908 14543 7439 14543 7437 14543 7441 14544 7439 14544 7908 14544 7909 14545 7441 14545 7908 14545 7444 14546 7441 14546 7909 14546 7910 14547 7444 14547 7909 14547 7446 14548 7444 14548 7910 14548 7911 14549 7451 14549 7448 14549 7452 14550 7451 14550 7911 14550 7454 14551 7452 14551 7911 14551 7456 14552 7454 14552 7912 14552 7459 14553 7456 14553 7912 14553 7913 14554 7463 14554 7461 14554 7466 14555 7463 14555 7913 14555 7468 14556 7466 14556 7914 14556 7470 14557 7468 14557 7914 14557 7915 14558 7472 14558 7470 14558 7475 14559 7472 14559 7915 14559 7477 14560 7475 14560 7916 14560 7479 14561 7477 14561 7916 14561 7917 14562 7479 14562 7916 14562 7481 14563 7479 14563 7917 14563 7918 14564 7481 14564 7917 14564 7484 14565 7481 14565 7918 14565 7919 14566 7484 14566 7918 14566 7487 14567 7484 14567 7919 14567 7920 14568 7487 14568 7919 14568 7921 14569 7487 14569 7920 14569 7490 14570 7487 14570 7921 14570 7492 14571 7490 14571 7921 14571 7922 14572 7492 14572 7921 14572 7494 14573 7492 14573 7922 14573 7501 14574 7498 14574 7923 14574 7924 14575 7501 14575 7923 14575 7503 14576 7501 14576 7924 14576 7506 14577 7503 14577 7924 14577 7925 14578 7508 14578 7506 14578 7510 14579 7508 14579 7925 14579 7510 14580 7925 14580 7926 14580 7512 14581 7510 14581 7926 14581 7514 14582 7512 14582 7926 14582 7518 14583 7516 14583 7927 14583 7521 14584 7518 14584 7927 14584 7928 14585 7522 14585 7521 14585 7524 14586 7522 14586 7928 14586 7539 14587 7537 14587 7929 14587 7930 14588 7539 14588 7929 14588 7541 14589 7539 14589 7930 14589 7543 14590 7541 14590 7930 14590 7545 14591 7543 14591 7931 14591 7548 14592 7545 14592 7931 14592 7932 14593 7550 14593 7548 14593 7552 14594 7550 14594 7932 14594 7933 14595 7552 14595 7932 14595 7556 14596 7552 14596 7933 14596 7934 14597 7556 14597 7933 14597 7558 14598 7556 14598 7934 14598 7935 14599 7558 14599 7934 14599 7936 14600 7558 14600 7935 14600 7560 14601 7558 14601 7936 14601 7562 14602 7560 14602 7936 14602 7937 14603 7564 14603 7562 14603 7566 14604 7564 14604 7937 14604 7938 14605 7566 14605 7937 14605 7939 14606 7566 14606 7938 14606 7569 14607 7566 14607 7939 14607 7940 14608 7569 14608 7939 14608 7571 14609 7569 14609 7940 14609 7941 14610 7571 14610 7940 14610 7574 14611 7571 14611 7941 14611 7576 14612 7574 14612 7942 14612 7578 14613 7576 14613 7942 14613 7943 14614 7580 14614 7578 14614 7583 14615 7580 14615 7943 14615 7589 14616 7587 14616 7944 14616 7945 14617 7589 14617 7944 14617 7592 14618 7589 14618 7945 14618 7946 14619 7594 14619 7592 14619 7597 14620 7594 14620 7946 14620 7947 14621 7597 14621 7946 14621 7599 14622 7597 14622 7947 14622 7948 14623 7610 14623 7609 14623 7612 14624 7610 14624 7948 14624 7949 14625 7615 14625 7612 14625 7617 14626 7615 14626 7949 14626 7950 14627 7620 14627 7617 14627 7622 14628 7620 14628 7950 14628 7951 14629 7622 14629 7950 14629 7624 14630 7622 14630 7951 14630 7952 14631 7624 14631 7951 14631 7626 14632 7624 14632 7952 14632 7953 14633 7626 14633 7952 14633 7629 14634 7626 14634 7953 14634 7954 14635 7630 14635 7629 14635 7633 14636 7630 14636 7954 14636 7635 14637 7633 14637 7955 14637 7637 14638 7635 14638 7955 14638 7956 14639 7637 14639 7955 14639 7957 14640 7637 14640 7956 14640 7639 14641 7637 14641 7957 14641 7958 14642 7639 14642 7957 14642 7642 14643 7639 14643 7958 14643 7642 14644 7958 14644 7959 14644 7644 14645 7642 14645 7959 14645 7960 14646 7645 14646 7644 14646 7648 14647 7645 14647 7960 14647 7961 14648 7648 14648 7960 14648 7651 14649 7648 14649 7961 14649 7962 14650 7651 14650 7961 14650 7653 14651 7651 14651 7962 14651 7963 14652 7655 14652 7653 14652 7658 14653 7655 14653 7963 14653 7964 14654 7664 14654 7662 14654 7667 14655 7664 14655 7964 14655 7965 14656 7667 14656 7964 14656 7669 14657 7667 14657 7965 14657 7966 14658 7669 14658 7965 14658 7672 14659 7669 14659 7966 14659 7967 14660 7672 14660 7966 14660 7674 14661 7672 14661 7967 14661 7674 14662 7967 14662 7968 14662 7676 14663 7674 14663 7968 14663 7969 14664 7676 14664 7968 14664 7679 14665 7676 14665 7969 14665 7681 14666 7679 14666 7969 14666 7970 14667 7693 14667 7691 14667 7696 14668 7693 14668 7970 14668 7971 14669 7697 14669 7696 14669 7700 14670 7697 14670 7971 14670 7972 14671 7700 14671 7971 14671 7702 14672 7700 14672 7972 14672 7704 14673 7702 14673 7972 14673 7973 14674 7706 14674 7704 14674 7709 14675 7706 14675 7973 14675 7974 14676 7713 14676 7711 14676 7715 14677 7713 14677 7974 14677 7718 14678 7715 14678 7974 14678 7719 14679 7718 14679 7975 14679 7721 14680 7719 14680 7975 14680 7723 14681 7721 14681 7976 14681 7726 14682 7723 14682 7976 14682 7977 14683 7728 14683 7726 14683 7730 14684 7728 14684 7977 14684 7978 14685 7740 14685 7738 14685 7979 14686 7740 14686 7978 14686 7743 14687 7740 14687 7979 14687 7980 14688 7743 14688 7979 14688 7746 14689 7743 14689 7980 14689 7746 14690 7980 14690 7981 14690 7748 14691 7746 14691 7981 14691 7750 14692 7748 14692 7981 14692 7752 14693 7750 14693 7982 14693 7983 14694 7752 14694 7982 14694 7755 14695 7752 14695 7983 14695 7757 14696 7755 14696 7983 14696 7771 14697 7768 14697 7984 14697 7985 14698 7771 14698 7984 14698 7774 14699 7771 14699 7985 14699 7776 14700 7774 14700 7985 14700 7986 14701 7776 14701 7985 14701 7987 14702 7776 14702 7986 14702 7779 14703 7776 14703 7987 14703 7781 14704 7779 14704 7987 14704 7782 14705 7781 14705 7988 14705 7989 14706 7782 14706 7988 14706 7785 14707 7782 14707 7989 14707 7990 14708 7785 14708 7989 14708 7787 14709 7785 14709 7990 14709 7991 14710 7787 14710 7990 14710 7790 14711 7787 14711 7991 14711 7992 14712 7790 14712 7991 14712 7793 14713 7790 14713 7992 14713 7795 14714 7793 14714 7992 14714 7993 14715 7795 14715 7992 14715 7797 14716 7795 14716 7993 14716 7994 14717 7799 14717 7797 14717 7801 14718 7799 14718 7994 14718 7804 14719 7801 14719 7995 14719 7807 14720 7804 14720 7995 14720 7996 14721 7809 14721 7807 14721 7811 14722 7809 14722 7996 14722 7997 14723 7817 14723 7815 14723 7820 14724 7817 14724 7997 14724 7998 14725 7820 14725 7997 14725 7823 14726 7820 14726 7998 14726 7999 14727 7823 14727 7998 14727 7825 14728 7823 14728 7999 14728 7827 14729 7825 14729 7999 14729 8000 14730 7827 14730 7999 14730 7829 14731 7827 14731 8000 14731 7831 14732 7829 14732 8000 14732 7835 14733 7832 14733 8001 14733 7838 14734 7835 14734 8001 14734 7842 14735 7840 14735 8002 14735 8003 14736 7842 14736 8002 14736 7844 14737 7842 14737 8003 14737 7847 14738 7844 14738 8003 14738 8004 14739 7847 14739 8003 14739 7849 14740 7847 14740 8004 14740 8005 14741 7849 14741 8004 14741 7851 14742 7849 14742 8005 14742 7851 14743 8005 14743 8006 14743 7853 14744 7851 14744 8006 14744 8007 14745 7853 14745 8006 14745 7856 14746 7853 14746 8007 14746 8008 14747 7856 14747 8007 14747 7858 14748 7856 14748 8008 14748 7859 14749 7858 14749 8008 14749 7860 14750 7859 14750 8008 14750 7862 14751 7861 14751 8009 14751 7254 14752 7862 14752 8009 14752 8010 14753 7254 14753 8009 14753 7250 14754 7254 14754 8010 14754 8011 14755 7250 14755 8010 14755 7247 14756 7250 14756 8011 14756 7244 14757 7247 14757 8011 14757 8013 14758 7865 14758 7864 14758 8013 14759 7281 14759 7865 14759 8013 14760 7283 14760 7281 14760 8012 14761 7283 14761 8013 14761 8012 14762 7866 14762 7283 14762 8014 14763 7866 14763 8012 14763 8014 14764 7285 14764 7866 14764 7261 14765 7285 14765 8014 14765 7261 14766 7867 14766 7285 14766 7262 14767 7867 14767 7261 14767 7265 14768 7867 14768 7262 14768 7265 14769 7868 14769 7867 14769 7267 14770 7868 14770 7265 14770 7267 14771 7292 14771 7868 14771 7269 14772 7292 14772 7267 14772 7269 14773 7869 14773 7292 14773 7270 14774 7869 14774 7269 14774 7270 14775 7297 14775 7869 14775 7271 14776 7297 14776 7270 14776 7274 14777 7297 14777 7271 14777 7274 14778 7299 14778 7297 14778 7275 14779 7299 14779 7274 14779 7275 14780 7301 14780 7299 14780 7277 14781 7301 14781 7275 14781 7277 14782 7870 14782 7301 14782 7279 14783 7870 14783 7277 14783 7279 14784 7871 14784 7870 14784 7280 14785 7871 14785 7279 14785 7280 14786 7872 14786 7871 14786 7282 14787 7872 14787 7280 14787 7284 14788 7872 14788 7282 14788 7284 14789 7873 14789 7872 14789 7284 14790 7874 14790 7873 14790 7286 14791 7874 14791 7284 14791 7286 14792 7314 14792 7874 14792 7288 14793 7314 14793 7286 14793 7290 14794 7875 14794 7288 14794 7288 14795 7875 14795 7314 14795 7291 14796 7875 14796 7290 14796 7291 14797 7876 14797 7875 14797 7293 14798 7876 14798 7291 14798 7293 14799 7877 14799 7876 14799 7295 14800 7877 14800 7293 14800 7296 14801 7878 14801 7295 14801 7295 14802 7878 14802 7877 14802 7298 14803 7878 14803 7296 14803 7298 14804 7879 14804 7878 14804 7300 14805 7879 14805 7298 14805 7300 14806 7325 14806 7879 14806 7302 14807 7325 14807 7300 14807 7302 14808 7327 14808 7325 14808 7304 14809 7327 14809 7302 14809 7305 14810 7327 14810 7304 14810 7305 14811 7332 14811 7327 14811 7307 14812 7332 14812 7305 14812 7307 14813 7333 14813 7332 14813 7309 14814 7333 14814 7307 14814 7309 14815 7336 14815 7333 14815 7310 14816 7336 14816 7309 14816 7310 14817 7880 14817 7336 14817 7312 14818 7880 14818 7310 14818 7313 14819 7880 14819 7312 14819 7313 14820 7881 14820 7880 14820 7315 14821 7881 14821 7313 14821 7317 14822 7881 14822 7315 14822 7317 14823 7882 14823 7881 14823 7318 14824 7882 14824 7317 14824 7318 14825 7883 14825 7882 14825 7320 14826 7883 14826 7318 14826 7322 14827 7884 14827 7320 14827 7320 14828 7884 14828 7883 14828 7324 14829 7884 14829 7322 14829 7324 14830 7351 14830 7884 14830 7326 14831 7351 14831 7324 14831 7326 14832 7353 14832 7351 14832 7328 14833 7353 14833 7326 14833 7328 14834 7355 14834 7353 14834 7330 14835 7355 14835 7328 14835 7330 14836 7885 14836 7355 14836 7331 14837 7885 14837 7330 14837 7334 14838 7885 14838 7331 14838 7334 14839 7886 14839 7885 14839 7335 14840 7886 14840 7334 14840 7338 14841 7886 14841 7335 14841 7338 14842 7362 14842 7886 14842 7340 14843 7887 14843 7338 14843 7338 14844 7887 14844 7362 14844 7341 14845 7887 14845 7340 14845 7341 14846 7368 14846 7887 14846 7342 14847 7370 14847 7341 14847 7341 14848 7370 14848 7368 14848 7344 14849 7370 14849 7342 14849 7344 14850 7888 14850 7370 14850 7346 14851 7888 14851 7344 14851 7346 14852 7374 14852 7888 14852 7348 14853 7374 14853 7346 14853 7348 14854 7889 14854 7374 14854 7349 14855 7889 14855 7348 14855 7350 14856 7889 14856 7349 14856 7350 14857 7890 14857 7889 14857 7352 14858 7890 14858 7350 14858 7352 14859 7891 14859 7890 14859 7354 14860 7891 14860 7352 14860 7357 14861 7891 14861 7354 14861 7357 14862 7892 14862 7891 14862 7358 14863 7892 14863 7357 14863 7359 14864 7892 14864 7358 14864 7359 14865 7893 14865 7892 14865 7361 14866 7893 14866 7359 14866 7363 14867 7893 14867 7361 14867 7363 14868 7894 14868 7893 14868 7364 14869 7894 14869 7363 14869 7364 14870 7895 14870 7894 14870 7364 14871 7896 14871 7895 14871 7367 14872 7896 14872 7364 14872 7369 14873 7896 14873 7367 14873 7369 14874 7897 14874 7896 14874 7371 14875 7897 14875 7369 14875 7373 14876 7897 14876 7371 14876 7373 14877 7398 14877 7897 14877 7373 14878 7898 14878 7398 14878 7375 14879 7898 14879 7373 14879 7377 14880 7898 14880 7375 14880 7377 14881 7899 14881 7898 14881 7378 14882 7899 14882 7377 14882 7378 14883 7900 14883 7899 14883 7380 14884 7900 14884 7378 14884 7380 14885 7407 14885 7900 14885 7382 14886 7407 14886 7380 14886 7382 14887 7901 14887 7407 14887 7383 14888 7901 14888 7382 14888 7385 14889 7901 14889 7383 14889 7385 14890 7412 14890 7901 14890 7386 14891 7412 14891 7385 14891 7386 14892 7902 14892 7412 14892 7388 14893 7902 14893 7386 14893 7388 14894 7416 14894 7902 14894 7390 14895 7416 14895 7388 14895 7392 14896 7903 14896 7390 14896 7390 14897 7903 14897 7416 14897 7393 14898 7903 14898 7392 14898 7393 14899 7423 14899 7903 14899 7396 14900 7423 14900 7393 14900 7397 14901 7423 14901 7396 14901 7397 14902 7904 14902 7423 14902 7399 14903 7904 14903 7397 14903 7399 14904 7428 14904 7904 14904 7401 14905 7428 14905 7399 14905 7401 14906 7905 14906 7428 14906 7402 14907 7905 14907 7401 14907 7404 14908 7905 14908 7402 14908 7404 14909 7906 14909 7905 14909 7406 14910 7906 14910 7404 14910 7406 14911 7907 14911 7906 14911 7408 14912 7907 14912 7406 14912 7410 14913 7907 14913 7408 14913 7410 14914 7437 14914 7907 14914 7411 14915 7437 14915 7410 14915 7414 14916 7437 14916 7411 14916 7414 14917 7908 14917 7437 14917 7415 14918 7908 14918 7414 14918 7415 14919 7909 14919 7908 14919 7417 14920 7909 14920 7415 14920 7419 14921 7909 14921 7417 14921 7419 14922 7910 14922 7909 14922 7420 14923 7910 14923 7419 14923 7420 14924 7446 14924 7910 14924 7422 14925 7446 14925 7420 14925 7422 14926 7448 14926 7446 14926 7424 14927 7448 14927 7422 14927 7424 14928 7911 14928 7448 14928 7425 14929 7911 14929 7424 14929 7425 14930 7454 14930 7911 14930 7427 14931 7454 14931 7425 14931 7429 14932 7454 14932 7427 14932 7429 14933 7912 14933 7454 14933 7431 14934 7912 14934 7429 14934 7431 14935 7459 14935 7912 14935 7433 14936 7459 14936 7431 14936 7434 14937 7459 14937 7433 14937 7434 14938 7461 14938 7459 14938 7434 14939 7913 14939 7461 14939 7436 14940 7913 14940 7434 14940 7438 14941 7913 14941 7436 14941 7438 14942 7466 14942 7913 14942 7440 14943 7466 14943 7438 14943 7442 14944 7914 14944 7440 14944 7440 14945 7914 14945 7466 14945 8015 14946 7914 14946 7442 14946 8015 14947 7470 14947 7914 14947 7443 14948 7470 14948 8015 14948 7443 14949 7915 14949 7470 14949 7445 14950 7915 14950 7443 14950 7447 14951 7915 14951 7445 14951 7447 14952 7475 14952 7915 14952 7449 14953 7475 14953 7447 14953 8016 14954 7475 14954 7449 14954 8016 14955 7916 14955 7475 14955 7450 14956 7916 14956 8016 14956 7453 14957 7917 14957 7450 14957 7450 14958 7917 14958 7916 14958 7455 14959 7917 14959 7453 14959 7455 14960 7918 14960 7917 14960 7457 14961 7918 14961 7455 14961 7458 14962 7918 14962 7457 14962 7458 14963 7919 14963 7918 14963 7460 14964 7919 14964 7458 14964 7460 14965 7920 14965 7919 14965 7462 14966 7920 14966 7460 14966 7464 14967 7920 14967 7462 14967 7464 14968 7921 14968 7920 14968 7465 14969 7921 14969 7464 14969 7465 14970 7922 14970 7921 14970 7467 14971 7922 14971 7465 14971 7467 14972 7494 14972 7922 14972 7469 14973 7494 14973 7467 14973 7469 14974 7497 14974 7494 14974 7471 14975 7497 14975 7469 14975 7473 14976 7497 14976 7471 14976 7473 14977 7498 14977 7497 14977 7474 14978 7498 14978 7473 14978 7474 14979 7923 14979 7498 14979 7476 14980 7923 14980 7474 14980 7476 14981 7924 14981 7923 14981 7478 14982 7924 14982 7476 14982 7478 14983 7506 14983 7924 14983 7480 14984 7506 14984 7478 14984 7482 14985 7506 14985 7480 14985 7482 14986 7925 14986 7506 14986 7483 14987 7925 14987 7482 14987 7483 14988 7926 14988 7925 14988 7485 14989 7926 14989 7483 14989 7486 14990 7926 14990 7485 14990 7488 14991 7926 14991 7486 14991 7488 14992 7514 14992 7926 14992 7491 14993 7514 14993 7488 14993 7491 14994 7516 14994 7514 14994 7491 14995 7927 14995 7516 14995 7493 14996 7927 14996 7491 14996 7495 14997 7927 14997 7493 14997 7495 14998 7521 14998 7927 14998 7496 14999 7521 14999 7495 14999 7496 15000 7928 15000 7521 15000 7499 15001 7928 15001 7496 15001 7500 15002 7928 15002 7499 15002 7500 15003 7524 15003 7928 15003 7500 15004 7527 15004 7524 15004 7502 15005 7527 15005 7500 15005 7502 15006 7528 15006 7527 15006 7504 15007 7528 15007 7502 15007 7504 15008 7531 15008 7528 15008 7505 15009 7531 15009 7504 15009 7505 15010 7532 15010 7531 15010 7507 15011 7532 15011 7505 15011 7507 15012 7535 15012 7532 15012 7509 15013 7535 15013 7507 15013 7509 15014 7537 15014 7535 15014 7511 15015 7537 15015 7509 15015 7511 15016 7929 15016 7537 15016 7513 15017 7929 15017 7511 15017 7513 15018 7930 15018 7929 15018 7515 15019 7930 15019 7513 15019 7515 15020 7543 15020 7930 15020 7517 15021 7543 15021 7515 15021 7517 15022 7931 15022 7543 15022 7519 15023 7931 15023 7517 15023 7519 15024 7548 15024 7931 15024 7520 15025 7548 15025 7519 15025 7520 15026 7932 15026 7548 15026 7523 15027 7932 15027 7520 15027 7523 15028 7933 15028 7932 15028 7525 15029 7933 15029 7523 15029 7526 15030 7933 15030 7525 15030 7526 15031 7934 15031 7933 15031 7529 15032 7934 15032 7526 15032 7529 15033 7935 15033 7934 15033 7530 15034 7935 15034 7529 15034 7530 15035 7936 15035 7935 15035 7533 15036 7936 15036 7530 15036 7534 15037 7936 15037 7533 15037 7534 15038 7562 15038 7936 15038 7536 15039 7562 15039 7534 15039 7536 15040 7937 15040 7562 15040 7538 15041 7937 15041 7536 15041 7538 15042 7938 15042 7937 15042 7540 15043 7938 15043 7538 15043 7542 15044 7938 15044 7540 15044 7542 15045 7939 15045 7938 15045 7544 15046 7939 15046 7542 15046 7544 15047 7940 15047 7939 15047 7546 15048 7940 15048 7544 15048 7546 15049 7941 15049 7940 15049 7547 15050 7941 15050 7546 15050 7549 15051 7941 15051 7547 15051 7549 15052 7574 15052 7941 15052 7551 15053 7574 15053 7549 15053 7551 15054 7942 15054 7574 15054 7553 15055 7942 15055 7551 15055 7554 15056 7942 15056 7553 15056 7554 15057 7578 15057 7942 15057 7555 15058 7578 15058 7554 15058 7555 15059 7943 15059 7578 15059 7557 15060 7943 15060 7555 15060 7559 15061 7943 15061 7557 15061 7559 15062 7583 15062 7943 15062 7559 15063 7585 15063 7583 15063 7561 15064 7585 15064 7559 15064 7563 15065 7585 15065 7561 15065 7563 15066 7587 15066 7585 15066 7563 15067 7944 15067 7587 15067 7565 15068 7944 15068 7563 15068 7567 15069 7944 15069 7565 15069 7567 15070 7945 15070 7944 15070 7568 15071 7945 15071 7567 15071 7568 15072 7592 15072 7945 15072 7568 15073 7946 15073 7592 15073 7570 15074 7946 15074 7568 15074 7572 15075 7946 15075 7570 15075 7572 15076 7947 15076 7946 15076 7573 15077 7947 15077 7572 15077 8017 15078 7947 15078 7573 15078 8017 15079 7599 15079 7947 15079 7575 15080 7599 15080 8017 15080 7575 15081 7602 15081 7599 15081 8018 15082 7602 15082 7575 15082 8018 15083 7604 15083 7602 15083 7577 15084 7604 15084 8018 15084 7577 15085 7606 15085 7604 15085 7579 15086 7606 15086 7577 15086 7579 15087 7609 15087 7606 15087 7582 15088 7609 15088 7579 15088 7584 15089 7609 15089 7582 15089 7584 15090 7948 15090 7609 15090 7586 15091 7948 15091 7584 15091 7586 15092 7612 15092 7948 15092 7588 15093 7612 15093 7586 15093 7588 15094 7949 15094 7612 15094 8019 15095 7949 15095 7588 15095 7590 15096 7949 15096 8019 15096 7590 15097 7617 15097 7949 15097 7593 15098 7617 15098 7590 15098 7593 15099 7950 15099 7617 15099 7595 15100 7950 15100 7593 15100 7595 15101 7951 15101 7950 15101 7596 15102 7951 15102 7595 15102 7598 15103 7951 15103 7596 15103 7598 15104 7952 15104 7951 15104 7600 15105 7952 15105 7598 15105 7600 15106 7953 15106 7952 15106 7601 15107 7953 15107 7600 15107 7603 15108 7629 15108 7601 15108 7601 15109 7629 15109 7953 15109 7603 15110 7954 15110 7629 15110 7605 15111 7954 15111 7603 15111 7607 15112 7954 15112 7605 15112 7607 15113 7633 15113 7954 15113 7608 15114 7633 15114 7607 15114 7608 15115 7955 15115 7633 15115 7611 15116 7955 15116 7608 15116 7613 15117 7955 15117 7611 15117 7613 15118 7956 15118 7955 15118 8020 15119 7956 15119 7613 15119 8020 15120 7957 15120 7956 15120 7614 15121 7957 15121 8020 15121 7616 15122 7957 15122 7614 15122 7616 15123 7958 15123 7957 15123 7618 15124 7958 15124 7616 15124 7618 15125 7959 15125 7958 15125 7619 15126 7959 15126 7618 15126 7619 15127 7644 15127 7959 15127 7621 15128 7644 15128 7619 15128 7621 15129 7960 15129 7644 15129 7623 15130 7960 15130 7621 15130 7625 15131 7960 15131 7623 15131 7625 15132 7961 15132 7960 15132 7627 15133 7961 15133 7625 15133 7627 15134 7962 15134 7961 15134 7628 15135 7962 15135 7627 15135 7628 15136 7653 15136 7962 15136 7631 15137 7653 15137 7628 15137 7631 15138 7963 15138 7653 15138 7632 15139 7963 15139 7631 15139 7634 15140 7963 15140 7632 15140 7634 15141 7658 15141 7963 15141 7636 15142 7658 15142 7634 15142 7636 15143 7660 15143 7658 15143 7638 15144 7660 15144 7636 15144 7638 15145 7662 15145 7660 15145 7638 15146 7964 15146 7662 15146 7640 15147 7964 15147 7638 15147 7641 15148 7964 15148 7640 15148 7641 15149 7965 15149 7964 15149 7643 15150 7965 15150 7641 15150 7643 15151 7966 15151 7965 15151 7646 15152 7966 15152 7643 15152 7647 15153 7967 15153 7646 15153 7646 15154 7967 15154 7966 15154 7649 15155 7967 15155 7647 15155 7650 15156 7967 15156 7649 15156 7650 15157 7968 15157 7967 15157 7652 15158 7968 15158 7650 15158 7654 15159 7968 15159 7652 15159 7654 15160 7969 15160 7968 15160 7656 15161 7969 15161 7654 15161 7656 15162 7681 15162 7969 15162 7657 15163 7681 15163 7656 15163 7659 15164 7681 15164 7657 15164 7659 15165 7683 15165 7681 15165 8021 15166 7685 15166 7659 15166 7659 15167 7685 15167 7683 15167 8021 15168 7687 15168 7685 15168 7661 15169 7687 15169 8021 15169 7663 15170 7687 15170 7661 15170 7663 15171 7689 15171 7687 15171 7665 15172 7689 15172 7663 15172 7665 15173 7691 15173 7689 15173 7666 15174 7691 15174 7665 15174 7666 15175 7970 15175 7691 15175 7668 15176 7970 15176 7666 15176 7670 15177 7970 15177 7668 15177 7670 15178 7696 15178 7970 15178 7671 15179 7696 15179 7670 15179 7671 15180 7971 15180 7696 15180 7673 15181 7971 15181 7671 15181 7673 15182 7972 15182 7971 15182 7675 15183 7972 15183 7673 15183 7675 15184 7704 15184 7972 15184 7677 15185 7704 15185 7675 15185 7678 15186 7704 15186 7677 15186 7678 15187 7973 15187 7704 15187 7680 15188 7973 15188 7678 15188 7682 15189 7973 15189 7680 15189 7682 15190 7709 15190 7973 15190 7682 15191 7711 15191 7709 15191 7684 15192 7711 15192 7682 15192 7684 15193 7974 15193 7711 15193 7686 15194 7974 15194 7684 15194 7688 15195 7974 15195 7686 15195 7688 15196 7718 15196 7974 15196 7690 15197 7718 15197 7688 15197 7690 15198 7975 15198 7718 15198 7692 15199 7975 15199 7690 15199 7694 15200 7975 15200 7692 15200 7694 15201 7721 15201 7975 15201 7694 15202 7976 15202 7721 15202 7695 15203 7976 15203 7694 15203 7698 15204 7976 15204 7695 15204 7698 15205 7726 15205 7976 15205 7699 15206 7726 15206 7698 15206 7699 15207 7977 15207 7726 15207 7701 15208 7977 15208 7699 15208 7703 15209 7977 15209 7701 15209 7703 15210 7730 15210 7977 15210 7705 15211 7730 15211 7703 15211 7705 15212 7733 15212 7730 15212 7707 15213 7733 15213 7705 15213 7707 15214 7734 15214 7733 15214 7708 15215 7734 15215 7707 15215 7708 15216 7736 15216 7734 15216 7710 15217 7736 15217 7708 15217 7710 15218 7738 15218 7736 15218 7712 15219 7738 15219 7710 15219 7714 15220 7978 15220 7712 15220 7712 15221 7978 15221 7738 15221 7716 15222 7979 15222 7714 15222 7714 15223 7979 15223 7978 15223 7717 15224 7979 15224 7716 15224 7717 15225 7980 15225 7979 15225 7720 15226 7980 15226 7717 15226 7720 15227 7981 15227 7980 15227 7722 15228 7981 15228 7720 15228 7724 15229 7981 15229 7722 15229 7724 15230 7750 15230 7981 15230 7724 15231 7982 15231 7750 15231 8022 15232 7982 15232 7724 15232 8022 15233 7983 15233 7982 15233 7727 15234 7983 15234 8022 15234 7729 15235 7757 15235 7727 15235 7727 15236 7757 15236 7983 15236 7731 15237 7757 15237 7729 15237 7731 15238 7759 15238 7757 15238 7732 15239 7759 15239 7731 15239 7732 15240 7761 15240 7759 15240 7735 15241 7761 15241 7732 15241 7735 15242 7763 15242 7761 15242 8023 15243 7763 15243 7735 15243 8023 15244 7766 15244 7763 15244 7739 15245 7766 15245 8023 15245 7739 15246 7768 15246 7766 15246 7741 15247 7768 15247 7739 15247 7741 15248 7984 15248 7768 15248 7742 15249 7984 15249 7741 15249 7742 15250 7985 15250 7984 15250 7744 15251 7985 15251 7742 15251 7745 15252 7985 15252 7744 15252 7747 15253 7985 15253 7745 15253 7747 15254 7986 15254 7985 15254 7749 15255 7986 15255 7747 15255 7749 15256 7987 15256 7986 15256 7751 15257 7987 15257 7749 15257 7751 15258 7781 15258 7987 15258 7751 15259 7988 15259 7781 15259 7753 15260 7988 15260 7751 15260 7754 15261 7988 15261 7753 15261 7754 15262 7989 15262 7988 15262 7756 15263 7989 15263 7754 15263 7758 15264 7989 15264 7756 15264 7758 15265 7990 15265 7989 15265 7760 15266 7990 15266 7758 15266 7762 15267 7990 15267 7760 15267 7762 15268 7991 15268 7990 15268 7764 15269 7991 15269 7762 15269 7765 15270 7992 15270 7764 15270 7764 15271 7992 15271 7991 15271 7767 15272 7992 15272 7765 15272 7769 15273 7992 15273 7767 15273 7769 15274 7993 15274 7992 15274 7770 15275 7993 15275 7769 15275 7772 15276 7993 15276 7770 15276 7772 15277 7797 15277 7993 15277 7773 15278 7797 15278 7772 15278 7773 15279 7994 15279 7797 15279 7775 15280 7994 15280 7773 15280 7775 15281 7801 15281 7994 15281 7777 15282 7801 15282 7775 15282 7777 15283 7995 15283 7801 15283 7778 15284 7995 15284 7777 15284 7778 15285 7807 15285 7995 15285 7780 15286 7807 15286 7778 15286 7780 15287 7996 15287 7807 15287 7783 15288 7996 15288 7780 15288 7784 15289 7996 15289 7783 15289 7784 15290 7811 15290 7996 15290 7786 15291 7811 15291 7784 15291 7786 15292 7813 15292 7811 15292 7788 15293 7813 15293 7786 15293 7789 15294 7813 15294 7788 15294 7789 15295 7815 15295 7813 15295 7791 15296 7815 15296 7789 15296 7791 15297 7997 15297 7815 15297 7792 15298 7997 15298 7791 15298 7794 15299 7997 15299 7792 15299 7794 15300 7998 15300 7997 15300 8024 15301 7998 15301 7794 15301 8024 15302 7999 15302 7998 15302 7796 15303 7999 15303 8024 15303 7798 15304 7999 15304 7796 15304 7798 15305 8000 15305 7999 15305 7800 15306 8000 15306 7798 15306 7802 15307 8000 15307 7800 15307 7802 15308 7831 15308 8000 15308 7803 15309 7831 15309 7802 15309 7803 15310 7832 15310 7831 15310 7805 15311 7832 15311 7803 15311 7806 15312 7832 15312 7805 15312 7806 15313 8001 15313 7832 15313 7808 15314 8001 15314 7806 15314 7808 15315 7838 15315 8001 15315 7810 15316 7838 15316 7808 15316 7810 15317 7840 15317 7838 15317 7812 15318 7840 15318 7810 15318 7812 15319 8002 15319 7840 15319 7816 15320 8002 15320 7812 15320 7816 15321 8003 15321 8002 15321 7818 15322 8003 15322 7816 15322 7819 15323 8003 15323 7818 15323 7819 15324 8004 15324 8003 15324 7821 15325 8004 15325 7819 15325 7822 15326 8004 15326 7821 15326 7822 15327 8005 15327 8004 15327 8025 15328 8005 15328 7822 15328 8025 15329 8006 15329 8005 15329 7826 15330 8006 15330 8025 15330 7826 15331 8007 15331 8006 15331 7828 15332 8007 15332 7826 15332 7830 15333 8007 15333 7828 15333 7830 15334 8008 15334 8007 15334 7833 15335 8008 15335 7830 15335 7833 15336 7860 15336 8008 15336 7834 15337 7860 15337 7833 15337 7836 15338 7860 15338 7834 15338 7836 15339 7861 15339 7860 15339 7837 15340 7861 15340 7836 15340 7837 15341 8009 15341 7861 15341 7839 15342 8009 15342 7837 15342 7839 15343 8010 15343 8009 15343 7841 15344 8010 15344 7839 15344 7843 15345 8011 15345 7841 15345 7841 15346 8011 15346 8010 15346 7845 15347 8011 15347 7843 15347 7845 15348 7244 15348 8011 15348 7846 15349 7244 15349 7845 15349 7846 15350 7242 15350 7244 15350 7848 15351 7242 15351 7846 15351 7848 15352 7245 15352 7242 15352 7850 15353 7245 15353 7848 15353 7850 15354 7248 15354 7245 15354 7852 15355 7248 15355 7850 15355 7854 15356 7248 15356 7852 15356 7854 15357 7253 15357 7248 15357 7855 15358 7253 15358 7854 15358 7855 15359 7255 15359 7253 15359 7260 15360 8014 15360 8012 15360 7261 15361 8014 15361 7260 15361 7367 15362 7364 15362 7366 15362 7443 15363 8015 15363 7442 15363 7450 15364 8016 15364 7449 15364 7491 15365 7488 15365 7489 15365 7575 15366 8017 15366 7573 15366 7577 15367 8018 15367 7575 15367 7582 15368 7579 15368 7581 15368 7590 15369 8019 15369 7588 15369 7593 15370 7590 15370 7591 15370 7614 15371 8020 15371 7613 15371 7661 15372 8021 15372 7659 15372 8022 15373 7724 15373 7725 15373 7727 15374 8022 15374 7725 15374 7737 15375 8023 15375 7735 15375 7739 15376 8023 15376 7737 15376 7796 15377 8024 15377 7794 15377 7816 15378 7812 15378 7814 15378 8025 15379 7822 15379 7824 15379 7826 15380 8025 15380 7824 15380 7857 15381 7255 15381 7855 15381 8051 15382 7255 15382 7857 15382 8049 15383 8051 15383 7857 15383 8030 15384 8027 15384 8026 15384 8031 15385 8028 15385 8027 15385 8031 15386 8027 15386 8030 15386 8030 15387 8026 15387 8029 15387 7249 15388 8072 15388 8028 15388 8031 15389 7249 15389 8028 15389 8032 15390 7249 15390 8031 15390 8033 15391 8031 15391 8030 15391 8033 15392 8030 15392 8029 15392 8032 15393 8031 15393 8033 15393 8032 15394 7251 15394 7249 15394 7251 15395 8032 15395 8033 15395 8034 15396 8033 15396 8029 15396 8034 15397 8029 15397 8035 15397 8036 15398 8033 15398 8034 15398 7251 15399 8033 15399 8036 15399 8037 15400 8036 15400 8034 15400 7256 15401 7251 15401 8036 15401 8037 15402 8034 15402 8035 15402 8037 15403 7256 15403 8036 15403 8037 15404 8035 15404 8039 15404 7256 15405 8037 15405 8041 15405 8040 15406 8037 15406 8039 15406 8038 15407 8039 15407 8035 15407 8040 15408 8041 15408 8037 15408 8041 15409 7258 15409 7256 15409 8042 15410 8039 15410 8038 15410 8040 15411 8039 15411 8042 15411 8043 15412 8041 15412 8040 15412 8043 15413 7258 15413 8041 15413 8044 15414 8040 15414 8042 15414 8043 15415 8040 15415 8044 15415 7258 15416 8043 15416 8044 15416 8046 15417 8044 15417 8042 15417 8045 15418 8042 15418 8038 15418 8045 15419 8046 15419 8042 15419 8046 15420 7258 15420 8044 15420 7259 15421 7258 15421 8046 15421 8047 15422 8045 15422 8038 15422 8048 15423 8045 15423 8047 15423 8048 15424 8046 15424 8045 15424 8049 15425 8046 15425 8048 15425 8047 15426 8038 15426 8050 15426 8046 15427 8049 15427 7259 15427 8052 15428 8048 15428 8047 15428 8051 15429 8049 15429 8048 15429 8051 15430 8048 15430 8052 15430 8053 15431 8052 15431 8047 15431 8053 15432 8047 15432 8050 15432 8054 15433 8052 15433 8053 15433 8054 15434 8051 15434 8052 15434 7255 15435 8051 15435 8054 15435 8055 15436 8054 15436 8053 15436 8054 15437 7253 15437 7255 15437 8056 15438 8053 15438 8050 15438 8055 15439 8053 15439 8056 15439 8057 15440 8056 15440 8050 15440 7253 15441 8054 15441 8055 15441 8055 15442 7252 15442 7253 15442 7252 15443 8055 15443 8056 15443 8058 15444 8057 15444 8050 15444 8059 15445 7252 15445 8056 15445 8060 15446 8056 15446 8057 15446 8059 15447 8056 15447 8060 15447 8060 15448 8057 15448 8058 15448 8059 15449 8062 15449 7252 15449 8062 15450 8059 15450 8060 15450 8063 15451 8060 15451 8058 15451 8063 15452 8064 15452 8060 15452 8063 15453 8058 15453 8061 15453 8064 15454 8062 15454 8060 15454 7246 15455 8062 15455 8064 15455 8065 15456 8063 15456 8061 15456 8066 15457 8063 15457 8065 15457 8066 15458 8064 15458 8063 15458 7243 15459 7246 15459 8064 15459 8066 15460 7243 15460 8064 15460 8068 15461 8066 15461 8065 15461 8068 15462 8065 15462 8061 15462 8068 15463 8061 15463 8067 15463 8067 15464 8061 15464 8026 15464 8068 15465 8069 15465 8066 15465 7243 15466 8066 15466 8069 15466 8070 15467 8068 15467 8067 15467 8027 15468 8067 15468 8026 15468 8069 15469 8068 15469 8070 15469 8027 15470 8070 15470 8067 15470 8071 15471 8069 15471 8070 15471 8028 15472 8070 15472 8027 15472 8072 15473 8071 15473 8070 15473 8028 15474 8072 15474 8070 15474 8038 15475 8026 15475 8061 15475 8038 15476 8029 15476 8026 15476 8038 15477 8058 15477 8050 15477 8038 15478 8035 15478 8029 15478 8038 15479 8061 15479 8058 15479 8074 15480 8073 15480 8082 15480 8082 15481 8073 15481 8080 15481 8073 15482 8075 15482 8080 15482 8080 15483 8075 15483 8079 15483 8075 15484 8076 15484 8079 15484 8079 15485 8076 15485 8084 15485 8076 15486 8077 15486 8084 15486 8084 15487 8077 15487 8083 15487 8077 15488 8078 15488 8083 15488 8083 15489 8078 15489 8081 15489 8078 15490 8082 15490 8081 15490 8078 15491 8074 15491 8082 15491 8079 15492 8085 15492 8086 15492 8079 15493 8086 15493 8087 15493 8084 15494 8089 15494 8088 15494 8084 15495 8088 15495 8085 15495 8084 15496 8085 15496 8079 15496 8084 15497 8092 15497 8089 15497 8080 15498 8087 15498 8090 15498 8080 15499 8079 15499 8087 15499 8091 15500 8080 15500 8090 15500 8083 15501 8092 15501 8084 15501 8093 15502 8092 15502 8083 15502 8082 15503 8080 15503 8091 15503 8094 15504 8082 15504 8091 15504 8095 15505 8093 15505 8083 15505 8095 15506 8083 15506 8081 15506 8096 15507 8082 15507 8094 15507 8097 15508 8095 15508 8081 15508 8096 15509 8081 15509 8082 15509 8097 15510 8081 15510 8096 15510 8073 15511 8077 15511 8075 15511 8075 15512 8077 15512 8076 15512 8078 15513 8077 15513 8074 15513 8074 15514 8077 15514 8073 15514 8098 15515 8110 15515 8089 15515 8098 15516 8089 15516 8092 15516 8099 15517 8092 15517 8093 15517 8099 15518 8098 15518 8092 15518 8100 15519 8099 15519 8093 15519 8100 15520 8093 15520 8095 15520 8101 15521 8100 15521 8095 15521 8101 15522 8095 15522 8097 15522 8102 15523 8101 15523 8097 15523 8102 15524 8097 15524 8096 15524 8102 15525 8096 15525 8094 15525 8103 15526 8102 15526 8094 15526 8104 15527 8103 15527 8094 15527 8104 15528 8094 15528 8091 15528 8105 15529 8104 15529 8091 15529 8105 15530 8091 15530 8090 15530 8106 15531 8105 15531 8090 15531 8106 15532 8090 15532 8087 15532 8107 15533 8106 15533 8087 15533 8107 15534 8087 15534 8086 15534 8108 15535 8086 15535 8085 15535 8108 15536 8107 15536 8086 15536 8109 15537 8108 15537 8085 15537 8109 15538 8085 15538 8088 15538 8110 15539 8109 15539 8088 15539 8110 15540 8088 15540 8089 15540 7863 15541 7272 15541 8105 15541 7272 15542 8104 15542 8105 15542 7863 15543 8105 15543 8106 15543 7264 15544 8104 15544 7272 15544 7863 15545 8106 15545 8107 15545 7264 15546 8103 15546 8104 15546 7864 15547 7863 15547 8107 15547 7264 15548 8102 15548 8103 15548 7268 15549 8102 15549 7264 15549 7864 15550 8107 15550 8108 15550 8013 15551 7864 15551 8108 15551 7266 15552 8102 15552 7268 15552 8101 15553 8102 15553 7266 15553 8109 15554 8013 15554 8108 15554 8100 15555 7266 15555 7263 15555 8100 15556 8101 15556 7266 15556 8109 15557 8012 15557 8013 15557 8110 15558 8012 15558 8109 15558 8098 15559 8012 15559 8110 15559 8100 15560 7263 15560 7260 15560 8099 15561 8100 15561 7260 15561 8098 15562 7260 15562 8012 15562 8098 15563 8099 15563 7260 15563

+
+ + + +

8132 15564 8111 15564 8133 15564 8133 15565 8111 15565 8112 15565 8111 15566 8113 15566 8112 15566 8112 15567 8113 15567 8114 15567 8113 15568 8115 15568 8114 15568 8115 15569 8116 15569 8114 15569 8114 15570 8116 15570 8117 15570 8116 15571 8118 15571 8117 15571 8117 15572 8118 15572 8119 15572 8118 15573 8120 15573 8119 15573 8119 15574 8120 15574 8121 15574 8120 15575 8122 15575 8121 15575 8121 15576 8122 15576 8123 15576 8122 15577 8124 15577 8123 15577 8123 15578 8124 15578 8125 15578 8124 15579 8126 15579 8125 15579 8125 15580 8126 15580 8127 15580 8126 15581 8128 15581 8127 15581 8127 15582 8128 15582 8129 15582 8128 15583 8130 15583 8129 15583 8129 15584 8130 15584 8131 15584 8130 15585 8132 15585 8131 15585 8131 15586 8132 15586 8133 15586 8134 15587 8163 15587 8135 15587 8136 15588 8134 15588 8135 15588 8136 15589 8135 15589 8137 15589 8138 15590 8136 15590 8137 15590 8138 15591 8137 15591 8139 15591 8138 15592 8139 15592 8140 15592 8141 15593 8138 15593 8140 15593 8141 15594 8140 15594 8142 15594 8143 15595 8141 15595 8142 15595 8143 15596 8142 15596 8144 15596 8145 15597 8143 15597 8144 15597 8145 15598 8144 15598 8146 15598 8145 15599 8146 15599 8147 15599 8148 15600 8145 15600 8147 15600 8148 15601 8147 15601 8149 15601 8150 15602 8148 15602 8149 15602 8151 15603 8150 15603 8149 15603 8151 15604 8149 15604 8152 15604 8153 15605 8151 15605 8152 15605 8153 15606 8152 15606 8154 15606 8155 15607 8153 15607 8154 15607 8155 15608 8154 15608 8156 15608 8157 15609 8155 15609 8156 15609 8157 15610 8156 15610 8158 15610 8159 15611 8157 15611 8158 15611 8159 15612 8158 15612 8160 15612 8161 15613 8159 15613 8160 15613 8162 15614 8161 15614 8160 15614 8162 15615 8160 15615 8163 15615 8134 15616 8162 15616 8163 15616 8124 213 8160 213 8158 213 8126 15617 8124 15617 8158 15617 8124 213 8163 213 8160 213 8122 213 8163 213 8124 213 8126 213 8158 213 8156 213 8128 15618 8126 15618 8156 15618 8122 15619 8135 15619 8163 15619 8128 15620 8156 15620 8154 15620 8120 15621 8135 15621 8122 15621 8130 213 8128 213 8154 213 8120 15622 8137 15622 8135 15622 8130 213 8154 213 8152 213 8137 15623 8120 15623 8118 15623 8139 213 8137 213 8118 213 8152 15624 8132 15624 8130 15624 8149 213 8132 213 8152 213 8139 15625 8118 15625 8116 15625 8140 213 8139 213 8116 213 8149 15626 8111 15626 8132 15626 8147 213 8111 213 8149 213 8142 15627 8140 15627 8116 15627 8142 213 8116 213 8115 213 8147 15628 8113 15628 8111 15628 8144 213 8142 213 8115 213 8146 213 8113 213 8147 213 8144 15629 8115 15629 8113 15629 8144 213 8113 213 8146 213 8129 67 8131 67 8151 67 8129 15630 8151 15630 8153 15630 8131 15631 8150 15631 8151 15631 8133 67 8150 67 8131 67 8129 67 8153 67 8155 67 8127 15632 8129 15632 8155 15632 8133 15633 8148 15633 8150 15633 8127 67 8155 67 8157 67 8112 67 8148 67 8133 67 8127 15634 8157 15634 8159 15634 8112 12106 8145 12106 8148 12106 8125 67 8127 67 8159 67 8114 15635 8145 15635 8112 15635 8161 15636 8125 15636 8159 15636 8143 15637 8145 15637 8114 15637 8161 67 8123 67 8125 67 8162 67 8123 67 8161 67 8141 67 8143 67 8114 67 8141 15638 8114 15638 8117 15638 8134 67 8123 67 8162 67 8134 15639 8121 15639 8123 15639 8138 15640 8141 15640 8117 15640 8136 67 8121 67 8134 67 8138 15641 8117 15641 8119 15641 8136 15642 8119 15642 8121 15642 8136 15643 8138 15643 8119 15643

+
+ + + +

8986 15644 8164 15644 8165 15644 8986 15645 8166 15645 8164 15645 8167 15646 8166 15646 8986 15646 8164 15647 8168 15647 8165 15647 8165 15648 8168 15648 8169 15648 8949 15649 8166 15649 8167 15649 8168 15650 8170 15650 8169 15650 8949 15651 8171 15651 8166 15651 8169 15652 8170 15652 8976 15652 8174 15653 8171 15653 8949 15653 8170 15654 8172 15654 8976 15654 8174 15655 8173 15655 8171 15655 8174 15656 8176 15656 8173 15656 8173 15657 8176 15657 8177 15657 8183 15658 8180 15658 8179 15658 8183 15659 8182 15659 8180 15659 8186 15660 8182 15660 8183 15660 8186 15661 8184 15661 8182 15661 8186 15662 8185 15662 8184 15662 8181 15663 8185 15663 8186 15663 8181 15664 8187 15664 8185 15664 8188 15665 8187 15665 8181 15665 8188 15666 8189 15666 8187 15666 8188 15667 8190 15667 8189 15667 8191 15668 8190 15668 8188 15668 8191 15669 8192 15669 8190 15669 8191 15670 8193 15670 8192 15670 8194 15671 8193 15671 8191 15671 8194 15672 8195 15672 8193 15672 8196 15673 8197 15673 8194 15673 8194 15674 8197 15674 8195 15674 8196 15675 8198 15675 8197 15675 8196 15676 8199 15676 8198 15676 8200 15677 8199 15677 8196 15677 8200 15678 8201 15678 8199 15678 8202 15679 8201 15679 8200 15679 8203 15680 8201 15680 8202 15680 8203 15681 8204 15681 8201 15681 8203 15682 8205 15682 8204 15682 8206 15683 8205 15683 8203 15683 8206 15684 8207 15684 8205 15684 8208 15685 8207 15685 8206 15685 8208 15686 8209 15686 8207 15686 8210 15687 8209 15687 8208 15687 8210 15688 8211 15688 8209 15688 8212 15689 8211 15689 8210 15689 8212 15690 8213 15690 8211 15690 8214 15691 8213 15691 8212 15691 8214 15692 8215 15692 8213 15692 8216 15693 8215 15693 8214 15693 8216 15694 8217 15694 8215 15694 8218 15695 8217 15695 8216 15695 8218 15696 8219 15696 8217 15696 8218 15697 8220 15697 8219 15697 8221 15698 8220 15698 8218 15698 8221 15699 8222 15699 8220 15699 8221 15700 8223 15700 8222 15700 8224 15701 8223 15701 8221 15701 8224 15702 8225 15702 8223 15702 8226 15703 8225 15703 8224 15703 8226 15704 8227 15704 8225 15704 8226 15705 8228 15705 8227 15705 8229 15706 8228 15706 8226 15706 8229 15707 8230 15707 8228 15707 8231 15708 8230 15708 8229 15708 8231 15709 8232 15709 8230 15709 8231 15710 8233 15710 8232 15710 8234 15711 8233 15711 8231 15711 8234 15712 8235 15712 8233 15712 8236 15713 8235 15713 8234 15713 8236 15714 8237 15714 8235 15714 8238 15715 8237 15715 8236 15715 8239 15716 8240 15716 8238 15716 8238 15717 8240 15717 8237 15717 8239 15718 8241 15718 8240 15718 8242 15719 8241 15719 8239 15719 8242 15720 8243 15720 8241 15720 8242 15721 8244 15721 8243 15721 8245 15722 8244 15722 8242 15722 8245 15723 8246 15723 8244 15723 8247 15724 8246 15724 8245 15724 8247 15725 8248 15725 8246 15725 8247 15726 8249 15726 8248 15726 8250 15727 8249 15727 8247 15727 8250 15728 8251 15728 8249 15728 8252 15729 8251 15729 8250 15729 8252 15730 8253 15730 8251 15730 8254 15731 8253 15731 8252 15731 8254 15732 8255 15732 8253 15732 8256 15733 8255 15733 8254 15733 8256 15734 8257 15734 8255 15734 8258 15735 8257 15735 8256 15735 8258 15736 8259 15736 8257 15736 8260 15737 8259 15737 8258 15737 8260 15738 8261 15738 8259 15738 8260 15739 8262 15739 8261 15739 8263 15740 8262 15740 8260 15740 8263 15741 8264 15741 8262 15741 8265 15742 8264 15742 8263 15742 8265 15743 8266 15743 8264 15743 8267 15744 8266 15744 8265 15744 8267 15745 8268 15745 8266 15745 8269 15746 8268 15746 8267 15746 8269 15747 8270 15747 8268 15747 8271 15748 8270 15748 8269 15748 8271 15749 8272 15749 8270 15749 8271 15750 8273 15750 8272 15750 8274 15751 8273 15751 8271 15751 8274 15752 8275 15752 8273 15752 8276 15753 8275 15753 8274 15753 8276 15754 8277 15754 8275 15754 8278 15755 8277 15755 8276 15755 8278 15756 8279 15756 8277 15756 8280 15757 8281 15757 8278 15757 8278 15758 8281 15758 8279 15758 8280 15759 8282 15759 8281 15759 8283 15760 8282 15760 8280 15760 8283 15761 8284 15761 8282 15761 8283 15762 8285 15762 8284 15762 8286 15763 8285 15763 8283 15763 8286 15764 8287 15764 8285 15764 8288 15765 8287 15765 8286 15765 8288 15766 8289 15766 8287 15766 8288 15767 8290 15767 8289 15767 8291 15768 8290 15768 8288 15768 8291 15769 8292 15769 8290 15769 8293 15770 8294 15770 8291 15770 8291 15771 8294 15771 8292 15771 8295 15772 8294 15772 8293 15772 8295 15773 8296 15773 8294 15773 8295 15774 8297 15774 8296 15774 8298 15775 8299 15775 8295 15775 8295 15776 8299 15776 8297 15776 8298 15777 8300 15777 8299 15777 8301 15778 8300 15778 8298 15778 8301 15779 8302 15779 8300 15779 8301 15780 8303 15780 8302 15780 8304 15781 8303 15781 8301 15781 8304 15782 8305 15782 8303 15782 8306 15783 8305 15783 8304 15783 8306 15784 8307 15784 8305 15784 8308 15785 8307 15785 8306 15785 8308 15786 8309 15786 8307 15786 8308 15787 8310 15787 8309 15787 8311 15788 8310 15788 8308 15788 8311 15789 8312 15789 8310 15789 8313 15790 8312 15790 8311 15790 8313 15791 8314 15791 8312 15791 8315 15792 8314 15792 8313 15792 8315 15793 8316 15793 8314 15793 8317 15794 8316 15794 8315 15794 8317 15795 8318 15795 8316 15795 8319 15796 8318 15796 8317 15796 8319 15797 8320 15797 8318 15797 8319 15798 8321 15798 8320 15798 8322 15799 8321 15799 8319 15799 8322 15800 8323 15800 8321 15800 8324 15801 8323 15801 8322 15801 8324 15802 8325 15802 8323 15802 8324 15803 8326 15803 8325 15803 8327 15804 8326 15804 8324 15804 8327 15805 8328 15805 8326 15805 8329 15806 8328 15806 8327 15806 8329 15807 8330 15807 8328 15807 8331 15808 8330 15808 8329 15808 8331 15809 8332 15809 8330 15809 8333 15810 8332 15810 8331 15810 8333 15811 8334 15811 8332 15811 8335 15812 8334 15812 8333 15812 8335 15813 8336 15813 8334 15813 8335 15814 8337 15814 8336 15814 8338 15815 8337 15815 8335 15815 8338 15816 8339 15816 8337 15816 8340 15817 8339 15817 8338 15817 8340 15818 8341 15818 8339 15818 8342 15819 8341 15819 8340 15819 8342 15820 8343 15820 8341 15820 8344 15821 8343 15821 8342 15821 8344 15822 8345 15822 8343 15822 8344 15823 8346 15823 8345 15823 8347 15824 8346 15824 8344 15824 8347 15825 8348 15825 8346 15825 8349 15826 8348 15826 8347 15826 8349 15827 8350 15827 8348 15827 8351 15828 8350 15828 8349 15828 8351 15829 8352 15829 8350 15829 8351 15830 8353 15830 8352 15830 8354 15831 8353 15831 8351 15831 8354 15832 8355 15832 8353 15832 8356 15833 8355 15833 8354 15833 8356 15834 8357 15834 8355 15834 8358 15835 8357 15835 8356 15835 8358 15836 8359 15836 8357 15836 8360 15837 8359 15837 8358 15837 8360 15838 8361 15838 8359 15838 8362 15839 8361 15839 8360 15839 8362 15840 8363 15840 8361 15840 8364 15841 8363 15841 8362 15841 8364 15842 8365 15842 8363 15842 8366 15843 8367 15843 8364 15843 8364 15844 8367 15844 8365 15844 8366 15845 8368 15845 8367 15845 8369 15846 8368 15846 8366 15846 8369 15847 8370 15847 8368 15847 8369 15848 8371 15848 8370 15848 8372 15849 8371 15849 8369 15849 8372 15850 8373 15850 8371 15850 8374 15851 8373 15851 8372 15851 8374 15852 8375 15852 8373 15852 8374 15853 8376 15853 8375 15853 8377 15854 8376 15854 8374 15854 8377 15855 8378 15855 8376 15855 8379 15856 8378 15856 8377 15856 8379 15857 8380 15857 8378 15857 8381 15858 8380 15858 8379 15858 8381 15859 8382 15859 8380 15859 8381 15860 8383 15860 8382 15860 8384 15861 8383 15861 8381 15861 8384 15862 8385 15862 8383 15862 8386 15863 8385 15863 8384 15863 8386 15864 8387 15864 8385 15864 8388 15865 8387 15865 8386 15865 8388 15866 8389 15866 8387 15866 8388 15867 8390 15867 8389 15867 8391 15868 8390 15868 8388 15868 8391 15869 8392 15869 8390 15869 8393 15870 8392 15870 8391 15870 8393 15871 8394 15871 8392 15871 8393 15872 8395 15872 8394 15872 8396 15873 8395 15873 8393 15873 8396 15874 8397 15874 8395 15874 8398 15875 8397 15875 8396 15875 8399 15876 8397 15876 8398 15876 8399 15877 8400 15877 8397 15877 8399 15878 8401 15878 8400 15878 8402 15879 8401 15879 8399 15879 8402 15880 8403 15880 8401 15880 8404 15881 8403 15881 8402 15881 8404 15882 8405 15882 8403 15882 8406 15883 8405 15883 8404 15883 8406 15884 8407 15884 8405 15884 8406 15885 8408 15885 8407 15885 8409 15886 8408 15886 8406 15886 8409 15887 8410 15887 8408 15887 8411 15888 8410 15888 8409 15888 8411 15889 8412 15889 8410 15889 8413 15890 8412 15890 8411 15890 8413 15891 8414 15891 8412 15891 8413 15892 8415 15892 8414 15892 8416 15893 8415 15893 8413 15893 8416 15894 8417 15894 8415 15894 8418 15895 8419 15895 8416 15895 8416 15896 8419 15896 8417 15896 8420 15897 8419 15897 8418 15897 8420 15898 8421 15898 8419 15898 8420 15899 8422 15899 8421 15899 8423 15900 8422 15900 8420 15900 8423 15901 8424 15901 8422 15901 8425 15902 8424 15902 8423 15902 8426 15903 8427 15903 8425 15903 8425 15904 8427 15904 8424 15904 8428 15905 8427 15905 8426 15905 8428 15906 8429 15906 8427 15906 8428 15907 8430 15907 8429 15907 8431 15908 8430 15908 8428 15908 8431 15909 8432 15909 8430 15909 8433 15910 8432 15910 8431 15910 8433 15911 8434 15911 8432 15911 8435 15912 8436 15912 8433 15912 8433 15913 8436 15913 8434 15913 8435 15914 8437 15914 8436 15914 8438 15915 8437 15915 8435 15915 8438 15916 8439 15916 8437 15916 8440 15917 8439 15917 8438 15917 8440 15918 8441 15918 8439 15918 8442 15919 8441 15919 8440 15919 8442 15920 8443 15920 8441 15920 8444 15921 8445 15921 8442 15921 8442 15922 8445 15922 8443 15922 8444 15923 8446 15923 8445 15923 8447 15924 8446 15924 8444 15924 8447 15925 8448 15925 8446 15925 8447 15926 8449 15926 8448 15926 8450 15927 8449 15927 8447 15927 8450 15928 8451 15928 8449 15928 8452 15929 8451 15929 8450 15929 8452 15930 8453 15930 8451 15930 8452 15931 8454 15931 8453 15931 8455 15932 8454 15932 8452 15932 8455 15933 8456 15933 8454 15933 8457 15934 8458 15934 8455 15934 8455 15935 8458 15935 8456 15935 8457 15936 8459 15936 8458 15936 8460 15937 8459 15937 8457 15937 8460 15938 8461 15938 8459 15938 8460 15939 8462 15939 8461 15939 8463 15940 8462 15940 8460 15940 8464 15941 8462 15941 8463 15941 8464 15942 8465 15942 8462 15942 8464 15943 8466 15943 8465 15943 8467 15944 8466 15944 8464 15944 8468 15945 8466 15945 8467 15945 8468 15946 8469 15946 8466 15946 8470 15947 8469 15947 8468 15947 8470 15948 8471 15948 8469 15948 8472 15949 8471 15949 8470 15949 8472 15950 8473 15950 8471 15950 8474 15951 8473 15951 8472 15951 8474 15952 8475 15952 8473 15952 8474 15953 8476 15953 8475 15953 8477 15954 8476 15954 8474 15954 8477 15955 8478 15955 8476 15955 8479 15956 8478 15956 8477 15956 8479 15957 8480 15957 8478 15957 8481 15958 8480 15958 8479 15958 8481 15959 8482 15959 8480 15959 8483 15960 8482 15960 8481 15960 8483 15961 8484 15961 8482 15961 8485 15962 8484 15962 8483 15962 8485 15963 8486 15963 8484 15963 8485 15964 8487 15964 8486 15964 8488 15965 8487 15965 8485 15965 8488 15966 8489 15966 8487 15966 8490 15967 8489 15967 8488 15967 8490 15968 8491 15968 8489 15968 8492 15969 8491 15969 8490 15969 8492 15970 8493 15970 8491 15970 8492 15971 8494 15971 8493 15971 8495 15972 8494 15972 8492 15972 8495 15973 8496 15973 8494 15973 8497 15974 8496 15974 8495 15974 8498 15975 8496 15975 8497 15975 8498 15976 8499 15976 8496 15976 8500 15977 8499 15977 8498 15977 8500 15978 8501 15978 8499 15978 8502 15979 8503 15979 8500 15979 8500 15980 8503 15980 8501 15980 8502 15981 8504 15981 8503 15981 8505 15982 8504 15982 8502 15982 8505 15983 8506 15983 8504 15983 8507 15984 8506 15984 8505 15984 8507 15985 8508 15985 8506 15985 8509 15986 8508 15986 8507 15986 8509 15987 8510 15987 8508 15987 8511 15988 8510 15988 8509 15988 8511 15989 8512 15989 8510 15989 8513 15990 8512 15990 8511 15990 8513 15991 8514 15991 8512 15991 8515 15992 8516 15992 8513 15992 8513 15993 8516 15993 8514 15993 8515 15994 8517 15994 8516 15994 8518 15995 8517 15995 8515 15995 8518 15996 8519 15996 8517 15996 8518 15997 8520 15997 8519 15997 8521 15998 8520 15998 8518 15998 8521 15999 8522 15999 8520 15999 8523 16000 8522 16000 8521 16000 8523 16001 8524 16001 8522 16001 8525 16002 8524 16002 8523 16002 8525 16003 8526 16003 8524 16003 8525 16004 8527 16004 8526 16004 8528 16005 8527 16005 8525 16005 8528 16006 8529 16006 8527 16006 8530 16007 8529 16007 8528 16007 8530 16008 8531 16008 8529 16008 8530 16009 8532 16009 8531 16009 8533 16010 8532 16010 8530 16010 8533 16011 8534 16011 8532 16011 8535 16012 8534 16012 8533 16012 8535 16013 8536 16013 8534 16013 8537 16014 8536 16014 8535 16014 8537 16015 8538 16015 8536 16015 8539 16016 8538 16016 8537 16016 8539 16017 8540 16017 8538 16017 8541 16018 8540 16018 8539 16018 8541 16019 8542 16019 8540 16019 8541 16020 8543 16020 8542 16020 8544 16021 8543 16021 8541 16021 8544 16022 8545 16022 8543 16022 8546 16023 8545 16023 8544 16023 8547 16024 8545 16024 8546 16024 8547 16025 8548 16025 8545 16025 8549 16026 8548 16026 8547 16026 8549 16027 8550 16027 8548 16027 8551 16028 8550 16028 8549 16028 8551 16029 8552 16029 8550 16029 8551 16030 8553 16030 8552 16030 8554 16031 8553 16031 8551 16031 8554 16032 8555 16032 8553 16032 8556 16033 8555 16033 8554 16033 8556 16034 8557 16034 8555 16034 8556 16035 8558 16035 8557 16035 8559 16036 8558 16036 8556 16036 8559 16037 8560 16037 8558 16037 8561 16038 8560 16038 8559 16038 8561 16039 8562 16039 8560 16039 8563 16040 8562 16040 8561 16040 8563 16041 8564 16041 8562 16041 8565 16042 8564 16042 8563 16042 8565 16043 8566 16043 8564 16043 8565 16044 8567 16044 8566 16044 8568 16045 8567 16045 8565 16045 8568 16046 8569 16046 8567 16046 8570 16047 8569 16047 8568 16047 8570 16048 8571 16048 8569 16048 8570 16049 8572 16049 8571 16049 8573 16050 8572 16050 8570 16050 8574 16051 8575 16051 8573 16051 8573 16052 8575 16052 8572 16052 8574 16053 8576 16053 8575 16053 8577 16054 8576 16054 8574 16054 8577 16055 8578 16055 8576 16055 8579 16056 8580 16056 8577 16056 8577 16057 8580 16057 8578 16057 8579 16058 8581 16058 8580 16058 8582 16059 8581 16059 8579 16059 8582 16060 8583 16060 8581 16060 8584 16061 8585 16061 8582 16061 8582 16062 8585 16062 8583 16062 8586 16063 8585 16063 8584 16063 8586 16064 8587 16064 8585 16064 8586 16065 8588 16065 8587 16065 8589 16066 8588 16066 8586 16066 8589 16067 8590 16067 8588 16067 8591 16068 8590 16068 8589 16068 8591 16069 8592 16069 8590 16069 8593 16070 8592 16070 8591 16070 8593 16071 8594 16071 8592 16071 8595 16072 8594 16072 8593 16072 8595 16073 8596 16073 8594 16073 8595 16074 8597 16074 8596 16074 8598 16075 8599 16075 8595 16075 8595 16076 8599 16076 8597 16076 8598 16077 8600 16077 8599 16077 8601 16078 8600 16078 8598 16078 8601 16079 8602 16079 8600 16079 8601 16080 8603 16080 8602 16080 8604 16081 8603 16081 8601 16081 8604 16082 8605 16082 8603 16082 8606 16083 8605 16083 8604 16083 8606 16084 8607 16084 8605 16084 8606 16085 8608 16085 8607 16085 8609 16086 8608 16086 8606 16086 8609 16087 8610 16087 8608 16087 8611 16088 8612 16088 8609 16088 8609 16089 8612 16089 8610 16089 8613 16090 8612 16090 8611 16090 8613 16091 8614 16091 8612 16091 8613 16092 8615 16092 8614 16092 8616 16093 8615 16093 8613 16093 8616 16094 8617 16094 8615 16094 8618 16095 8617 16095 8616 16095 8618 16096 8619 16096 8617 16096 8618 16097 8620 16097 8619 16097 8621 16098 8620 16098 8618 16098 8621 16099 8622 16099 8620 16099 8623 16100 8622 16100 8621 16100 8623 16101 8624 16101 8622 16101 8625 16102 8624 16102 8623 16102 8625 16103 8626 16103 8624 16103 8625 16104 8627 16104 8626 16104 8628 16105 8627 16105 8625 16105 8628 16106 8629 16106 8627 16106 8630 16107 8629 16107 8628 16107 8630 16108 8631 16108 8629 16108 8630 16109 8632 16109 8631 16109 8633 16110 8632 16110 8630 16110 8633 16111 8634 16111 8632 16111 8635 16112 8634 16112 8633 16112 8635 16113 8636 16113 8634 16113 8635 16114 8637 16114 8636 16114 8638 16115 8637 16115 8635 16115 8638 16116 8639 16116 8637 16116 8640 16117 8639 16117 8638 16117 8641 16118 8639 16118 8640 16118 8641 16119 8642 16119 8639 16119 8641 16120 8643 16120 8642 16120 8644 16121 8643 16121 8641 16121 8645 16122 8643 16122 8644 16122 8645 16123 8646 16123 8643 16123 8647 16124 8646 16124 8645 16124 8647 16125 8648 16125 8646 16125 8649 16126 8648 16126 8647 16126 8649 16127 8650 16127 8648 16127 8651 16128 8650 16128 8649 16128 8651 16129 8652 16129 8650 16129 8653 16130 8652 16130 8651 16130 8653 16131 8654 16131 8652 16131 8655 16132 8654 16132 8653 16132 8655 16133 8656 16133 8654 16133 8657 16134 8656 16134 8655 16134 8657 16135 8658 16135 8656 16135 8659 16136 8658 16136 8657 16136 8659 16137 8660 16137 8658 16137 8661 16138 8662 16138 8659 16138 8659 16139 8662 16139 8660 16139 8663 16140 8662 16140 8661 16140 8663 16141 8664 16141 8662 16141 8663 16142 8665 16142 8664 16142 8666 16143 8665 16143 8663 16143 8667 16144 8665 16144 8666 16144 8667 16145 8668 16145 8665 16145 8667 16146 8669 16146 8668 16146 8670 16147 8669 16147 8667 16147 8670 16148 8671 16148 8669 16148 8670 16149 8672 16149 8671 16149 8673 16150 8672 16150 8670 16150 8673 16151 8674 16151 8672 16151 8675 16152 8674 16152 8673 16152 8675 16153 8676 16153 8674 16153 8677 16154 8676 16154 8675 16154 8677 16155 8678 16155 8676 16155 8677 16156 8679 16156 8678 16156 8680 16157 8679 16157 8677 16157 8680 16158 8681 16158 8679 16158 8680 16159 8682 16159 8681 16159 8683 16160 8682 16160 8680 16160 8683 16161 8684 16161 8682 16161 8685 16162 8684 16162 8683 16162 8685 16163 8686 16163 8684 16163 8687 16164 8686 16164 8685 16164 8687 16165 8688 16165 8686 16165 8687 16166 8689 16166 8688 16166 8690 16167 8689 16167 8687 16167 8690 16168 8691 16168 8689 16168 8692 16169 8691 16169 8690 16169 8692 16170 8693 16170 8691 16170 8694 16171 8695 16171 8692 16171 8692 16172 8695 16172 8693 16172 8696 16173 8695 16173 8694 16173 8696 16174 8697 16174 8695 16174 8698 16175 8699 16175 8696 16175 8696 16176 8699 16176 8697 16176 8700 16177 8699 16177 8698 16177 8700 16178 8701 16178 8699 16178 8702 16179 8701 16179 8700 16179 8702 16180 8703 16180 8701 16180 8704 16181 8703 16181 8702 16181 8704 16182 8705 16182 8703 16182 8706 16183 8705 16183 8704 16183 8706 16184 8707 16184 8705 16184 8708 16185 8707 16185 8706 16185 8708 16186 8709 16186 8707 16186 8710 16187 8709 16187 8708 16187 8710 16188 8711 16188 8709 16188 8712 16189 8711 16189 8710 16189 8712 16190 8713 16190 8711 16190 8712 16191 8714 16191 8713 16191 8715 16192 8714 16192 8712 16192 8715 16193 8716 16193 8714 16193 8717 16194 8716 16194 8715 16194 8717 16195 8718 16195 8716 16195 8717 16196 8719 16196 8718 16196 8720 16197 8719 16197 8717 16197 8720 16198 8721 16198 8719 16198 8722 16199 8721 16199 8720 16199 8722 16200 8723 16200 8721 16200 8724 16201 8723 16201 8722 16201 8724 16202 8725 16202 8723 16202 8724 16203 8726 16203 8725 16203 8727 16204 8726 16204 8724 16204 8727 16205 8728 16205 8726 16205 8729 16206 8728 16206 8727 16206 8729 16207 8730 16207 8728 16207 8729 16208 8731 16208 8730 16208 8732 16209 8731 16209 8729 16209 8732 16210 8733 16210 8731 16210 8734 16211 8733 16211 8732 16211 8734 16212 8735 16212 8733 16212 8736 16213 8735 16213 8734 16213 8736 16214 8737 16214 8735 16214 8736 16215 8738 16215 8737 16215 8739 16216 8738 16216 8736 16216 8739 16217 8740 16217 8738 16217 8741 16218 8740 16218 8739 16218 8741 16219 8742 16219 8740 16219 8741 16220 8743 16220 8742 16220 8744 16221 8743 16221 8741 16221 8744 16222 8745 16222 8743 16222 8746 16223 8747 16223 8744 16223 8744 16224 8747 16224 8745 16224 8746 16225 8748 16225 8747 16225 8749 16226 8748 16226 8746 16226 8749 16227 8750 16227 8748 16227 8751 16228 8750 16228 8749 16228 8751 16229 8752 16229 8750 16229 8753 16230 8752 16230 8751 16230 8753 16231 8754 16231 8752 16231 8755 16232 8754 16232 8753 16232 8755 16233 8756 16233 8754 16233 8757 16234 8756 16234 8755 16234 8757 16235 8758 16235 8756 16235 8759 16236 8758 16236 8757 16236 8759 16237 8760 16237 8758 16237 8761 16238 8762 16238 8759 16238 8759 16239 8762 16239 8760 16239 8761 16240 8763 16240 8762 16240 8764 16241 8763 16241 8761 16241 8764 16242 8765 16242 8763 16242 8764 16243 8766 16243 8765 16243 8767 16244 8766 16244 8764 16244 8767 16245 8768 16245 8766 16245 8769 16246 8768 16246 8767 16246 8769 16247 8770 16247 8768 16247 8771 16248 8770 16248 8769 16248 8771 16249 8772 16249 8770 16249 8773 16250 8772 16250 8771 16250 8773 16251 8966 16251 8772 16251 8774 16252 8966 16252 8773 16252 8774 16253 8178 16253 8966 16253 8774 16254 8177 16254 8178 16254 8775 16255 8177 16255 8774 16255 8776 16256 8177 16256 8775 16256 8776 16257 8173 16257 8177 16257 8777 16258 8188 16258 8181 16258 8191 16259 8188 16259 8777 16259 8778 16260 8191 16260 8777 16260 8779 16261 8191 16261 8778 16261 8194 16262 8191 16262 8779 16262 8780 16263 8194 16263 8779 16263 8196 16264 8194 16264 8780 16264 8200 16265 8196 16265 8780 16265 8210 16266 8208 16266 8781 16266 8212 16267 8210 16267 8781 16267 8782 16268 8212 16268 8781 16268 8214 16269 8212 16269 8782 16269 8783 16270 8214 16270 8782 16270 8216 16271 8214 16271 8783 16271 8784 16272 8216 16272 8783 16272 8218 16273 8216 16273 8784 16273 8785 16274 8218 16274 8784 16274 8221 16275 8218 16275 8785 16275 8224 16276 8221 16276 8785 16276 8226 16277 8224 16277 8786 16277 8787 16278 8226 16278 8786 16278 8229 16279 8226 16279 8787 16279 8788 16280 8229 16280 8787 16280 8231 16281 8229 16281 8788 16281 8789 16282 8231 16282 8788 16282 8234 16283 8231 16283 8789 16283 8790 16284 8234 16284 8789 16284 8236 16285 8234 16285 8790 16285 8791 16286 8236 16286 8790 16286 8238 16287 8236 16287 8791 16287 8792 16288 8238 16288 8791 16288 8239 16289 8238 16289 8792 16289 8793 16290 8239 16290 8792 16290 8242 16291 8239 16291 8793 16291 8794 16292 8242 16292 8793 16292 8245 16293 8242 16293 8794 16293 8795 16294 8245 16294 8794 16294 8247 16295 8245 16295 8795 16295 8796 16296 8247 16296 8795 16296 8797 16297 8247 16297 8796 16297 8250 16298 8247 16298 8797 16298 8798 16299 8250 16299 8797 16299 8252 16300 8250 16300 8798 16300 8799 16301 8254 16301 8252 16301 8256 16302 8254 16302 8799 16302 8800 16303 8256 16303 8799 16303 8258 16304 8256 16304 8800 16304 8801 16305 8258 16305 8800 16305 8260 16306 8258 16306 8801 16306 8802 16307 8260 16307 8801 16307 8263 16308 8260 16308 8802 16308 8265 16309 8263 16309 8803 16309 8267 16310 8265 16310 8803 16310 8274 16311 8271 16311 8804 16311 8276 16312 8274 16312 8804 16312 8278 16313 8276 16313 8805 16313 8280 16314 8278 16314 8805 16314 8806 16315 8280 16315 8805 16315 8807 16316 8280 16316 8806 16316 8283 16317 8280 16317 8807 16317 8808 16318 8283 16318 8807 16318 8286 16319 8283 16319 8808 16319 8288 16320 8286 16320 8808 16320 8809 16321 8288 16321 8808 16321 8291 16322 8288 16322 8809 16322 8810 16323 8295 16323 8293 16323 8811 16324 8295 16324 8810 16324 8298 16325 8295 16325 8811 16325 8812 16326 8298 16326 8811 16326 8301 16327 8298 16327 8812 16327 8301 16328 8812 16328 8304 16328 8308 16329 8306 16329 8813 16329 8814 16330 8308 16330 8813 16330 8311 16331 8308 16331 8814 16331 8815 16332 8311 16332 8814 16332 8313 16333 8311 16333 8815 16333 8317 16334 8315 16334 8313 16334 8319 16335 8317 16335 8816 16335 8817 16336 8319 16336 8816 16336 8322 16337 8319 16337 8817 16337 8818 16338 8322 16338 8817 16338 8324 16339 8322 16339 8818 16339 8819 16340 8329 16340 8327 16340 8331 16341 8329 16341 8819 16341 8820 16342 8333 16342 8331 16342 8335 16343 8333 16343 8820 16343 8821 16344 8335 16344 8820 16344 8338 16345 8335 16345 8821 16345 8822 16346 8340 16346 8338 16346 8342 16347 8340 16347 8822 16347 8823 16348 8342 16348 8822 16348 8344 16349 8342 16349 8823 16349 8824 16350 8344 16350 8823 16350 8347 16351 8344 16351 8824 16351 8825 16352 8347 16352 8824 16352 8826 16353 8347 16353 8825 16353 8349 16354 8347 16354 8826 16354 8351 16355 8349 16355 8826 16355 8827 16356 8362 16356 8360 16356 8364 16357 8362 16357 8827 16357 8366 16358 8364 16358 8827 16358 8828 16359 8366 16359 8827 16359 8829 16360 8366 16360 8828 16360 8369 16361 8366 16361 8829 16361 8372 16362 8369 16362 8829 16362 8374 16363 8372 16363 8830 16363 8831 16364 8377 16364 8374 16364 8379 16365 8377 16365 8831 16365 8381 16366 8379 16366 8832 16366 8384 16367 8381 16367 8832 16367 8833 16368 8388 16368 8386 16368 8391 16369 8388 16369 8833 16369 8834 16370 8391 16370 8833 16370 8393 16371 8391 16371 8834 16371 8835 16372 8393 16372 8834 16372 8396 16373 8393 16373 8835 16373 8836 16374 8402 16374 8399 16374 8404 16375 8402 16375 8836 16375 8837 16376 8404 16376 8836 16376 8406 16377 8404 16377 8837 16377 8406 16378 8837 16378 8838 16378 8409 16379 8406 16379 8838 16379 8839 16380 8409 16380 8838 16380 8411 16381 8409 16381 8839 16381 8840 16382 8413 16382 8411 16382 8416 16383 8413 16383 8840 16383 8841 16384 8416 16384 8840 16384 8418 16385 8416 16385 8841 16385 8418 16386 8841 16386 8842 16386 8420 16387 8418 16387 8842 16387 8423 16388 8420 16388 8842 16388 8843 16389 8428 16389 8426 16389 8431 16390 8428 16390 8843 16390 8844 16391 8433 16391 8431 16391 8435 16392 8433 16392 8844 16392 8845 16393 8435 16393 8844 16393 8438 16394 8435 16394 8845 16394 8846 16395 8438 16395 8845 16395 8440 16396 8438 16396 8846 16396 8440 16397 8846 16397 8847 16397 8442 16398 8440 16398 8847 16398 8848 16399 8442 16399 8847 16399 8444 16400 8442 16400 8848 16400 8849 16401 8444 16401 8848 16401 8447 16402 8444 16402 8849 16402 8850 16403 8447 16403 8849 16403 8450 16404 8447 16404 8850 16404 8851 16405 8450 16405 8850 16405 8452 16406 8450 16406 8851 16406 8852 16407 8455 16407 8452 16407 8457 16408 8455 16408 8852 16408 8853 16409 8457 16409 8852 16409 8460 16410 8457 16410 8853 16410 8854 16411 8460 16411 8853 16411 8463 16412 8460 16412 8854 16412 8472 16413 8470 16413 8855 16413 8474 16414 8472 16414 8855 16414 8481 16415 8479 16415 8856 16415 8483 16416 8481 16416 8856 16416 8857 16417 8485 16417 8483 16417 8488 16418 8485 16418 8857 16418 8492 16419 8490 16419 8858 16419 8859 16420 8492 16420 8858 16420 8495 16421 8492 16421 8859 16421 8497 16422 8495 16422 8859 16422 8498 16423 8497 16423 8860 16423 8500 16424 8498 16424 8860 16424 8502 16425 8500 16425 8860 16425 8861 16426 8513 16426 8511 16426 8515 16427 8513 16427 8861 16427 8862 16428 8515 16428 8861 16428 8863 16429 8515 16429 8862 16429 8518 16430 8515 16430 8863 16430 8864 16431 8518 16431 8863 16431 8521 16432 8518 16432 8864 16432 8865 16433 8521 16433 8864 16433 8523 16434 8521 16434 8865 16434 8525 16435 8523 16435 8865 16435 8866 16436 8525 16436 8865 16436 8528 16437 8525 16437 8866 16437 8867 16438 8530 16438 8528 16438 8868 16439 8530 16439 8867 16439 8533 16440 8530 16440 8868 16440 8535 16441 8533 16441 8868 16441 8541 16442 8539 16442 8869 16442 8544 16443 8541 16443 8869 16443 8870 16444 8549 16444 8547 16444 8871 16445 8549 16445 8870 16445 8551 16446 8549 16446 8871 16446 8872 16447 8551 16447 8871 16447 8554 16448 8551 16448 8872 16448 8873 16449 8554 16449 8872 16449 8556 16450 8554 16450 8873 16450 8874 16451 8556 16451 8873 16451 8559 16452 8556 16452 8874 16452 8561 16453 8559 16453 8874 16453 8565 16454 8563 16454 8875 16454 8876 16455 8565 16455 8875 16455 8568 16456 8565 16456 8876 16456 8877 16457 8570 16457 8568 16457 8573 16458 8570 16458 8877 16458 8878 16459 8573 16459 8877 16459 8574 16460 8573 16460 8878 16460 8577 16461 8574 16461 8878 16461 8879 16462 8577 16462 8878 16462 8579 16463 8577 16463 8879 16463 8582 16464 8579 16464 8880 16464 8584 16465 8582 16465 8880 16465 8589 16466 8586 16466 8584 16466 8595 16467 8593 16467 8881 16467 8882 16468 8595 16468 8881 16468 8598 16469 8595 16469 8882 16469 8883 16470 8598 16470 8882 16470 8601 16471 8598 16471 8883 16471 8884 16472 8601 16472 8883 16472 8604 16473 8601 16473 8884 16473 8885 16474 8604 16474 8884 16474 8606 16475 8604 16475 8885 16475 8886 16476 8606 16476 8885 16476 8609 16477 8606 16477 8886 16477 8887 16478 8609 16478 8886 16478 8611 16479 8609 16479 8887 16479 8613 16480 8611 16480 8887 16480 8623 16481 8621 16481 8888 16481 8625 16482 8623 16482 8888 16482 8889 16483 8625 16483 8888 16483 8628 16484 8625 16484 8889 16484 8890 16485 8628 16485 8889 16485 8630 16486 8628 16486 8890 16486 8891 16487 8630 16487 8890 16487 8633 16488 8630 16488 8891 16488 8892 16489 8635 16489 8633 16489 8638 16490 8635 16490 8892 16490 8640 16491 8638 16491 8893 16491 8641 16492 8640 16492 8893 16492 8894 16493 8641 16493 8893 16493 8644 16494 8641 16494 8894 16494 8645 16495 8644 16495 8894 16495 8895 16496 8653 16496 8651 16496 8655 16497 8653 16497 8895 16497 8896 16498 8657 16498 8655 16498 8659 16499 8657 16499 8896 16499 8897 16500 8667 16500 8666 16500 8898 16501 8667 16501 8897 16501 8670 16502 8667 16502 8898 16502 8673 16503 8670 16503 8898 16503 8675 16504 8673 16504 8899 16504 8677 16505 8675 16505 8899 16505 8680 16506 8677 16506 8900 16506 8683 16507 8680 16507 8900 16507 8685 16508 8683 16508 8901 16508 8902 16509 8685 16509 8901 16509 8687 16510 8685 16510 8902 16510 8903 16511 8687 16511 8902 16511 8690 16512 8687 16512 8903 16512 8904 16513 8690 16513 8903 16513 8692 16514 8690 16514 8904 16514 8905 16515 8692 16515 8904 16515 8694 16516 8692 16516 8905 16516 8906 16517 8696 16517 8694 16517 8698 16518 8696 16518 8906 16518 8700 16519 8698 16519 8907 16519 8702 16520 8700 16520 8907 16520 8908 16521 8702 16521 8907 16521 8704 16522 8702 16522 8908 16522 8909 16523 8706 16523 8704 16523 8708 16524 8706 16524 8909 16524 8910 16525 8708 16525 8909 16525 8710 16526 8708 16526 8910 16526 8911 16527 8710 16527 8910 16527 8712 16528 8710 16528 8911 16528 8912 16529 8712 16529 8911 16529 8715 16530 8712 16530 8912 16530 8717 16531 8715 16531 8913 16531 8720 16532 8717 16532 8913 16532 8914 16533 8720 16533 8913 16533 8722 16534 8720 16534 8914 16534 8915 16535 8722 16535 8914 16535 8724 16536 8722 16536 8915 16536 8916 16537 8724 16537 8915 16537 8727 16538 8724 16538 8916 16538 8729 16539 8727 16539 8916 16539 8917 16540 8729 16540 8916 16540 8732 16541 8729 16541 8917 16541 8918 16542 8732 16542 8917 16542 8734 16543 8732 16543 8918 16543 8919 16544 8734 16544 8918 16544 8736 16545 8734 16545 8919 16545 8920 16546 8736 16546 8919 16546 8739 16547 8736 16547 8920 16547 8921 16548 8741 16548 8739 16548 8922 16549 8741 16549 8921 16549 8744 16550 8741 16550 8922 16550 8746 16551 8744 16551 8922 16551 8923 16552 8746 16552 8922 16552 8749 16553 8746 16553 8923 16553 8924 16554 8749 16554 8923 16554 8751 16555 8749 16555 8924 16555 8753 16556 8751 16556 8924 16556 8759 16557 8757 16557 8925 16557 8761 16558 8759 16558 8925 16558 8767 16559 8764 16559 8926 16559 8769 16560 8767 16560 8926 16560 8775 16561 8774 16561 8927 16561 8776 16562 8775 16562 8927 16562 8928 16563 8776 16563 8927 16563 8173 16564 8776 16564 8928 16564 8929 16565 8173 16565 8928 16565 8171 16566 8173 16566 8929 16566 8930 16567 8171 16567 8929 16567 8166 16568 8171 16568 8930 16568 8932 16569 8780 16569 8779 16569 8932 16570 8200 16570 8780 16570 8931 16571 8200 16571 8932 16571 8931 16572 8202 16572 8200 16572 8933 16573 8202 16573 8931 16573 8933 16574 8203 16574 8202 16574 8179 16575 8203 16575 8933 16575 8179 16576 8206 16576 8203 16576 8180 16577 8206 16577 8179 16577 8180 16578 8208 16578 8206 16578 8182 16579 8208 16579 8180 16579 8182 16580 8781 16580 8208 16580 8184 16581 8781 16581 8182 16581 8185 16582 8781 16582 8184 16582 8185 16583 8782 16583 8781 16583 8187 16584 8782 16584 8185 16584 8187 16585 8783 16585 8782 16585 8189 16586 8783 16586 8187 16586 8190 16587 8783 16587 8189 16587 8190 16588 8784 16588 8783 16588 8192 16589 8784 16589 8190 16589 8193 16590 8784 16590 8192 16590 8193 16591 8785 16591 8784 16591 8195 16592 8785 16592 8193 16592 8195 16593 8224 16593 8785 16593 8197 16594 8224 16594 8195 16594 8198 16595 8224 16595 8197 16595 8198 16596 8786 16596 8224 16596 8199 16597 8786 16597 8198 16597 8199 16598 8787 16598 8786 16598 8201 16599 8787 16599 8199 16599 8204 16600 8787 16600 8201 16600 8204 16601 8788 16601 8787 16601 8205 16602 8788 16602 8204 16602 8205 16603 8789 16603 8788 16603 8207 16604 8789 16604 8205 16604 8209 16605 8789 16605 8207 16605 8209 16606 8790 16606 8789 16606 8211 16607 8790 16607 8209 16607 8211 16608 8791 16608 8790 16608 8213 16609 8791 16609 8211 16609 8213 16610 8792 16610 8791 16610 8215 16611 8792 16611 8213 16611 8934 16612 8792 16612 8215 16612 8934 16613 8793 16613 8792 16613 8217 16614 8793 16614 8934 16614 8217 16615 8794 16615 8793 16615 8219 16616 8794 16616 8217 16616 8220 16617 8794 16617 8219 16617 8220 16618 8795 16618 8794 16618 8222 16619 8795 16619 8220 16619 8223 16620 8795 16620 8222 16620 8223 16621 8796 16621 8795 16621 8225 16622 8796 16622 8223 16622 8225 16623 8797 16623 8796 16623 8227 16624 8797 16624 8225 16624 8227 16625 8798 16625 8797 16625 8228 16626 8798 16626 8227 16626 8228 16627 8252 16627 8798 16627 8230 16628 8252 16628 8228 16628 8935 16629 8252 16629 8230 16629 8935 16630 8799 16630 8252 16630 8232 16631 8799 16631 8935 16631 8232 16632 8800 16632 8799 16632 8233 16633 8800 16633 8232 16633 8233 16634 8801 16634 8800 16634 8235 16635 8801 16635 8233 16635 8237 16636 8801 16636 8235 16636 8237 16637 8802 16637 8801 16637 8237 16638 8263 16638 8802 16638 8240 16639 8263 16639 8237 16639 8240 16640 8803 16640 8263 16640 8241 16641 8803 16641 8240 16641 8241 16642 8267 16642 8803 16642 8243 16643 8267 16643 8241 16643 8244 16644 8267 16644 8243 16644 8244 16645 8269 16645 8267 16645 8246 16646 8269 16646 8244 16646 8246 16647 8271 16647 8269 16647 8248 16648 8271 16648 8246 16648 8248 16649 8804 16649 8271 16649 8249 16650 8804 16650 8248 16650 8251 16651 8804 16651 8249 16651 8251 16652 8276 16652 8804 16652 8936 16653 8276 16653 8251 16653 8936 16654 8805 16654 8276 16654 8253 16655 8805 16655 8936 16655 8255 16656 8805 16656 8253 16656 8255 16657 8806 16657 8805 16657 8255 16658 8807 16658 8806 16658 8257 16659 8807 16659 8255 16659 8259 16660 8808 16660 8257 16660 8257 16661 8808 16661 8807 16661 8261 16662 8808 16662 8259 16662 8261 16663 8809 16663 8808 16663 8262 16664 8809 16664 8261 16664 8264 16665 8809 16665 8262 16665 8264 16666 8291 16666 8809 16666 8266 16667 8291 16667 8264 16667 8266 16668 8293 16668 8291 16668 8268 16669 8293 16669 8266 16669 8268 16670 8810 16670 8293 16670 8270 16671 8810 16671 8268 16671 8270 16672 8811 16672 8810 16672 8272 16673 8811 16673 8270 16673 8273 16674 8811 16674 8272 16674 8273 16675 8812 16675 8811 16675 8275 16676 8812 16676 8273 16676 8275 16677 8304 16677 8812 16677 8277 16678 8304 16678 8275 16678 8277 16679 8306 16679 8304 16679 8279 16680 8306 16680 8277 16680 8279 16681 8813 16681 8306 16681 8281 16682 8813 16682 8279 16682 8281 16683 8814 16683 8813 16683 8282 16684 8814 16684 8281 16684 8282 16685 8815 16685 8814 16685 8284 16686 8815 16686 8282 16686 8285 16687 8815 16687 8284 16687 8285 16688 8313 16688 8815 16688 8289 16689 8313 16689 8285 16689 8289 16690 8317 16690 8313 16690 8290 16691 8317 16691 8289 16691 8292 16692 8317 16692 8290 16692 8292 16693 8816 16693 8317 16693 8292 16694 8817 16694 8816 16694 8294 16695 8817 16695 8292 16695 8296 16696 8817 16696 8294 16696 8296 16697 8818 16697 8817 16697 8297 16698 8818 16698 8296 16698 8299 16699 8818 16699 8297 16699 8299 16700 8324 16700 8818 16700 8299 16701 8327 16701 8324 16701 8300 16702 8327 16702 8299 16702 8302 16703 8327 16703 8300 16703 8302 16704 8819 16704 8327 16704 8303 16705 8819 16705 8302 16705 8305 16706 8819 16706 8303 16706 8305 16707 8331 16707 8819 16707 8307 16708 8331 16708 8305 16708 8307 16709 8820 16709 8331 16709 8309 16710 8820 16710 8307 16710 8309 16711 8821 16711 8820 16711 8310 16712 8821 16712 8309 16712 8310 16713 8338 16713 8821 16713 8312 16714 8338 16714 8310 16714 8314 16715 8338 16715 8312 16715 8314 16716 8822 16716 8338 16716 8316 16717 8822 16717 8314 16717 8316 16718 8823 16718 8822 16718 8318 16719 8823 16719 8316 16719 8318 16720 8824 16720 8823 16720 8320 16721 8824 16721 8318 16721 8321 16722 8824 16722 8320 16722 8321 16723 8825 16723 8824 16723 8323 16724 8825 16724 8321 16724 8323 16725 8826 16725 8825 16725 8325 16726 8826 16726 8323 16726 8326 16727 8826 16727 8325 16727 8326 16728 8351 16728 8826 16728 8328 16729 8351 16729 8326 16729 8328 16730 8354 16730 8351 16730 8330 16731 8354 16731 8328 16731 8330 16732 8356 16732 8354 16732 8332 16733 8356 16733 8330 16733 8332 16734 8358 16734 8356 16734 8334 16735 8358 16735 8332 16735 8334 16736 8360 16736 8358 16736 8336 16737 8360 16737 8334 16737 8336 16738 8827 16738 8360 16738 8337 16739 8827 16739 8336 16739 8339 16740 8827 16740 8337 16740 8341 16741 8827 16741 8339 16741 8341 16742 8828 16742 8827 16742 8343 16743 8828 16743 8341 16743 8343 16744 8829 16744 8828 16744 8345 16745 8829 16745 8343 16745 8345 16746 8372 16746 8829 16746 8345 16747 8830 16747 8372 16747 8346 16748 8830 16748 8345 16748 8346 16749 8374 16749 8830 16749 8348 16750 8374 16750 8346 16750 8350 16751 8374 16751 8348 16751 8350 16752 8831 16752 8374 16752 8352 16753 8831 16753 8350 16753 8352 16754 8379 16754 8831 16754 8353 16755 8832 16755 8352 16755 8352 16756 8832 16756 8379 16756 8355 16757 8832 16757 8353 16757 8357 16758 8384 16758 8355 16758 8355 16759 8384 16759 8832 16759 8359 16760 8384 16760 8357 16760 8359 16761 8386 16761 8384 16761 8361 16762 8386 16762 8359 16762 8361 16763 8833 16763 8386 16763 8363 16764 8833 16764 8361 16764 8365 16765 8833 16765 8363 16765 8365 16766 8834 16766 8833 16766 8367 16767 8834 16767 8365 16767 8368 16768 8834 16768 8367 16768 8368 16769 8835 16769 8834 16769 8368 16770 8396 16770 8835 16770 8370 16771 8396 16771 8368 16771 8371 16772 8396 16772 8370 16772 8371 16773 8398 16773 8396 16773 8371 16774 8399 16774 8398 16774 8373 16775 8399 16775 8371 16775 8373 16776 8836 16776 8399 16776 8375 16777 8836 16777 8373 16777 8937 16778 8836 16778 8375 16778 8937 16779 8837 16779 8836 16779 8380 16780 8837 16780 8937 16780 8380 16781 8838 16781 8837 16781 8382 16782 8838 16782 8380 16782 8382 16783 8839 16783 8838 16783 8383 16784 8839 16784 8382 16784 8383 16785 8411 16785 8839 16785 8385 16786 8411 16786 8383 16786 8385 16787 8840 16787 8411 16787 8387 16788 8840 16788 8385 16788 8387 16789 8841 16789 8840 16789 8389 16790 8841 16790 8387 16790 8390 16791 8841 16791 8389 16791 8390 16792 8842 16792 8841 16792 8392 16793 8842 16793 8390 16793 8394 16794 8842 16794 8392 16794 8394 16795 8423 16795 8842 16795 8394 16796 8425 16796 8423 16796 8395 16797 8425 16797 8394 16797 8397 16798 8425 16798 8395 16798 8397 16799 8426 16799 8425 16799 8400 16800 8426 16800 8397 16800 8400 16801 8843 16801 8426 16801 8401 16802 8843 16802 8400 16802 8403 16803 8843 16803 8401 16803 8403 16804 8431 16804 8843 16804 8405 16805 8431 16805 8403 16805 8405 16806 8844 16806 8431 16806 8407 16807 8844 16807 8405 16807 8408 16808 8844 16808 8407 16808 8408 16809 8845 16809 8844 16809 8410 16810 8845 16810 8408 16810 8410 16811 8846 16811 8845 16811 8412 16812 8846 16812 8410 16812 8414 16813 8846 16813 8412 16813 8414 16814 8847 16814 8846 16814 8415 16815 8847 16815 8414 16815 8417 16816 8847 16816 8415 16816 8417 16817 8848 16817 8847 16817 8419 16818 8848 16818 8417 16818 8419 16819 8849 16819 8848 16819 8421 16820 8849 16820 8419 16820 8421 16821 8850 16821 8849 16821 8422 16822 8850 16822 8421 16822 8424 16823 8850 16823 8422 16823 8424 16824 8851 16824 8850 16824 8427 16825 8851 16825 8424 16825 8427 16826 8452 16826 8851 16826 8429 16827 8452 16827 8427 16827 8430 16828 8452 16828 8429 16828 8430 16829 8852 16829 8452 16829 8432 16830 8852 16830 8430 16830 8434 16831 8852 16831 8432 16831 8434 16832 8853 16832 8852 16832 8434 16833 8854 16833 8853 16833 8938 16834 8854 16834 8434 16834 8938 16835 8463 16835 8854 16835 8437 16836 8463 16836 8938 16836 8437 16837 8464 16837 8463 16837 8439 16838 8464 16838 8437 16838 8439 16839 8467 16839 8464 16839 8441 16840 8467 16840 8439 16840 8441 16841 8468 16841 8467 16841 8441 16842 8470 16842 8468 16842 8443 16843 8470 16843 8441 16843 8443 16844 8855 16844 8470 16844 8445 16845 8855 16845 8443 16845 8446 16846 8855 16846 8445 16846 8446 16847 8474 16847 8855 16847 8448 16848 8474 16848 8446 16848 8448 16849 8477 16849 8474 16849 8449 16850 8477 16850 8448 16850 8449 16851 8479 16851 8477 16851 8451 16852 8479 16852 8449 16852 8453 16853 8479 16853 8451 16853 8453 16854 8856 16854 8479 16854 8454 16855 8856 16855 8453 16855 8456 16856 8856 16856 8454 16856 8456 16857 8483 16857 8856 16857 8458 16858 8483 16858 8456 16858 8458 16859 8857 16859 8483 16859 8459 16860 8857 16860 8458 16860 8461 16861 8857 16861 8459 16861 8461 16862 8488 16862 8857 16862 8462 16863 8488 16863 8461 16863 8462 16864 8490 16864 8488 16864 8465 16865 8490 16865 8462 16865 8465 16866 8858 16866 8490 16866 8466 16867 8858 16867 8465 16867 8466 16868 8859 16868 8858 16868 8469 16869 8859 16869 8466 16869 8471 16870 8859 16870 8469 16870 8471 16871 8497 16871 8859 16871 8473 16872 8497 16872 8471 16872 8473 16873 8860 16873 8497 16873 8475 16874 8860 16874 8473 16874 8476 16875 8860 16875 8475 16875 8476 16876 8502 16876 8860 16876 8478 16877 8502 16877 8476 16877 8478 16878 8505 16878 8502 16878 8480 16879 8505 16879 8478 16879 8480 16880 8507 16880 8505 16880 8482 16881 8507 16881 8480 16881 8482 16882 8509 16882 8507 16882 8939 16883 8509 16883 8482 16883 8939 16884 8511 16884 8509 16884 8484 16885 8511 16885 8939 16885 8484 16886 8861 16886 8511 16886 8486 16887 8861 16887 8484 16887 8487 16888 8861 16888 8486 16888 8487 16889 8862 16889 8861 16889 8489 16890 8862 16890 8487 16890 8489 16891 8863 16891 8862 16891 8491 16892 8863 16892 8489 16892 8491 16893 8864 16893 8863 16893 8493 16894 8864 16894 8491 16894 8494 16895 8864 16895 8493 16895 8494 16896 8865 16896 8864 16896 8496 16897 8865 16897 8494 16897 8496 16898 8866 16898 8865 16898 8499 16899 8866 16899 8496 16899 8501 16900 8866 16900 8499 16900 8501 16901 8528 16901 8866 16901 8503 16902 8528 16902 8501 16902 8503 16903 8867 16903 8528 16903 8504 16904 8867 16904 8503 16904 8504 16905 8868 16905 8867 16905 8506 16906 8868 16906 8504 16906 8508 16907 8868 16907 8506 16907 8508 16908 8535 16908 8868 16908 8510 16909 8535 16909 8508 16909 8510 16910 8537 16910 8535 16910 8512 16911 8537 16911 8510 16911 8514 16912 8537 16912 8512 16912 8514 16913 8539 16913 8537 16913 8516 16914 8539 16914 8514 16914 8516 16915 8869 16915 8539 16915 8517 16916 8869 16916 8516 16916 8519 16917 8869 16917 8517 16917 8519 16918 8544 16918 8869 16918 8520 16919 8544 16919 8519 16919 8520 16920 8546 16920 8544 16920 8520 16921 8547 16921 8546 16921 8522 16922 8547 16922 8520 16922 8524 16923 8547 16923 8522 16923 8524 16924 8870 16924 8547 16924 8524 16925 8871 16925 8870 16925 8526 16926 8871 16926 8524 16926 8526 16927 8872 16927 8871 16927 8527 16928 8872 16928 8526 16928 8529 16929 8872 16929 8527 16929 8529 16930 8873 16930 8872 16930 8531 16931 8873 16931 8529 16931 8532 16932 8873 16932 8531 16932 8532 16933 8874 16933 8873 16933 8534 16934 8874 16934 8532 16934 8536 16935 8874 16935 8534 16935 8536 16936 8561 16936 8874 16936 8538 16937 8561 16937 8536 16937 8538 16938 8563 16938 8561 16938 8540 16939 8563 16939 8538 16939 8540 16940 8875 16940 8563 16940 8540 16941 8876 16941 8875 16941 8542 16942 8876 16942 8540 16942 8543 16943 8876 16943 8542 16943 8543 16944 8568 16944 8876 16944 8543 16945 8877 16945 8568 16945 8545 16946 8877 16946 8543 16946 8940 16947 8877 16947 8545 16947 8940 16948 8878 16948 8877 16948 8550 16949 8878 16949 8940 16949 8550 16950 8879 16950 8878 16950 8552 16951 8879 16951 8550 16951 8553 16952 8879 16952 8552 16952 8553 16953 8579 16953 8879 16953 8941 16954 8579 16954 8553 16954 8941 16955 8880 16955 8579 16955 8555 16956 8880 16956 8941 16956 8557 16957 8880 16957 8555 16957 8557 16958 8584 16958 8880 16958 8558 16959 8584 16959 8557 16959 8558 16960 8589 16960 8584 16960 8560 16961 8589 16961 8558 16961 8560 16962 8591 16962 8589 16962 8562 16963 8591 16963 8560 16963 8564 16964 8591 16964 8562 16964 8564 16965 8593 16965 8591 16965 8566 16966 8593 16966 8564 16966 8566 16967 8881 16967 8593 16967 8567 16968 8881 16968 8566 16968 8567 16969 8882 16969 8881 16969 8569 16970 8882 16970 8567 16970 8569 16971 8883 16971 8882 16971 8571 16972 8883 16972 8569 16972 8572 16973 8883 16973 8571 16973 8572 16974 8884 16974 8883 16974 8575 16975 8884 16975 8572 16975 8576 16976 8884 16976 8575 16976 8576 16977 8885 16977 8884 16977 8578 16978 8885 16978 8576 16978 8580 16979 8885 16979 8578 16979 8580 16980 8886 16980 8885 16980 8581 16981 8886 16981 8580 16981 8581 16982 8887 16982 8886 16982 8583 16983 8887 16983 8581 16983 8585 16984 8887 16984 8583 16984 8585 16985 8613 16985 8887 16985 8587 16986 8613 16986 8585 16986 8587 16987 8616 16987 8613 16987 8588 16988 8616 16988 8587 16988 8590 16989 8616 16989 8588 16989 8590 16990 8618 16990 8616 16990 8592 16991 8618 16991 8590 16991 8592 16992 8621 16992 8618 16992 8594 16993 8621 16993 8592 16993 8594 16994 8888 16994 8621 16994 8596 16995 8888 16995 8594 16995 8597 16996 8888 16996 8596 16996 8597 16997 8889 16997 8888 16997 8599 16998 8889 16998 8597 16998 8600 16999 8889 16999 8599 16999 8600 17000 8890 17000 8889 17000 8602 17001 8890 17001 8600 17001 8603 17002 8890 17002 8602 17002 8603 17003 8891 17003 8890 17003 8605 17004 8891 17004 8603 17004 8605 17005 8633 17005 8891 17005 8607 17006 8633 17006 8605 17006 8607 17007 8892 17007 8633 17007 8608 17008 8892 17008 8607 17008 8610 17009 8892 17009 8608 17009 8610 17010 8638 17010 8892 17010 8612 17011 8638 17011 8610 17011 8612 17012 8893 17012 8638 17012 8614 17013 8893 17013 8612 17013 8615 17014 8893 17014 8614 17014 8615 17015 8894 17015 8893 17015 8617 17016 8894 17016 8615 17016 8619 17017 8894 17017 8617 17017 8619 17018 8645 17018 8894 17018 8620 17019 8645 17019 8619 17019 8620 17020 8647 17020 8645 17020 8622 17021 8647 17021 8620 17021 8622 17022 8649 17022 8647 17022 8624 17023 8649 17023 8622 17023 8624 17024 8651 17024 8649 17024 8626 17025 8651 17025 8624 17025 8626 17026 8895 17026 8651 17026 8627 17027 8895 17027 8626 17027 8629 17028 8895 17028 8627 17028 8629 17029 8655 17029 8895 17029 8631 17030 8655 17030 8629 17030 8631 17031 8896 17031 8655 17031 8632 17032 8896 17032 8631 17032 8634 17033 8896 17033 8632 17033 8634 17034 8659 17034 8896 17034 8636 17035 8659 17035 8634 17035 8636 17036 8661 17036 8659 17036 8636 17037 8663 17037 8661 17037 8637 17038 8663 17038 8636 17038 8639 17039 8666 17039 8637 17039 8637 17040 8666 17040 8663 17040 8642 17041 8666 17041 8639 17041 8642 17042 8897 17042 8666 17042 8642 17043 8898 17043 8897 17043 8643 17044 8898 17044 8642 17044 8646 17045 8898 17045 8643 17045 8646 17046 8673 17046 8898 17046 8648 17047 8673 17047 8646 17047 8648 17048 8899 17048 8673 17048 8650 17049 8899 17049 8648 17049 8650 17050 8677 17050 8899 17050 8652 17051 8677 17051 8650 17051 8652 17052 8900 17052 8677 17052 8654 17053 8900 17053 8652 17053 8656 17054 8900 17054 8654 17054 8656 17055 8683 17055 8900 17055 8658 17056 8683 17056 8656 17056 8658 17057 8901 17057 8683 17057 8660 17058 8901 17058 8658 17058 8662 17059 8901 17059 8660 17059 8662 17060 8902 17060 8901 17060 8664 17061 8902 17061 8662 17061 8664 17062 8903 17062 8902 17062 8665 17063 8903 17063 8664 17063 8665 17064 8904 17064 8903 17064 8668 17065 8904 17065 8665 17065 8668 17066 8905 17066 8904 17066 8669 17067 8905 17067 8668 17067 8671 17068 8694 17068 8669 17068 8669 17069 8694 17069 8905 17069 8672 17070 8694 17070 8671 17070 8672 17071 8906 17071 8694 17071 8674 17072 8906 17072 8672 17072 8674 17073 8698 17073 8906 17073 8676 17074 8698 17074 8674 17074 8676 17075 8907 17075 8698 17075 8678 17076 8907 17076 8676 17076 8679 17077 8907 17077 8678 17077 8679 17078 8908 17078 8907 17078 8681 17079 8908 17079 8679 17079 8682 17080 8908 17080 8681 17080 8682 17081 8704 17081 8908 17081 8684 17082 8704 17082 8682 17082 8684 17083 8909 17083 8704 17083 8686 17084 8909 17084 8684 17084 8686 17085 8910 17085 8909 17085 8688 17086 8910 17086 8686 17086 8688 17087 8911 17087 8910 17087 8689 17088 8911 17088 8688 17088 8689 17089 8912 17089 8911 17089 8691 17090 8912 17090 8689 17090 8691 17091 8715 17091 8912 17091 8693 17092 8715 17092 8691 17092 8693 17093 8913 17093 8715 17093 8942 17094 8913 17094 8693 17094 8943 17095 8913 17095 8942 17095 8943 17096 8914 17096 8913 17096 8697 17097 8914 17097 8943 17097 8699 17098 8914 17098 8697 17098 8699 17099 8915 17099 8914 17099 8701 17100 8915 17100 8699 17100 8701 17101 8916 17101 8915 17101 8944 17102 8916 17102 8701 17102 8945 17103 8916 17103 8944 17103 8945 17104 8917 17104 8916 17104 8705 17105 8917 17105 8945 17105 8707 17106 8917 17106 8705 17106 8707 17107 8918 17107 8917 17107 8709 17108 8918 17108 8707 17108 8709 17109 8919 17109 8918 17109 8711 17110 8919 17110 8709 17110 8713 17111 8919 17111 8711 17111 8713 17112 8920 17112 8919 17112 8714 17113 8739 17113 8713 17113 8713 17114 8739 17114 8920 17114 8716 17115 8739 17115 8714 17115 8716 17116 8921 17116 8739 17116 8718 17117 8921 17117 8716 17117 8719 17118 8921 17118 8718 17118 8719 17119 8922 17119 8921 17119 8721 17120 8922 17120 8719 17120 8721 17121 8923 17121 8922 17121 8723 17122 8923 17122 8721 17122 8725 17123 8923 17123 8723 17123 8725 17124 8924 17124 8923 17124 8726 17125 8924 17125 8725 17125 8728 17126 8924 17126 8726 17126 8728 17127 8753 17127 8924 17127 8730 17128 8753 17128 8728 17128 8730 17129 8755 17129 8753 17129 8731 17130 8755 17130 8730 17130 8731 17131 8757 17131 8755 17131 8731 17132 8925 17132 8757 17132 8733 17133 8925 17133 8731 17133 8735 17134 8925 17134 8733 17134 8735 17135 8761 17135 8925 17135 8737 17136 8761 17136 8735 17136 8737 17137 8764 17137 8761 17137 8738 17138 8764 17138 8737 17138 8738 17139 8926 17139 8764 17139 8740 17140 8926 17140 8738 17140 8742 17141 8926 17141 8740 17141 8742 17142 8769 17142 8926 17142 8743 17143 8769 17143 8742 17143 8743 17144 8771 17144 8769 17144 8745 17145 8771 17145 8743 17145 8745 17146 8773 17146 8771 17146 8747 17147 8774 17147 8745 17147 8745 17148 8774 17148 8773 17148 8748 17149 8774 17149 8747 17149 8748 17150 8927 17150 8774 17150 8750 17151 8927 17151 8748 17151 8752 17152 8927 17152 8750 17152 8752 17153 8928 17153 8927 17153 8754 17154 8928 17154 8752 17154 8754 17155 8929 17155 8928 17155 8754 17156 8930 17156 8929 17156 8756 17157 8930 17157 8754 17157 8758 17158 8930 17158 8756 17158 8760 17159 8166 17159 8758 17159 8758 17160 8166 17160 8930 17160 8762 17161 8166 17161 8760 17161 8762 17162 8164 17162 8166 17162 8763 17163 8164 17163 8762 17163 8763 17164 8168 17164 8164 17164 8765 17165 8168 17165 8763 17165 8765 17166 8170 17166 8168 17166 8766 17167 8170 17167 8765 17167 8768 17168 8170 17168 8766 17168 8768 17169 8172 17169 8170 17169 8217 17170 8934 17170 8215 17170 8232 17171 8935 17171 8230 17171 8253 17172 8936 17172 8251 17172 8289 17173 8285 17173 8287 17173 8937 17174 8375 17174 8376 17174 8378 17175 8937 17175 8376 17175 8380 17176 8937 17176 8378 17176 8938 17177 8434 17177 8436 17177 8437 17178 8938 17178 8436 17178 8484 17179 8939 17179 8482 17179 8548 17180 8940 17180 8545 17180 8550 17181 8940 17181 8548 17181 8555 17182 8941 17182 8553 17182 8695 17183 8942 17183 8693 17183 8943 17184 8942 17184 8695 17184 8697 17185 8943 17185 8695 17185 8703 17186 8944 17186 8701 17186 8945 17187 8944 17187 8703 17187 8705 17188 8945 17188 8703 17188 8770 17189 8172 17189 8768 17189 8175 17190 8172 17190 8770 17190 8772 17191 8175 17191 8770 17191 8968 17192 8772 17192 8966 17192 8948 17193 8946 17193 8984 17193 8950 17194 8947 17194 8946 17194 8949 17195 8947 17195 8950 17195 8950 17196 8946 17196 8948 17196 8951 17197 8949 17197 8950 17197 8953 17198 8951 17198 8950 17198 8953 17199 8950 17199 8948 17199 8174 17200 8949 17200 8951 17200 8954 17201 8953 17201 8948 17201 8954 17202 8948 17202 8952 17202 8174 17203 8951 17203 8953 17203 8956 17204 8954 17204 8952 17204 8956 17205 8952 17205 8955 17205 8176 17206 8174 17206 8953 17206 8957 17207 8954 17207 8956 17207 8957 17208 8953 17208 8954 17208 8176 17209 8953 17209 8957 17209 8959 17210 8176 17210 8957 17210 8955 17211 8958 17211 8956 17211 8959 17212 8957 17212 8956 17212 8958 17213 8959 17213 8956 17213 8958 17214 8962 17214 8959 17214 8959 17215 8177 17215 8176 17215 8958 17216 8955 17216 8961 17216 8177 17217 8959 17217 8962 17217 8963 17218 8958 17218 8961 17218 8963 17219 8962 17219 8958 17219 8961 17220 8955 17220 8960 17220 8177 17221 8962 17221 8963 17221 8964 17222 8963 17222 8961 17222 8963 17223 8178 17223 8177 17223 8964 17224 8178 17224 8963 17224 8965 17225 8961 17225 8960 17225 8965 17226 8964 17226 8961 17226 8966 17227 8964 17227 8965 17227 8966 17228 8178 17228 8964 17228 8967 17229 8965 17229 8960 17229 8968 17230 8965 17230 8967 17230 8967 17231 8960 17231 8969 17231 8968 17232 8966 17232 8965 17232 8970 17233 8968 17233 8967 17233 8970 17234 8772 17234 8968 17234 8972 17235 8970 17235 8967 17235 8972 17236 8967 17236 8969 17236 8175 17237 8772 17237 8970 17237 8175 17238 8970 17238 8972 17238 8972 17239 8969 17239 8971 17239 8973 17240 8175 17240 8972 17240 8974 17241 8972 17241 8971 17241 8172 17242 8175 17242 8973 17242 8973 17243 8972 17243 8974 17243 8973 17244 8976 17244 8172 17244 8976 17245 8973 17245 8974 17245 8977 17246 8975 17246 8971 17246 8975 17247 8974 17247 8971 17247 8975 17248 8976 17248 8974 17248 8978 17249 8976 17249 8975 17249 8169 17250 8976 17250 8978 17250 8979 17251 8975 17251 8977 17251 8978 17252 8975 17252 8979 17252 8982 17253 8979 17253 8977 17253 8980 17254 8978 17254 8979 17254 8169 17255 8978 17255 8980 17255 8980 17256 8165 17256 8169 17256 8981 17257 8980 17257 8979 17257 8982 17258 8981 17258 8979 17258 8165 17259 8980 17259 8981 17259 8981 17260 8982 17260 8983 17260 8984 17261 8983 17261 8982 17261 8985 17262 8983 17262 8984 17262 8986 17263 8165 17263 8981 17263 8986 17264 8981 17264 8983 17264 8985 17265 8167 17265 8983 17265 8167 17266 8986 17266 8983 17266 8947 17267 8985 17267 8984 17267 8947 17268 8167 17268 8985 17268 8947 17269 8984 17269 8946 17269 8949 17270 8167 17270 8947 17270 8960 17271 8955 17271 8952 17271 8960 17272 8977 17272 8971 17272 8960 17273 8982 17273 8977 17273 8960 17274 8984 17274 8982 17274 8960 17275 8952 17275 8948 17275 8960 17276 8948 17276 8984 17276 8960 17277 8971 17277 8969 17277 8988 17278 8987 17278 8996 17278 8996 17279 8987 17279 8993 17279 8987 17280 8989 17280 8993 17280 8993 17281 8989 17281 8994 17281 8989 17282 8990 17282 8994 17282 8994 17283 8990 17283 8998 17283 8990 17284 8997 17284 8998 17284 8990 17285 8991 17285 8997 17285 8991 17286 8992 17286 8997 17286 8997 17287 8992 17287 8995 17287 8992 13753 8996 13753 8995 13753 8992 13754 8988 13754 8996 13754 8994 17288 9001 17288 8999 17288 8994 17289 8999 17289 9000 17289 8998 17290 9003 17290 9001 17290 8998 17291 9001 17291 8994 17291 8998 17292 9002 17292 9003 17292 8993 17293 9000 17293 9004 17293 8993 17294 8994 17294 9000 17294 9005 17295 8993 17295 9004 17295 8997 17296 9006 17296 9002 17296 8997 17297 9002 17297 8998 17297 8996 17298 8993 17298 9005 17298 9007 17299 8996 17299 9005 17299 9008 17300 9006 17300 8997 17300 9009 17301 8996 17301 9007 17301 9008 17302 8997 17302 8995 17302 9010 17303 9008 17303 8995 17303 9011 17304 8996 17304 9009 17304 9011 17305 8995 17305 8996 17305 9011 17306 9010 17306 8995 17306 8987 17307 8990 17307 8989 17307 8992 17308 8991 17308 8988 17308 8988 17309 8991 17309 8987 17309 8987 17310 8991 17310 8990 17310 9026 17311 9003 17311 9002 17311 9012 17312 9026 17312 9002 17312 9013 17313 9012 17313 9002 17313 9013 17314 9002 17314 9006 17314 9014 17315 9013 17315 9006 17315 9014 17316 9006 17316 9008 17316 9015 17317 9014 17317 9008 17317 9015 17318 9008 17318 9010 17318 9016 17319 9015 17319 9010 17319 9016 17320 9010 17320 9011 17320 9017 17321 9016 17321 9011 17321 9017 17322 9011 17322 9009 17322 9018 17323 9017 17323 9009 17323 9018 17324 9009 17324 9007 17324 9019 17325 9018 17325 9007 17325 9020 17326 9019 17326 9007 17326 9020 17327 9007 17327 9005 17327 9021 17328 9020 17328 9005 17328 9021 17329 9005 17329 9004 17329 9022 17330 9021 17330 9004 17330 9022 17331 9004 17331 9000 17331 9023 17332 9022 17332 9000 17332 9024 17333 9000 17333 8999 17333 9024 17334 9023 17334 9000 17334 9025 17335 8999 17335 9001 17335 9025 17336 9024 17336 8999 17336 9025 17337 9001 17337 9003 17337 9026 17338 9025 17338 9003 17338 8777 17339 9020 17339 9021 17339 8181 17340 9020 17340 8777 17340 8181 17341 9019 17341 9020 17341 8778 17342 8777 17342 9021 17342 8778 17343 9021 17343 9022 17343 8181 17344 9018 17344 9019 17344 8778 17345 9022 17345 9023 17345 8779 17346 8778 17346 9023 17346 8181 17347 9017 17347 9018 17347 8779 17348 9023 17348 9024 17348 8186 17349 9017 17349 8181 17349 8932 17350 8779 17350 9024 17350 8186 17351 9016 17351 9017 17351 8932 17352 9024 17352 9025 17352 9016 17353 8186 17353 8183 17353 9015 17354 9016 17354 8183 17354 9025 17355 8931 17355 8932 17355 9026 17356 8931 17356 9025 17356 9015 17357 8183 17357 8179 17357 9014 17358 9015 17358 8179 17358 9012 17359 8931 17359 9026 17359 9014 17360 8179 17360 8933 17360 9013 17361 8931 17361 9012 17361 9013 17362 9014 17362 8933 17362 9013 17363 8933 17363 8931 17363

+
+ + + +

9047 17364 9027 17364 9028 17364 9028 17365 9027 17365 9029 17365 9027 17366 9030 17366 9029 17366 9029 17367 9030 17367 9031 17367 9030 17368 9032 17368 9031 17368 9031 17369 9032 17369 9033 17369 9032 17370 9034 17370 9033 17370 9033 17371 9034 17371 9035 17371 9035 17372 9036 17372 9037 17372 9034 17373 9036 17373 9035 17373 9037 17374 9036 17374 9038 17374 9036 17375 9039 17375 9038 17375 9039 17376 9040 17376 9038 17376 9038 17377 9040 17377 9041 17377 9040 17378 9042 17378 9041 17378 9041 17379 9042 17379 9043 17379 9042 17380 9044 17380 9043 17380 9043 17381 9044 17381 9045 17381 9044 17382 9046 17382 9045 17382 9045 17383 9046 17383 9047 17383 9046 17384 9048 17384 9047 17384 9048 17385 9027 17385 9047 17385 9049 17386 9078 17386 9050 17386 9051 17387 9049 17387 9050 17387 9051 17388 9050 17388 9052 17388 9053 17389 9051 17389 9052 17389 9053 17390 9052 17390 9054 17390 9055 17391 9053 17391 9054 17391 9055 17392 9054 17392 9056 17392 9057 17393 9055 17393 9056 17393 9057 17394 9056 17394 9058 17394 9059 17395 9057 17395 9058 17395 9059 17396 9058 17396 9060 17396 9061 17397 9059 17397 9060 17397 9061 17398 9060 17398 9062 17398 9063 17399 9061 17399 9062 17399 9063 17400 9062 17400 9064 17400 9065 17401 9063 17401 9064 17401 9065 17402 9064 17402 9066 17402 9067 17403 9065 17403 9066 17403 9067 17404 9066 17404 9068 17404 9069 17405 9067 17405 9068 17405 9069 17406 9068 17406 9070 17406 9071 17407 9069 17407 9070 17407 9071 17408 9070 17408 9072 17408 9073 17409 9071 17409 9072 17409 9073 17410 9072 17410 9074 17410 9075 17411 9073 17411 9074 17411 9075 17412 9074 17412 9076 17412 9077 17413 9075 17413 9076 17413 9077 17414 9076 17414 9078 17414 9049 17415 9077 17415 9078 17415 9040 213 9076 213 9074 213 9042 17416 9040 17416 9074 17416 9039 213 9076 213 9040 213 9042 213 9074 213 9072 213 9039 213 9078 213 9076 213 9036 213 9078 213 9039 213 9036 17417 9050 17417 9078 17417 9042 213 9072 213 9070 213 9044 213 9042 213 9070 213 9044 213 9070 213 9068 213 9046 213 9044 213 9068 213 9034 17418 9052 17418 9050 17418 9034 213 9050 213 9036 213 9066 17419 9046 17419 9068 17419 9054 213 9034 213 9032 213 9054 17420 9052 17420 9034 17420 9066 17421 9048 17421 9046 17421 9064 17422 9048 17422 9066 17422 9064 17423 9027 17423 9048 17423 9056 17424 9054 17424 9032 17424 9062 17425 9027 17425 9064 17425 9058 17426 9056 17426 9032 17426 9058 213 9032 213 9030 213 9060 213 9027 213 9062 213 9060 213 9058 213 9030 213 9060 213 9030 213 9027 213 9045 67 9067 67 9069 67 9047 67 9067 67 9045 67 9045 67 9069 67 9071 67 9047 17427 9065 17427 9067 17427 9043 67 9045 67 9071 67 9047 17428 9063 17428 9065 17428 9028 67 9063 67 9047 67 9043 67 9071 67 9073 67 9041 67 9043 67 9073 67 9028 17429 9061 17429 9063 17429 9029 67 9061 67 9028 67 9041 67 9073 67 9075 67 9038 67 9041 67 9075 67 9059 67 9061 67 9029 67 9059 67 9029 67 9031 67 9077 67 9038 67 9075 67 9057 67 9059 67 9031 67 9057 17430 9031 17430 9033 17430 9049 67 9038 67 9077 67 9055 67 9057 67 9033 67 9049 17431 9037 17431 9038 17431 9053 17432 9055 17432 9033 17432 9051 67 9037 67 9049 67 9053 17433 9033 17433 9035 17433 9051 17434 9035 17434 9037 17434 9051 67 9053 67 9035 67

+
+ + + +

9079 17435 9081 17435 9082 17435 9080 17436 9081 17436 9079 17436 9082 17437 9083 17437 9084 17437 9081 17438 9083 17438 9082 17438 9083 17439 9085 17439 9084 17439 9084 17440 9085 17440 9086 17440 9085 17441 9087 17441 9086 17441 9086 17442 9087 17442 9088 17442 9087 17443 9089 17443 9088 17443 9088 17444 9089 17444 9090 17444 9089 17445 9091 17445 9090 17445 9090 17446 9091 17446 9092 17446 9091 17447 9093 17447 9092 17447 9092 17448 9093 17448 9094 17448 9093 17449 9095 17449 9094 17449 9094 17450 9095 17450 9096 17450 9095 17451 9097 17451 9096 17451 9096 17452 9097 17452 9098 17452 9098 17453 9097 17453 9099 17453 9097 17454 9100 17454 9099 17454 9100 17455 9080 17455 9099 17455 9099 17456 9080 17456 9079 17456 9129 17457 9128 17457 9101 17457 9102 17458 9129 17458 9101 17458 9102 17459 9101 17459 9103 17459 9104 17460 9102 17460 9103 17460 9104 17461 9103 17461 9105 17461 9106 17462 9104 17462 9105 17462 9106 17463 9105 17463 9107 17463 9108 17464 9106 17464 9107 17464 9108 17465 9107 17465 9109 17465 9110 17466 9108 17466 9109 17466 9110 17467 9109 17467 9111 17467 9112 17468 9110 17468 9111 17468 9112 17469 9111 17469 9113 17469 9114 17470 9113 17470 9115 17470 9114 17471 9112 17471 9113 17471 9116 17472 9114 17472 9115 17472 9116 17473 9115 17473 9117 17473 9118 17474 9116 17474 9117 17474 9118 17475 9117 17475 9119 17475 9118 17476 9119 17476 9120 17476 9121 17477 9118 17477 9120 17477 9122 17478 9121 17478 9120 17478 9122 17479 9120 17479 9123 17479 9122 17480 9123 17480 9124 17480 9125 17481 9122 17481 9124 17481 9125 17482 9124 17482 9126 17482 9127 17483 9125 17483 9126 17483 9127 17484 9126 17484 9128 17484 9129 17485 9127 17485 9128 17485 9093 213 9126 213 9124 213 9095 213 9093 213 9124 213 9091 213 9126 213 9093 213 9095 17486 9124 17486 9123 17486 9091 213 9128 213 9126 213 9089 213 9128 213 9091 213 9097 17487 9095 17487 9123 17487 9089 17488 9101 17488 9128 17488 9097 213 9123 213 9120 213 9089 17489 9103 17489 9101 17489 9097 17490 9120 17490 9119 17490 9087 213 9103 213 9089 213 9100 213 9097 213 9119 213 9117 17491 9100 17491 9119 17491 9105 213 9103 213 9087 213 9105 213 9087 213 9085 213 9115 17492 9100 17492 9117 17492 9115 213 9080 213 9100 213 9107 213 9105 213 9085 213 9109 17493 9107 17493 9085 17493 9109 213 9085 213 9083 213 9113 17494 9080 17494 9115 17494 9113 17495 9081 17495 9080 17495 9111 213 9081 213 9113 213 9111 213 9109 213 9083 213 9111 213 9083 213 9081 213 9098 67 9099 67 9118 67 9099 67 9116 67 9118 67 9098 67 9118 67 9121 67 9096 17496 9098 17496 9121 17496 9099 17497 9114 17497 9116 17497 9096 67 9121 67 9122 67 9079 17498 9114 17498 9099 17498 9079 67 9112 67 9114 67 9094 17499 9096 17499 9122 17499 9082 67 9112 67 9079 67 9094 67 9122 67 9125 67 9082 67 9110 67 9112 67 9110 17500 9082 17500 9084 17500 9127 17501 9092 17501 9094 17501 9127 67 9094 67 9125 67 9108 17502 9110 17502 9084 17502 9129 17503 9092 17503 9127 17503 9129 17504 9090 17504 9092 17504 9106 67 9084 67 9086 67 9106 17505 9108 17505 9084 17505 9102 67 9090 67 9129 67 9102 17506 9088 17506 9090 17506 9104 17507 9106 17507 9086 17507 9104 67 9088 67 9102 67 9104 17508 9086 17508 9088 17508

+
+ + + +

9130 17509 9131 17509 9954 17509 9130 17510 9132 17510 9131 17510 9131 17511 9133 17511 9954 17511 9134 17512 9132 17512 9130 17512 9954 17513 9133 17513 9949 17513 9134 17514 9135 17514 9132 17514 9133 17515 9136 17515 9949 17515 9920 17516 9135 17516 9134 17516 9949 17517 9136 17517 9137 17517 9137 17518 9136 17518 9944 17518 9920 17519 9138 17519 9135 17519 9136 17520 9139 17520 9944 17520 9140 17521 9138 17521 9920 17521 9138 17522 9140 17522 9141 17522 9140 17523 9928 17523 9141 17523 9141 17524 9928 17524 9143 17524 9150 17525 9147 17525 9146 17525 9150 17526 9149 17526 9147 17526 9152 17527 9149 17527 9150 17527 9152 17528 9151 17528 9149 17528 9152 17529 9153 17529 9151 17529 9148 17530 9153 17530 9152 17530 9148 17531 9154 17531 9153 17531 9155 17532 9154 17532 9148 17532 9155 17533 9156 17533 9154 17533 9157 17534 9156 17534 9155 17534 9157 17535 9158 17535 9156 17535 9157 17536 9159 17536 9158 17536 9160 17537 9159 17537 9157 17537 9160 17538 9161 17538 9159 17538 9162 17539 9161 17539 9160 17539 9163 17540 9161 17540 9162 17540 9163 17541 9164 17541 9161 17541 9165 17542 9164 17542 9163 17542 9165 17543 9166 17543 9164 17543 9167 17544 9166 17544 9165 17544 9167 17545 9168 17545 9166 17545 9169 17546 9168 17546 9167 17546 9169 17547 9170 17547 9168 17547 9169 17548 9171 17548 9170 17548 9172 17549 9171 17549 9169 17549 9172 17550 9173 17550 9171 17550 9174 17551 9173 17551 9172 17551 9174 17552 9175 17552 9173 17552 9176 17553 9177 17553 9174 17553 9174 17554 9177 17554 9175 17554 9176 17555 9178 17555 9177 17555 9179 17556 9178 17556 9176 17556 9179 17557 9180 17557 9178 17557 9179 17558 9181 17558 9180 17558 9182 17559 9181 17559 9179 17559 9182 17560 9183 17560 9181 17560 9184 17561 9183 17561 9182 17561 9184 17562 9185 17562 9183 17562 9184 17563 9186 17563 9185 17563 9187 17564 9186 17564 9184 17564 9187 17565 9188 17565 9186 17565 9189 17566 9188 17566 9187 17566 9189 17567 9190 17567 9188 17567 9191 17568 9190 17568 9189 17568 9191 17569 9192 17569 9190 17569 9191 17570 9193 17570 9192 17570 9194 17571 9193 17571 9191 17571 9194 17572 9195 17572 9193 17572 9194 17573 9196 17573 9195 17573 9197 17574 9196 17574 9194 17574 9197 17575 9198 17575 9196 17575 9199 17576 9198 17576 9197 17576 9199 17577 9200 17577 9198 17577 9201 17578 9202 17578 9199 17578 9199 17579 9202 17579 9200 17579 9201 17580 9203 17580 9202 17580 9204 17581 9203 17581 9201 17581 9204 17582 9205 17582 9203 17582 9206 17583 9205 17583 9204 17583 9206 17584 9207 17584 9205 17584 9208 17585 9207 17585 9206 17585 9208 17586 9209 17586 9207 17586 9208 17587 9210 17587 9209 17587 9211 17588 9210 17588 9208 17588 9211 17589 9212 17589 9210 17589 9211 17590 9213 17590 9212 17590 9214 17591 9213 17591 9211 17591 9214 17592 9215 17592 9213 17592 9216 17593 9215 17593 9214 17593 9216 17594 9217 17594 9215 17594 9218 17595 9219 17595 9216 17595 9216 17596 9219 17596 9217 17596 9220 17597 9219 17597 9218 17597 9220 17598 9221 17598 9219 17598 9220 17599 9222 17599 9221 17599 9223 17600 9222 17600 9220 17600 9223 17601 9224 17601 9222 17601 9223 17602 9225 17602 9224 17602 9226 17603 9225 17603 9223 17603 9226 17604 9227 17604 9225 17604 9228 17605 9227 17605 9226 17605 9229 17606 9230 17606 9228 17606 9228 17607 9230 17607 9227 17607 9229 17608 9231 17608 9230 17608 9232 17609 9231 17609 9229 17609 9232 17610 9233 17610 9231 17610 9234 17611 9233 17611 9232 17611 9234 17612 9235 17612 9233 17612 9236 17613 9235 17613 9234 17613 9236 17614 9237 17614 9235 17614 9238 17615 9237 17615 9236 17615 9238 17616 9239 17616 9237 17616 9240 17617 9239 17617 9238 17617 9241 17618 9239 17618 9240 17618 9241 17619 9242 17619 9239 17619 9241 17620 9243 17620 9242 17620 9244 17621 9243 17621 9241 17621 9244 17622 9245 17622 9243 17622 9244 17623 9246 17623 9245 17623 9247 17624 9246 17624 9244 17624 9247 17625 9248 17625 9246 17625 9247 17626 9249 17626 9248 17626 9250 17627 9249 17627 9247 17627 9250 17628 9251 17628 9249 17628 9252 17629 9251 17629 9250 17629 9252 17630 9253 17630 9251 17630 9252 17631 9254 17631 9253 17631 9255 17632 9254 17632 9252 17632 9255 17633 9256 17633 9254 17633 9255 17634 9257 17634 9256 17634 9258 17635 9257 17635 9255 17635 9258 17636 9259 17636 9257 17636 9260 17637 9259 17637 9258 17637 9260 17638 9261 17638 9259 17638 9262 17639 9261 17639 9260 17639 9262 17640 9263 17640 9261 17640 9264 17641 9263 17641 9262 17641 9264 17642 9265 17642 9263 17642 9266 17643 9265 17643 9264 17643 9266 17644 9267 17644 9265 17644 9268 17645 9267 17645 9266 17645 9268 17646 9269 17646 9267 17646 9270 17647 9269 17647 9268 17647 9270 17648 9271 17648 9269 17648 9272 17649 9271 17649 9270 17649 9272 17650 9273 17650 9271 17650 9272 17651 9274 17651 9273 17651 9275 17652 9274 17652 9272 17652 9275 17653 9276 17653 9274 17653 9277 17654 9276 17654 9275 17654 9277 17655 9278 17655 9276 17655 9279 17656 9278 17656 9277 17656 9279 17657 9280 17657 9278 17657 9279 17658 9281 17658 9280 17658 9282 17659 9281 17659 9279 17659 9282 17660 9283 17660 9281 17660 9284 17661 9283 17661 9282 17661 9284 17662 9285 17662 9283 17662 9286 17663 9287 17663 9284 17663 9284 17664 9287 17664 9285 17664 9286 17665 9288 17665 9287 17665 9289 17666 9288 17666 9286 17666 9289 17667 9290 17667 9288 17667 9289 17668 9291 17668 9290 17668 9292 17669 9291 17669 9289 17669 9292 17670 9293 17670 9291 17670 9294 17671 9293 17671 9292 17671 9294 17672 9295 17672 9293 17672 9294 17673 9296 17673 9295 17673 9297 17674 9296 17674 9294 17674 9297 17675 9298 17675 9296 17675 9299 17676 9298 17676 9297 17676 9299 17677 9300 17677 9298 17677 9301 17678 9302 17678 9299 17678 9299 17679 9302 17679 9300 17679 9301 17680 9303 17680 9302 17680 9304 17681 9303 17681 9301 17681 9304 17682 9305 17682 9303 17682 9306 17683 9305 17683 9304 17683 9306 17684 9307 17684 9305 17684 9306 17685 9308 17685 9307 17685 9309 17686 9308 17686 9306 17686 9309 17687 9310 17687 9308 17687 9311 17688 9310 17688 9309 17688 9311 17689 9312 17689 9310 17689 9311 17690 9313 17690 9312 17690 9314 17691 9313 17691 9311 17691 9314 17692 9315 17692 9313 17692 9316 17693 9315 17693 9314 17693 9316 17694 9317 17694 9315 17694 9316 17695 9318 17695 9317 17695 9319 17696 9318 17696 9316 17696 9319 17697 9320 17697 9318 17697 9321 17698 9320 17698 9319 17698 9321 17699 9322 17699 9320 17699 9323 17700 9324 17700 9321 17700 9321 17701 9324 17701 9322 17701 9323 17702 9325 17702 9324 17702 9326 17703 9325 17703 9323 17703 9326 17704 9327 17704 9325 17704 9328 17705 9327 17705 9326 17705 9328 17706 9329 17706 9327 17706 9330 17707 9329 17707 9328 17707 9330 17708 9331 17708 9329 17708 9330 17709 9332 17709 9331 17709 9333 17710 9332 17710 9330 17710 9333 17711 9334 17711 9332 17711 9333 17712 9335 17712 9334 17712 9336 17713 9335 17713 9333 17713 9336 17714 9337 17714 9335 17714 9336 17715 9338 17715 9337 17715 9339 17716 9338 17716 9336 17716 9339 17717 9340 17717 9338 17717 9341 17718 9340 17718 9339 17718 9341 17719 9342 17719 9340 17719 9343 17720 9342 17720 9341 17720 9343 17721 9344 17721 9342 17721 9345 17722 9344 17722 9343 17722 9345 17723 9346 17723 9344 17723 9347 17724 9346 17724 9345 17724 9347 17725 9348 17725 9346 17725 9347 17726 9349 17726 9348 17726 9350 17727 9349 17727 9347 17727 9350 17728 9351 17728 9349 17728 9350 17729 9352 17729 9351 17729 9353 17730 9352 17730 9350 17730 9353 17731 9354 17731 9352 17731 9355 17732 9354 17732 9353 17732 9355 17733 9356 17733 9354 17733 9357 17734 9356 17734 9355 17734 9358 17735 9356 17735 9357 17735 9358 17736 9359 17736 9356 17736 9360 17737 9359 17737 9358 17737 9360 17738 9361 17738 9359 17738 9360 17739 9362 17739 9361 17739 9363 17740 9362 17740 9360 17740 9363 17741 9364 17741 9362 17741 9365 17742 9364 17742 9363 17742 9365 17743 9366 17743 9364 17743 9365 17744 9367 17744 9366 17744 9368 17745 9367 17745 9365 17745 9368 17746 9369 17746 9367 17746 9370 17747 9369 17747 9368 17747 9370 17748 9371 17748 9369 17748 9372 17749 9371 17749 9370 17749 9372 17750 9373 17750 9371 17750 9374 17751 9373 17751 9372 17751 9374 17752 9375 17752 9373 17752 9376 17753 9375 17753 9374 17753 9376 17754 9377 17754 9375 17754 9378 17755 9377 17755 9376 17755 9378 17756 9379 17756 9377 17756 9380 17757 9379 17757 9378 17757 9380 17758 9381 17758 9379 17758 9380 17759 9382 17759 9381 17759 9383 17760 9382 17760 9380 17760 9383 17761 9384 17761 9382 17761 9385 17762 9384 17762 9383 17762 9385 17763 9386 17763 9384 17763 9387 17764 9386 17764 9385 17764 9387 17765 9388 17765 9386 17765 9389 17766 9388 17766 9387 17766 9389 17767 9390 17767 9388 17767 9391 17768 9390 17768 9389 17768 9391 17769 9392 17769 9390 17769 9393 17770 9392 17770 9391 17770 9393 17771 9394 17771 9392 17771 9393 17772 9395 17772 9394 17772 9396 17773 9395 17773 9393 17773 9396 17774 9397 17774 9395 17774 9398 17775 9397 17775 9396 17775 9398 17776 9399 17776 9397 17776 9398 17777 9400 17777 9399 17777 9401 17778 9400 17778 9398 17778 9401 17779 9402 17779 9400 17779 9403 17780 9402 17780 9401 17780 9403 17781 9404 17781 9402 17781 9403 17782 9405 17782 9404 17782 9406 17783 9405 17783 9403 17783 9406 17784 9407 17784 9405 17784 9408 17785 9407 17785 9406 17785 9408 17786 9409 17786 9407 17786 9408 17787 9410 17787 9409 17787 9411 17788 9410 17788 9408 17788 9411 17789 9412 17789 9410 17789 9411 17790 9413 17790 9412 17790 9414 17791 9413 17791 9411 17791 9415 17792 9413 17792 9414 17792 9415 17793 9416 17793 9413 17793 9415 17794 9417 17794 9416 17794 9418 17795 9417 17795 9415 17795 9418 17796 9419 17796 9417 17796 9420 17797 9419 17797 9418 17797 9420 17798 9421 17798 9419 17798 9422 17799 9421 17799 9420 17799 9422 17800 9423 17800 9421 17800 9422 17801 9424 17801 9423 17801 9425 17802 9424 17802 9422 17802 9425 17803 9426 17803 9424 17803 9425 17804 9427 17804 9426 17804 9428 17805 9427 17805 9425 17805 9428 17806 9429 17806 9427 17806 9430 17807 9429 17807 9428 17807 9431 17808 9429 17808 9430 17808 9431 17809 9432 17809 9429 17809 9433 17810 9432 17810 9431 17810 9433 17811 9434 17811 9432 17811 9435 17812 9434 17812 9433 17812 9435 17813 9436 17813 9434 17813 9437 17814 9436 17814 9435 17814 9437 17815 9438 17815 9436 17815 9439 17816 9440 17816 9437 17816 9437 17817 9440 17817 9438 17817 9441 17818 9442 17818 9439 17818 9439 17819 9442 17819 9440 17819 9441 17820 9443 17820 9442 17820 9444 17821 9443 17821 9441 17821 9444 17822 9445 17822 9443 17822 9446 17823 9445 17823 9444 17823 9446 17824 9447 17824 9445 17824 9448 17825 9447 17825 9446 17825 9448 17826 9449 17826 9447 17826 9450 17827 9449 17827 9448 17827 9450 17828 9451 17828 9449 17828 9452 17829 9451 17829 9450 17829 9452 17830 9453 17830 9451 17830 9454 17831 9453 17831 9452 17831 9454 17832 9455 17832 9453 17832 9454 17833 9456 17833 9455 17833 9457 17834 9456 17834 9454 17834 9457 17835 9458 17835 9456 17835 9459 17836 9458 17836 9457 17836 9460 17837 9458 17837 9459 17837 9460 17838 9461 17838 9458 17838 9462 17839 9461 17839 9460 17839 9462 17840 9463 17840 9461 17840 9462 17841 9464 17841 9463 17841 9465 17842 9464 17842 9462 17842 9465 17843 9466 17843 9464 17843 9467 17844 9466 17844 9465 17844 9467 17845 9468 17845 9466 17845 9469 17846 9468 17846 9467 17846 9469 17847 9470 17847 9468 17847 9469 17848 9471 17848 9470 17848 9472 17849 9471 17849 9469 17849 9472 17850 9473 17850 9471 17850 9474 17851 9473 17851 9472 17851 9474 17852 9475 17852 9473 17852 9476 17853 9475 17853 9474 17853 9476 17854 9477 17854 9475 17854 9478 17855 9477 17855 9476 17855 9478 17856 9479 17856 9477 17856 9478 17857 9480 17857 9479 17857 9481 17858 9480 17858 9478 17858 9481 17859 9482 17859 9480 17859 9483 17860 9482 17860 9481 17860 9483 17861 9484 17861 9482 17861 9483 17862 9485 17862 9484 17862 9486 17863 9485 17863 9483 17863 9486 17864 9487 17864 9485 17864 9488 17865 9487 17865 9486 17865 9488 17866 9489 17866 9487 17866 9490 17867 9489 17867 9488 17867 9490 17868 9491 17868 9489 17868 9492 17869 9491 17869 9490 17869 9492 17870 9493 17870 9491 17870 9494 17871 9493 17871 9492 17871 9494 17872 9495 17872 9493 17872 9494 17873 9496 17873 9495 17873 9497 17874 9496 17874 9494 17874 9497 17875 9498 17875 9496 17875 9499 17876 9498 17876 9497 17876 9499 17877 9500 17877 9498 17877 9501 17878 9500 17878 9499 17878 9501 17879 9502 17879 9500 17879 9501 17880 9503 17880 9502 17880 9504 17881 9503 17881 9501 17881 9504 17882 9505 17882 9503 17882 9506 17883 9505 17883 9504 17883 9506 17884 9507 17884 9505 17884 9508 17885 9507 17885 9506 17885 9508 17886 9509 17886 9507 17886 9510 17887 9509 17887 9508 17887 9510 17888 9511 17888 9509 17888 9512 17889 9511 17889 9510 17889 9512 17890 9513 17890 9511 17890 9514 17891 9513 17891 9512 17891 9514 17892 9515 17892 9513 17892 9514 17893 9516 17893 9515 17893 9517 17894 9516 17894 9514 17894 9517 17895 9518 17895 9516 17895 9519 17896 9518 17896 9517 17896 9519 17897 9520 17897 9518 17897 9521 17898 9520 17898 9519 17898 9521 17899 9522 17899 9520 17899 9521 17900 9523 17900 9522 17900 9524 17901 9523 17901 9521 17901 9525 17902 9523 17902 9524 17902 9525 17903 9526 17903 9523 17903 9525 17904 9527 17904 9526 17904 9528 17905 9527 17905 9525 17905 9528 17906 9529 17906 9527 17906 9530 17907 9529 17907 9528 17907 9530 17908 9531 17908 9529 17908 9530 17909 9532 17909 9531 17909 9533 17910 9532 17910 9530 17910 9533 17911 9534 17911 9532 17911 9533 17912 9535 17912 9534 17912 9536 17913 9535 17913 9533 17913 9536 17914 9537 17914 9535 17914 9538 17915 9537 17915 9536 17915 9538 17916 9539 17916 9537 17916 9538 17917 9540 17917 9539 17917 9541 17918 9540 17918 9538 17918 9541 17919 9542 17919 9540 17919 9543 17920 9542 17920 9541 17920 9543 17921 9544 17921 9542 17921 9545 17922 9544 17922 9543 17922 9545 17923 9546 17923 9544 17923 9547 17924 9546 17924 9545 17924 9547 17925 9548 17925 9546 17925 9547 17926 9549 17926 9548 17926 9550 17927 9549 17927 9547 17927 9550 17928 9551 17928 9549 17928 9552 17929 9551 17929 9550 17929 9552 17930 9553 17930 9551 17930 9552 17931 9554 17931 9553 17931 9555 17932 9554 17932 9552 17932 9556 17933 9554 17933 9555 17933 9556 17934 9557 17934 9554 17934 9556 17935 9558 17935 9557 17935 9559 17936 9558 17936 9556 17936 9560 17937 9558 17937 9559 17937 9560 17938 9561 17938 9558 17938 9560 17939 9562 17939 9561 17939 9563 17940 9562 17940 9560 17940 9564 17941 9562 17941 9563 17941 9564 17942 9565 17942 9562 17942 9564 17943 9566 17943 9565 17943 9567 17944 9566 17944 9564 17944 9567 17945 9568 17945 9566 17945 9569 17946 9568 17946 9567 17946 9569 17947 9570 17947 9568 17947 9571 17948 9570 17948 9569 17948 9571 17949 9572 17949 9570 17949 9573 17950 9572 17950 9571 17950 9573 17951 9574 17951 9572 17951 9575 17952 9574 17952 9573 17952 9575 17953 9576 17953 9574 17953 9577 17954 9576 17954 9575 17954 9577 17955 9578 17955 9576 17955 9577 17956 9579 17956 9578 17956 9580 17957 9579 17957 9577 17957 9580 17958 9581 17958 9579 17958 9582 17959 9581 17959 9580 17959 9582 17960 9583 17960 9581 17960 9584 17961 9583 17961 9582 17961 9584 17962 9585 17962 9583 17962 9586 17963 9585 17963 9584 17963 9586 17964 9587 17964 9585 17964 9588 17965 9587 17965 9586 17965 9588 17966 9589 17966 9587 17966 9590 17967 9589 17967 9588 17967 9590 17968 9591 17968 9589 17968 9590 17969 9592 17969 9591 17969 9593 17970 9592 17970 9590 17970 9593 17971 9594 17971 9592 17971 9593 17972 9595 17972 9594 17972 9596 17973 9595 17973 9593 17973 9596 17974 9597 17974 9595 17974 9598 17975 9597 17975 9596 17975 9598 17976 9599 17976 9597 17976 9598 17977 9600 17977 9599 17977 9601 17978 9600 17978 9598 17978 9601 17979 9602 17979 9600 17979 9603 17980 9602 17980 9601 17980 9603 17981 9604 17981 9602 17981 9605 17982 9604 17982 9603 17982 9605 17983 9606 17983 9604 17983 9607 17984 9606 17984 9605 17984 9607 17985 9608 17985 9606 17985 9609 17986 9608 17986 9607 17986 9609 17987 9610 17987 9608 17987 9609 17988 9611 17988 9610 17988 9612 17989 9611 17989 9609 17989 9612 17990 9613 17990 9611 17990 9614 17991 9613 17991 9612 17991 9614 17992 9615 17992 9613 17992 9614 17993 9616 17993 9615 17993 9617 17994 9616 17994 9614 17994 9617 17995 9618 17995 9616 17995 9619 17996 9618 17996 9617 17996 9619 17997 9620 17997 9618 17997 9621 17998 9622 17998 9619 17998 9619 17999 9622 17999 9620 17999 9623 18000 9622 18000 9621 18000 9623 18001 9624 18001 9622 18001 9625 18002 9626 18002 9623 18002 9623 18003 9626 18003 9624 18003 9625 18004 9627 18004 9626 18004 9628 18005 9627 18005 9625 18005 9628 18006 9629 18006 9627 18006 9630 18007 9629 18007 9628 18007 9630 18008 9631 18008 9629 18008 9632 18009 9631 18009 9630 18009 9632 18010 9633 18010 9631 18010 9634 18011 9633 18011 9632 18011 9635 18012 9636 18012 9634 18012 9634 18013 9636 18013 9633 18013 9635 18014 9637 18014 9636 18014 9638 18015 9637 18015 9635 18015 9638 18016 9639 18016 9637 18016 9638 18017 9640 18017 9639 18017 9641 18018 9640 18018 9638 18018 9641 18019 9642 18019 9640 18019 9643 18020 9642 18020 9641 18020 9643 18021 9644 18021 9642 18021 9645 18022 9644 18022 9643 18022 9645 18023 9646 18023 9644 18023 9645 18024 9647 18024 9646 18024 9645 18025 9648 18025 9647 18025 9649 18026 9648 18026 9645 18026 9649 18027 9650 18027 9648 18027 9651 18028 9650 18028 9649 18028 9651 18029 9652 18029 9650 18029 9653 18030 9652 18030 9651 18030 9653 18031 9654 18031 9652 18031 9655 18032 9654 18032 9653 18032 9655 18033 9656 18033 9654 18033 9655 18034 9657 18034 9656 18034 9658 18035 9657 18035 9655 18035 9658 18036 9659 18036 9657 18036 9660 18037 9659 18037 9658 18037 9660 18038 9661 18038 9659 18038 9662 18039 9661 18039 9660 18039 9662 18040 9663 18040 9661 18040 9664 18041 9663 18041 9662 18041 9664 18042 9665 18042 9663 18042 9664 18043 9666 18043 9665 18043 9667 18044 9666 18044 9664 18044 9667 18045 9668 18045 9666 18045 9669 18046 9668 18046 9667 18046 9669 18047 9670 18047 9668 18047 9671 18048 9670 18048 9669 18048 9671 18049 9672 18049 9670 18049 9673 18050 9672 18050 9671 18050 9673 18051 9674 18051 9672 18051 9675 18052 9674 18052 9673 18052 9675 18053 9676 18053 9674 18053 9677 18054 9676 18054 9675 18054 9677 18055 9678 18055 9676 18055 9677 18056 9679 18056 9678 18056 9680 18057 9679 18057 9677 18057 9680 18058 9681 18058 9679 18058 9682 18059 9681 18059 9680 18059 9682 18060 9683 18060 9681 18060 9684 18061 9683 18061 9682 18061 9684 18062 9685 18062 9683 18062 9686 18063 9685 18063 9684 18063 9686 18064 9687 18064 9685 18064 9688 18065 9687 18065 9686 18065 9688 18066 9689 18066 9687 18066 9690 18067 9689 18067 9688 18067 9690 18068 9691 18068 9689 18068 9690 18069 9692 18069 9691 18069 9693 18070 9692 18070 9690 18070 9693 18071 9694 18071 9692 18071 9695 18072 9694 18072 9693 18072 9695 18073 9696 18073 9694 18073 9697 18074 9696 18074 9695 18074 9697 18075 9698 18075 9696 18075 9697 18076 9699 18076 9698 18076 9700 18077 9699 18077 9697 18077 9700 18078 9701 18078 9699 18078 9702 18079 9701 18079 9700 18079 9702 18080 9703 18080 9701 18080 9702 18081 9704 18081 9703 18081 9705 18082 9704 18082 9702 18082 9705 18083 9706 18083 9704 18083 9705 18084 9707 18084 9706 18084 9708 18085 9707 18085 9705 18085 9708 18086 9709 18086 9707 18086 9708 18087 9710 18087 9709 18087 9711 18088 9710 18088 9708 18088 9711 18089 9712 18089 9710 18089 9711 18090 9713 18090 9712 18090 9714 18091 9713 18091 9711 18091 9714 18092 9715 18092 9713 18092 9716 18093 9715 18093 9714 18093 9716 18094 9717 18094 9715 18094 9718 18095 9717 18095 9716 18095 9718 18096 9719 18096 9717 18096 9720 18097 9719 18097 9718 18097 9720 18098 9721 18098 9719 18098 9722 18099 9721 18099 9720 18099 9722 18100 9723 18100 9721 18100 9724 18101 9723 18101 9722 18101 9724 18102 9725 18102 9723 18102 9726 18103 9725 18103 9724 18103 9726 18104 9727 18104 9725 18104 9726 18105 9728 18105 9727 18105 9729 18106 9728 18106 9726 18106 9729 18107 9730 18107 9728 18107 9731 18108 9730 18108 9729 18108 9731 18109 9732 18109 9730 18109 9733 18110 9732 18110 9731 18110 9733 18111 9142 18111 9732 18111 9733 18112 9734 18112 9142 18112 9735 18113 9734 18113 9733 18113 9735 18114 9736 18114 9734 18114 9735 18115 9144 18115 9736 18115 9735 18116 9143 18116 9144 18116 9737 18117 9143 18117 9735 18117 9738 18118 9143 18118 9737 18118 9738 18119 9141 18119 9143 18119 9138 18120 9141 18120 9738 18120 9155 18121 9148 18121 9739 18121 9740 18122 9155 18122 9739 18122 9157 18123 9155 18123 9740 18123 9741 18124 9157 18124 9740 18124 9160 18125 9157 18125 9741 18125 9163 18126 9162 18126 9742 18126 9743 18127 9165 18127 9163 18127 9167 18128 9165 18128 9743 18128 9744 18129 9167 18129 9743 18129 9169 18130 9167 18130 9744 18130 9172 18131 9169 18131 9744 18131 9745 18132 9174 18132 9172 18132 9176 18133 9174 18133 9745 18133 9179 18134 9176 18134 9746 18134 9747 18135 9179 18135 9746 18135 9182 18136 9179 18136 9747 18136 9748 18137 9182 18137 9747 18137 9184 18138 9182 18138 9748 18138 9749 18139 9184 18139 9748 18139 9187 18140 9184 18140 9749 18140 9750 18141 9187 18141 9749 18141 9189 18142 9187 18142 9750 18142 9751 18143 9189 18143 9750 18143 9191 18144 9189 18144 9751 18144 9752 18145 9191 18145 9751 18145 9194 18146 9191 18146 9752 18146 9753 18147 9194 18147 9752 18147 9197 18148 9194 18148 9753 18148 9754 18149 9197 18149 9753 18149 9199 18150 9197 18150 9754 18150 9208 18151 9206 18151 9755 18151 9756 18152 9208 18152 9755 18152 9211 18153 9208 18153 9756 18153 9757 18154 9216 18154 9214 18154 9758 18155 9216 18155 9757 18155 9218 18156 9216 18156 9758 18156 9220 18157 9218 18157 9758 18157 9759 18158 9220 18158 9758 18158 9760 18159 9220 18159 9759 18159 9223 18160 9220 18160 9760 18160 9761 18161 9223 18161 9760 18161 9226 18162 9223 18162 9761 18162 9762 18163 9241 18163 9240 18163 9763 18164 9241 18164 9762 18164 9244 18165 9241 18165 9763 18165 9247 18166 9244 18166 9763 18166 9252 18167 9250 18167 9764 18167 9765 18168 9252 18168 9764 18168 9255 18169 9252 18169 9765 18169 9766 18170 9255 18170 9765 18170 9258 18171 9255 18171 9766 18171 9767 18172 9258 18172 9766 18172 9260 18173 9258 18173 9767 18173 9768 18174 9260 18174 9767 18174 9262 18175 9260 18175 9768 18175 9769 18176 9262 18176 9768 18176 9264 18177 9262 18177 9769 18177 9770 18178 9264 18178 9769 18178 9266 18179 9264 18179 9770 18179 9268 18180 9266 18180 9770 18180 9771 18181 9272 18181 9270 18181 9275 18182 9272 18182 9771 18182 9772 18183 9275 18183 9771 18183 9277 18184 9275 18184 9772 18184 9773 18185 9277 18185 9772 18185 9279 18186 9277 18186 9773 18186 9774 18187 9279 18187 9773 18187 9282 18188 9279 18188 9774 18188 9284 18189 9282 18189 9775 18189 9776 18190 9284 18190 9775 18190 9286 18191 9284 18191 9776 18191 9289 18192 9286 18192 9777 18192 9292 18193 9289 18193 9777 18193 9294 18194 9292 18194 9778 18194 9297 18195 9294 18195 9778 18195 9299 18196 9297 18196 9779 18196 9780 18197 9299 18197 9779 18197 9301 18198 9299 18198 9780 18198 9781 18199 9304 18199 9301 18199 9306 18200 9304 18200 9781 18200 9309 18201 9306 18201 9781 18201 9782 18202 9311 18202 9309 18202 9314 18203 9311 18203 9782 18203 9783 18204 9314 18204 9782 18204 9316 18205 9314 18205 9783 18205 9319 18206 9316 18206 9784 18206 9785 18207 9319 18207 9784 18207 9321 18208 9319 18208 9785 18208 9786 18209 9321 18209 9785 18209 9323 18210 9321 18210 9786 18210 9330 18211 9328 18211 9787 18211 9788 18212 9330 18212 9787 18212 9333 18213 9330 18213 9788 18213 9789 18214 9333 18214 9788 18214 9336 18215 9333 18215 9789 18215 9790 18216 9336 18216 9789 18216 9791 18217 9336 18217 9790 18217 9339 18218 9336 18218 9791 18218 9341 18219 9339 18219 9791 18219 9792 18220 9341 18220 9791 18220 9343 18221 9341 18221 9792 18221 9345 18222 9343 18222 9793 18222 9347 18223 9345 18223 9793 18223 9350 18224 9347 18224 9794 18224 9795 18225 9350 18225 9794 18225 9353 18226 9350 18226 9795 18226 9355 18227 9353 18227 9795 18227 9360 18228 9358 18228 9796 18228 9797 18229 9360 18229 9796 18229 9363 18230 9360 18230 9797 18230 9798 18231 9363 18231 9797 18231 9365 18232 9363 18232 9798 18232 9799 18233 9365 18233 9798 18233 9368 18234 9365 18234 9799 18234 9368 18235 9799 18235 9370 18235 9372 18236 9370 18236 9800 18236 9801 18237 9372 18237 9800 18237 9374 18238 9372 18238 9801 18238 9802 18239 9374 18239 9801 18239 9376 18240 9374 18240 9802 18240 9378 18241 9376 18241 9802 18241 9803 18242 9378 18242 9802 18242 9378 18243 9803 18243 9380 18243 9804 18244 9385 18244 9383 18244 9387 18245 9385 18245 9804 18245 9805 18246 9387 18246 9804 18246 9389 18247 9387 18247 9805 18247 9806 18248 9391 18248 9389 18248 9393 18249 9391 18249 9806 18249 9807 18250 9393 18250 9806 18250 9396 18251 9393 18251 9807 18251 9808 18252 9398 18252 9396 18252 9401 18253 9398 18253 9808 18253 9401 18254 9808 18254 9809 18254 9403 18255 9401 18255 9809 18255 9810 18256 9403 18256 9809 18256 9406 18257 9403 18257 9810 18257 9811 18258 9406 18258 9810 18258 9408 18259 9406 18259 9811 18259 9812 18260 9408 18260 9811 18260 9411 18261 9408 18261 9812 18261 9813 18262 9411 18262 9812 18262 9414 18263 9411 18263 9813 18263 9814 18264 9414 18264 9813 18264 9415 18265 9414 18265 9814 18265 9815 18266 9415 18266 9814 18266 9418 18267 9415 18267 9815 18267 9816 18268 9418 18268 9815 18268 9420 18269 9418 18269 9816 18269 9817 18270 9420 18270 9816 18270 9422 18271 9420 18271 9817 18271 9425 18272 9422 18272 9817 18272 9818 18273 9425 18273 9817 18273 9819 18274 9425 18274 9818 18274 9428 18275 9425 18275 9819 18275 9430 18276 9428 18276 9819 18276 9820 18277 9437 18277 9435 18277 9439 18278 9437 18278 9820 18278 9821 18279 9439 18279 9820 18279 9441 18280 9439 18280 9821 18280 9822 18281 9441 18281 9821 18281 9444 18282 9441 18282 9822 18282 9446 18283 9444 18283 9822 18283 9448 18284 9446 18284 9822 18284 9454 18285 9452 18285 9823 18285 9457 18286 9454 18286 9823 18286 9824 18287 9460 18287 9459 18287 9462 18288 9460 18288 9824 18288 9472 18289 9469 18289 9825 18289 9826 18290 9472 18290 9825 18290 9474 18291 9472 18291 9826 18291 9476 18292 9474 18292 9826 18292 9827 18293 9476 18293 9826 18293 9478 18294 9476 18294 9827 18294 9828 18295 9478 18295 9827 18295 9481 18296 9478 18296 9828 18296 9829 18297 9481 18297 9828 18297 9483 18298 9481 18298 9829 18298 9486 18299 9483 18299 9829 18299 9488 18300 9486 18300 9830 18300 9490 18301 9488 18301 9830 18301 9492 18302 9490 18302 9831 18302 9494 18303 9492 18303 9831 18303 9832 18304 9494 18304 9831 18304 9497 18305 9494 18305 9832 18305 9833 18306 9497 18306 9832 18306 9499 18307 9497 18307 9833 18307 9834 18308 9501 18308 9499 18308 9504 18309 9501 18309 9834 18309 9835 18310 9504 18310 9834 18310 9506 18311 9504 18311 9835 18311 9836 18312 9506 18312 9835 18312 9508 18313 9506 18313 9836 18313 9510 18314 9508 18314 9836 18314 9517 18315 9514 18315 9837 18315 9838 18316 9517 18316 9837 18316 9519 18317 9517 18317 9838 18317 9521 18318 9519 18318 9838 18318 9839 18319 9525 18319 9524 18319 9528 18320 9525 18320 9839 18320 9840 18321 9528 18321 9839 18321 9530 18322 9528 18322 9840 18322 9841 18323 9530 18323 9840 18323 9533 18324 9530 18324 9841 18324 9842 18325 9533 18325 9841 18325 9536 18326 9533 18326 9842 18326 9843 18327 9538 18327 9536 18327 9844 18328 9538 18328 9843 18328 9541 18329 9538 18329 9844 18329 9543 18330 9541 18330 9844 18330 9550 18331 9547 18331 9845 18331 9846 18332 9552 18332 9550 18332 9555 18333 9552 18333 9846 18333 9847 18334 9560 18334 9559 18334 9563 18335 9560 18335 9847 18335 9848 18336 9564 18336 9563 18336 9567 18337 9564 18337 9848 18337 9849 18338 9567 18338 9848 18338 9569 18339 9567 18339 9849 18339 9571 18340 9569 18340 9849 18340 9850 18341 9573 18341 9571 18341 9575 18342 9573 18342 9850 18342 9851 18343 9575 18343 9850 18343 9577 18344 9575 18344 9851 18344 9852 18345 9577 18345 9851 18345 9580 18346 9577 18346 9852 18346 9582 18347 9580 18347 9852 18347 9584 18348 9582 18348 9853 18348 9586 18349 9584 18349 9853 18349 9854 18350 9588 18350 9586 18350 9590 18351 9588 18351 9854 18351 9593 18352 9590 18352 9855 18352 9596 18353 9593 18353 9855 18353 9598 18354 9596 18354 9856 18354 9857 18355 9598 18355 9856 18355 9601 18356 9598 18356 9857 18356 9603 18357 9601 18357 9857 18357 9607 18358 9605 18358 9858 18358 9859 18359 9607 18359 9858 18359 9609 18360 9607 18360 9859 18360 9860 18361 9609 18361 9859 18361 9612 18362 9609 18362 9860 18362 9861 18363 9612 18363 9860 18363 9862 18364 9612 18364 9861 18364 9614 18365 9612 18365 9862 18365 9617 18366 9614 18366 9862 18366 9863 18367 9619 18367 9617 18367 9621 18368 9619 18368 9863 18368 9864 18369 9623 18369 9621 18369 9625 18370 9623 18370 9864 18370 9628 18371 9625 18371 9864 18371 9630 18372 9628 18372 9865 18372 9866 18373 9630 18373 9865 18373 9632 18374 9630 18374 9866 18374 9634 18375 9632 18375 9866 18375 9635 18376 9634 18376 9867 18376 9868 18377 9635 18377 9867 18377 9638 18378 9635 18378 9868 18378 9641 18379 9638 18379 9868 18379 9643 18380 9641 18380 9869 18380 9870 18381 9643 18381 9869 18381 9645 18382 9643 18382 9870 18382 9871 18383 9645 18383 9870 18383 9649 18384 9645 18384 9871 18384 9651 18385 9649 18385 9871 18385 9655 18386 9653 18386 9872 18386 9658 18387 9655 18387 9872 18387 9660 18388 9658 18388 9873 18388 9662 18389 9660 18389 9873 18389 9874 18390 9664 18390 9662 18390 9667 18391 9664 18391 9874 18391 9875 18392 9675 18392 9673 18392 9677 18393 9675 18393 9875 18393 9680 18394 9677 18394 9876 18394 9682 18395 9680 18395 9876 18395 9877 18396 9682 18396 9876 18396 9684 18397 9682 18397 9877 18397 9878 18398 9684 18398 9877 18398 9686 18399 9684 18399 9878 18399 9879 18400 9686 18400 9878 18400 9688 18401 9686 18401 9879 18401 9880 18402 9688 18402 9879 18402 9690 18403 9688 18403 9880 18403 9881 18404 9690 18404 9880 18404 9693 18405 9690 18405 9881 18405 9882 18406 9693 18406 9881 18406 9695 18407 9693 18407 9882 18407 9883 18408 9695 18408 9882 18408 9697 18409 9695 18409 9883 18409 9884 18410 9697 18410 9883 18410 9700 18411 9697 18411 9884 18411 9885 18412 9700 18412 9884 18412 9702 18413 9700 18413 9885 18413 9886 18414 9702 18414 9885 18414 9705 18415 9702 18415 9886 18415 9887 18416 9705 18416 9886 18416 9708 18417 9705 18417 9887 18417 9888 18418 9708 18418 9887 18418 9889 18419 9708 18419 9888 18419 9711 18420 9708 18420 9889 18420 9890 18421 9711 18421 9889 18421 9714 18422 9711 18422 9890 18422 9716 18423 9714 18423 9890 18423 9718 18424 9716 18424 9891 18424 9892 18425 9720 18425 9718 18425 9722 18426 9720 18426 9892 18426 9893 18427 9722 18427 9892 18427 9724 18428 9722 18428 9893 18428 9894 18429 9724 18429 9893 18429 9726 18430 9724 18430 9894 18430 9895 18431 9726 18431 9894 18431 9729 18432 9726 18432 9895 18432 9896 18433 9729 18433 9895 18433 9731 18434 9729 18434 9896 18434 9897 18435 9731 18435 9896 18435 9733 18436 9731 18436 9897 18436 9735 18437 9733 18437 9897 18437 9737 18438 9735 18438 9898 18438 9738 18439 9737 18439 9898 18439 9738 18440 9898 18440 9899 18440 9138 18441 9738 18441 9899 18441 9900 18442 9138 18442 9899 18442 9135 18443 9138 18443 9900 18443 9901 18444 9135 18444 9900 18444 9132 18445 9135 18445 9901 18445 9903 18446 9160 18446 9741 18446 9903 18447 9162 18447 9160 18447 9903 18448 9742 18448 9162 18448 9903 18449 9163 18449 9742 18449 9902 18450 9163 18450 9903 18450 9904 18451 9163 18451 9902 18451 9904 18452 9743 18452 9163 18452 9145 18453 9743 18453 9904 18453 9145 18454 9744 18454 9743 18454 9147 18455 9744 18455 9145 18455 9149 18456 9744 18456 9147 18456 9149 18457 9172 18457 9744 18457 9151 18458 9745 18458 9149 18458 9149 18459 9745 18459 9172 18459 9151 18460 9176 18460 9745 18460 9153 18461 9176 18461 9151 18461 9153 18462 9746 18462 9176 18462 9154 18463 9746 18463 9153 18463 9154 18464 9747 18464 9746 18464 9905 18465 9747 18465 9154 18465 9906 18466 9747 18466 9905 18466 9906 18467 9748 18467 9747 18467 9158 18468 9748 18468 9906 18468 9158 18469 9749 18469 9748 18469 9159 18470 9749 18470 9158 18470 9159 18471 9750 18471 9749 18471 9161 18472 9750 18472 9159 18472 9161 18473 9751 18473 9750 18473 9164 18474 9751 18474 9161 18474 9164 18475 9752 18475 9751 18475 9166 18476 9752 18476 9164 18476 9166 18477 9753 18477 9752 18477 9168 18478 9753 18478 9166 18478 9170 18479 9753 18479 9168 18479 9170 18480 9754 18480 9753 18480 9171 18481 9754 18481 9170 18481 9173 18482 9199 18482 9171 18482 9171 18483 9199 18483 9754 18483 9175 18484 9199 18484 9173 18484 9175 18485 9201 18485 9199 18485 9177 18486 9201 18486 9175 18486 9177 18487 9204 18487 9201 18487 9178 18488 9204 18488 9177 18488 9178 18489 9206 18489 9204 18489 9180 18490 9206 18490 9178 18490 9180 18491 9755 18491 9206 18491 9181 18492 9755 18492 9180 18492 9181 18493 9756 18493 9755 18493 9183 18494 9756 18494 9181 18494 9183 18495 9211 18495 9756 18495 9185 18496 9211 18496 9183 18496 9185 18497 9214 18497 9211 18497 9186 18498 9214 18498 9185 18498 9188 18499 9214 18499 9186 18499 9188 18500 9757 18500 9214 18500 9190 18501 9757 18501 9188 18501 9190 18502 9758 18502 9757 18502 9192 18503 9758 18503 9190 18503 9193 18504 9758 18504 9192 18504 9193 18505 9759 18505 9758 18505 9195 18506 9759 18506 9193 18506 9196 18507 9760 18507 9195 18507 9195 18508 9760 18508 9759 18508 9907 18509 9760 18509 9196 18509 9907 18510 9761 18510 9760 18510 9198 18511 9761 18511 9907 18511 9198 18512 9226 18512 9761 18512 9200 18513 9226 18513 9198 18513 9200 18514 9228 18514 9226 18514 9202 18515 9228 18515 9200 18515 9202 18516 9229 18516 9228 18516 9203 18517 9229 18517 9202 18517 9203 18518 9232 18518 9229 18518 9205 18519 9232 18519 9203 18519 9207 18520 9232 18520 9205 18520 9207 18521 9234 18521 9232 18521 9209 18522 9234 18522 9207 18522 9209 18523 9236 18523 9234 18523 9210 18524 9236 18524 9209 18524 9210 18525 9238 18525 9236 18525 9212 18526 9238 18526 9210 18526 9213 18527 9238 18527 9212 18527 9213 18528 9240 18528 9238 18528 9215 18529 9240 18529 9213 18529 9215 18530 9762 18530 9240 18530 9217 18531 9762 18531 9215 18531 9217 18532 9763 18532 9762 18532 9219 18533 9763 18533 9217 18533 9221 18534 9763 18534 9219 18534 9221 18535 9247 18535 9763 18535 9222 18536 9247 18536 9221 18536 9222 18537 9250 18537 9247 18537 9224 18538 9250 18538 9222 18538 9224 18539 9764 18539 9250 18539 9225 18540 9764 18540 9224 18540 9225 18541 9765 18541 9764 18541 9227 18542 9765 18542 9225 18542 9230 18543 9765 18543 9227 18543 9230 18544 9766 18544 9765 18544 9231 18545 9766 18545 9230 18545 9231 18546 9767 18546 9766 18546 9233 18547 9767 18547 9231 18547 9233 18548 9768 18548 9767 18548 9235 18549 9768 18549 9233 18549 9237 18550 9769 18550 9235 18550 9235 18551 9769 18551 9768 18551 9239 18552 9770 18552 9237 18552 9237 18553 9770 18553 9769 18553 9242 18554 9770 18554 9239 18554 9242 18555 9268 18555 9770 18555 9243 18556 9268 18556 9242 18556 9245 18557 9268 18557 9243 18557 9245 18558 9270 18558 9268 18558 9246 18559 9270 18559 9245 18559 9246 18560 9771 18560 9270 18560 9248 18561 9771 18561 9246 18561 9249 18562 9771 18562 9248 18562 9249 18563 9772 18563 9771 18563 9251 18564 9772 18564 9249 18564 9251 18565 9773 18565 9772 18565 9253 18566 9773 18566 9251 18566 9254 18567 9773 18567 9253 18567 9254 18568 9774 18568 9773 18568 9256 18569 9774 18569 9254 18569 9257 18570 9774 18570 9256 18570 9257 18571 9282 18571 9774 18571 9257 18572 9775 18572 9282 18572 9259 18573 9775 18573 9257 18573 9261 18574 9775 18574 9259 18574 9261 18575 9776 18575 9775 18575 9263 18576 9776 18576 9261 18576 9263 18577 9286 18577 9776 18577 9263 18578 9777 18578 9286 18578 9265 18579 9777 18579 9263 18579 9265 18580 9292 18580 9777 18580 9267 18581 9292 18581 9265 18581 9267 18582 9778 18582 9292 18582 9269 18583 9778 18583 9267 18583 9269 18584 9297 18584 9778 18584 9271 18585 9297 18585 9269 18585 9271 18586 9779 18586 9297 18586 9273 18587 9779 18587 9271 18587 9273 18588 9780 18588 9779 18588 9274 18589 9780 18589 9273 18589 9276 18590 9780 18590 9274 18590 9276 18591 9301 18591 9780 18591 9276 18592 9781 18592 9301 18592 9278 18593 9781 18593 9276 18593 9280 18594 9781 18594 9278 18594 9280 18595 9309 18595 9781 18595 9281 18596 9309 18596 9280 18596 9281 18597 9782 18597 9309 18597 9283 18598 9782 18598 9281 18598 9285 18599 9782 18599 9283 18599 9287 18600 9782 18600 9285 18600 9287 18601 9783 18601 9782 18601 9288 18602 9783 18602 9287 18602 9288 18603 9316 18603 9783 18603 9290 18604 9316 18604 9288 18604 9290 18605 9784 18605 9316 18605 9291 18606 9784 18606 9290 18606 9293 18607 9785 18607 9291 18607 9291 18608 9785 18608 9784 18608 9295 18609 9785 18609 9293 18609 9295 18610 9786 18610 9785 18610 9296 18611 9786 18611 9295 18611 9296 18612 9323 18612 9786 18612 9298 18613 9323 18613 9296 18613 9298 18614 9326 18614 9323 18614 9300 18615 9326 18615 9298 18615 9302 18616 9326 18616 9300 18616 9302 18617 9328 18617 9326 18617 9303 18618 9328 18618 9302 18618 9303 18619 9787 18619 9328 18619 9305 18620 9787 18620 9303 18620 9305 18621 9788 18621 9787 18621 9307 18622 9788 18622 9305 18622 9308 18623 9788 18623 9307 18623 9308 18624 9789 18624 9788 18624 9310 18625 9789 18625 9308 18625 9312 18626 9790 18626 9310 18626 9310 18627 9790 18627 9789 18627 9313 18628 9790 18628 9312 18628 9313 18629 9791 18629 9790 18629 9315 18630 9791 18630 9313 18630 9317 18631 9791 18631 9315 18631 9317 18632 9792 18632 9791 18632 9318 18633 9792 18633 9317 18633 9318 18634 9343 18634 9792 18634 9318 18635 9793 18635 9343 18635 9320 18636 9793 18636 9318 18636 9322 18637 9793 18637 9320 18637 9322 18638 9347 18638 9793 18638 9324 18639 9347 18639 9322 18639 9325 18640 9347 18640 9324 18640 9325 18641 9794 18641 9347 18641 9325 18642 9795 18642 9794 18642 9327 18643 9795 18643 9325 18643 9329 18644 9795 18644 9327 18644 9329 18645 9355 18645 9795 18645 9331 18646 9355 18646 9329 18646 9331 18647 9357 18647 9355 18647 9332 18648 9357 18648 9331 18648 9332 18649 9358 18649 9357 18649 9334 18650 9358 18650 9332 18650 9334 18651 9796 18651 9358 18651 9335 18652 9796 18652 9334 18652 9337 18653 9796 18653 9335 18653 9337 18654 9797 18654 9796 18654 9338 18655 9797 18655 9337 18655 9340 18656 9798 18656 9338 18656 9338 18657 9798 18657 9797 18657 9342 18658 9798 18658 9340 18658 9342 18659 9799 18659 9798 18659 9344 18660 9799 18660 9342 18660 9344 18661 9370 18661 9799 18661 9344 18662 9800 18662 9370 18662 9346 18663 9800 18663 9344 18663 9348 18664 9800 18664 9346 18664 9348 18665 9801 18665 9800 18665 9349 18666 9801 18666 9348 18666 9349 18667 9802 18667 9801 18667 9351 18668 9802 18668 9349 18668 9352 18669 9802 18669 9351 18669 9352 18670 9803 18670 9802 18670 9354 18671 9803 18671 9352 18671 9354 18672 9380 18672 9803 18672 9356 18673 9380 18673 9354 18673 9356 18674 9383 18674 9380 18674 9359 18675 9383 18675 9356 18675 9361 18676 9383 18676 9359 18676 9361 18677 9804 18677 9383 18677 9362 18678 9804 18678 9361 18678 9362 18679 9805 18679 9804 18679 9364 18680 9805 18680 9362 18680 9364 18681 9389 18681 9805 18681 9366 18682 9389 18682 9364 18682 9366 18683 9806 18683 9389 18683 9367 18684 9806 18684 9366 18684 9369 18685 9806 18685 9367 18685 9369 18686 9807 18686 9806 18686 9371 18687 9807 18687 9369 18687 9371 18688 9396 18688 9807 18688 9373 18689 9396 18689 9371 18689 9373 18690 9808 18690 9396 18690 9375 18691 9808 18691 9373 18691 9377 18692 9808 18692 9375 18692 9377 18693 9809 18693 9808 18693 9377 18694 9810 18694 9809 18694 9379 18695 9810 18695 9377 18695 9381 18696 9810 18696 9379 18696 9381 18697 9811 18697 9810 18697 9382 18698 9811 18698 9381 18698 9382 18699 9812 18699 9811 18699 9384 18700 9812 18700 9382 18700 9384 18701 9813 18701 9812 18701 9386 18702 9813 18702 9384 18702 9388 18703 9813 18703 9386 18703 9388 18704 9814 18704 9813 18704 9390 18705 9814 18705 9388 18705 9392 18706 9814 18706 9390 18706 9392 18707 9815 18707 9814 18707 9394 18708 9815 18708 9392 18708 9394 18709 9816 18709 9815 18709 9395 18710 9816 18710 9394 18710 9397 18711 9816 18711 9395 18711 9397 18712 9817 18712 9816 18712 9399 18713 9817 18713 9397 18713 9400 18714 9817 18714 9399 18714 9400 18715 9818 18715 9817 18715 9402 18716 9818 18716 9400 18716 9402 18717 9819 18717 9818 18717 9404 18718 9819 18718 9402 18718 9908 18719 9819 18719 9404 18719 9908 18720 9430 18720 9819 18720 9407 18721 9430 18721 9908 18721 9407 18722 9431 18722 9430 18722 9409 18723 9431 18723 9407 18723 9409 18724 9433 18724 9431 18724 9409 18725 9435 18725 9433 18725 9412 18726 9435 18726 9409 18726 9412 18727 9820 18727 9435 18727 9413 18728 9820 18728 9412 18728 9413 18729 9821 18729 9820 18729 9416 18730 9821 18730 9413 18730 9417 18731 9821 18731 9416 18731 9417 18732 9822 18732 9821 18732 9419 18733 9822 18733 9417 18733 9419 18734 9448 18734 9822 18734 9421 18735 9448 18735 9419 18735 9423 18736 9448 18736 9421 18736 9423 18737 9450 18737 9448 18737 9424 18738 9450 18738 9423 18738 9424 18739 9452 18739 9450 18739 9426 18740 9452 18740 9424 18740 9426 18741 9823 18741 9452 18741 9427 18742 9823 18742 9426 18742 9427 18743 9457 18743 9823 18743 9429 18744 9457 18744 9427 18744 9432 18745 9459 18745 9429 18745 9429 18746 9459 18746 9457 18746 9432 18747 9824 18747 9459 18747 9434 18748 9824 18748 9432 18748 9434 18749 9462 18749 9824 18749 9436 18750 9462 18750 9434 18750 9436 18751 9465 18751 9462 18751 9438 18752 9465 18752 9436 18752 9440 18753 9465 18753 9438 18753 9440 18754 9467 18754 9465 18754 9442 18755 9467 18755 9440 18755 9442 18756 9469 18756 9467 18756 9443 18757 9469 18757 9442 18757 9443 18758 9825 18758 9469 18758 9445 18759 9825 18759 9443 18759 9445 18760 9826 18760 9825 18760 9447 18761 9826 18761 9445 18761 9449 18762 9827 18762 9447 18762 9447 18763 9827 18763 9826 18763 9451 18764 9827 18764 9449 18764 9451 18765 9828 18765 9827 18765 9453 18766 9828 18766 9451 18766 9455 18767 9828 18767 9453 18767 9455 18768 9829 18768 9828 18768 9456 18769 9829 18769 9455 18769 9458 18770 9829 18770 9456 18770 9458 18771 9486 18771 9829 18771 9461 18772 9486 18772 9458 18772 9461 18773 9830 18773 9486 18773 9463 18774 9830 18774 9461 18774 9463 18775 9490 18775 9830 18775 9464 18776 9490 18776 9463 18776 9466 18777 9490 18777 9464 18777 9466 18778 9831 18778 9490 18778 9468 18779 9831 18779 9466 18779 9468 18780 9832 18780 9831 18780 9470 18781 9832 18781 9468 18781 9471 18782 9832 18782 9470 18782 9471 18783 9833 18783 9832 18783 9473 18784 9833 18784 9471 18784 9473 18785 9499 18785 9833 18785 9475 18786 9499 18786 9473 18786 9477 18787 9499 18787 9475 18787 9477 18788 9834 18788 9499 18788 9479 18789 9834 18789 9477 18789 9479 18790 9835 18790 9834 18790 9480 18791 9835 18791 9479 18791 9480 18792 9836 18792 9835 18792 9482 18793 9836 18793 9480 18793 9484 18794 9836 18794 9482 18794 9484 18795 9510 18795 9836 18795 9485 18796 9510 18796 9484 18796 9487 18797 9510 18797 9485 18797 9487 18798 9512 18798 9510 18798 9489 18799 9512 18799 9487 18799 9489 18800 9514 18800 9512 18800 9489 18801 9837 18801 9514 18801 9491 18802 9837 18802 9489 18802 9493 18803 9838 18803 9491 18803 9491 18804 9838 18804 9837 18804 9495 18805 9838 18805 9493 18805 9495 18806 9521 18806 9838 18806 9496 18807 9521 18807 9495 18807 9496 18808 9524 18808 9521 18808 9498 18809 9524 18809 9496 18809 9498 18810 9839 18810 9524 18810 9500 18811 9839 18811 9498 18811 9502 18812 9839 18812 9500 18812 9502 18813 9840 18813 9839 18813 9503 18814 9840 18814 9502 18814 9909 18815 9840 18815 9503 18815 9909 18816 9841 18816 9840 18816 9505 18817 9841 18817 9909 18817 9505 18818 9842 18818 9841 18818 9507 18819 9842 18819 9505 18819 9507 18820 9536 18820 9842 18820 9509 18821 9536 18821 9507 18821 9511 18822 9536 18822 9509 18822 9511 18823 9843 18823 9536 18823 9513 18824 9843 18824 9511 18824 9515 18825 9844 18825 9513 18825 9513 18826 9844 18826 9843 18826 9910 18827 9844 18827 9515 18827 9910 18828 9543 18828 9844 18828 9516 18829 9543 18829 9910 18829 9516 18830 9545 18830 9543 18830 9518 18831 9545 18831 9516 18831 9518 18832 9547 18832 9545 18832 9520 18833 9547 18833 9518 18833 9522 18834 9547 18834 9520 18834 9522 18835 9845 18835 9547 18835 9523 18836 9845 18836 9522 18836 9523 18837 9550 18837 9845 18837 9526 18838 9550 18838 9523 18838 9526 18839 9846 18839 9550 18839 9527 18840 9846 18840 9526 18840 9529 18841 9846 18841 9527 18841 9529 18842 9555 18842 9846 18842 9529 18843 9556 18843 9555 18843 9531 18844 9556 18844 9529 18844 9532 18845 9559 18845 9531 18845 9531 18846 9559 18846 9556 18846 9534 18847 9559 18847 9532 18847 9534 18848 9847 18848 9559 18848 9535 18849 9847 18849 9534 18849 9537 18850 9847 18850 9535 18850 9537 18851 9563 18851 9847 18851 9539 18852 9563 18852 9537 18852 9539 18853 9848 18853 9563 18853 9540 18854 9848 18854 9539 18854 9540 18855 9849 18855 9848 18855 9542 18856 9849 18856 9540 18856 9544 18857 9849 18857 9542 18857 9544 18858 9571 18858 9849 18858 9546 18859 9571 18859 9544 18859 9546 18860 9850 18860 9571 18860 9548 18861 9850 18861 9546 18861 9549 18862 9850 18862 9548 18862 9549 18863 9851 18863 9850 18863 9551 18864 9851 18864 9549 18864 9553 18865 9851 18865 9551 18865 9553 18866 9852 18866 9851 18866 9554 18867 9852 18867 9553 18867 9554 18868 9582 18868 9852 18868 9557 18869 9582 18869 9554 18869 9557 18870 9853 18870 9582 18870 9558 18871 9853 18871 9557 18871 9558 18872 9586 18872 9853 18872 9561 18873 9586 18873 9558 18873 9561 18874 9854 18874 9586 18874 9562 18875 9854 18875 9561 18875 9562 18876 9590 18876 9854 18876 9565 18877 9590 18877 9562 18877 9565 18878 9855 18878 9590 18878 9566 18879 9855 18879 9565 18879 9568 18880 9855 18880 9566 18880 9568 18881 9596 18881 9855 18881 9570 18882 9596 18882 9568 18882 9570 18883 9856 18883 9596 18883 9911 18884 9856 18884 9570 18884 9572 18885 9856 18885 9911 18885 9572 18886 9857 18886 9856 18886 9574 18887 9857 18887 9572 18887 9574 18888 9603 18888 9857 18888 9576 18889 9603 18889 9574 18889 9576 18890 9605 18890 9603 18890 9578 18891 9605 18891 9576 18891 9578 18892 9858 18892 9605 18892 9579 18893 9858 18893 9578 18893 9579 18894 9859 18894 9858 18894 9581 18895 9859 18895 9579 18895 9581 18896 9860 18896 9859 18896 9583 18897 9860 18897 9581 18897 9583 18898 9861 18898 9860 18898 9585 18899 9861 18899 9583 18899 9587 18900 9861 18900 9585 18900 9587 18901 9862 18901 9861 18901 9589 18902 9862 18902 9587 18902 9591 18903 9862 18903 9589 18903 9591 18904 9617 18904 9862 18904 9592 18905 9617 18905 9591 18905 9592 18906 9863 18906 9617 18906 9594 18907 9863 18907 9592 18907 9595 18908 9863 18908 9594 18908 9595 18909 9621 18909 9863 18909 9597 18910 9621 18910 9595 18910 9597 18911 9864 18911 9621 18911 9599 18912 9864 18912 9597 18912 9600 18913 9864 18913 9599 18913 9600 18914 9628 18914 9864 18914 9600 18915 9865 18915 9628 18915 9602 18916 9865 18916 9600 18916 9604 18917 9865 18917 9602 18917 9604 18918 9866 18918 9865 18918 9606 18919 9866 18919 9604 18919 9606 18920 9634 18920 9866 18920 9608 18921 9867 18921 9606 18921 9606 18922 9867 18922 9634 18922 9610 18923 9867 18923 9608 18923 9610 18924 9868 18924 9867 18924 9611 18925 9868 18925 9610 18925 9611 18926 9641 18926 9868 18926 9613 18927 9641 18927 9611 18927 9615 18928 9641 18928 9613 18928 9615 18929 9869 18929 9641 18929 9616 18930 9869 18930 9615 18930 9618 18931 9869 18931 9616 18931 9618 18932 9870 18932 9869 18932 9620 18933 9870 18933 9618 18933 9622 18934 9870 18934 9620 18934 9622 18935 9871 18935 9870 18935 9912 18936 9871 18936 9622 18936 9624 18937 9871 18937 9912 18937 9624 18938 9651 18938 9871 18938 9627 18939 9651 18939 9624 18939 9627 18940 9653 18940 9651 18940 9629 18941 9653 18941 9627 18941 9629 18942 9872 18942 9653 18942 9913 18943 9872 18943 9629 18943 9913 18944 9658 18944 9872 18944 9631 18945 9658 18945 9913 18945 9631 18946 9873 18946 9658 18946 9633 18947 9873 18947 9631 18947 9636 18948 9873 18948 9633 18948 9636 18949 9662 18949 9873 18949 9639 18950 9662 18950 9636 18950 9639 18951 9874 18951 9662 18951 9640 18952 9874 18952 9639 18952 9640 18953 9667 18953 9874 18953 9642 18954 9667 18954 9640 18954 9642 18955 9669 18955 9667 18955 9644 18956 9669 18956 9642 18956 9646 18957 9669 18957 9644 18957 9646 18958 9671 18958 9669 18958 9647 18959 9671 18959 9646 18959 9647 18960 9673 18960 9671 18960 9648 18961 9673 18961 9647 18961 9648 18962 9875 18962 9673 18962 9650 18963 9875 18963 9648 18963 9650 18964 9677 18964 9875 18964 9652 18965 9677 18965 9650 18965 9652 18966 9876 18966 9677 18966 9654 18967 9876 18967 9652 18967 9656 18968 9876 18968 9654 18968 9656 18969 9877 18969 9876 18969 9657 18970 9877 18970 9656 18970 9657 18971 9878 18971 9877 18971 9659 18972 9878 18972 9657 18972 9659 18973 9879 18973 9878 18973 9661 18974 9879 18974 9659 18974 9663 18975 9879 18975 9661 18975 9663 18976 9880 18976 9879 18976 9665 18977 9880 18977 9663 18977 9665 18978 9881 18978 9880 18978 9666 18979 9881 18979 9665 18979 9666 18980 9882 18980 9881 18980 9668 18981 9882 18981 9666 18981 9670 18982 9882 18982 9668 18982 9670 18983 9883 18983 9882 18983 9672 18984 9883 18984 9670 18984 9674 18985 9883 18985 9672 18985 9674 18986 9884 18986 9883 18986 9676 18987 9884 18987 9674 18987 9676 18988 9885 18988 9884 18988 9678 18989 9885 18989 9676 18989 9678 18990 9886 18990 9885 18990 9679 18991 9886 18991 9678 18991 9681 18992 9887 18992 9679 18992 9679 18993 9887 18993 9886 18993 9681 18994 9888 18994 9887 18994 9914 18995 9888 18995 9681 18995 9683 18996 9888 18996 9914 18996 9683 18997 9889 18997 9888 18997 9685 18998 9889 18998 9683 18998 9687 18999 9889 18999 9685 18999 9687 19000 9890 19000 9889 19000 9689 19001 9890 19001 9687 19001 9689 19002 9716 19002 9890 19002 9691 19003 9716 19003 9689 19003 9691 19004 9891 19004 9716 19004 9692 19005 9891 19005 9691 19005 9692 19006 9718 19006 9891 19006 9694 19007 9718 19007 9692 19007 9694 19008 9892 19008 9718 19008 9696 19009 9892 19009 9694 19009 9696 19010 9893 19010 9892 19010 9698 19011 9893 19011 9696 19011 9699 19012 9893 19012 9698 19012 9699 19013 9894 19013 9893 19013 9701 19014 9894 19014 9699 19014 9703 19015 9894 19015 9701 19015 9703 19016 9895 19016 9894 19016 9704 19017 9895 19017 9703 19017 9704 19018 9896 19018 9895 19018 9706 19019 9896 19019 9704 19019 9707 19020 9896 19020 9706 19020 9707 19021 9897 19021 9896 19021 9709 19022 9897 19022 9707 19022 9710 19023 9897 19023 9709 19023 9710 19024 9735 19024 9897 19024 9712 19025 9735 19025 9710 19025 9712 19026 9898 19026 9735 19026 9713 19027 9898 19027 9712 19027 9715 19028 9898 19028 9713 19028 9715 19029 9899 19029 9898 19029 9717 19030 9899 19030 9715 19030 9717 19031 9900 19031 9899 19031 9719 19032 9900 19032 9717 19032 9719 19033 9901 19033 9900 19033 9721 19034 9901 19034 9719 19034 9723 19035 9901 19035 9721 19035 9723 19036 9132 19036 9901 19036 9723 19037 9131 19037 9132 19037 9725 19038 9131 19038 9723 19038 9725 19039 9133 19039 9131 19039 9727 19040 9133 19040 9725 19040 9727 19041 9136 19041 9133 19041 9728 19042 9136 19042 9727 19042 9730 19043 9136 19043 9728 19043 9730 19044 9139 19044 9136 19044 9732 19045 9139 19045 9730 19045 9732 19046 9142 19046 9139 19046 9145 19047 9904 19047 9902 19047 9147 19048 9145 19048 9146 19048 9156 19049 9905 19049 9154 19049 9906 19050 9905 19050 9156 19050 9158 19051 9906 19051 9156 19051 9198 19052 9907 19052 9196 19052 9908 19053 9404 19053 9405 19053 9407 19054 9908 19054 9405 19054 9412 19055 9409 19055 9410 19055 9505 19056 9909 19056 9503 19056 9516 19057 9910 19057 9515 19057 9572 19058 9911 19058 9570 19058 9624 19059 9912 19059 9622 19059 9627 19060 9624 19060 9626 19060 9631 19061 9913 19061 9629 19061 9639 19062 9636 19062 9637 19062 9683 19063 9914 19063 9681 19063 9938 19064 9142 19064 9734 19064 9915 19065 9951 19065 9916 19065 9917 19066 9915 19066 9918 19066 9918 19067 9915 19067 9916 19067 9919 19068 9917 19068 9918 19068 9920 19069 9134 19069 9917 19069 9920 19070 9917 19070 9919 19070 9921 19071 9918 19071 9916 19071 9923 19072 9919 19072 9918 19072 9921 19073 9923 19073 9918 19073 9922 19074 9921 19074 9916 19074 9919 19075 9140 19075 9920 19075 9923 19076 9140 19076 9919 19076 9925 19077 9923 19077 9921 19077 9926 19078 9921 19078 9922 19078 9926 19079 9925 19079 9921 19079 9926 19080 9922 19080 9924 19080 9140 19081 9923 19081 9925 19081 9925 19082 9928 19082 9140 19082 9927 19083 9925 19083 9926 19083 9928 19084 9925 19084 9927 19084 9927 19085 9926 19085 9924 19085 9929 19086 9928 19086 9927 19086 9927 19087 9924 19087 9930 19087 9932 19088 9927 19088 9930 19088 9933 19089 9930 19089 9924 19089 9929 19090 9927 19090 9932 19090 9929 19091 9143 19091 9928 19091 9933 19092 9924 19092 9931 19092 9932 19093 9930 19093 9933 19093 9143 19094 9929 19094 9932 19094 9934 19095 9932 19095 9933 19095 9144 19096 9143 19096 9932 19096 9144 19097 9932 19097 9934 19097 9935 19098 9934 19098 9933 19098 9935 19099 9933 19099 9931 19099 9736 19100 9934 19100 9935 19100 9937 19101 9935 19101 9931 19101 9736 19102 9144 19102 9934 19102 9937 19103 9931 19103 9936 19103 9938 19104 9935 19104 9937 19104 9938 19105 9736 19105 9935 19105 9734 19106 9736 19106 9938 19106 9940 19107 9937 19107 9936 19107 9939 19108 9938 19108 9937 19108 9939 19109 9937 19109 9940 19109 9939 19110 9142 19110 9938 19110 9940 19111 9936 19111 9942 19111 9943 19112 9939 19112 9940 19112 9943 19113 9142 19113 9939 19113 9943 19114 9940 19114 9942 19114 9942 19115 9936 19115 9941 19115 9139 19116 9142 19116 9943 19116 9944 19117 9943 19117 9942 19117 9943 19118 9944 19118 9139 19118 9947 19119 9942 19119 9941 19119 9946 19120 9942 19120 9947 19120 9946 19121 9944 19121 9942 19121 9947 19122 9941 19122 9945 19122 9946 19123 9137 19123 9944 19123 9948 19124 9946 19124 9947 19124 9948 19125 9947 19125 9945 19125 9949 19126 9137 19126 9946 19126 9949 19127 9946 19127 9948 19127 9950 19128 9948 19128 9945 19128 9952 19129 9948 19129 9950 19129 9951 19130 9950 19130 9945 19130 9952 19131 9949 19131 9948 19131 9953 19132 9952 19132 9950 19132 9952 19133 9954 19133 9949 19133 9953 19134 9950 19134 9951 19134 9955 19135 9954 19135 9952 19135 9953 19136 9955 19136 9952 19136 9955 19137 9130 19137 9954 19137 9956 19138 9953 19138 9951 19138 9955 19139 9953 19139 9956 19139 9957 19140 9956 19140 9951 19140 9130 19141 9955 19141 9956 19141 9958 19142 9956 19142 9957 19142 9915 19143 9957 19143 9951 19143 9958 19144 9957 19144 9915 19144 9130 19145 9956 19145 9958 19145 9958 19146 9134 19146 9130 19146 9958 19147 9915 19147 9917 19147 9958 19148 9917 19148 9134 19148 9931 19149 9916 19149 9951 19149 9931 19150 9951 19150 9945 19150 9931 19151 9945 19151 9941 19151 9931 19152 9941 19152 9936 19152 9931 19153 9924 19153 9922 19153 9931 19154 9922 19154 9916 19154 9960 19155 9965 19155 9968 19155 9960 19156 9959 19156 9965 19156 9959 19157 9961 19157 9965 19157 9965 19158 9961 19158 9966 19158 9961 19159 9962 19159 9966 19159 9966 19160 9962 19160 9970 19160 9962 19161 9963 19161 9970 19161 9970 19162 9963 19162 9969 19162 9963 19163 9964 19163 9969 19163 9969 19164 9964 19164 9967 19164 9964 19165 9968 19165 9967 19165 9964 19166 9960 19166 9968 19166 9966 19167 9971 19167 9972 19167 9966 19168 9972 19168 9973 19168 9970 19169 9975 19169 9974 19169 9970 19170 9974 19170 9971 19170 9970 19171 9971 19171 9966 19171 9970 19172 9978 19172 9975 19172 9965 19173 9966 19173 9973 19173 9965 19174 9973 19174 9976 19174 9969 19175 9977 19175 9978 19175 9969 19176 9978 19176 9970 19176 9979 19177 9965 19177 9976 19177 9968 19178 9965 19178 9979 19178 9980 19179 9977 19179 9969 19179 9981 19180 9968 19180 9979 19180 9982 19181 9980 19181 9969 19181 9982 19182 9969 19182 9967 19182 9983 19183 9968 19183 9981 19183 9983 19184 9967 19184 9968 19184 9984 19185 9982 19185 9967 19185 9984 19186 9967 19186 9983 19186 9959 19187 9963 19187 9961 19187 9961 19188 9963 19188 9962 19188 9964 19189 9963 19189 9960 19189 9960 19190 9963 19190 9959 19190 9985 19191 9997 19191 9975 19191 9985 19192 9975 19192 9978 19192 9986 19193 9985 19193 9978 19193 9986 19194 9978 19194 9977 19194 9987 19195 9977 19195 9980 19195 9987 19196 9986 19196 9977 19196 9987 19197 9980 19197 9982 19197 9988 19198 9987 19198 9982 19198 9988 19199 9982 19199 9984 19199 9989 19200 9988 19200 9984 19200 9989 19201 9984 19201 9983 19201 9990 19202 9989 19202 9983 19202 9990 19203 9983 19203 9981 19203 9991 19204 9990 19204 9981 19204 9991 19205 9981 19205 9979 19205 9991 19206 9979 19206 9976 19206 9992 19207 9991 19207 9976 19207 9992 19208 9976 19208 9973 19208 9993 19209 9992 19209 9973 19209 9994 19210 9993 19210 9973 19210 9994 19211 9973 19211 9972 19211 9995 19212 9994 19212 9972 19212 9995 19213 9972 19213 9971 19213 9996 19214 9995 19214 9971 19214 9996 19215 9971 19215 9974 19215 9997 19216 9996 19216 9974 19216 9997 19217 9974 19217 9975 19217 9739 19218 9991 19218 9992 19218 9148 19219 9991 19219 9739 19219 9739 19220 9992 19220 9993 19220 9740 19221 9739 19221 9993 19221 9148 19222 9990 19222 9991 19222 9740 19223 9993 19223 9994 19223 9741 19224 9740 19224 9994 19224 9148 19225 9989 19225 9990 19225 9152 19226 9989 19226 9148 19226 9741 19227 9994 19227 9995 19227 9903 19228 9741 19228 9995 19228 9988 19229 9989 19229 9152 19229 9996 19230 9903 19230 9995 19230 9988 19231 9152 19231 9150 19231 9987 19232 9988 19232 9150 19232 9996 19233 9902 19233 9903 19233 9997 19234 9902 19234 9996 19234 9987 19235 9150 19235 9146 19235 9985 19236 9902 19236 9997 19236 9986 19237 9987 19237 9146 19237 9985 19238 9145 19238 9902 19238 9986 19239 9146 19239 9145 19239 9986 19240 9145 19240 9985 19240

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 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 + + + + + + + +
\ No newline at end of file diff --git a/models/gimbal_small_3d/model.config b/models/gimbal_small_3d/model.config new file mode 100644 index 0000000..d91da66 --- /dev/null +++ b/models/gimbal_small_3d/model.config @@ -0,0 +1,21 @@ + + + Gimbal Small 3D + 2.0 + model.sdf + + + Rhys Mainwaring + rhys.mainwaring@me.com + + + + MotorPixie 3D Gimbal for DJI Phantom 2 Vision - Discontinued. + 3D mesh: https://www.thingiverse.com/thing:391130 + by: http://www.thingiverse.com/Motorpixiegimbals/about. + + 11 May, 2023: model retrieved from + https://www.thingiverse.com/thing:391130 + and modified for Gazebo in FreeCAD and Blender. + + diff --git a/models/gimbal_small_3d/model.sdf b/models/gimbal_small_3d/model.sdf new file mode 100644 index 0000000..ada294d --- /dev/null +++ b/models/gimbal_small_3d/model.sdf @@ -0,0 +1,231 @@ + + + + 0 0 0.18 0 0 0 + + + 0.2 + + 0.0001 + 0 + 0 + 0.0001 + 0 + 0.0001 + + + + + + model://gimbal_small_3d/meshes/base_plate.dae + + + + 0.1 0.1 0.1 + 0.1 0.1 0.1 + 0.01 0.01 0.01 1.0 + + + + 0.01 0.075 -0.025 0 0 0 + + + 0.1 0.05 0.15 + + + + + + + + 0.01 + + 0.00001 + 0 + 0 + 0.00001 + 0 + 0.00001 + + + + + + model://gimbal_small_3d/meshes/yaw_arm.dae + + + + 0.1 0.1 0.1 + 0.1 0.1 0.1 + 0.01 0.01 0.01 1.0 + + + + + + model://gimbal_small_3d/meshes/yaw_arm.dae + + + + + + base_link + yaw_link + + 0 1 0 + + 0.5 + + + -1.57079632 + 1.57079632 + + + 0.0105 0.065 -0.002 0 0 0 + + + + + 0.01 + + 0.00001 + 0 + 0 + 0.00001 + 0 + 0.00001 + + + + + + model://gimbal_small_3d/meshes/roll_arm.dae + + + + 0.1 0.1 0.1 + 0.1 0.1 0.1 + 0.01 0.01 0.01 1.0 + + + + + + model://gimbal_small_3d/meshes/roll_arm.dae + + + + + + yaw_link + roll_link + + 0 0 1 + + 0.5 + + + -1.57079632 + 1.57079632 + + + 0.0099 0.002 -0.05 0 0 0 + + + + + 0.01 + + 0.00001 + 0 + 0 + 0.00001 + 0 + 0.00001 + + + + 0 0 0 0 0 0 + + + model://gimbal_small_3d/meshes/camera_enclosure.dae + + + + 0.4 0.4 0.4 + 0.4 0.4 0.4 + 0.1 0.1 0.1 1.0 + + + + 0 0 0 0 0 0 + + + model://gimbal_small_3d/meshes/camera_enclosure.dae + + + + + 0 0 0.02 0 0 0 + + + 0.025 + 0.050 + + + + 0.4 0.4 0.4 + 0.4 0.4 0.4 + 0.1 0.1 0.1 1.0 + + + + 0 0 0.02 0 0 0 + + + 0.025 + 0.050 + + + + + 0 0 0 -1.57 -1.57 0 + + 2.0 + + 640 + 480 + + + 0.05 + 15000 + + + 1 + 10 + 1 + + + 15.0 + + + + + + roll_link + pitch_link + + 1 0 0 + + 0.5 + + + -1.57079632 + 1.57079632 + + + 0.045 0.0021 0.0199 0 0 0 + + + diff --git a/src/CameraZoomPlugin.cc b/src/CameraZoomPlugin.cc new file mode 100644 index 0000000..f65473a --- /dev/null +++ b/src/CameraZoomPlugin.cc @@ -0,0 +1,412 @@ +/* + Copyright (C) 2023 ArduPilot.org + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "CameraZoomPlugin.hh" + +#include +#include +#include + +#include + +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include "gz/sim/Events.hh" +#include +#include +/// \todo(srmainwaring) use when gz-sim7 v7.5 is released. +// #include +#include +#include + +#include + +#include +#include + +namespace gz { +namespace sim { +inline namespace GZ_SIM_VERSION_NAMESPACE { +namespace systems { + +////////////////////////////////////////////////// +class CameraZoomPlugin::Impl +{ + /// \brief Handle a zoom command. + public: void OnZoom(const msgs::Double &_msg); + + /// \brief Initialise the rendering camera. + public: void InitialiseCamera(); + + /// \todo(srmainwaring) replace with `gz::sim::Sensor` when available. + /// \brief Check sensor entity is valid. + public: bool SensorValid(const EntityComponentManager &_ecm) const + { + return nullptr != + _ecm.Component(this->cameraSensorEntity); + } + + /// \todo(srmainwaring) replace with `gz::sim::Sensor` when available. + /// \brief Get sensor name. + public: std::optional SensorName( + const EntityComponentManager &_ecm) const + { + return _ecm.ComponentData(this->cameraSensorEntity); + } + + /// \todo(srmainwaring) replace with `gz::sim::Sensor` when available. + /// \brief Get sensor parent. + public: std::optional SensorParent( + const EntityComponentManager &_ecm) const + { + auto parent = + _ecm.Component(this->cameraSensorEntity); + + if (!parent) + return std::nullopt; + + return std::optional(parent->Data()); + } + + + /// \brief World occupied by the parent model. + public: World world{kNullEntity}; + + /// \brief The parent model. + public: Model parentModel{kNullEntity}; + + /// \brief Camera sensor. + /// \todo(srmainwaring) replace with `gz::sim::Sensor` when available. + // public: Sensor cameraSensor{kNullEntity}; + public: Entity cameraSensorEntity{kNullEntity}; + + /// \brief Name of the camera. + public: std::string cameraName; + + /// \brief Name of the topic to subscribe to zoom commands. + public: std::string zoomTopic; + + /// \brief Flag to mark if zoom command has changed. + public: std::atomic zoomChanged{false}; + + /// \brief Value of the most recently received zoom command. + public: std::atomic zoomCommand{1.0}; + + /// \brief Current horizontal field of view (radians). + public: double hfov{2.0}; + + /// \brief Zoom factor. + public: double zoom{1.0}; + + /// \brief Maximum zoom factor. + public: double maxZoom{10.0}; + + /// \brief Minimum zoom factor == 1.0. + public: static constexpr double minZoom{1.0}; + + /// \brief Flag set to true if the plugin is correctly initialised. + public: bool isValidConfig{false}; + + /// \brief Connections to event callbacks. + public: std::vector connections; + + /// \brief Transport node for subscriptions. + public: transport::Node node; + + /// \brief Reset the camera and scene when the tear down event is received. + public: void OnRenderTeardown(); + + //// \brief Pointer to the rendering scene + public: rendering::ScenePtr scene; + + /// \brief Pointer to the rendering camera + public: rendering::CameraPtr camera; +}; + +////////////////////////////////////////////////// +void CameraZoomPlugin::Impl::OnZoom(const msgs::Double &_msg) +{ + this->zoomCommand = _msg.data(); + this->zoomChanged = true; +} + +////////////////////////////////////////////////// +void CameraZoomPlugin::Impl::InitialiseCamera() +{ + // Wait for render engine to be available. + if (rendering::loadedEngines().empty()) + return; + + // Get scene. + if (!this->scene) + { + this->scene = rendering::sceneFromFirstRenderEngine(); + } + + // Return if scene not ready or no sensors available. + if (!this->scene->IsInitialized() || + this->scene->SensorCount() == 0) + { + gzwarn << "No scene or camera sensors available.\n"; + return; + } + + // Get camera. + if (!this->camera) + { + auto sensor = this->scene->SensorByName(this->cameraName); + if (!sensor) + { + gzerr << "Unable to find sensor: [" << this->cameraName << "]." + << std::endl; + return; + } + this->camera = std::dynamic_pointer_cast(sensor); + if (!this->camera) + { + gzerr << "[" << this->cameraName << "] is not a camera." + << std::endl; + return; + } + } +} + +////////////////////////////////////////////////// +void CameraZoomPlugin::Impl::OnRenderTeardown() +{ + gzdbg << "CameraZoomPlugin disabled.\n"; + + this->camera.reset(); + this->scene.reset(); + this->isValidConfig = false; +} + +////////////////////////////////////////////////// +////////////////////////////////////////////////// +CameraZoomPlugin::~CameraZoomPlugin() = default; + +////////////////////////////////////////////////// +CameraZoomPlugin::CameraZoomPlugin() : + impl(std::make_unique()) +{ +} + +////////////////////////////////////////////////// +void CameraZoomPlugin::Configure( + const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &_eventMgr) +{ + // Capture camera sensor. + /// \todo(srmainwaring) replace with `gz::sim::Sensor` when available. + // this->impl->cameraSensor = Sensor(_entity); + // if (!this->impl->cameraSensor.Valid(_ecm)) + this->impl->cameraSensorEntity = _entity; + if (!this->impl->SensorValid(_ecm)) + { + gzerr << "CameraZoomPlugin must be attached to a camera sensor. " + "Failed to initialize.\n"; + return; + } + + // Display plugin load status. + /// \todo(srmainwaring) replace with `gz::sim::Sensor` when available. + // if (auto maybeName = this->impl->cameraSensor.Name(_ecm)) + if (auto maybeName = this->impl->SensorName(_ecm)) + { + gzdbg << "CameraZoomPlugin attached to sensor [" + << maybeName.value() << "].\n"; + } + else + { + gzerr << "Camera sensor has invalid name.\n"; + return; + } + + // Retrieve parent model. + /// \todo(srmainwaring) replace with `gz::sim::Sensor` when available. + // if (auto maybeParentLink = this->impl->cameraSensor.Parent(_ecm)) + if (auto maybeParentLink = this->impl->SensorParent(_ecm)) + { + Link link(maybeParentLink.value()); + if (link.Valid(_ecm)) + { + if (auto maybeParentModel = link.ParentModel(_ecm)) + { + this->impl->parentModel = maybeParentModel.value(); + } + } + } + if (!this->impl->parentModel.Valid(_ecm)) + { + gzerr << "CameraZoomPlugin - parent model not found. " + "Failed to initialize.\n"; + return; + } + + // Retrieve world entity. + this->impl->world = World( + _ecm.EntityByComponents(components::World())); + if (!this->impl->world.Valid(_ecm)) + { + gzerr << "CameraZoomPlugin - world not found. " + "Failed to initialize.\n"; + return; + } + + // Parameters + if (_sdf->HasElement("max_zoom")) + { + this->impl->maxZoom = _sdf->Get("max_zoom"); + } + + // Configure zoom command topic. + { + std::vector topics; + if (_sdf->HasElement("topic")) + { + topics.push_back(_sdf->Get("topic")); + } + auto parentModelName = this->impl->parentModel.Name(_ecm); + /// \todo(srmainwaring) replace with `gz::sim::Sensor` when available. + // auto sensorName = this->impl->cameraSensor.Name(_ecm).value(); + auto sensorName = this->impl->SensorName(_ecm).value(); + topics.push_back("/model/" + parentModelName + + "/sensor/" + sensorName + "/zoom/cmd_zoom"); + this->impl->zoomTopic = validTopic(topics); + } + + // Subscriptions. + this->impl->node.Subscribe( + this->impl->zoomTopic, + &CameraZoomPlugin::Impl::OnZoom, this->impl.get()); + + gzdbg << "CameraZoomPlugin subscribing to messages on " + << "[" << this->impl->zoomTopic << "]\n"; + + // Connections + this->impl->connections.push_back( + _eventMgr.Connect( + std::bind(&CameraZoomPlugin::Impl::OnRenderTeardown, + this->impl.get()))); + + this->impl->isValidConfig = true; +} + +////////////////////////////////////////////////// +void CameraZoomPlugin::PreUpdate( + const UpdateInfo &/*_info*/, + EntityComponentManager &_ecm) +{ + GZ_PROFILE("CameraZoomPlugin::PreUpdate"); + + if (!this->impl->isValidConfig) + return; + + // Set up the render connection. + if (!this->impl->camera) + { + this->impl->InitialiseCamera(); + return; + } + + /// \todo(srmainwaring) replace with `gz::sim::Sensor` when available. + // Entity cameraEntity = this->impl->cameraSensor.Entity(); + Entity cameraEntity = this->impl->cameraSensorEntity; + auto comp = _ecm.Component(cameraEntity); + if (!comp) + return; + + if (!this->impl->zoomChanged) + return; + + // Update component. + sdf::Sensor &sensor = comp->Data(); + sdf::Camera *cameraSdf = sensor.CameraSensor(); + + this->impl->zoom = std::max(std::min(this->impl->zoomCommand.load(), + this->impl->maxZoom), this->impl->minZoom); + math::Angle oldHfov = cameraSdf->HorizontalFov(); + math::Angle newHfov = this->impl->hfov / this->impl->zoom; + + cameraSdf->SetHorizontalFov(newHfov); + _ecm.SetChanged(cameraEntity, components::Camera::typeId, + ComponentState::OneTimeChange); + + // Update rendering camera. + this->impl->camera->SetHFOV(newHfov); + + gzdbg << "CameraZoomPlugin:\n" + << "Zoom: " << this->impl->zoom << "\n" + << "Old HFOV: " << oldHfov << " rad\n" + << "New HFOV: " << newHfov << " rad\n"; + + this->impl->zoomChanged = false; +} + +////////////////////////////////////////////////// +void CameraZoomPlugin::PostUpdate( + const UpdateInfo &/*_info*/, + const EntityComponentManager &_ecm) +{ + if (!this->impl->cameraName.empty()) + return; + + /// \todo(srmainwaring) replace with `gz::sim::Sensor` when available. + // Entity cameraEntity = this->impl->cameraSensor.Entity(); + Entity cameraEntity = this->impl->cameraSensorEntity; + this->impl->cameraName = + removeParentScope(scopedName(cameraEntity, _ecm, "::", false), "::"); + + gzdbg << "Camera name: [" << this->impl->cameraName << "].\n"; +} + +////////////////////////////////////////////////// + +} // namespace systems +} +} // namespace sim +} // namespace gz + +GZ_ADD_PLUGIN( + gz::sim::systems::CameraZoomPlugin, + gz::sim::System, + gz::sim::systems::CameraZoomPlugin::ISystemConfigure, + gz::sim::systems::CameraZoomPlugin::ISystemPreUpdate, + gz::sim::systems::CameraZoomPlugin::ISystemPostUpdate) + +GZ_ADD_PLUGIN_ALIAS( + gz::sim::systems::CameraZoomPlugin, + "CameraZoomPlugin") diff --git a/tests/worlds/test_gimbal.sdf b/tests/worlds/test_gimbal.sdf index 73960da..728702b 100755 --- a/tests/worlds/test_gimbal.sdf +++ b/tests/worlds/test_gimbal.sdf @@ -6,22 +6,21 @@ 1.0 - + - + ogre2 - + - + - + @@ -52,11 +51,10 @@ - + 2 0 0.5 0 0 0 @@ -137,21 +134,25 @@ - + - - gimbal::arm_joint - arm_cmd + + gimbal::roll_joint + /gimbal/cmd_roll 2 - + gimbal::tilt_joint - tilt_cmd + /gimbal/cmd_pitch + 2 + + + gimbal::yaw_joint + /gimbal/cmd_yaw 2 diff --git a/worlds/gimbal.sdf b/worlds/gimbal.sdf new file mode 100755 index 0000000..8c1dfff --- /dev/null +++ b/worlds/gimbal.sdf @@ -0,0 +1,288 @@ + + + + + 0.001 + 1.0 + + + + + + ogre2 + + + + + + + + + + 1.0 1.0 1.0 + 0.8 0.8 0.8 + + + + + 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 + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + + + + 10 + + 0.13733333 + 0.00 + 0.00 + 0.13733333 + 0.00 + 0.008 + + + + -0.2 0 0.5 0 0 0 + + + 0.04 + 1.0 + + + + 1 1 0 + 1 1 0 + 0.1 0.1 0 1 + + + + -0.1 0 1.01 0 0 0 + + + 0.2 + 0.02 + + + + 1 1 0 + 1 1 0 + 0.1 0.1 0 1 + + + + -0.2 0 0.5 0 0 0 + + + 0.04 + 1.0 + + + + + -0.1 0 1.01 0 0 0 + + + 0.2 + 0.02 + + + + + + world + mount_link + + + + model://gimbal_small_3d + gimbal + 0 0 0.9055 90 0 90 + + + mount_link + gimbal::base_link + + + 0.5 + + + 0 + 0 + + 0 0 1 + + + + + + + gimbal::yaw_joint + /gimbal/cmd_yaw + 2 + + + gimbal::roll_joint + /gimbal/cmd_roll + 2 + + + gimbal::pitch_joint + /gimbal/cmd_pitch + 2 + + + + + + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Oak tree + oak_tree0 + 10 10 0 0 0 0 + + + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Oak tree + oak_tree1 + 8 15 0 0 0 0 + + + + + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Pine Tree + pine_tree0 + 15 -15 0 0 0 0 + + + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Pine Tree + pine_tree1 + 10 -20 0 0 0 0 + + + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Pine Tree + pine_tree2 + 12 -10 0 0 0 0 + + + + + https://fuel.gazebosim.org/1.0/OpenRobotics/models/ground_station + ground_station + 10 0 0 0 0 0 + + + + + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Walking person + walking_person0 + 8 2 0 0 0 0 + + + + + https://fuel.gazebosim.org/1.0/plateau/models/Casual female + casual_female0 + 6 -4 0 0 0 145 + + + + + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Prius Hybrid + prius_hybrid0 + 0 7 0 0 0 40 + + + +