From 321371c1f67aa181b906620fa7a227838518ebc9 Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Thu, 22 Dec 2022 09:39:40 +0000 Subject: [PATCH] Add parachute plugin (#36) * Parachute: initial version 1. Add parachute model from px4 gazebo 2. Initial parachute support 3. gitignore upd 4. cmakelists add ParachuteLib 5. cmake add debug config 6. fix debug options 7. create parachute on release Author: Alex Molchanov ardupilot parachute initial support * Parachute: migrate to gz-sim, add tests and prepare for PR 1. Parachute: namespace migration - Migrate from ignition to gz. - Fix for cpplint. Signed-off-by: Rhys Mainwaring 2. Parachute: move implementation details to private class. Signed-off-by: Rhys Mainwaring 3. Parachute: update plugin - Update variable name to Gazebo style. - Remove unused variables. - Only create parachute model if not already created. Signed-off-by: Rhys Mainwaring 4. Parachute: update plugin - Fix linter. Signed-off-by: Rhys Mainwaring 5. Parachute: update model and world files - Add notes re. servo config for parachute to zephyr model. - Add review notes to zephyr runway world and param settings. Signed-off-by: Rhys Mainwaring 6. Parachute: apply formatting changes to parachute model Signed-off-by: Rhys Mainwaring 7. Parachute: revert changes to ArduPilotPlugin - Revert changes to ArduPilotPlugin and use the COMMAND control type to forward parachute servo commands. - Update ParachutePlugin to subscribe to a servo command (double). - Update control xml for parachute in zephyr_with_ardupilot model. Signed-off-by: Rhys Mainwaring 8. Parachute: update ParachutePlugin - Remove unused code - simplify plugin to minimal functionality (parachute release only). Signed-off-by: Rhys Mainwaring 9. Parachute: add test world - Add box with parachute attached to test deployment and pose. Signed-off-by: Rhys Mainwaring 10. Parachute: update test world Models - Attach plugin to model rather than world. - Add usage notes Plugin - Verify plugin attached to model. - Use Link to wrap link entities. - Resolve parent link in configure rather than at update time. - Enable velocity checks so we can get parent link pose. Signed-off-by: Rhys Mainwaring 11. Parachute: update parachute model - Change collision to a sphere matching the parachute canopy. - Update lift-drag plugin to gz::sim. Signed-off-by: Rhys Mainwaring 12. Parachute: update zephyr model and world Models - Add 'attachment_link' to connect to parachute when it is released. - Move parachute plugin into model and update sdf definitions. Plugin - Change pose parameter name to 'child_pose'. - Update pose variable names to use Kane notation and simplify calculation. Signed-off-by: Rhys Mainwaring 13. Parachute: update parachute model - Update inertial and move CoM to centre of collision sphere. - Update pose notation. - Add version where only the position of the parachute may be adjusted (no rotation). Signed-off-by: Rhys Mainwaring 14. Parachute: update parachute model - Fix for cpplint. Signed-off-by: Rhys Mainwaring 15. Parachute: update zephyr model - Alter angle of parachute on release (towards rear of aircraft) Signed-off-by: Rhys Mainwaring 16. Parachute: add separate models and worlds for the parachute example. Signed-off-by: Rhys Mainwaring 17. Parachute: revert changes to original zephyr models and worlds. Signed-off-by: Rhys Mainwaring 18. Parachute: update class documentation - Fix name of zephyr_with_parachute in model. - Refer to correct model in zephyr_parachute world. - Document header with parameter descriptions. - Document private class in ParachutePlugin.cc - Fix MAVProxy commands in zephyr example help. Signed-off-by: Rhys Mainwaring * Parachute: standardise topic names and relocate test worlds - Update plugin documentation. - Update parachute release command topic to match other Gazebo system plugins. - Update example models and worlds to use new topic name. - Move the test world under ./tests/worlds/ Signed-off-by: Rhys Mainwaring Co-authored-by: Alex Molchanov --- .gitignore | 4 + CMakeLists.txt | 15 +- include/ParachutePlugin.hh | 80 ++++ .../meshes/parachute_small.dae | 174 ++++++++ models/parachute_small/model.config | 18 + models/parachute_small/model.sdf | 66 +++ models/zephyr/meshes/parachute_small.dae | 174 ++++++++ models/zephyr_with_parachute/model.config | 27 ++ models/zephyr_with_parachute/model.sdf | 315 ++++++++++++++ src/ParachutePlugin.cc | 390 ++++++++++++++++++ tests/worlds/test_parachute.sdf | 142 +++++++ worlds/zephyr_parachute.sdf | 154 +++++++ 12 files changed, 1557 insertions(+), 2 deletions(-) create mode 100644 include/ParachutePlugin.hh create mode 100644 models/parachute_small/meshes/parachute_small.dae create mode 100644 models/parachute_small/model.config create mode 100644 models/parachute_small/model.sdf create mode 100644 models/zephyr/meshes/parachute_small.dae create mode 100644 models/zephyr_with_parachute/model.config create mode 100644 models/zephyr_with_parachute/model.sdf create mode 100644 src/ParachutePlugin.cc create mode 100755 tests/worlds/test_parachute.sdf create mode 100755 worlds/zephyr_parachute.sdf diff --git a/.gitignore b/.gitignore index a538daa..41719bb 100755 --- a/.gitignore +++ b/.gitignore @@ -26,6 +26,10 @@ msg/_*.py .project .cproject +# vscode +.vscode +.devcontainer + # qcreator stuff CMakeLists.txt.user diff --git a/CMakeLists.txt b/CMakeLists.txt index 8d69ea0..521d570 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -39,12 +39,23 @@ add_library(ArduPilotPlugin src/Socket.cpp src/Util.cc ) - target_include_directories(ArduPilotPlugin PUBLIC include ${GZ-SIM_INCLUDE_DIRS} ) - target_link_libraries(ArduPilotPlugin PUBLIC ${GZ-SIM_LIBRARIES} ) + +add_library(ParachutePlugin + SHARED + src/ParachutePlugin.cc +) +target_include_directories(ParachutePlugin PUBLIC + include + ${GZ-SIM_INCLUDE_DIRS} +) + +target_link_libraries(ParachutePlugin PUBLIC + ${GZ-SIM_LIBRARIES} +) \ No newline at end of file diff --git a/include/ParachutePlugin.hh b/include/ParachutePlugin.hh new file mode 100644 index 0000000..5dd7779 --- /dev/null +++ b/include/ParachutePlugin.hh @@ -0,0 +1,80 @@ +/* + Copyright (C) 2022 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 PARACHUTEPLUGIN_HH_ +#define PARACHUTEPLUGIN_HH_ + +#include + +#include + +namespace gz { +namespace sim { +inline namespace GZ_SIM_VERSION_NAMESPACE { +namespace systems { + +/// \brief Parachute releaase plugin which may be attached to a model. +/// +/// ## System Parameters: +/// +/// `` The link in the target model to attach the parachute. +/// Required. +/// +/// `` The name of the parachute model. +/// Required. +/// +/// `` The base link of the parachute model (bridle point). +/// Required. +/// +/// `` The relative pose of parent link to the child link. +/// The default value is: `0, 0, 0, 0, 0, 0`. +/// +/// `` The topic to receive the parachute release command. +/// The default value is: `/model//parachute/cmd_release`. +/// +class ParachutePlugin : + public System, + public ISystemPreUpdate, + public ISystemConfigure +{ + /// \brief Destructor + public: virtual ~ParachutePlugin(); + + /// \brief Constructor + public: ParachutePlugin(); + + // Documentation inherited + public: void PreUpdate(const gz::sim::UpdateInfo &_info, + 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 // PARACHUTEPLUGIN_HH_ diff --git a/models/parachute_small/meshes/parachute_small.dae b/models/parachute_small/meshes/parachute_small.dae new file mode 100644 index 0000000..8d3be3a --- /dev/null +++ b/models/parachute_small/meshes/parachute_small.dae @@ -0,0 +1,174 @@ + + + + + Blender User + Blender 2.75.0 commit date:2015-07-07, commit time:14:56, hash:c27589e + + 2015-11-30T00:26:27 + 2015-11-30T00:26:27 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0.5200037 0.5200037 0.5200037 1 + + + 0.5200037 0.5200037 0.5200037 1 + + + 0.09782609 0.09782609 0.09782609 1 + + + 50 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.3815912 0.002340029 0.004364488 1 + + + 0.3815912 0.002340029 0.004364488 1 + + + 0.2065217 0.04548923 0.04548923 1 + + + 50 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.3508343 0.2753002 0.109524 1 + + + 0.3508343 0.2753002 0.109524 1 + + + 1 + + + + + + + + + + + + + + + + + + + + + + -0.7071068 0 0.7071068 -0.1643761 0.01479417 1.042025 -0.3247048 0.02922403 1.003378 -0.4770381 0.04293423 0.9400242 -0.6176251 0.05558729 0.8535241 -0.7430042 0.06687164 0.7460074 -0.8500881 0.07650935 0.6201215 -0.93624 0.08426314 0.4789662 -0.9993385 0.08994215 0.3260172 -1.03783 0.09340643 0.1650404 -1.050767 0.09457075 -0.03003466 -0.1661515 0.0301522 1.048885 -0.3282119 0.05956178 1.026631 -0.4821906 0.0875048 0.9618088 -0.6242961 0.1132931 0.8733041 -0.7510293 0.1362919 0.7632958 -0.8592699 0.1559346 0.6344926 -0.9463522 0.1717377 0.4900661 -1.010132 0.1833121 0.3335725 -1.049039 0.1903727 0.1688652 -1.062116 0.1927458 -1.65927e-7 -0.1627799 0.04492461 1.048885 -0.3215516 0.08874279 1.026631 -0.4724055 0.1303759 0.9618088 -0.6116273 0.1687986 0.8733041 -0.7357888 0.203065 0.7632958 -0.8418328 0.2323313 0.6344926 -0.9271481 0.2558768 0.4900661 -0.9896339 0.2731218 0.3335725 -1.027752 0.2836416 0.1688652 -1.040562 0.2871772 -1.65927e-7 -0.1545167 0.05799138 1.042025 -0.3052287 0.1145545 1.003378 -0.4484249 0.168297 0.9400242 -0.5805795 0.2178953 0.8535241 -0.6984382 0.2621285 0.7460074 -0.799099 0.2999072 0.6201215 -0.8800835 0.3303011 0.4789662 -0.9393973 0.352562 0.3260172 -0.97558 0.3661416 0.1650404 -0.9877406 0.3707056 -0.03003466 -0.1409425 0.06787472 1.03354 -0.2784147 0.1340778 0.9692877 -0.4090312 0.1969795 0.8910065 -0.5295762 0.2550308 0.809017 -0.6370812 0.3068025 0.7071068 -0.7288991 0.3510197 0.5877853 -0.8027692 0.3865936 0.4539905 -0.8568723 0.4126483 0.309017 -0.8898765 0.4285423 0.1564344 -0.9009689 0.4338841 -0.08259546 -0.1416788 0.08464962 1.042025 -0.279869 0.1672144 1.003378 -0.4111679 0.2456619 0.9400242 -0.5323426 0.3180603 0.8535241 -0.6404091 0.3826271 0.7460074 -0.7327066 0.4377723 0.6201215 -0.8069627 0.4821381 0.4789662 -0.8613485 0.5146322 0.3260172 -0.8945251 0.5344542 0.1650404 -0.9056754 0.5411163 -0.03003466 -0.1366148 0.09925705 1.048885 -0.2698658 0.1960695 1.026631 -0.3964717 0.2880541 0.9618088 -0.5133152 0.3729458 0.8733041 -0.6175192 0.4486545 0.7632958 -0.7065178 0.5133158 0.6344926 -0.7781198 0.5653375 0.4900661 -0.8305616 0.6034387 0.3335725 -0.8625524 0.6266815 0.1688652 -0.8733041 0.6344932 -1.65927e-7 -0.1271675 0.1111036 1.048885 -0.2512038 0.2194708 1.026631 -0.3690546 0.322434 0.9618088 -0.4778181 0.4174578 0.8733041 -0.5748162 0.5022025 0.7632958 -0.6576604 0.5745812 0.6344926 -0.7243108 0.6328119 0.4900661 -0.7731262 0.6754605 0.3335725 -0.8029047 0.7014773 0.1688652 -0.8129129 0.7102213 -1.65927e-7 -0.1140531 0.1192911 1.042025 -0.2252981 0.2356442 1.003378 -0.3309955 0.346195 0.9400242 -0.4285427 0.4482212 0.8535241 -0.5155377 0.5392109 0.7460074 -0.5898385 0.6169235 0.6201215 -0.6496155 0.6794453 0.4789662 -0.6933968 0.7252368 0.3260172 -0.7201043 0.7531709 0.1650404 -0.7290805 0.7625593 -0.03003466 -0.09753501 0.1223061 1.03354 -0.1926687 0.2415999 0.9692877 -0.2830582 0.3549447 0.8910065 -0.3664779 0.4595496 0.809017 -0.4408737 0.5528389 0.7071068 -0.5044137 0.6325156 0.5877853 -0.5555334 0.6966176 0.4539905 -0.592974 0.7435665 0.309017 -0.6158134 0.7722065 0.1564344 -0.6234896 0.7818322 -0.08259546 -0.09092003 0.1377392 1.042025 -0.1796016 0.272086 1.003378 -0.2638608 0.3997331 0.9400242 -0.3416229 0.5175375 0.8535241 -0.410973 0.6225985 0.7460074 -0.4702036 0.7123291 0.6201215 -0.5178562 0.7845197 0.4789662 -0.5527577 0.8373929 0.3260172 -0.5740481 0.8696468 0.1650404 -0.5812037 0.8804871 -0.03003466 -0.08001959 0.1487028 1.048885 -0.1580692 0.2937432 1.026631 -0.2322266 0.4315508 0.9618088 -0.3006659 0.558732 0.8733041 -0.3617017 0.6721556 0.7632958 -0.4138312 0.7690285 0.6344926 -0.4557708 0.8469654 0.4900661 -0.4864879 0.904047 0.3335725 -0.5052258 0.9388682 0.1688652 -0.5115235 0.9505714 -1.65927e-7 -0.0663678 0.1552772 1.048885 -0.131102 0.30673 1.026631 -0.1926078 0.4506301 0.9618088 -0.2493711 0.5834343 0.8733041 -0.2999941 0.7018724 0.7632958 -0.3432301 0.8030282 0.6344926 -0.3780146 0.8844108 0.4900661 -0.4034913 0.944016 0.3335725 -0.4190325 0.9803768 0.1688652 -0.4242557 0.9925974 -1.65927e-7 -0.05099982 0.1569637 1.042025 -0.1007444 0.3100616 1.003378 -0.1480082 0.4555248 0.9400242 -0.1916277 0.5897714 0.8535241 -0.2305286 0.7094959 0.7460074 -0.263753 0.8117505 0.6201215 -0.2904831 0.894017 0.4789662 -0.3100605 0.9542697 0.3260172 -0.322003 0.9910254 0.1650404 -0.3260167 1.003379 -0.03003466 -0.03480935 0.1525132 1.03354 -0.06876224 0.3012701 0.9692877 -0.1010218 0.4426088 0.8910065 -0.1307941 0.573049 0.809017 -0.1573456 0.6893788 0.7071068 -0.1800227 0.7887341 0.5877853 -0.1982672 0.868668 0.4539905 -0.2116296 0.9272123 0.309017 -0.2197809 0.9629258 0.1564344 -0.2225204 0.9749289 -0.08259546 -0.02215325 0.1635478 1.042025 -0.04376173 0.3230675 1.003378 -0.06429255 0.4746323 0.9400242 -0.08324044 0.6145101 0.8535241 -0.1001385 0.7392566 0.7460074 -0.1145707 0.8458004 0.6201215 -0.126182 0.9315177 0.4789662 -0.1346862 0.9942977 0.3260172 -0.1398739 1.032595 0.1650404 -0.1416173 1.045467 -0.03003466 -0.007575333 0.1686962 1.048885 -0.01496499 0.3332375 1.026631 -0.021986 0.4895734 0.9618088 -0.0284658 0.6338545 0.8733041 -0.03424459 0.762528 0.7632958 -0.03917998 0.8724257 0.6344926 -0.04315078 0.9608414 0.4900661 -0.04605913 1.025598 0.3335725 -0.04783308 1.065101 0.1688652 -0.04842925 1.078377 -1.65927e-7 0.007576942 0.1686962 1.048885 0.01496636 0.3332375 1.026631 0.02198749 0.4895734 0.9618088 0.02846699 0.6338545 0.8733041 0.03424572 0.762528 0.7632958 0.03918135 0.8724257 0.6344926 0.04315203 0.9608414 0.4900661 0.04606014 1.025598 0.3335725 0.04783433 1.065101 0.1688652 0.04843068 1.078377 -1.65927e-7 0.02215486 0.1635478 1.042025 0.04376316 0.3230676 1.003378 0.06429404 0.4746323 0.9400242 0.08324164 0.6145101 0.8535241 0.1001396 0.7392566 0.7460074 0.1145721 0.8458004 0.6201215 0.1261833 0.9315178 0.4789662 0.1346873 0.9942977 0.3260172 0.1398751 1.032595 0.1650404 0.1416187 1.045467 -0.03003466 0.0348109 0.1525132 1.03354 0.06876361 0.3012701 0.9692877 0.1010233 0.4426088 0.8910065 0.1307953 0.573049 0.809017 0.1573467 0.6893788 0.7071068 0.180024 0.7887341 0.5877853 0.1982684 0.8686681 0.4539905 0.2116307 0.9272123 0.309017 0.2197821 0.9629259 0.1564344 0.2225218 0.9749289 -0.08259546 0.05100142 0.1569638 1.042025 0.1007458 0.3100616 1.003378 0.1480097 0.4555248 0.9400242 0.1916289 0.5897714 0.8535241 0.2305297 0.7094959 0.7460074 0.2637544 0.8117505 0.6201215 0.2904844 0.8940172 0.4789662 0.3100615 0.9542697 0.3260172 0.3220043 0.9910255 0.1650404 0.3260182 1.003379 -0.03003466 0.06636947 0.1552772 1.048885 0.1311033 0.30673 1.026631 0.1926093 0.4506301 0.9618088 0.2493724 0.5834343 0.8733041 0.2999952 0.7018723 0.7632958 0.3432314 0.8030282 0.6344926 0.378016 0.884411 0.4900661 0.4034923 0.944016 0.3335725 0.4190338 0.9803769 0.1688652 0.4242572 0.9925974 -1.65927e-7 0.0800212 0.1487029 1.048885 0.1580706 0.2937433 1.026631 0.2322281 0.4315508 0.9618088 0.3006671 0.5587321 0.8733041 0.3617029 0.6721554 0.7632958 0.4138326 0.7690285 0.6344926 0.4557722 0.8469656 0.4900661 0.4864889 0.904047 0.3335725 0.5052273 0.9388684 0.1688652 0.511525 0.9505714 -1.65927e-7 0.09092164 0.1377393 1.042025 0.179603 0.272086 1.003378 0.2638623 0.3997331 0.9400242 0.3416242 0.5175376 0.8535241 0.4109742 0.6225984 0.7460074 0.4702051 0.712329 0.6201215 0.5178577 0.78452 0.4789662 0.5527587 0.8373929 0.3260172 0.5740495 0.869647 0.1650404 0.5812051 0.8804872 -0.03003466 0.09753662 0.1223061 1.03354 0.1926701 0.2415999 0.9692877 0.2830597 0.3549447 0.8910065 0.3664792 0.4595497 0.809017 0.4408748 0.5528388 0.7071068 0.5044151 0.6325156 0.5877853 0.5555347 0.6966179 0.4539905 0.592975 0.7435666 0.309017 0.6158149 0.7722067 0.1564344 0.6234911 0.7818323 -0.08259546 0.1140548 0.1192912 1.042025 0.2252996 0.2356442 1.003378 0.330997 0.3461949 0.9400242 0.4285441 0.4482213 0.8535241 0.5155389 0.5392108 0.7460074 0.58984 0.6169234 0.6201215 0.6496169 0.6794456 0.4789662 0.6933978 0.725237 0.3260172 0.7201058 0.753171 0.1650404 0.7290819 0.7625594 -0.03003466 0.1271691 0.1111037 1.048885 0.2512053 0.2194709 1.026631 0.3690561 0.322434 0.9618088 0.4778195 0.4174578 0.8733041 0.5748173 0.5022023 0.7632958 0.6576619 0.5745812 0.6344926 0.7243122 0.6328121 0.4900661 0.7731272 0.6754607 0.3335725 0.8029061 0.7014774 0.1688652 0.8129144 0.7102214 -1.65927e-7 0.1366165 0.09925711 1.048885 0.2698673 0.1960695 1.026631 0.3964732 0.2880541 0.9618088 0.5133166 0.3729459 0.8733041 0.6175203 0.4486544 0.7632958 0.7065193 0.5133159 0.6344926 0.7781212 0.5653378 0.4900661 0.8305627 0.603439 0.3335725 0.8625538 0.6266816 0.1688652 0.8733056 0.6344932 -1.65927e-7 0.1416804 0.08464968 1.042025 0.2798705 0.1672145 1.003378 0.4111695 0.2456619 0.9400242 0.532344 0.3180603 0.8535241 0.6404103 0.382627 0.7460074 0.7327082 0.4377723 0.6201215 0.8069641 0.4821384 0.4789662 0.8613495 0.5146324 0.3260172 0.8945266 0.5344544 0.1650404 0.9056769 0.5411164 -0.03003466 0.1409442 0.06787478 1.03354 0.2784162 0.1340779 0.9692877 0.4090328 0.1969795 0.8910065 0.5295776 0.2550309 0.809017 0.6370823 0.3068025 0.7071068 0.7289006 0.3510197 0.5877853 0.8027707 0.3865938 0.4539905 0.8568735 0.4126485 0.309017 0.889878 0.4285424 0.1564344 0.9009704 0.4338842 -0.08259546 0.1545184 0.05799144 1.042025 0.3052302 0.1145547 1.003378 0.4484264 0.168297 0.9400242 0.5805808 0.2178955 0.8535241 0.6984393 0.2621285 0.7460074 0.7991006 0.2999072 0.6201215 0.8800851 0.3303014 0.4789662 0.9393985 0.3525622 0.3260172 0.9755817 0.3661417 0.1650404 0.9877424 0.3707057 -0.03003466 0.1627816 0.04492467 1.048885 0.3215531 0.08874291 1.026631 0.4724071 0.1303759 0.9618088 0.6116287 0.1687987 0.8733041 0.73579 0.203065 0.7632958 0.8418343 0.2323313 0.6344926 0.9271497 0.2558771 0.4900661 0.9896349 0.273122 0.3335725 1.027753 0.2836418 0.1688652 1.040564 0.2871774 -1.65927e-7 0.1661533 0.03015226 1.048885 0.3282135 0.05956196 1.026631 0.4821921 0.08750486 0.9618088 0.6242975 0.1132933 0.8733041 0.7510305 0.136292 0.7632958 0.8592714 0.1559346 0.6344926 0.946354 0.171738 0.4900661 1.010133 0.1833124 0.3335725 1.049041 0.1903728 0.1688652 1.062118 0.1927459 -1.65927e-7 0.1643779 0.01479423 1.042025 0.3247064 0.02922415 1.003378 0.4770396 0.04293435 0.9400242 0.6176266 0.05558747 0.8535241 0.7430054 0.06687182 0.7460074 0.8500897 0.07650941 0.6201215 0.9362418 0.08426344 0.4789662 0.9993398 0.08994251 0.3260172 1.037832 0.09340655 0.1650404 1.050768 0.09457087 -0.03003466 0.1564362 0 1.03354 0.3090186 1.37144e-7 0.9692877 0.4539921 0 0.8910065 0.5877867 1.53908e-7 0.809017 0.7071079 2.06062e-7 0.7071068 0.8090186 0 0.5877853 0.8910084 2.43315e-7 0.4539905 0.9510578 3.55074e-7 0.309017 0.9876901 0 0.1564344 1.000002 0 -0.08259546 0.1643779 -0.01479411 1.042025 0.3247064 -0.02922385 1.003378 0.4770396 -0.04293417 0.9400242 0.6176266 -0.05558711 0.8535241 0.7430054 -0.06687134 0.7460074 0.8500897 -0.07650929 0.6201215 0.9362418 -0.0842629 0.4789662 0.9993399 -0.08994174 0.3260172 1.037832 -0.09340631 0.1650404 1.050768 -0.09457063 -0.03003466 0.1661533 -0.03015214 1.048885 0.3282135 -0.05956166 1.026631 0.4821922 -0.08750468 0.9618088 0.6242976 -0.1132929 0.8733041 0.7510305 -0.1362915 0.7632958 0.8592714 -0.1559345 0.6344926 0.9463541 -0.1717375 0.4900661 1.010134 -0.1833117 0.3335725 1.049041 -0.1903726 0.1688652 1.062118 -0.1927456 -1.65927e-7 0.1627816 -0.04492455 1.048885 0.3215532 -0.08874261 1.026631 0.4724071 -0.1303757 0.9618088 0.6116289 -0.1687984 0.8733041 0.73579 -0.2030646 0.7632958 0.8418344 -0.2323312 0.6344926 0.9271499 -0.2558766 0.4900661 0.9896352 -0.2731213 0.3335725 1.027753 -0.2836415 0.1688652 1.040564 -0.2871772 -1.65927e-7 0.1545184 -0.05799132 1.042025 0.3052303 -0.1145544 1.003378 0.4484265 -0.1682968 0.9400242 0.5805811 -0.2178952 0.8535241 0.6984393 -0.2621281 0.7460074 0.7991006 -0.2999071 0.6201215 0.8800853 -0.3303009 0.4789662 0.9393987 -0.3525615 0.3260172 0.9755817 -0.3661415 0.1650404 0.9877427 -0.3707056 -0.03003466 0.1409442 -0.06787472 1.03354 0.2784163 -0.1340777 0.9692877 0.4090328 -0.1969793 0.8910065 0.5295777 -0.2550306 0.809017 0.6370823 -0.306802 0.7071068 0.7289006 -0.3510196 0.5877853 0.802771 -0.3865935 0.4539905 0.8568738 -0.4126479 0.309017 0.8898781 -0.4285422 0.1564344 0.9009708 -0.4338841 -0.08259546 0.1416805 -0.08464962 1.042025 0.2798707 -0.1672143 1.003378 0.4111695 -0.2456617 0.9400242 0.5323442 -0.3180602 0.8535241 0.6404103 -0.3826266 0.7460074 0.7327082 -0.4377722 0.6201215 0.8069646 -0.4821381 0.4789662 0.8613499 -0.5146318 0.3260172 0.8945267 -0.5344542 0.1650404 0.9056773 -0.5411164 -0.03003466 0.1366165 -0.09925705 1.048885 0.2698674 -0.1960694 1.026631 0.3964733 -0.288054 0.9618088 0.5133168 -0.3729457 0.8733041 0.6175204 -0.448654 0.7632958 0.7065193 -0.5133157 0.6344926 0.7781217 -0.5653375 0.4900661 0.8305631 -0.6034384 0.3335725 0.862554 -0.6266815 0.1688652 0.873306 -0.6344932 -1.65927e-7 0.1271692 -0.1111035 1.048885 0.2512055 -0.2194707 1.026631 0.3690562 -0.322434 0.9618088 0.4778197 -0.4174576 0.8733041 0.5748174 -0.5022019 0.7632958 0.6576618 -0.5745811 0.6344926 0.7243127 -0.6328119 0.4900661 0.7731277 -0.6754602 0.3335725 0.8029063 -0.7014773 0.1688652 0.8129148 -0.7102214 -1.65927e-7 0.1140549 -0.1192911 1.042025 0.2252998 -0.2356441 1.003378 0.3309971 -0.3461949 0.9400242 0.4285442 -0.4482211 0.8535241 0.515539 -0.5392104 0.7460074 0.5898399 -0.6169234 0.6201215 0.6496174 -0.6794455 0.4789662 0.6933984 -0.7252366 0.3260172 0.720106 -0.7531709 0.1650404 0.7290824 -0.7625594 -0.03003466 0.09753668 -0.1223061 1.03354 0.1926704 -0.2415997 0.9692877 0.2830598 -0.3549447 0.8910065 0.3664794 -0.4595495 0.809017 0.4408749 -0.5528385 0.7071068 0.5044151 -0.6325156 0.5877853 0.5555351 -0.6966178 0.4539905 0.5929754 -0.7435663 0.309017 0.6158151 -0.7722066 0.1564344 0.6234914 -0.7818323 -0.08259546 0.0909217 -0.1377391 1.042025 0.1796033 -0.2720859 1.003378 0.2638624 -0.3997331 0.9400242 0.3416244 -0.5175374 0.8535241 0.4109743 -0.6225979 0.7460074 0.4702051 -0.712329 0.6201215 0.5178582 -0.7845199 0.4789662 0.5527591 -0.8373928 0.3260172 0.5740497 -0.8696469 0.1650404 0.5812055 -0.8804873 -0.03003466 0.08002126 -0.1487028 1.048885 0.1580709 -0.2937432 1.026631 0.2322282 -0.4315508 0.9618088 0.3006674 -0.558732 0.8733041 0.361703 -0.672155 0.7632958 0.4138327 -0.7690285 0.6344926 0.4557726 -0.8469656 0.4900661 0.4864894 -0.904047 0.3335725 0.5052275 -0.9388684 0.1688652 0.5115253 -0.9505716 -1.65927e-7 0.06636953 -0.1552771 1.048885 0.1311036 -0.30673 1.026631 0.1926094 -0.4506302 0.9618088 0.2493727 -0.5834342 0.8733041 0.2999954 -0.7018719 0.7632958 0.3432315 -0.8030282 0.6344926 0.3780164 -0.884411 0.4900661 0.4034928 -0.944016 0.3335725 0.4190341 -0.9803769 0.1688652 0.4242575 -0.9925976 -1.65927e-7 0.05100148 -0.1569637 1.042025 0.100746 -0.3100616 1.003378 0.1480098 -0.4555248 0.9400242 0.1916292 -0.5897714 0.8535241 0.23053 -0.7094955 0.7460074 0.2637545 -0.8117505 0.6201215 0.2904847 -0.8940173 0.4789662 0.310062 -0.9542697 0.3260172 0.3220046 -0.9910255 0.1650404 0.3260185 -1.003379 -0.03003466 0.03481096 -0.1525132 1.03354 0.06876385 -0.3012701 0.9692877 0.1010233 -0.4426088 0.8910065 0.1307955 -0.573049 0.809017 0.1573471 -0.6893784 0.7071068 0.1800242 -0.7887341 0.5877853 0.1982687 -0.8686683 0.4539905 0.2116311 -0.9272123 0.309017 0.2197824 -0.9629259 0.1564344 0.222522 -0.9749292 -0.08259546 0.02215492 -0.1635478 1.042025 0.04376339 -0.3230676 1.003378 0.06429409 -0.4746324 0.9400242 0.08324193 -0.6145101 0.8535241 0.10014 -0.7392562 0.7460074 0.1145722 -0.8458004 0.6201215 0.1261836 -0.931518 0.4789662 0.1346877 -0.9942978 0.3260172 0.1398754 -1.032595 0.1650404 0.141619 -1.045467 -0.03003466 0.007577002 -0.1686962 1.048885 0.0149666 -0.3332376 1.026631 0.02198755 -0.4895735 0.9618088 0.02846735 -0.6338546 0.8733041 0.03424614 -0.7625275 0.7632958 0.03918141 -0.8724257 0.6344926 0.04315233 -0.9608417 0.4900661 0.04606062 -1.025598 0.3335725 0.04783457 -1.065101 0.1688652 0.04843086 -1.078378 -1.65927e-7 -0.007575213 -0.1686962 1.048885 -0.01496475 -0.3332376 1.026631 -0.02198594 -0.4895736 0.9618088 -0.0284655 -0.6338546 0.8733041 -0.03424412 -0.7625275 0.7632958 -0.03917986 -0.8724257 0.6344926 -0.04315048 -0.9608418 0.4900661 -0.04605865 -1.025598 0.3335725 -0.04783284 -1.065101 0.1688652 -0.04842913 -1.078378 -1.65927e-7 -0.02215313 -0.1635478 1.042025 -0.04376149 -0.3230677 1.003378 -0.06429249 -0.4746325 0.9400242 -0.08324015 -0.6145102 0.8535241 -0.100138 -0.7392562 0.7460074 -0.1145706 -0.8458004 0.6201215 -0.1261817 -0.9315181 0.4789662 -0.1346858 -0.9942979 0.3260172 -0.1398736 -1.032595 0.1650404 -0.1416172 -1.045467 -0.03003466 -0.03480923 -0.1525132 1.03354 -0.068762 -0.3012703 0.9692877 -0.1010218 -0.442609 0.8910065 -0.1307938 -0.5730491 0.809017 -0.1573451 -0.6893784 0.7071068 -0.1800226 -0.7887341 0.5877853 -0.198267 -0.8686685 0.4539905 -0.2116292 -0.9272125 0.309017 -0.2197807 -0.962926 0.1564344 -0.2225204 -0.9749292 -0.08259546 -0.0509997 -0.1569638 1.042025 -0.1007442 -0.3100618 1.003378 -0.1480082 -0.4555249 0.9400242 -0.1916275 -0.5897715 0.8535241 -0.2305281 -0.7094956 0.7460074 -0.2637529 -0.8117505 0.6201215 -0.2904829 -0.8940176 0.4789662 -0.3100601 -0.95427 0.3260172 -0.3220028 -0.9910256 0.1650404 -0.3260167 -1.003379 -0.03003466 -0.06636774 -0.1552772 1.048885 -0.1311018 -0.3067302 1.026631 -0.1926078 -0.4506303 0.9618088 -0.2493709 -0.5834344 0.8733041 -0.2999935 -0.7018721 0.7632958 -0.34323 -0.8030282 0.6344926 -0.3780146 -0.8844114 0.4900661 -0.4034909 -0.9440163 0.3335725 -0.4190323 -0.980377 0.1688652 -0.4242558 -0.9925978 -1.65927e-7 -0.08001953 -0.1487028 1.048885 -0.1580691 -0.2937435 1.026631 -0.2322266 -0.4315509 0.9618088 -0.3006657 -0.5587322 0.8733041 -0.3617011 -0.6721552 0.7632958 -0.4138311 -0.7690285 0.6344926 -0.4557709 -0.846966 0.4900661 -0.4864875 -0.9040473 0.3335725 -0.5052258 -0.9388685 0.1688652 -0.5115236 -0.9505719 -1.65927e-7 -0.09091997 -0.1377392 1.042025 -0.1796016 -0.2720863 1.003378 -0.2638608 -0.3997333 0.9400242 -0.3416227 -0.5175377 0.8535241 -0.4109724 -0.6225982 0.7460074 -0.4702036 -0.712329 0.6201215 -0.5178564 -0.7845204 0.4789662 -0.5527574 -0.8373932 0.3260172 -0.5740481 -0.8696471 0.1650404 -0.5812038 -0.8804876 -0.03003466 -0.09753501 -0.1223061 1.03354 -0.1926687 -0.2416001 0.9692877 -0.2830583 -0.3549449 0.8910065 -0.3664778 -0.4595498 0.809017 -0.4408732 -0.5528387 0.7071068 -0.5044137 -0.6325156 0.5877853 -0.5555335 -0.6966182 0.4539905 -0.5929738 -0.7435668 0.309017 -0.6158135 -0.7722069 0.1564344 -0.6234898 -0.7818326 -0.08259546 -0.1643761 0.01479417 1.042025 -0.1140531 -0.1192911 1.042025 -0.2252981 -0.2356445 1.003378 -0.3309956 -0.3461951 0.9400242 -0.4285426 -0.4482215 0.8535241 -0.5155372 -0.5392107 0.7460074 -0.5898385 -0.6169235 0.6201215 -0.6496158 -0.6794459 0.4789662 -0.6933968 -0.7252372 0.3260172 -0.7201044 -0.7531712 0.1650404 -0.7290807 -0.7625597 -0.03003466 -0.1271675 -0.1111037 1.048885 -0.2512039 -0.2194711 1.026631 -0.3690548 -0.3224342 0.9618088 -0.4778181 -0.417458 0.8733041 -0.5748157 -0.5022022 0.7632958 -0.6576604 -0.5745812 0.6344926 -0.7243111 -0.6328125 0.4900661 -0.7731262 -0.6754609 0.3335725 -0.8029047 -0.7014777 0.1688652 -0.8129132 -0.7102218 -1.65927e-7 -0.1366148 -0.09925711 1.048885 -0.2698659 -0.1960698 1.026631 -0.3964719 -0.2880543 0.9618088 -0.5133152 -0.3729461 0.8733041 -0.6175187 -0.4486544 0.7632958 -0.7065179 -0.5133159 0.6344926 -0.7781201 -0.5653381 0.4900661 -0.8305616 -0.6034392 0.3335725 -0.8625525 -0.6266818 0.1688652 -0.8733044 -0.6344936 -1.65927e-7 -0.1416788 -0.08464968 1.042025 -0.2798691 -0.1672146 1.003378 -0.4111682 -0.245662 0.9400242 -0.5323426 -0.3180605 0.8535241 -0.6404086 -0.382627 0.7460074 -0.7327067 -0.4377724 0.6201215 -0.8069632 -0.4821387 0.4789662 -0.8613486 -0.5146325 0.3260172 -0.8945252 -0.5344546 0.1650404 -0.9056757 -0.5411167 -0.03003466 -0.1409426 -0.06787478 1.03354 -0.2784148 -0.134078 0.9692877 -0.4090315 -0.1969795 0.8910065 -0.5295762 -0.2550311 0.809017 -0.6370807 -0.3068025 0.7071068 -0.7288992 -0.3510198 0.5877853 -0.8027697 -0.3865941 0.4539905 -0.8568725 -0.4126486 0.309017 -0.8898767 -0.4285426 0.1564344 -0.9009693 -0.4338846 -0.08259546 -0.1545168 -0.05799144 1.042025 -0.3052289 -0.1145547 1.003378 -0.4484252 -0.1682971 0.9400242 -0.5805795 -0.2178956 0.8535241 -0.6984377 -0.2621286 0.7460074 -0.7990992 -0.2999073 0.6201215 -0.8800841 -0.3303016 0.4789662 -0.9393975 -0.3525623 0.3260172 -0.9755803 -0.3661419 0.1650404 -0.9877412 -0.370706 -0.03003466 -0.1627799 -0.04492467 1.048885 -0.3215517 -0.08874297 1.026631 -0.4724058 -0.1303759 0.9618088 -0.6116273 -0.1687988 0.8733041 -0.7357884 -0.2030651 0.7632958 -0.8418329 -0.2323314 0.6344926 -0.9271488 -0.2558772 0.4900661 -0.9896341 -0.2731221 0.3335725 -1.027752 -0.2836419 0.1688652 -1.040563 -0.2871776 -1.65927e-7 -0.1661517 -0.03015226 1.048885 -0.3282122 -0.05956196 1.026631 -0.4821909 -0.08750486 0.9618088 -0.6242962 -0.1132934 0.8733041 -0.7510289 -0.136292 0.7632958 -0.85927 -0.1559347 0.6344926 -0.946353 -0.171738 0.4900661 -1.010133 -0.1833124 0.3335725 -1.04904 -0.190373 0.1688652 -1.062117 -0.1927461 -1.65927e-7 -0.1643763 -0.01479423 1.042025 -0.3247051 -0.02922415 1.003378 -0.4770384 -0.04293429 0.9400242 -0.6176252 -0.05558753 0.8535241 -0.7430039 -0.06687182 0.7460074 -0.8500883 -0.07650947 0.6201215 -0.9362408 -0.08426344 0.4789662 -0.9993388 -0.08994239 0.3260172 -1.03783 -0.09340667 0.1650404 -1.050767 -0.09457105 -0.03003466 -0.1564346 0 1.03354 -0.3090173 0 0.9692877 -0.4539908 0 0.8910065 -0.5877854 -1.96269e-7 0.809017 -0.8090173 0 0.5877853 -0.8910074 -1.73918e-7 0.4539905 -0.9510569 -1.96269e-7 0.309017 -0.9876888 -2.0372e-7 0.1564344 -1.000001 -2.40973e-7 -0.08259546 -0.8817924 0.4246492 -0.06851685 -0.6102191 0.7651914 -0.06851685 -0.2177842 0.9541782 -0.06851685 0.2177856 0.9541782 -0.06851685 0.6102205 0.7651916 -0.06851685 0.8817939 0.4246493 -0.06851685 0.9787175 0 -0.06851685 0.8817943 -0.4246492 -0.06851685 0.6102209 -0.7651916 -0.06851685 0.2177858 -0.9541785 -0.06851685 -0.2177842 -0.9541786 -0.06851685 -0.6102192 -0.7651919 -0.06851685 -0.8817928 -0.4246497 -0.06851685 -0.9787164 -2.38385e-7 -0.06851685 7.32286e-7 -1.21337e-7 -2.088751 -0.1661515 0.0301522 1.048885 -0.1627799 0.04492461 1.048885 -0.1545167 0.05799138 1.042025 -0.1409425 0.06787472 1.03354 -0.1416788 0.08464962 1.042025 -0.1366148 0.09925705 1.048885 -0.1271675 0.1111036 1.048885 -0.1140531 0.1192911 1.042025 -0.09753501 0.1223061 1.03354 -0.09092003 0.1377392 1.042025 -0.08001959 0.1487028 1.048885 -0.0663678 0.1552772 1.048885 -0.05099982 0.1569637 1.042025 -0.03480935 0.1525132 1.03354 -0.02215325 0.1635478 1.042025 -0.007575333 0.1686962 1.048885 0.007576942 0.1686962 1.048885 0.02215486 0.1635478 1.042025 0.0348109 0.1525132 1.03354 0.05100142 0.1569638 1.042025 0.06636947 0.1552772 1.048885 0.0800212 0.1487029 1.048885 0.09092164 0.1377393 1.042025 0.09753662 0.1223061 1.03354 0.1140548 0.1192912 1.042025 0.1271691 0.1111037 1.048885 0.1366165 0.09925711 1.048885 0.1416804 0.08464968 1.042025 0.1409442 0.06787478 1.03354 0.1545184 0.05799144 1.042025 0.1627816 0.04492467 1.048885 0.1661533 0.03015226 1.048885 0.1643779 0.01479423 1.042025 0.1564362 0 1.03354 0.1643779 -0.01479411 1.042025 0.1661533 -0.03015214 1.048885 0.1627816 -0.04492455 1.048885 0.1545184 -0.05799132 1.042025 0.1409442 -0.06787472 1.03354 0.1416805 -0.08464962 1.042025 0.1366165 -0.09925705 1.048885 0.1271692 -0.1111035 1.048885 0.1140549 -0.1192911 1.042025 0.09753668 -0.1223061 1.03354 0.0909217 -0.1377391 1.042025 0.08002126 -0.1487028 1.048885 0.06636953 -0.1552771 1.048885 0.05100148 -0.1569637 1.042025 0.03481096 -0.1525132 1.03354 0.02215492 -0.1635478 1.042025 0.007577002 -0.1686962 1.048885 -0.007575213 -0.1686962 1.048885 -0.02215313 -0.1635478 1.042025 -0.03480923 -0.1525132 1.03354 -0.0509997 -0.1569638 1.042025 -0.06636774 -0.1552772 1.048885 -0.08001953 -0.1487028 1.048885 -0.09091997 -0.1377392 1.042025 -0.09753501 -0.1223061 1.03354 -0.1140531 -0.1192911 1.042025 -0.1271675 -0.1111037 1.048885 -0.1366148 -0.09925711 1.048885 -0.1416788 -0.08464968 1.042025 -0.1409426 -0.06787478 1.03354 -0.1545168 -0.05799144 1.042025 -0.1627799 -0.04492467 1.048885 -0.1661517 -0.03015226 1.048885 -0.1643763 -0.01479423 1.042025 -0.1564346 0 1.03354 -0.08197021 0.007377505 1.053733 -0.08134949 0.01476287 1.053802 -0.07969868 0.02199566 1.053802 -0.07705354 0.02891898 1.053733 -0.07426726 0.03576564 1.053202 -0.07065159 0.04221284 1.053733 -0.06688791 0.04859751 1.053802 -0.06226241 0.05439776 1.053802 -0.05687528 0.05948776 1.053733 -0.05139428 0.06444746 1.053202 -0.04533928 0.06868743 1.053733 -0.03917819 0.07280683 1.053802 -0.03249406 0.07602572 1.053802 -0.02543199 0.07827425 1.053733 -0.01834189 0.0803647 1.053202 -0.01104688 0.08155757 1.053733 -0.003708541 0.08259582 1.053802 0.00371015 0.08259582 1.053802 0.01104855 0.08155763 1.053733 0.0183435 0.0803647 1.053202 0.02543365 0.0782743 1.053733 0.03249573 0.07602572 1.053802 0.03917986 0.07280683 1.053802 0.04534095 0.06868743 1.053733 0.05139595 0.06444752 1.053202 0.05687695 0.05948781 1.053733 0.06226408 0.05439776 1.053802 0.06688958 0.04859757 1.053802 0.07065325 0.0422129 1.053733 0.07426893 0.03576564 1.053202 0.07705527 0.02891904 1.053733 0.07970035 0.02199572 1.053802 0.08135122 0.01476293 1.053802 0.08197194 0.007377564 1.053733 0.08243227 0 1.053202 0.08197194 -0.007377445 1.053733 0.08135122 -0.01476287 1.053802 0.07970035 -0.0219956 1.053802 0.07705527 -0.02891898 1.053733 0.07426893 -0.03576558 1.053202 0.07065325 -0.04221278 1.053733 0.06688958 -0.04859751 1.053802 0.06226408 -0.0543977 1.053802 0.05687701 -0.05948776 1.053733 0.05139595 -0.06444746 1.053202 0.04534101 -0.06868737 1.053733 0.03917986 -0.07280677 1.053802 0.03249579 -0.07602566 1.053802 0.02543371 -0.07827425 1.053733 0.01834356 -0.08036464 1.053202 0.01104855 -0.08155757 1.053733 0.00371021 -0.08259576 1.053802 -0.003708481 -0.08259576 1.053802 -0.01104682 -0.08155757 1.053733 -0.01834183 -0.08036464 1.053202 -0.02543199 -0.07827425 1.053733 -0.03249406 -0.07602566 1.053802 -0.03917813 -0.07280677 1.053802 -0.04533928 -0.06868737 1.053733 -0.05139428 -0.06444746 1.053202 -0.05687528 -0.05948776 1.053733 -0.06226235 -0.05439776 1.053802 -0.06688791 -0.04859751 1.053802 -0.07065159 -0.04221284 1.053733 -0.07426732 -0.03576564 1.053202 -0.0770536 -0.02891898 1.053733 -0.07969874 -0.02199566 1.053802 -0.08134955 -0.01476287 1.053802 -0.08197033 -0.007377505 1.053733 -0.0824306 0 1.053202 -0.692779 0 0.6953256 -0.1610454 0.01449441 1.023457 -0.3181254 0.02863186 0.9855934 -0.467372 0.0420643 0.9235236 -0.6051104 0.054461 0.8387761 -0.727949 0.06551665 0.733438 -0.8328631 0.07495909 0.610103 -0.9172693 0.08255577 0.4718078 -0.9790893 0.08811968 0.3219579 -1.016801 0.09151381 0.1642429 -1.029475 0.09265452 -0.02687948 -0.1627849 0.02954125 1.030179 -0.3215615 0.05835491 1.008375 -0.4724201 0.08573174 0.9448667 -0.6116462 0.1109975 0.8581554 -0.7358115 0.1335302 0.7503761 -0.8418588 0.1527749 0.6241828 -0.9271766 0.1682578 0.4826827 -0.9896644 0.1795977 0.3293601 -1.027783 0.1865153 0.1679901 -1.040595 0.1888402 0.002546489 -0.1594815 0.04401427 1.030179 -0.3150361 0.08694463 1.008375 -0.4628334 0.1277341 0.9448667 -0.5992342 0.1653783 0.8581554 -0.7208798 0.1989504 0.7503761 -0.824775 0.2276237 0.6241828 -0.9083617 0.250692 0.4826827 -0.9695813 0.2675876 0.3293601 -1.006927 0.2778943 0.1679901 -1.019478 0.2813583 0.002546489 -0.1513857 0.05681627 1.023457 -0.299044 0.1122334 0.9855934 -0.4393386 0.1648868 0.9235236 -0.5688154 0.2134802 0.8387761 -0.684286 0.2568171 0.733438 -0.7829072 0.2938303 0.610103 -0.8622506 0.3236083 0.4718078 -0.9203627 0.3454182 0.3219579 -0.9558122 0.3587226 0.1642429 -0.9677264 0.3631941 -0.02687948 -0.1380866 0.06649941 1.015144 -0.2727732 0.131361 0.9521941 -0.4007432 0.1929881 0.8754991 -0.5188456 0.2498632 0.7951709 -0.6241722 0.3005859 0.6953256 -0.7141297 0.3439071 0.5784218 -0.786503 0.3787602 0.4473382 -0.8395099 0.404287 0.3053022 -0.8718453 0.4198589 0.1558112 -0.8827129 0.4250925 -0.07837527 -0.138808 0.08293437 1.023457 -0.2741981 0.1638262 0.9855934 -0.4028366 0.2406841 0.9235236 -0.5215559 0.3116155 0.8387761 -0.6274328 0.3748741 0.733438 -0.7178601 0.4289019 0.610103 -0.7906115 0.4723687 0.4718078 -0.8438953 0.5042044 0.3219579 -0.8763996 0.5236248 0.1642429 -0.887324 0.5301519 -0.02687948 -0.1338466 0.09724581 1.030179 -0.2643976 0.1920966 1.008375 -0.3884381 0.2822174 0.9448667 -0.5029141 0.3653889 0.8581554 -0.6050066 0.4395636 0.7503761 -0.6922019 0.5029147 0.6241828 -0.762353 0.5538824 0.4826827 -0.8137322 0.5912115 0.3293601 -0.8450748 0.6139833 0.1679901 -0.8556087 0.6216367 0.002546489 -0.1245907 0.1088523 1.030179 -0.2461138 0.2150238 1.008375 -0.3615766 0.3159007 0.9448667 -0.4681363 0.408999 0.8581554 -0.5631689 0.4920265 0.7503761 -0.6443344 0.5629386 0.6241828 -0.7096344 0.6199895 0.4826827 -0.7574607 0.6617739 0.3293601 -0.7866357 0.6872636 0.1679901 -0.7964411 0.6958304 0.002546489 -0.1117421 0.1168739 1.023457 -0.220733 0.2308694 0.9855934 -0.3242886 0.3391802 0.9235236 -0.4198593 0.4391391 0.8387761 -0.5050916 0.5282851 0.733438 -0.5778868 0.6044231 0.610103 -0.6364526 0.665678 0.4718078 -0.6793468 0.7105417 0.3219579 -0.7055131 0.7379097 0.1642429 -0.7143074 0.7471079 -0.02687948 -0.0955587 0.1198278 1.015144 -0.1887647 0.2367044 0.9521941 -0.2773227 0.3477526 0.8754991 -0.3590521 0.4502379 0.7951709 -0.4319404 0.541637 0.6953256 -0.4941929 0.6196992 0.5784218 -0.5442768 0.6825023 0.4473382 -0.5809587 0.7285 0.3053022 -0.6033354 0.7565596 0.1558112 -0.6108561 0.7659902 -0.07837527 -0.08907771 0.1349482 1.023457 -0.1759624 0.2665728 0.9855934 -0.2585142 0.3916335 0.9235236 -0.3347007 0.5070509 0.8387761 -0.4026456 0.609983 0.733438 -0.460676 0.6978955 0.610103 -0.5073632 0.7686234 0.4718078 -0.5415574 0.8204252 0.3219579 -0.5624164 0.8520255 0.1642429 -0.569427 0.8626461 -0.02687948 -0.07839816 0.1456897 1.030179 -0.1548663 0.2877912 1.008375 -0.2275211 0.4228064 0.9448667 -0.2945736 0.5474107 0.8581554 -0.3543727 0.658536 0.7503761 -0.4054459 0.753446 0.6241828 -0.4465357 0.8298037 0.4826827 -0.4766303 0.8857287 0.3293601 -0.4949886 0.9198443 0.1679901 -0.5011587 0.9313103 0.002546489 -0.065023 0.1521309 1.030179 -0.1284455 0.3005148 1.008375 -0.188705 0.4414992 0.9448667 -0.2443182 0.5716124 0.8581554 -0.2939154 0.6876506 0.7503761 -0.3362753 0.7867568 0.6241828 -0.3703551 0.8664904 0.4826827 -0.3953155 0.9248878 0.3293601 -0.4105418 0.9605118 0.1679901 -0.4156592 0.9724848 0.002546489 -0.04996639 0.1537833 1.023457 -0.09870302 0.3037789 0.9855934 -0.1450092 0.4462947 0.9235236 -0.1877448 0.5778211 0.8387761 -0.2258574 0.6951197 0.733438 -0.2584087 0.7953023 0.610103 -0.2845971 0.8759019 0.4718078 -0.3037778 0.9349337 0.3219579 -0.3154784 0.9709447 0.1642429 -0.3194108 0.9830477 -0.02687948 -0.03410398 0.1494229 1.015144 -0.06736892 0.2951655 0.9521941 -0.09897482 0.4336404 0.8754991 -0.1281438 0.5614376 0.7951709 -0.1541574 0.6754102 0.6953256 -0.176375 0.7727523 0.5784218 -0.1942497 0.8510665 0.4473382 -0.2073414 0.9084246 0.3053022 -0.2153275 0.9434144 0.1558112 -0.2180115 0.9551743 -0.07837527 -0.02170431 0.1602339 1.023457 -0.04287499 0.3165213 0.9855934 -0.06298983 0.465015 0.9235236 -0.08155375 0.6020585 0.8387761 -0.09810942 0.7242773 0.733438 -0.1122492 0.8286623 0.610103 -0.1236252 0.9126428 0.4718078 -0.1319571 0.9741507 0.3219579 -0.1370397 1.011672 0.1642429 -0.1387478 1.024283 -0.02687948 -0.007421791 0.165278 1.030179 -0.01466172 0.3264852 1.008375 -0.02154052 0.4796534 0.9448667 -0.02788901 0.621011 0.8581554 -0.03355067 0.7470772 0.7503761 -0.03838604 0.8547481 0.6241828 -0.04227644 0.9413722 0.4826827 -0.04512584 1.004816 0.3293601 -0.04686385 1.043519 0.1679901 -0.04744791 1.056527 0.002546489 0.0074234 0.165278 1.030179 0.01466315 0.3264852 1.008375 0.02154195 0.4796534 0.9448667 0.0278902 0.621011 0.8581554 0.03355181 0.7470772 0.7503761 0.03838741 0.8547481 0.6241828 0.04227769 0.9413722 0.4826827 0.04512685 1.004816 0.3293601 0.0468651 1.043519 0.1679901 0.04744935 1.056527 0.002546489 0.02170592 0.1602339 1.023457 0.04287642 0.3165214 0.9855934 0.06299126 0.465015 0.9235236 0.08155494 0.6020585 0.8387761 0.09811055 0.7242773 0.733438 0.1122506 0.8286623 0.610103 0.1236265 0.9126428 0.4718078 0.1319581 0.9741507 0.3219579 0.1370409 1.011672 0.1642429 0.1387492 1.024283 -0.02687948 0.03410553 0.1494229 1.015144 0.06737029 0.2951656 0.9521941 0.09897631 0.4336404 0.8754991 0.128145 0.5614376 0.7951709 0.1541585 0.6754102 0.6953256 0.1763763 0.7727523 0.5784218 0.194251 0.8510667 0.4473382 0.2073425 0.9084246 0.3053022 0.2153288 0.9434145 0.1558112 0.2180129 0.9551743 -0.07837527 0.049968 0.1537833 1.023457 0.09870445 0.303779 0.9855934 0.1450106 0.4462947 0.9235236 0.187746 0.5778211 0.8387761 0.2258586 0.6951196 0.733438 0.2584101 0.7953023 0.610103 0.2845984 0.8759021 0.4718078 0.3037789 0.9349337 0.3219579 0.3154796 0.9709448 0.1642429 0.3194122 0.9830477 -0.02687948 0.06502467 0.1521309 1.030179 0.1284469 0.3005148 1.008375 0.1887065 0.4414992 0.9448667 0.2443194 0.5716124 0.8581554 0.2939165 0.6876506 0.7503761 0.3362767 0.7867568 0.6241828 0.3703564 0.8664905 0.4826827 0.3953166 0.9248878 0.3293601 0.4105431 0.9605119 0.1679901 0.4156606 0.9724848 0.002546489 0.07839977 0.1456898 1.030179 0.1548677 0.2877913 1.008375 0.2275226 0.4228064 0.9448667 0.2945749 0.5474107 0.8581554 0.3543738 0.6585358 0.7503761 0.4054473 0.753446 0.6241828 0.446537 0.8298039 0.4826827 0.4766314 0.8857287 0.3293601 0.4949901 0.9198445 0.1679901 0.5011602 0.9313104 0.002546489 0.08907938 0.1349483 1.023457 0.1759638 0.2665728 0.9855934 0.2585158 0.3916335 0.9235236 0.334702 0.5070509 0.8387761 0.4026468 0.6099829 0.733438 0.4606775 0.6978954 0.610103 0.5073646 0.7686236 0.4718078 0.5415584 0.8204252 0.3219579 0.5624178 0.8520257 0.1642429 0.5694285 0.8626462 -0.02687948 0.09556031 0.1198279 1.015144 0.1887661 0.2367044 0.9521941 0.2773241 0.3477526 0.8754991 0.3590534 0.450238 0.7951709 0.4319416 0.5416368 0.6953256 0.4941944 0.6196991 0.5784218 0.5442782 0.6825026 0.4473382 0.5809597 0.7285 0.3053022 0.6033369 0.7565597 0.1558112 0.6108575 0.7659903 -0.07837527 0.1117438 0.116874 1.023457 0.2207344 0.2308694 0.9855934 0.3242902 0.3391801 0.9235236 0.4198606 0.4391391 0.8387761 0.5050928 0.528285 0.733438 0.5778883 0.6044229 0.610103 0.636454 0.6656782 0.4718078 0.6793478 0.7105418 0.3219579 0.7055146 0.7379098 0.1642429 0.7143089 0.7471079 -0.02687948 0.1245924 0.1088525 1.030179 0.2461152 0.2150238 1.008375 0.3615781 0.3159006 0.9448667 0.4681377 0.408999 0.8581554 0.56317 0.4920264 0.7503761 0.6443359 0.5629386 0.6241828 0.7096357 0.6199897 0.4826827 0.7574617 0.6617741 0.3293601 0.7866371 0.6872637 0.1679901 0.7964427 0.6958304 0.002546489 0.1338483 0.09724593 1.030179 0.2643991 0.1920967 1.008375 0.3884396 0.2822174 0.9448667 0.5029155 0.3653891 0.8581554 0.6050078 0.4395635 0.7503761 0.6922034 0.5029147 0.6241828 0.7623544 0.5538825 0.4826827 0.8137333 0.5912117 0.3293601 0.8450763 0.6139835 0.1679901 0.8556102 0.6216368 0.002546489 0.1388096 0.08293449 1.023457 0.2741997 0.1638263 0.9855934 0.4028381 0.2406841 0.9235236 0.5215573 0.3116157 0.8387761 0.6274339 0.374874 0.733438 0.7178617 0.4289019 0.610103 0.7906129 0.472369 0.4718078 0.8438963 0.5042046 0.3219579 0.8764012 0.523625 0.1642429 0.8873255 0.530152 -0.02687948 0.1380883 0.06649947 1.015144 0.2727747 0.1313611 0.9521941 0.4007447 0.1929881 0.8754991 0.5188469 0.2498633 0.7951709 0.6241734 0.3005858 0.6953256 0.7141312 0.3439071 0.5784218 0.7865045 0.3787605 0.4473382 0.839511 0.4042872 0.3053022 0.8718468 0.4198591 0.1558112 0.8827144 0.4250926 -0.07837527 0.1513875 0.05681639 1.023457 0.2990455 0.1122335 0.9855934 0.4393401 0.1648869 0.9235236 0.5688167 0.2134803 0.8387761 0.6842871 0.2568171 0.733438 0.7829087 0.2938303 0.610103 0.8622522 0.3236086 0.4718078 0.9203639 0.3454183 0.3219579 0.9558139 0.3587228 0.1642429 0.9677281 0.3631942 -0.02687948 0.1594833 0.04401439 1.030179 0.3150376 0.08694475 1.008375 0.4628349 0.1277341 0.9448667 0.5992355 0.1653784 0.8581554 0.7208809 0.1989504 0.7503761 0.8247766 0.2276237 0.6241828 0.9083633 0.2506923 0.4826827 0.9695824 0.2675879 0.3293601 1.006928 0.2778944 0.1679901 1.01948 0.2813584 0.002546489 0.1627866 0.02954131 1.030179 0.321563 0.05835509 1.008375 0.4724217 0.0857318 0.9448667 0.6116476 0.1109977 0.8581554 0.7358126 0.1335303 0.7503761 0.8418603 0.152775 0.6241828 0.9271784 0.1682581 0.4826827 0.9896655 0.179598 0.3293601 1.027785 0.1865154 0.1679901 1.040596 0.1888403 0.002546489 0.1610472 0.01449447 1.023457 0.318127 0.02863198 0.9855934 0.4673736 0.04206436 0.9235236 0.6051118 0.05446112 0.8387761 0.7279502 0.06551682 0.733438 0.8328647 0.07495915 0.610103 0.9172711 0.08255606 0.4718078 0.9790906 0.08812004 0.3219579 1.016803 0.09151393 0.1642429 1.029477 0.09265464 -0.02687948 0.1532664 0 1.015144 0.3027571 1.34388e-7 0.9521941 0.444793 0 0.8754991 0.5758767 1.50812e-7 0.7951709 0.6927801 2.0191e-7 0.6953256 0.7926257 0 0.5784218 0.8729543 2.38408e-7 0.4473382 0.9317869 3.47902e-7 0.3053022 0.9676769 0 0.1558112 0.9797392 0 -0.07837527 0.1610472 -0.01449435 1.023457 0.318127 -0.02863168 0.9855934 0.4673736 -0.04206418 0.9235236 0.6051119 -0.05446082 0.8387761 0.7279502 -0.06551641 0.733438 0.8328647 -0.07495898 0.610103 0.9172711 -0.08255553 0.4718078 0.9790908 -0.08811926 0.3219579 1.016803 -0.09151369 0.1642429 1.029477 -0.0926544 -0.02687948 0.1627866 -0.02954119 1.030179 0.3215631 -0.05835479 1.008375 0.4724217 -0.08573162 0.9448667 0.6116477 -0.1109973 0.8581554 0.7358126 -0.1335299 0.7503761 0.8418604 -0.1527749 0.6241828 0.9271785 -0.1682576 0.4826827 0.9896657 -0.1795973 0.3293601 1.027785 -0.1865152 0.1679901 1.040597 -0.1888401 0.002546489 0.1594833 -0.04401427 1.030179 0.3150377 -0.08694446 1.008375 0.462835 -0.127734 0.9448667 0.5992357 -0.1653781 0.8581554 0.7208809 -0.19895 0.7503761 0.8247767 -0.2276235 0.6241828 0.9083635 -0.2506919 0.4826827 0.9695827 -0.2675872 0.3293601 1.006928 -0.2778942 0.1679901 1.01948 -0.2813582 0.002546489 0.1513875 -0.05681627 1.023457 0.2990456 -0.1122332 0.9855934 0.4393402 -0.1648867 0.9235236 0.568817 -0.2134801 0.8387761 0.6842871 -0.2568167 0.733438 0.7829088 -0.2938302 0.610103 0.8622525 -0.3236082 0.4718078 0.9203641 -0.3454177 0.3219579 0.9558139 -0.3587225 0.1642429 0.9677285 -0.3631941 -0.02687948 0.1380883 -0.06649941 1.015144 0.2727748 -0.1313609 0.9521941 0.4007447 -0.192988 0.8754991 0.5188471 -0.249863 0.7951709 0.6241734 -0.3005855 0.6953256 0.7141312 -0.343907 0.5784218 0.7865048 -0.3787601 0.4473382 0.8395113 -0.4042866 0.3053022 0.8718469 -0.4198588 0.1558112 0.8827148 -0.4250925 -0.07837527 0.1388097 -0.08293437 1.023457 0.2741998 -0.1638261 0.9855934 0.4028382 -0.240684 0.9235236 0.5215575 -0.3116154 0.8387761 0.6274339 -0.3748736 0.733438 0.7178617 -0.4289019 0.610103 0.7906134 -0.4723687 0.4718078 0.8438968 -0.504204 0.3219579 0.8764013 -0.5236248 0.1642429 0.8873259 -0.5301519 -0.02687948 0.1338483 -0.09724581 1.030179 0.2643992 -0.1920965 1.008375 0.3884397 -0.2822173 0.9448667 0.5029157 -0.3653889 0.8581554 0.6050078 -0.4395631 0.7503761 0.6922034 -0.5029146 0.6241828 0.7623549 -0.5538824 0.4826827 0.8137338 -0.5912112 0.3293601 0.8450764 -0.6139833 0.1679901 0.8556106 -0.6216368 0.002546489 0.1245924 -0.1088523 1.030179 0.2461154 -0.2150236 1.008375 0.3615782 -0.3159006 0.9448667 0.4681379 -0.4089989 0.8581554 0.5631701 -0.4920259 0.7503761 0.6443359 -0.5629386 0.6241828 0.7096362 -0.6199895 0.4826827 0.7574621 -0.6617736 0.3293601 0.7866374 -0.6872636 0.1679901 0.7964431 -0.6958305 0.002546489 0.1117438 -0.1168739 1.023457 0.2207347 -0.2308693 0.9855934 0.3242903 -0.3391801 0.9235236 0.4198608 -0.439139 0.8387761 0.5050929 -0.5282846 0.733438 0.5778883 -0.6044229 0.610103 0.6364545 -0.6656782 0.4718078 0.6793483 -0.7105414 0.3219579 0.7055148 -0.7379097 0.1642429 0.7143093 -0.747108 -0.02687948 0.09556037 -0.1198278 1.015144 0.1887664 -0.2367043 0.9521941 0.2773243 -0.3477526 0.8754991 0.3590536 -0.4502378 0.7951709 0.4319417 -0.5416365 0.6953256 0.4941944 -0.6196991 0.5784218 0.5442786 -0.6825025 0.4473382 0.5809602 -0.7284998 0.3053022 0.6033371 -0.7565596 0.1558112 0.6108579 -0.7659904 -0.07837527 0.08907938 -0.1349482 1.023457 0.1759641 -0.2665727 0.9855934 0.2585158 -0.3916335 0.9235236 0.3347022 -0.5070508 0.8387761 0.4026469 -0.6099825 0.733438 0.4606775 -0.6978954 0.610103 0.507365 -0.7686235 0.4718078 0.5415588 -0.820425 0.3219579 0.562418 -0.8520256 0.1642429 0.5694288 -0.8626463 -0.02687948 0.07839983 -0.1456897 1.030179 0.154868 -0.2877912 1.008375 0.2275226 -0.4228065 0.9448667 0.2945752 -0.5474106 0.8581554 0.3543741 -0.6585354 0.7503761 0.4054474 -0.753446 0.6241828 0.4465374 -0.8298039 0.4826827 0.4766318 -0.8857286 0.3293601 0.4949903 -0.9198445 0.1679901 0.5011605 -0.9313105 0.002546489 0.06502473 -0.1521308 1.030179 0.1284471 -0.3005148 1.008375 0.1887066 -0.4414993 0.9448667 0.2443197 -0.5716124 0.8581554 0.2939168 -0.6876502 0.7503761 0.3362768 -0.7867568 0.6241828 0.3703567 -0.8664906 0.4826827 0.395317 -0.9248878 0.3293601 0.4105433 -0.9605119 0.1679901 0.4156609 -0.972485 0.002546489 0.04996806 -0.1537832 1.023457 0.09870469 -0.303779 0.9855934 0.1450107 -0.4462947 0.9235236 0.1877464 -0.5778211 0.8387761 0.2258589 -0.6951193 0.733438 0.2584102 -0.7953023 0.610103 0.2845988 -0.8759022 0.4718078 0.3037793 -0.9349337 0.3219579 0.3154799 -0.9709448 0.1642429 0.3194125 -0.9830479 -0.02687948 0.03410565 -0.1494228 1.015144 0.06737053 -0.2951656 0.9521941 0.09897637 -0.4336404 0.8754991 0.1281453 -0.5614376 0.7951709 0.1541588 -0.6754098 0.6953256 0.1763764 -0.7727523 0.5784218 0.1942513 -0.8510668 0.4473382 0.2073429 -0.9084246 0.3053022 0.2153291 -0.9434145 0.1558112 0.2180132 -0.9551746 -0.07837527 0.02170604 -0.1602339 1.023457 0.04287666 -0.3165214 0.9855934 0.06299138 -0.4650151 0.9235236 0.08155524 -0.6020585 0.8387761 0.09811097 -0.7242769 0.733438 0.1122507 -0.8286623 0.610103 0.1236268 -0.912643 0.4718078 0.1319586 -0.9741507 0.3219579 0.1370412 -1.011672 0.1642429 0.1387494 -1.024283 -0.02687948 0.00742352 -0.165278 1.030179 0.01466339 -0.3264853 1.008375 0.02154207 -0.4796535 0.9448667 0.02789056 -0.621011 0.8581554 0.03355222 -0.7470767 0.7503761 0.03838753 -0.8547481 0.6241828 0.04227799 -0.9413726 0.4826827 0.04512733 -1.004816 0.3293601 0.04686534 -1.043519 0.1679901 0.04744952 -1.056527 0.002546489 -0.007421731 -0.165278 1.030179 -0.01466149 -0.3264853 1.008375 -0.0215404 -0.4796535 0.9448667 -0.02788871 -0.6210111 0.8581554 -0.0335502 -0.7470767 0.7503761 -0.03838598 -0.8547481 0.6241828 -0.04227614 -0.9413726 0.4826827 -0.04512536 -1.004816 0.3293601 -0.04686361 -1.043519 0.1679901 -0.0474478 -1.056527 0.002546489 -0.02170425 -0.1602339 1.023457 -0.04287475 -0.3165215 0.9855934 -0.06298977 -0.4650152 0.9235236 -0.08155345 -0.6020587 0.8387761 -0.09810894 -0.7242769 0.733438 -0.1122491 -0.8286623 0.610103 -0.123625 -0.9126431 0.4718078 -0.1319566 -0.9741508 0.3219579 -0.1370394 -1.011672 0.1642429 -0.1387477 -1.024283 -0.02687948 -0.03410392 -0.1494229 1.015144 -0.06736874 -0.2951658 0.9521941 -0.09897482 -0.4336405 0.8754991 -0.1281436 -0.5614377 0.7951709 -0.1541569 -0.6754099 0.6953256 -0.1763749 -0.7727523 0.5784218 -0.1942496 -0.851067 0.4473382 -0.207341 -0.9084247 0.3053022 -0.2153273 -0.9434146 0.1558112 -0.2180115 -0.9551746 -0.07837527 -0.04996633 -0.1537833 1.023457 -0.09870284 -0.3037791 0.9855934 -0.1450091 -0.4462949 0.9235236 -0.1877446 -0.5778212 0.8387761 -0.225857 -0.6951193 0.733438 -0.2584086 -0.7953023 0.610103 -0.284597 -0.8759025 0.4718078 -0.3037775 -0.934934 0.3219579 -0.3154782 -0.9709449 0.1642429 -0.3194108 -0.983048 -0.02687948 -0.06502294 -0.1521309 1.030179 -0.1284453 -0.3005151 1.008375 -0.1887051 -0.4414994 0.9448667 -0.244318 -0.5716125 0.8581554 -0.2939148 -0.6876503 0.7503761 -0.3362752 -0.7867568 0.6241828 -0.370355 -0.8664909 0.4826827 -0.3953151 -0.9248881 0.3293601 -0.4105417 -0.9605121 0.1679901 -0.4156593 -0.9724852 0.002546489 -0.0783981 -0.1456897 1.030179 -0.1548662 -0.2877915 1.008375 -0.2275211 -0.4228066 0.9448667 -0.2945734 -0.5474109 0.8581554 -0.3543721 -0.6585356 0.7503761 -0.4054458 -0.753446 0.6241828 -0.4465358 -0.8298043 0.4826827 -0.47663 -0.885729 0.3293601 -0.4949886 -0.9198446 0.1679901 -0.5011588 -0.9313108 0.002546489 -0.08907765 -0.1349483 1.023457 -0.1759623 -0.2665731 0.9855934 -0.2585144 -0.3916336 0.9235236 -0.3347005 -0.507051 0.8387761 -0.4026451 -0.6099827 0.733438 -0.460676 -0.6978954 0.610103 -0.5073633 -0.768624 0.4718078 -0.5415571 -0.8204254 0.3219579 -0.5624164 -0.8520258 0.1642429 -0.5694271 -0.8626466 -0.02687948 -0.09555864 -0.1198279 1.015144 -0.1887647 -0.2367047 0.9521941 -0.2773228 -0.3477528 0.8754991 -0.359052 -0.4502381 0.7951709 -0.4319399 -0.5416367 0.6953256 -0.4941929 -0.6196992 0.5784218 -0.544277 -0.6825029 0.4473382 -0.5809586 -0.7285002 0.3053022 -0.6033355 -0.7565599 0.1558112 -0.6108562 -0.7659907 -0.07837527 -0.1610454 0.01449441 1.023457 -0.1117421 -0.116874 1.023457 -0.220733 -0.2308697 0.9855934 -0.3242888 -0.3391803 0.9235236 -0.4198592 -0.4391393 0.8387761 -0.505091 -0.5282849 0.733438 -0.5778868 -0.6044231 0.610103 -0.6364529 -0.6656785 0.4718078 -0.6793467 -0.710542 0.3219579 -0.7055132 -0.7379099 0.1642429 -0.7143076 -0.7471083 -0.02687948 -0.1245907 -0.1088524 1.030179 -0.2461138 -0.2150241 1.008375 -0.3615768 -0.3159008 0.9448667 -0.4681363 -0.4089992 0.8581554 -0.5631684 -0.4920263 0.7503761 -0.6443345 -0.5629387 0.6241828 -0.7096347 -0.61999 0.4826827 -0.7574607 -0.6617743 0.3293601 -0.7866358 -0.6872639 0.1679901 -0.7964414 -0.6958308 0.002546489 -0.1338466 -0.09724587 1.030179 -0.2643977 -0.1920969 1.008375 -0.3884384 -0.2822176 0.9448667 -0.5029141 -0.3653892 0.8581554 -0.6050061 -0.4395635 0.7503761 -0.692202 -0.5029147 0.6241828 -0.7623534 -0.5538829 0.4826827 -0.8137323 -0.5912119 0.3293601 -0.8450749 -0.6139836 0.1679901 -0.855609 -0.6216371 0.002546489 -0.138808 -0.08293443 1.023457 -0.2741982 -0.1638265 0.9855934 -0.4028368 -0.2406843 0.9235236 -0.5215559 -0.3116158 0.8387761 -0.6274322 -0.374874 0.733438 -0.7178602 -0.428902 0.610103 -0.790612 -0.4723693 0.4718078 -0.8438954 -0.5042047 0.3219579 -0.8763998 -0.5236251 0.1642429 -0.8873243 -0.5301523 -0.02687948 -0.1380867 -0.06649947 1.015144 -0.2727734 -0.1313613 0.9521941 -0.4007434 -0.1929882 0.8754991 -0.5188456 -0.2498635 0.7951709 -0.6241717 -0.3005859 0.6953256 -0.7141298 -0.3439072 0.5784218 -0.7865035 -0.3787607 0.4473382 -0.83951 -0.4042873 0.3053022 -0.8718455 -0.4198592 0.1558112 -0.8827133 -0.4250929 -0.07837527 -0.1513858 -0.05681639 1.023457 -0.2990441 -0.1122335 0.9855934 -0.4393389 -0.1648869 0.9235236 -0.5688154 -0.2134805 0.8387761 -0.6842855 -0.2568172 0.733438 -0.7829073 -0.2938304 0.610103 -0.8622513 -0.3236088 0.4718078 -0.9203629 -0.3454185 0.3219579 -0.9558125 -0.3587229 0.1642429 -0.967727 -0.3631946 -0.02687948 -0.1594816 -0.04401439 1.030179 -0.3150362 -0.08694481 1.008375 -0.4628336 -0.1277341 0.9448667 -0.5992342 -0.1653785 0.8581554 -0.7208794 -0.1989505 0.7503761 -0.8247752 -0.2276238 0.6241828 -0.9083623 -0.2506925 0.4826827 -0.9695816 -0.2675879 0.3293601 -1.006927 -0.2778946 0.1679901 -1.019479 -0.2813587 0.002546489 -0.162785 -0.02954131 1.030179 -0.3215617 -0.05835509 1.008375 -0.4724204 -0.0857318 0.9448667 -0.6116463 -0.1109977 0.8581554 -0.7358111 -0.1335303 0.7503761 -0.8418589 -0.1527751 0.6241828 -0.9271774 -0.1682582 0.4826827 -0.9896646 -0.179598 0.3293601 -1.027783 -0.1865156 0.1679901 -1.040595 -0.1888406 0.002546489 -0.1610456 -0.01449441 1.023457 -0.3181257 -0.02863198 0.9855934 -0.4673723 -0.0420643 0.9235236 -0.6051105 -0.05446118 0.8387761 -0.7279487 -0.06551682 0.733438 -0.8328633 -0.07495915 0.610103 -0.9172701 -0.082556 0.4718078 -0.9790896 -0.08811992 0.3219579 -1.016801 -0.09151405 0.1642429 -1.029476 -0.09265482 -0.02687948 -0.1532648 0 1.015144 -0.3027558 0 0.9521941 -0.4447917 0 0.8754991 -0.5758754 -1.92269e-7 0.7951709 -0.7926244 0 0.5784218 -0.8729533 -1.7037e-7 0.4473382 -0.931786 -1.92269e-7 0.3053022 -0.9676757 -1.99569e-7 0.1558112 -0.9797381 -2.36067e-7 -0.07837527 -0.8817924 0.4246492 -0.06851685 -0.6102191 0.7651914 -0.06851685 -0.2177842 0.9541782 -0.06851685 0.2177856 0.9541782 -0.06851685 0.6102205 0.7651916 -0.06851685 0.8817939 0.4246493 -0.06851685 0.9787175 0 -0.06851685 0.8817943 -0.4246492 -0.06851685 0.6102209 -0.7651916 -0.06851685 0.2177858 -0.9541785 -0.06851685 -0.2177842 -0.9541786 -0.06851685 -0.6102192 -0.7651919 -0.06851685 -0.8817928 -0.4246497 -0.06851685 -0.9787164 -2.38385e-7 -0.06851685 7.32286e-7 -1.21337e-7 -2.088751 -0.1627849 0.02954125 1.030179 -0.1594815 0.04401427 1.030179 -0.1513857 0.05681627 1.023457 -0.1380866 0.06649941 1.015144 -0.138808 0.08293437 1.023457 -0.1338466 0.09724581 1.030179 -0.1245907 0.1088523 1.030179 -0.1117421 0.1168739 1.023457 -0.0955587 0.1198278 1.015144 -0.08907771 0.1349482 1.023457 -0.07839816 0.1456897 1.030179 -0.065023 0.1521309 1.030179 -0.04996639 0.1537833 1.023457 -0.03410398 0.1494229 1.015144 -0.02170431 0.1602339 1.023457 -0.007421791 0.165278 1.030179 0.0074234 0.165278 1.030179 0.02170592 0.1602339 1.023457 0.03410553 0.1494229 1.015144 0.049968 0.1537833 1.023457 0.06502467 0.1521309 1.030179 0.07839977 0.1456898 1.030179 0.08907938 0.1349483 1.023457 0.09556031 0.1198279 1.015144 0.1117438 0.116874 1.023457 0.1245924 0.1088525 1.030179 0.1338483 0.09724593 1.030179 0.1388096 0.08293449 1.023457 0.1380883 0.06649947 1.015144 0.1513875 0.05681639 1.023457 0.1594833 0.04401439 1.030179 0.1627866 0.02954131 1.030179 0.1610472 0.01449447 1.023457 0.1532664 0 1.015144 0.1610472 -0.01449435 1.023457 0.1627866 -0.02954119 1.030179 0.1594833 -0.04401427 1.030179 0.1513875 -0.05681627 1.023457 0.1380883 -0.06649941 1.015144 0.1388097 -0.08293437 1.023457 0.1338483 -0.09724581 1.030179 0.1245924 -0.1088523 1.030179 0.1117438 -0.1168739 1.023457 0.09556037 -0.1198278 1.015144 0.08907938 -0.1349482 1.023457 0.07839983 -0.1456897 1.030179 0.06502473 -0.1521308 1.030179 0.04996806 -0.1537832 1.023457 0.03410565 -0.1494228 1.015144 0.02170604 -0.1602339 1.023457 0.00742352 -0.165278 1.030179 -0.007421731 -0.165278 1.030179 -0.02170425 -0.1602339 1.023457 -0.03410392 -0.1494229 1.015144 -0.04996633 -0.1537833 1.023457 -0.06502294 -0.1521309 1.030179 -0.0783981 -0.1456897 1.030179 -0.08907765 -0.1349483 1.023457 -0.09555864 -0.1198279 1.015144 -0.1117421 -0.116874 1.023457 -0.1245907 -0.1088524 1.030179 -0.1338466 -0.09724587 1.030179 -0.138808 -0.08293443 1.023457 -0.1380867 -0.06649947 1.015144 -0.1513858 -0.05681639 1.023457 -0.1594816 -0.04401439 1.030179 -0.162785 -0.02954131 1.030179 -0.1610456 -0.01449441 1.023457 -0.1532648 0 1.015144 -0.08030927 0.007228016 1.034929 -0.07970112 0.01446378 1.034996 -0.07808375 0.02154994 1.034996 -0.07549226 0.028333 1.034929 -0.07276242 0.03504091 1.034408 -0.06922 0.04135751 1.034929 -0.06553256 0.04761278 1.034996 -0.06100076 0.05329549 1.034996 -0.05572283 0.05828237 1.034929 -0.05035293 0.06314158 1.034408 -0.04442059 0.06729561 1.034929 -0.03838431 0.07133156 1.034996 -0.03183567 0.07448524 1.034996 -0.02491664 0.07668823 1.034929 -0.0179702 0.0787363 1.034408 -0.01082301 0.07990503 1.034929 -0.003633379 0.08092224 1.034996 0.003634989 0.08092224 1.034996 0.01082468 0.07990503 1.034929 0.01797181 0.0787363 1.034408 0.02491831 0.07668828 1.034929 0.03183734 0.07448524 1.034996 0.03838598 0.07133156 1.034996 0.04442226 0.06729567 1.034929 0.05035454 0.06314164 1.034408 0.0557245 0.05828243 1.034929 0.06100243 0.05329555 1.034996 0.06553423 0.04761284 1.034996 0.06922161 0.04135757 1.034929 0.07276409 0.03504097 1.034408 0.07549393 0.02833306 1.034929 0.07808548 0.02154999 1.034996 0.07970285 0.01446378 1.034996 0.080311 0.007228076 1.034929 0.08076196 0 1.034408 0.080311 -0.007227957 1.034929 0.07970285 -0.01446372 1.034996 0.07808548 -0.02154994 1.034996 0.07549393 -0.028333 1.034929 0.07276409 -0.03504091 1.034408 0.06922167 -0.04135745 1.034929 0.06553423 -0.04761278 1.034996 0.06100243 -0.05329549 1.034996 0.0557245 -0.05828237 1.034929 0.05035459 -0.06314158 1.034408 0.04442226 -0.06729561 1.034929 0.03838598 -0.0713315 1.034996 0.03183734 -0.07448518 1.034996 0.02491837 -0.07668817 1.034929 0.01797187 -0.07873624 1.034408 0.01082468 -0.07990497 1.034929 0.003635048 -0.08092218 1.034996 -0.00363332 -0.08092218 1.034996 -0.01082301 -0.07990497 1.034929 -0.01797014 -0.07873624 1.034408 -0.02491664 -0.07668823 1.034929 -0.03183561 -0.07448518 1.034996 -0.03838425 -0.07133156 1.034996 -0.04442059 -0.06729561 1.034929 -0.05035287 -0.06314158 1.034408 -0.05572283 -0.05828237 1.034929 -0.06100076 -0.05329549 1.034996 -0.06553256 -0.04761278 1.034996 -0.06922 -0.04135751 1.034929 -0.07276242 -0.03504091 1.034408 -0.07549226 -0.028333 1.034929 -0.07808381 -0.02154999 1.034996 -0.07970118 -0.01446378 1.034996 -0.08030933 -0.007228016 1.034929 -0.08076035 0 1.034408 + + + + + + + + + + -0.6525359 -0.4471096 0.6117924 -0.5306315 -0.5253517 0.6651586 -0.5994818 -0.09152603 0.7951381 -0.7574163 -0.3894508 0.5240693 -0.7144243 -0.04077363 0.6985238 -0.8419654 -0.3479806 0.4123152 -0.813043 -0.003601312 0.5821925 -0.9045135 -0.3189815 0.2830305 -0.8925853 0.02331638 0.4502754 -0.9512246 0.04092633 0.3057726 -0.9864731 0.05124175 0.1557091 -0.2751592 -0.6960771 0.6631472 -0.1534833 -0.2970477 0.9424466 -0.1018124 -0.1171637 0.9878801 -0.9422732 -0.303328 0.1418216 -0.9967463 0.03256362 0.07373356 -0.4093548 -0.6216773 0.6677919 -0.2934443 -0.2737288 0.9159492 -0.4718872 -0.1627892 0.8665 -0.8739027 0.3760513 0.3080251 -0.04089593 0.149728 0.9878811 -0.9114354 0.381189 0.1548561 -0.9121829 0.4030951 0.07373392 -0.1456077 0.3739534 0.9159462 -0.3545141 0.3514011 0.8665086 -0.5027731 0.347522 0.7914845 -0.623019 0.3523747 0.6983405 -0.7282428 0.357804 0.5844987 -0.8144721 0.3677287 0.4487883 -0.2668008 0.6929741 0.6697794 -0.4055753 0.6736903 0.6177784 -0.5195875 0.6711148 0.5288043 -0.6133557 0.6761959 0.4081103 -0.6766743 0.6779256 0.2872783 -0.7181906 0.68175 0.1393531 -0.00939995 0.3342482 0.9424383 0.05407994 0.7465294 0.663151 -0.09543234 0.7290336 0.6777926 -0.8064376 0.3893325 0.4450605 -0.8591849 0.4107925 0.3050424 -0.8918038 0.4294673 0.1422808 -0.1460938 0.07034593 0.9867665 -0.3705354 0.1784161 0.9115214 -0.6871189 0.7244444 0.05520999 -0.4614873 0.2339634 0.8557398 -0.5376878 0.2679893 0.7994208 -0.6511596 0.3135552 0.6911399 -0.7384743 0.3604934 0.5698249 -0.6439212 -0.3738887 0.6675124 -0.6942288 -0.2388462 0.678969 -0.7810723 -0.1085865 0.6149269 -0.8535017 -0.01608365 0.5208418 -0.9080557 0.05371302 0.4153911 -0.9529137 0.108219 0.2832739 -0.2671614 -0.2010272 0.9424505 -0.9808009 0.1364216 0.1393514 -0.9948061 0.08551496 0.05520933 -0.5499266 -0.5077489 0.663153 -0.7940633 0.4082934 0.4502887 -0.8386606 0.4501239 0.3066543 -0.142556 -0.06137448 0.9878821 -0.8662993 0.4749157 0.1548565 -0.8839036 0.4618199 0.07373487 -0.3831684 -0.1192995 0.915942 -0.5039353 0.05688804 0.861866 -0.5779997 0.170998 0.7979198 -0.6613806 0.2732074 0.6985224 -0.7340916 0.3495122 0.5821948 -0.1570528 0.4692661 0.8689786 -0.3021737 0.5312532 0.7914931 -0.4087814 0.5841479 0.7011911 -0.5040925 0.637921 0.5821922 -0.5747675 0.6832938 0.4502798 -0.6251022 0.7181564 0.3057757 0.02810823 0.1526575 0.9878795 -0.655127 0.7392992 0.1557094 0.02908468 0.4127401 0.9103844 -0.1760365 0.83245 0.5253933 -0.2589254 0.8734003 0.4124678 -0.317433 0.9057875 0.2806876 0.1365439 0.3052249 0.9424402 0.3589978 0.6545767 0.6653195 -0.6469364 0.7589708 0.07373327 -0.3503288 0.9258274 0.1418222 0.2314619 0.690357 0.6854434 0.06027644 0.7401036 0.6697861 -0.06854659 0.78206 0.619422 -0.3047372 0.950835 0.05520975 -0.6181992 0.7726576 0.1443258 -0.2563951 0.3215238 0.9115284 -0.3142602 0.4110378 0.8557387 -0.3681843 0.474727 0.7994214 -0.4506187 0.5650359 0.691142 -0.508936 0.6452035 0.5698215 -0.5530382 0.7043218 0.4450613 -0.5934159 0.7456763 0.3030254 -0.1010786 0.1267756 0.986768 -0.7472013 0.2408574 0.6194175 -0.7759566 0.3558261 0.5208447 -0.7966709 0.443107 0.4110619 -0.8115078 0.5088481 0.2872781 -0.3279615 -0.06518942 0.9424392 -0.8244809 0.5484637 0.1393514 -0.8591758 0.5086935 0.05520915 -0.7157707 -0.2188544 0.6631554 -0.7423768 -0.0574674 0.6675135 -0.7294365 0.09293055 0.6777067 -0.155069 0.006531119 0.9878821 -0.5744404 0.8037648 0.1548565 -0.5959811 0.799606 0.07373464 -0.3969669 0.05874997 0.9159508 -0.4293451 0.2699124 0.8618643 -0.4519284 0.4060886 0.7942624 -0.4785414 0.5285319 0.7011792 -0.5097432 0.6334098 0.5821974 -0.539736 0.7122319 0.4487882 -0.5610877 0.7683103 0.308026 -0.1172845 0.7087122 0.6956806 -0.1742935 0.7924541 0.5844982 -0.2213574 0.865012 0.4502835 -0.2515712 0.9182671 0.3057736 0.09155827 0.1253128 0.9878836 0.2015504 0.3470062 0.9159499 -0.2694834 0.9503335 0.1557083 0.05368345 0.4962745 0.8665044 -0.0441302 0.6048219 0.7951372 0.1070004 0.953817 0.2806852 0.2554488 0.2157428 0.9424442 0.6173809 0.4231541 0.6631603 -0.2535557 0.9645065 0.07373499 0.08606475 0.9861435 0.1418237 0.5104613 0.5291694 0.6777971 0.3806694 0.636148 0.6711233 0.2759544 0.7400901 0.6132829 0.2007258 0.8246638 0.5288091 0.1456386 0.8992542 0.4124698 -0.1200925 0.5988756 0.7917866 -0.1528072 0.6988789 0.6987263 -0.1821085 0.7979266 0.5745865 -0.1969124 0.876004 0.4402757 -0.2111008 0.9293077 0.3030245 -0.03607326 0.1580876 0.986766 -0.09149748 0.4009347 0.911526 0.1379748 0.9888958 0.0552082 -0.2217206 0.9643705 0.1443244 -0.1048024 0.506708 0.855724 -0.5103462 0.810566 0.2872796 -0.3237433 0.08352988 0.9424507 -0.50485 0.8518849 0.139351 -0.5533751 0.8311004 0.05520927 -0.7398474 0.113379 0.6631525 -0.6937955 0.2703095 0.6675184 -0.6233807 0.4034914 0.6697695 -0.5728801 0.5332659 0.6224436 -0.5394634 0.6592221 0.5238373 -0.5210316 0.7482809 0.4106114 -0.2309707 0.5619537 0.7942674 -0.201825 0.6838184 0.701184 -0.1865655 0.7929261 0.5800529 -0.1789975 0.8745698 0.4506525 -0.1721559 0.9356725 0.3080251 -0.1368792 0.07318538 0.9878806 -0.1688016 0.9734095 0.1548544 -0.1900095 0.9790097 0.07373321 -0.3321727 0.2251718 0.9159471 -0.2697002 0.4294695 0.8618688 0.1758542 0.8753952 0.450287 0.1717327 0.9364882 0.305774 0.1368792 0.07318538 0.9878806 0.3408384 0.2345706 0.9103878 0.1695309 0.9731469 0.1557059 0.2689676 0.4153692 0.8689792 0.2226353 0.5640808 0.7951393 0.2017919 0.6894252 0.6956816 0.1867787 0.7895978 0.5845075 0.6840687 0.2494376 0.6854422 0.6189917 0.4079815 0.6711187 0.5697375 0.5470615 0.6132888 0.5386682 0.6558934 0.5288105 0.5238639 0.7469905 0.4093555 0.5108634 0.8111128 0.2848066 0.3237526 0.08353227 0.9424471 0.7356052 0.1274178 0.6653194 0.1900095 0.9790097 0.07373321 0.5041757 0.852124 0.1403268 0.1821085 0.7979266 0.5745865 0.200145 0.8769696 0.4368826 0.2116478 0.9274053 0.308423 0.2202554 0.96501 0.1422795 0.03607326 0.1580876 0.986766 0.09149748 0.4009347 0.911526 0.5533751 0.8311004 0.05520927 0.1254047 0.5019849 0.8557366 0.1516193 0.5916757 0.79179 0.165533 0.695977 0.6987237 -0.6173809 0.4231541 0.6631603 -0.507804 0.5445793 0.6675094 -0.3865587 0.6340101 0.6697788 -0.2847704 0.7290316 0.6224297 -0.2025563 0.8264003 0.5253889 -0.1462487 0.9011448 0.4081047 -0.1081309 0.9517233 0.287281 -0.2554431 0.2157075 0.9424538 -0.08521014 0.98657 0.1393516 -0.1379748 0.9888958 0.0552082 0.1773781 0.7934712 0.5821861 0.2203204 0.8660525 0.4487896 0.2508376 0.9177134 0.3080306 -0.09155791 0.1253428 0.9878798 0.2702502 0.950255 0.1548559 0.2535557 0.9645065 0.07373499 -0.2015797 0.3470041 0.9159442 -0.05664378 0.503965 0.8618647 0.03570783 0.6065143 0.7942703 0.1148433 0.7036785 0.701176 0.5749856 0.8032098 0.15571 0.4088652 0.06344932 0.9103865 0.4225664 0.25755 0.8689681 0.4507037 0.4128298 0.7914782 0.482173 0.5289894 0.6983405 0.5108946 0.6303475 0.5845074 0.539736 0.7122319 0.4487882 0.5618551 0.7681027 0.3071434 0.1550988 0.006531059 0.9878774 0.7474268 0.236558 0.6208007 0.7699142 0.3571997 0.5288106 0.7957317 0.4475057 0.4081051 0.8112204 0.5097557 0.28648 0.3279615 -0.06518942 0.9424392 0.7180505 -0.2043551 0.6653138 0.5959811 0.799606 0.07373464 0.8239771 0.5489722 0.1403254 0.7245603 -0.07205617 0.6854344 0.7421342 0.106054 0.6618078 0.1010786 0.1267756 0.986768 0.2564235 0.3215213 0.9115213 0.8591758 0.5086935 0.05520915 0.6171365 0.7738851 0.1422823 0.3308008 0.3978522 0.8557363 0.3930571 0.4800064 0.7842831 0.4414338 0.5535624 0.7061904 0.5157759 0.6397453 0.5698256 0.5623433 0.6990685 0.4416711 0.5930815 0.7437248 0.3084281 0.0597251 0.780394 0.6224292 0.1772266 0.8360201 0.519289 0.2556596 0.8738573 0.4135357 0.3155125 0.9043899 0.2872818 -0.1365439 0.3052249 0.9424402 0.3512436 0.9258561 0.1393499 0.3047372 0.950835 0.05520975 -0.3726362 0.6491377 0.663146 -0.2212328 0.7109725 0.6675134 -0.07318437 0.7389549 0.6697685 0.6241793 0.7179954 0.3080306 -0.02810823 0.1526575 0.9878795 0.6557718 0.7389068 0.1548557 0.6469364 0.7589708 0.07373327 -0.03103804 0.400107 0.9159428 0.1676123 0.4786352 0.8618668 0.295338 0.5309492 0.7942723 0.4087814 0.5841479 0.7011911 0.5035969 0.6402618 0.5800474 0.5721451 0.6852495 0.4506477 0.5851764 0.1764013 0.7914866 0.6604727 0.2685412 0.7011858 0.7340916 0.3495122 0.5821948 0.7940633 0.4082934 0.4502887 0.8392555 0.4496132 0.3057748 0.142556 -0.06137448 0.9878821 0.3959227 -0.1202142 0.9103811 0.8665463 0.4741849 0.1557116 0.4924582 0.04867815 0.8689739 0.9106435 0.05615603 0.4093592 0.9526748 0.106297 0.2848014 0.2671614 -0.2010272 0.9424505 0.5582836 -0.4956586 0.6653136 0.8839036 0.4618199 0.07373487 0.9805687 0.1370904 0.1403254 0.6215329 -0.3792983 0.6854411 0.7146602 -0.2264499 0.6618015 0.7741168 -0.1153927 0.622437 0.8507541 -0.01358103 0.5253885 0.4706702 0.2149176 0.8557336 0.5624074 0.2619156 0.7842819 0.6379113 0.3072057 0.7061827 0.7373898 0.3550983 0.5745969 0.8104403 0.3902809 0.4368839 0.8570507 0.4127162 0.3084308 0.8918038 0.4294673 0.1422808 0.1460938 0.07034593 0.9867665 0.3705354 0.1784161 0.9115214 0.9948061 0.08551496 0.05520933 0.6135876 0.6744733 0.4106047 0.6766743 0.6779256 0.2872783 0.00939995 0.3342482 0.9424383 0.7181906 0.68175 0.1393531 0.6871189 0.7244444 0.05520999 -0.05407994 0.7465294 0.663151 0.1091369 0.7365523 0.6675177 0.2546501 0.6975409 0.6697687 0.3924144 0.677188 0.6224368 0.5226408 0.6726424 0.523831 0.358693 0.3585099 0.8618643 0.4964641 0.3502137 0.7942756 0.621769 0.3489267 0.7011802 0.7315411 0.3583239 0.5800446 0.8128131 0.3691275 0.4506438 0.8739027 0.3760513 0.3080251 0.04089593 0.149728 0.9878811 0.9114354 0.381189 0.1548561 0.9121829 0.4030951 0.07373392 0.1456077 0.3739534 0.9159462 0.8113616 -0.006378531 0.5845099 0.8933656 0.02206552 0.4487887 0.9508396 0.03961318 0.3071398 0.1018124 -0.1171637 0.9878801 0.2934443 -0.2737288 0.9159492 0.9864731 0.05124175 0.1557091 0.9967463 0.03256362 0.07373356 0.4718872 -0.1627892 0.8665 0.6037642 -0.09494566 0.7914886 0.7142118 -0.0471217 0.6983418 0.2751592 -0.6960771 0.6631472 0.4093548 -0.6216773 0.6677919 0.5362473 -0.521293 0.6638467 0.6509482 -0.4368546 0.6208256 0.7593204 -0.3792024 0.5288081 0.8460153 -0.3430938 0.4080991 0.9043373 -0.3163899 0.2864813 0.1534833 -0.2970477 0.9424466 0.9429474 -0.301925 0.1403266 0.8184411 0 0.5745904 0.8995195 0 0.4368807 0.9512485 0 0.3084256 0.9898266 0 0.1422801 0.1621468 0 0.9867667 0.411249 0 0.9115231 0.9333976 -0.3545714 0.0552091 0.5328053 0 0.846238 0.6087679 0 0.7933484 0.7080218 0 0.7061907 0.9428659 0.3026303 0.1393515 0.9333976 0.3545714 0.0552091 0.2751592 0.6960771 0.6631472 0.4093548 0.6216773 0.6677919 0.5362473 0.521293 0.6638467 0.6473785 0.4398462 0.6224441 0.7627339 0.3792611 0.5238302 0.8454695 0.3414472 0.4106034 0.903804 0.317189 0.2872799 0.1534789 0.2970392 0.9424501 0.7115879 0.04458868 0.7011808 0.814562 0.005432426 0.5800512 0.8924759 -0.02008169 0.450648 0.9505206 -0.04034638 0.3080303 0.1018124 0.1171637 0.9878801 0.9865676 -0.05200487 0.154855 0.9967463 -0.03256362 0.07373356 0.2934443 0.2737288 0.9159492 0.4718872 0.1627892 0.8665 0.6037642 0.09494566 0.7914886 0.8747975 -0.3758113 0.3057702 0.04089593 -0.149728 0.9878811 0.1456077 -0.3739534 0.9159462 0.9110244 -0.381824 0.1557082 0.9121829 -0.4030951 0.07373392 0.3545141 -0.3514011 0.8665086 0.5027731 -0.347522 0.7914845 0.623019 -0.3523747 0.6983405 0.7282428 -0.357804 0.5844987 0.8143202 -0.3662335 0.4502841 0.2685381 -0.6999266 0.6618082 0.3969342 -0.6760333 0.6208239 0.5195875 -0.6711148 0.5288043 0.6116965 -0.6769466 0.4093541 0.6765269 -0.6798535 0.2830383 0.009399771 -0.3342115 0.9424514 -0.05407994 -0.7465294 0.663151 0.7173326 -0.6821435 0.1418246 0.09543234 -0.7290336 0.6777926 0.8583683 -0.4114979 0.3063879 0.1460938 -0.07034593 0.9867665 0.3705354 -0.1784161 0.9115214 0.6871189 -0.7244444 0.05520999 0.8922249 -0.4279078 0.1443247 0.4516872 -0.2175118 0.8652557 0.5693992 -0.2742162 0.7749774 0.6379113 -0.3072057 0.7061827 0.7373898 -0.3550983 0.5745969 0.8104403 -0.3902809 0.4368839 0.7095115 0.225232 0.6677306 0.7741168 0.1153927 0.622437 0.8517559 0.01074266 0.5238288 0.9098924 -0.05917626 0.4106021 0.9519272 -0.1063292 0.2872781 0.2671691 0.2010329 0.9424471 0.9808009 -0.1364216 0.1393514 0.9948061 -0.08551496 0.05520933 0.5499266 0.5077489 0.663153 0.6348558 0.3713244 0.6775519 0.142556 0.06137448 0.9878821 0.8662993 -0.4749157 0.1548565 0.8839036 -0.4618199 0.07373487 0.3831684 0.1192995 0.915942 0.5039353 -0.05688804 0.861866 0.5833535 -0.169781 0.7942752 0.6604727 -0.2685412 0.7011858 0.7362585 -0.348505 0.5800584 0.7953729 -0.4053316 0.4506533 0.8388761 -0.4487822 0.3080284 0.4084364 -0.5877969 0.698337 0.5008801 -0.6383384 0.5845026 0.574275 -0.6846925 0.4487811 0.6238109 -0.7186949 0.3071445 -0.02810823 -0.1526575 0.9878795 -0.02908468 -0.4127401 0.9103844 0.655127 -0.7392992 0.1557094 0.6469364 -0.7589708 0.07373327 0.1570528 -0.4692661 0.8689786 0.3021737 -0.5312532 0.7914931 0.3164535 -0.9043143 0.2864837 -0.1365439 -0.3052249 0.9424402 -0.3589978 -0.6545767 0.6653195 0.3518596 -0.9254743 0.1403288 -0.2314619 -0.690357 0.6854434 -0.06173962 -0.7471324 0.6618016 0.06430333 -0.7813148 0.6208158 0.1769208 -0.8300964 0.5288092 0.2592316 -0.8753567 0.4081051 0.3804863 -0.4900206 0.7842895 0.4414338 -0.5535624 0.7061904 0.5102906 -0.6398776 0.5745958 0.5608342 -0.7032707 0.4368928 0.5930815 -0.7437248 0.3084281 0.6171554 -0.7738706 0.1422796 0.1011088 -0.1267752 0.986765 0.2563951 -0.3215238 0.9115284 0.3047372 -0.950835 0.05520975 0.3142602 -0.4110378 0.8557387 0.7957317 -0.4475057 0.4081051 0.8115078 -0.5088481 0.2872781 0.3279615 0.06518942 0.9424392 0.8244809 -0.5484637 0.1393514 0.8591758 -0.5086935 0.05520915 0.7157707 0.2188544 0.6631554 0.7412797 0.06753885 0.6677896 0.7419123 -0.09421157 0.6638452 0.7475324 -0.2318834 0.622435 0.7724103 -0.3568609 0.525388 0.4214984 -0.2674383 0.8664965 0.4507037 -0.4128298 0.7914782 0.4785414 -0.5285319 0.7011792 0.5097432 -0.6334098 0.5821974 0.539736 -0.7122319 0.4487882 0.5610877 -0.7683103 0.308026 0.1550988 -0.006531059 0.9878774 0.5744404 -0.8037648 0.1548565 0.5959811 -0.799606 0.07373464 0.3969669 -0.05874997 0.9159508 0.2203204 -0.8660525 0.4487896 0.2501928 -0.9181874 0.3071408 -0.09155827 -0.1253128 0.9878836 0.2694834 -0.9503335 0.1557083 0.2535557 -0.9645065 0.07373499 -0.2053017 -0.3592398 0.9103834 -0.06207567 -0.4909595 0.868968 0.04174989 -0.609769 0.7914789 0.1129518 -0.7067959 0.698342 0.1742935 -0.7924541 0.5844982 -0.508091 -0.5215502 0.6854407 -0.3797783 -0.6463618 0.6618044 -0.2810493 -0.7318452 0.6208171 -0.2007258 -0.8246638 0.5288091 -0.1462487 -0.9011448 0.4081047 -0.1072431 -0.9520652 0.2864802 -0.2554488 -0.2157428 0.9424442 -0.6074763 -0.433977 0.6653094 -0.08450675 -0.9864924 0.1403258 0.1821085 -0.7979266 0.5745865 0.200145 -0.8769696 0.4368826 0.2116478 -0.9274053 0.308423 0.2202554 -0.96501 0.1422795 0.03607326 -0.1580876 0.986766 0.09149748 -0.4009347 0.911526 -0.1379748 -0.9888958 0.0552082 0.1048024 -0.506708 0.855724 0.1301965 -0.6065765 0.784292 0.1575397 -0.6902814 0.7061819 0.7398474 -0.113379 0.6631525 0.6971811 -0.2607562 0.667791 0.6275417 -0.4067943 0.6638599 0.5728801 -0.5332659 0.6224436 0.5410789 -0.656656 0.5253919 0.5227606 -0.7484488 0.4081005 0.5103462 -0.810566 0.2872796 0.3237526 -0.08353227 0.9424471 0.50485 -0.8518849 0.139351 0.5533751 -0.8311004 0.05520927 0.1844294 -0.791859 0.58219 0.1772576 -0.8758808 0.4487901 0.1721575 -0.9356813 0.3079975 0.1368792 -0.07318538 0.9878806 0.1688016 -0.9734095 0.1548544 0.1900095 -0.9790097 0.07373321 0.3321727 -0.2251718 0.9159471 0.2637172 -0.4238214 0.8665038 0.2269394 -0.5675012 0.7914803 0.201825 -0.6838184 0.701184 -0.1695309 -0.9731469 0.1557059 -0.3408384 -0.2345706 0.9103878 -0.2689676 -0.4153692 0.8689792 -0.2269394 -0.5675012 0.7914803 -0.2048741 -0.6858232 0.6983361 -0.1867787 -0.7895978 0.5845075 -0.1772576 -0.8758808 0.4487901 -0.172953 -0.9358143 0.3071466 -0.1368792 -0.07318538 0.9878806 -0.5707672 -0.5374099 0.6208184 -0.5386682 -0.6558934 0.5288105 -0.5227606 -0.7484488 0.4081005 -0.5111078 -0.810991 0.2847151 -0.3237433 -0.08352988 0.9424507 -0.7356052 -0.1274178 0.6653194 -0.1900095 -0.9790097 0.07373321 -0.5053987 -0.8511512 0.1418229 -0.6840687 -0.2494376 0.6854422 -0.6226195 -0.4175619 0.661806 -0.2101836 -0.9284152 0.3063791 -0.03607326 -0.1580876 0.986766 -0.09149748 -0.4009347 0.911526 -0.5533751 -0.8311004 0.05520927 -0.2186385 -0.9650739 0.1443247 -0.1254047 -0.5019849 0.8557366 -0.1458528 -0.6030049 0.7842909 -0.1575397 -0.6902814 0.7061819 -0.1821085 -0.7979266 0.5745865 -0.200145 -0.8769696 0.4368826 0.3865587 -0.6340101 0.6697788 0.2847704 -0.7290316 0.6224297 0.2025563 -0.8264003 0.5253889 0.1462487 -0.9011448 0.4081047 0.1081309 -0.9517233 0.287281 0.2554488 -0.2157428 0.9424442 0.08521014 -0.98657 0.1393516 0.1379748 -0.9888958 0.0552082 0.6173809 -0.4231541 0.6631603 0.507804 -0.5445793 0.6675094 -0.25084 -0.917722 0.308003 0.09155827 -0.1253128 0.9878836 -0.2702502 -0.950255 0.1548559 -0.2535557 -0.9645065 0.07373499 0.2015797 -0.3470041 0.9159442 0.05664378 -0.503965 0.8618647 -0.03570783 -0.6065143 0.7942703 -0.1148433 -0.7036785 0.701176 -0.1773781 -0.7934712 0.5821861 -0.2203204 -0.8660525 0.4487896 -0.4507037 -0.4128298 0.7914782 -0.482173 -0.5289894 0.6983405 -0.5108946 -0.6303475 0.5845074 -0.539736 -0.7122319 0.4487882 -0.5618551 -0.7681027 0.3071434 -0.1550988 -0.006531059 0.9878774 -0.5749856 -0.8032098 0.15571 -0.5959811 -0.799606 0.07373464 -0.4088652 -0.06344932 0.9103865 -0.4225664 -0.25755 0.8689681 -0.7957317 -0.4475057 0.4081051 -0.8112204 -0.5097557 0.28648 -0.3279249 0.06518822 0.9424521 -0.7180505 0.2043551 0.6653138 -0.8239771 -0.5489722 0.1403254 -0.7245603 0.07205617 0.6854344 -0.7421342 -0.106054 0.6618078 -0.7474127 -0.2365535 0.6208195 -0.7699142 -0.3571997 0.5288106 -0.3308008 -0.3978522 0.8557363 -0.3930571 -0.4800064 0.7842831 -0.4414338 -0.5535624 0.7061904 -0.5102906 -0.6398776 0.5745958 -0.5608342 -0.7032707 0.4368928 -0.5930815 -0.7437248 0.3084281 -0.6171365 -0.7738851 0.1422823 -0.1011088 -0.1267752 0.986765 -0.2564235 -0.3215213 0.9115213 -0.8591758 -0.5086935 0.05520915 -0.2592031 -0.8753636 0.4081083 -0.3155125 -0.9043899 0.2872818 0.1365439 -0.3052249 0.9424402 -0.3512436 -0.9258561 0.1393499 -0.3047372 -0.950835 0.05520975 0.3726362 -0.6491377 0.663146 0.2212328 -0.7109725 0.6675134 0.07318437 -0.7389549 0.6697685 -0.0597251 -0.780394 0.6224292 -0.1760365 -0.83245 0.5253933 -0.1676123 -0.4786352 0.8618668 -0.295338 -0.5309492 0.7942723 -0.4087814 -0.5841479 0.7011911 -0.5040925 -0.637921 0.5821922 -0.5742545 -0.6847045 0.4487889 -0.6241793 -0.7179954 0.3080306 0.02810823 -0.1526575 0.9878795 -0.6557718 -0.7389068 0.1548557 -0.6469364 -0.7589708 0.07373327 0.03103804 -0.400107 0.9159428 -0.7337979 -0.3462681 0.5844991 -0.7953159 -0.4075006 0.4487939 -0.8388761 -0.4487822 0.3080284 -0.142556 0.06137448 0.9878821 -0.3959227 0.1202142 0.9103811 -0.8662993 -0.4749157 0.1548565 -0.8839036 -0.4618199 0.07373487 -0.4924582 -0.04867815 0.8689739 -0.5851764 -0.1764013 0.7914866 -0.6639418 -0.2674078 0.6983368 -0.9808009 -0.1364216 0.1393514 -0.5582836 0.4956586 0.6653136 -0.6215329 0.3792983 0.6854411 -0.7146602 0.2264499 0.6618015 -0.7760362 0.11115 0.6208168 -0.8486527 0.01220774 0.5288096 -0.9110953 -0.05792576 0.4081053 -0.9519242 -0.1063594 0.2872772 -0.2671614 0.2010272 0.9424505 -0.6379113 -0.3072057 0.7061827 -0.7373898 -0.3550983 0.5745969 -0.8104403 -0.3902809 0.4368839 -0.8570399 -0.4127416 0.3084269 -0.8918038 -0.4294673 0.1422808 -0.1460938 -0.07034593 0.9867665 -0.3705354 -0.1784161 0.9115214 -0.9948061 -0.08551496 0.05520933 -0.4706702 -0.2149176 0.8557336 -0.5624074 -0.2619156 0.7842819 -0.00939995 -0.3342482 0.9424383 -0.7181906 -0.68175 0.1393531 -0.6871189 -0.7244444 0.05520999 0.05407994 -0.7465294 0.663151 -0.1091369 -0.7365523 0.6675177 -0.2546501 -0.6975409 0.6697687 -0.3924144 -0.677188 0.6224368 -0.5198053 -0.6736227 0.5253903 -0.6133557 -0.6761959 0.4081103 -0.6766743 -0.6779256 0.2872783 -0.621769 -0.3489267 0.7011802 -0.7309693 -0.3560084 0.5821874 -0.8144721 -0.3677287 0.4487883 -0.8739027 -0.3760513 0.3080251 -0.04089593 -0.149728 0.9878811 -0.9114354 -0.381189 0.1548561 -0.9121829 -0.4030951 0.07373392 -0.1456077 -0.3739534 0.9159462 -0.358693 -0.3585099 0.8618643 -0.4964641 -0.3502137 0.7942756 -0.9505296 -0.04034674 0.3080027 -0.9865676 -0.05200487 0.154855 -0.1018124 0.1171637 0.9878801 -0.9967463 -0.03256362 0.07373356 -0.3045486 0.280103 0.9103804 -0.4648109 0.1697795 0.8689798 -0.6037642 0.09494566 0.7914886 -0.7142118 0.0471217 0.6983418 -0.8113616 0.006378531 0.5845099 -0.8933656 -0.02206552 0.4487887 -0.5456252 0.5140987 0.6618124 -0.6509482 0.4368546 0.6208256 -0.7593204 0.3792024 0.5288081 -0.8460153 0.3430938 0.4080991 -0.903804 0.317189 0.2872799 -0.9428659 0.3026303 0.1393515 -0.1534789 0.2970392 0.9424501 -0.2879158 0.6888127 0.6653131 -0.3954145 0.6114031 0.6854441 -0.9519059 0.001648008 0.3063861 -0.989529 0.001556456 0.144326 -0.1621468 0 0.9867667 -0.411249 0 0.9115231 -0.9333976 0.3545714 0.0552091 -0.5173053 0.01055973 0.8557358 -0.6203405 0.008026599 0.7842916 -0.8174007 0.009430468 0.5759924 -0.8971688 0.003784358 0.4416718 -0.7140334 0.00601232 0.7000859 -0.09775251 0.02270615 0.9949517 -0.220682 0.08575803 0.9715684 -0.9333976 -0.3545714 0.0552091 0.04388642 -0.09024488 0.9949522 -0.0782203 0.06286925 0.9949518 0.2360333 -0.0184639 0.9715696 0.09793555 -0.02194315 0.9949509 -0.1326967 -0.1960542 0.9715732 0.06375372 -0.07992869 0.9947598 -0.07870864 -0.06225883 0.9949517 -0.2046306 -0.1190245 0.9715759 -0.02273648 -0.0996744 0.9947604 0.2046298 -0.1190546 0.9715722 -0.1615981 0.1730122 0.9715723 -0.09793555 -0.02194315 0.9949509 0.03448629 -0.2342324 0.9715688 3.66229e-4 -0.1003467 0.9949525 -0.2206529 -0.08575856 0.9715749 -0.09775251 -0.02270615 0.9949517 -0.06375372 -0.07992869 0.9947598 -0.0705294 0.2259932 0.9715723 -0.1022379 0 0.99476 0.03448659 0.2342036 0.9715757 -0.09213608 0.0443437 0.9947586 -0.1326967 0.1960542 0.9715732 -0.04388642 0.09024488 0.9949522 0.04318445 0.09058058 0.9949524 -3.66229e-4 -0.1003467 0.9949525 0.04388642 0.09024488 0.9949522 0.1327267 0.1960534 0.9715692 -0.0705294 -0.2259932 0.9715723 -0.04318445 -0.09058058 0.9949524 0.2360333 0.0184639 0.9715696 0.02273643 0.09970462 0.9947573 -0.02273643 0.09970462 0.9947573 -0.2360333 0.0184639 0.9715696 -0.06375372 0.07992869 0.9947598 0.07870864 0.06225883 0.9949517 -0.1615981 -0.1730122 0.9715723 0.0921058 0.04434382 0.9947614 -0.03448629 0.2342324 0.9715688 0.09775251 -0.02270615 0.9949517 0.220682 -0.08575803 0.9715684 -0.2046298 0.1190546 0.9715722 -0.09790533 0.02194321 0.9949538 0.0705294 -0.2259932 0.9715723 0.1022681 0 0.9947569 0.0782203 -0.06286925 0.9949518 0.1615981 0.1730122 0.9715723 0.0782203 0.06286925 0.9949518 -0.03448659 -0.2342036 0.9715757 -3.66229e-4 0.1003467 0.9949525 -0.04318445 0.09058058 0.9949524 0.0705294 0.2259932 0.9715723 0.220682 0.08575803 0.9715684 0.02273643 -0.09970462 0.9947573 0.1326967 -0.1960542 0.9715732 -0.04388642 -0.09024488 0.9949522 0.07870864 -0.06225883 0.9949517 -0.0921058 -0.04434382 0.9947614 0.09775251 0.02270615 0.9949517 -0.2360333 -0.0184639 0.9715696 0.2046298 0.1190546 0.9715722 3.66229e-4 0.1003467 0.9949525 0.06375372 0.07992869 0.9947598 -0.0782203 -0.06286925 0.9949518 0.09793555 0.02194315 0.9949509 0.1615981 -0.1730122 0.9715723 -0.07870864 0.06225883 0.9949517 0.04318445 -0.09058058 0.9949524 0.09213608 -0.0443437 0.9947586 -0.1493295 0.1403569 0.9787751 0.2313341 0.1113944 0.9664761 0.1493295 0.1403569 0.9787751 0.01663285 -0.2042636 0.9787746 -0.00476098 -0.1001945 0.9949566 -0.08130329 0.05871903 0.9949582 0.20283 0.02920675 0.9787784 -0.05713117 -0.2503457 0.9664694 -0.09872978 -0.01760959 0.9949585 0.09659349 0.02694851 0.9949591 -0.1036124 -0.1767972 0.9787785 -0.1954438 0.06164836 0.9787755 -0.1954438 -0.06164836 0.9787755 0.04776257 0.0882005 0.994957 -0.03915607 -0.09235107 0.9949563 0.07364261 0.1912327 0.9787783 0.03915607 -0.09235107 0.9949563 0.1601018 0.2007529 0.9664708 0.1036124 -0.1767972 0.9787785 -0.09872978 0.01760959 0.9949585 0.1700529 0.1143248 0.9787808 0.05713117 -0.2503457 0.9664694 0.07535195 0.0661962 0.9949574 -0.01660233 -0.2042637 0.9787752 0.00476098 0.1001945 0.9949566 0.00476098 -0.1001945 0.9949566 -0.01660233 0.2042637 0.9787752 0.07535195 -0.0661962 0.9949574 0.05713117 0.2503457 0.9664694 0.1700529 -0.1143248 0.9787808 0.1036124 0.1767972 0.9787785 0.1601018 -0.2007529 0.9664708 0.03915607 0.09235107 0.9949563 0.07364261 -0.1912327 0.9787783 -0.03915607 0.09235107 0.9949563 0.04779303 -0.08820039 0.9949556 -0.1036124 0.1767972 0.9787785 0.09662371 -0.02694845 0.9949561 -0.05713117 0.2503457 0.9664694 0.20283 -0.02920675 0.9787784 -0.08130329 -0.05871903 0.9949582 0.01660233 0.2042637 0.9787752 0.2313341 -0.1113944 0.9664761 -0.1493295 -0.1403569 0.9787751 -0.00476098 0.1001945 0.9949566 0.1493295 -0.1403569 0.9787751 -0.2313341 -0.1113944 0.9664761 -0.07535195 0.0661962 0.9949574 0.08130329 -0.05871903 0.9949582 -0.20283 -0.02920675 0.9787784 -0.1700529 0.1143248 0.9787808 0.09872978 0.01760959 0.9949585 -0.09662371 -0.02694845 0.9949561 -0.1601018 0.2007529 0.9664708 0.1954438 0.06164836 0.9787755 -0.04776257 -0.0882005 0.994957 -0.07364261 0.1912327 0.9787783 0.256785 0 0.9664686 -0.07361221 -0.1912331 0.9787805 -0.04779303 0.08820039 0.9949556 0.1954438 -0.06164836 0.9787755 -0.1600721 -0.2007539 0.9664755 -0.09662371 0.02694845 0.9949561 0.09872978 -0.01760959 0.9949585 -0.1700529 -0.1143248 0.9787808 -0.20283 0.02920675 0.9787784 -0.256785 0 0.9664686 0.08130329 0.05871903 0.9949582 -0.07535195 -0.0661962 0.9949574 -0.2313341 0.1113944 0.9664761 0.4338842 -0.9009687 5.24891e-7 -1.21099e-7 1 0 2.3653e-7 -1 0 -0.4338834 -0.9009692 5.2489e-7 0.4338834 0.9009692 5.2489e-7 -0.7818319 -0.6234894 0 0.7818319 0.6234894 0 -0.9749281 -0.2225202 2.62444e-7 0.9749279 0.2225211 0 -0.9749279 0.2225211 2.62445e-7 0.9749279 -0.2225211 0 -0.7818319 0.6234894 5.2489e-7 0.7818319 -0.6234894 5.2489e-7 -0.4338834 0.9009692 5.2489e-7 0.6525359 0.4471096 -0.6117924 0.7144243 0.04077363 -0.6985238 0.5994818 0.09152603 -0.7951381 0.7574163 0.3894508 -0.5240693 0.813043 0.003601312 -0.5821925 0.8419654 0.3479806 -0.4123152 0.8925853 -0.02331638 -0.4502754 0.9045135 0.3189815 -0.2830305 0.9512246 -0.04092633 -0.3057726 0.9864731 -0.05124175 -0.1557091 0.2751592 0.6960771 -0.6631472 0.2934443 0.2737288 -0.9159492 0.6559213 0.7548039 0.006195366 0.9967463 -0.03256362 -0.07373356 0.9422732 0.303328 -0.1418216 0.4093548 0.6216773 -0.6677919 0.4718872 0.1627892 -0.8665 0.5306315 0.5253517 -0.6651586 0.9114354 -0.381189 -0.1548561 0.8748281 -0.3750179 -0.3066552 0.1456077 -0.3739534 -0.9159462 0.2634429 -0.9646552 0.006195366 0.9121829 -0.4030951 -0.07373392 0.3545141 -0.3514011 -0.8665086 0.5027731 -0.347522 -0.7914845 0.623019 -0.3523747 -0.6983405 0.7282428 -0.357804 -0.5844987 0.8143202 -0.3662335 -0.4502841 0.4055753 -0.6736903 -0.6177784 0.2668008 -0.6929741 -0.6697794 0.5195875 -0.6711148 -0.5288043 0.6116965 -0.6769466 -0.4093541 0.6762802 -0.6790269 -0.2856009 0.7181906 -0.68175 -0.1393531 -0.05407994 -0.7465294 -0.663151 0.02749776 -0.978293 0.2053942 0.6871189 -0.7244444 -0.05520999 0.09543234 -0.7290336 -0.6777926 0.8590343 -0.412594 -0.3030288 0.8064376 -0.3893325 -0.4450605 0.8908569 -0.4307487 -0.1443255 0.3705354 -0.1784161 -0.9115214 0.540037 -0.260054 0.8004573 0.2040833 -0.9784526 -0.03131288 0.4516872 -0.2175118 -0.8652557 0.5519417 -0.2657926 -0.790389 0.6537851 -0.3215821 -0.6849453 0.7323677 -0.3631472 -0.5759876 0.70293 0.2222445 -0.6756454 0.6348558 0.3713244 -0.6775519 0.7821391 0.1100512 -0.6133084 0.8513847 0.0222482 -0.5240699 0.9080557 -0.05371302 -0.4153911 0.9535771 -0.1069703 -0.2815105 0.9808023 -0.1348347 -0.1408776 0.5499266 0.5077489 -0.663153 0.7820198 0.5884376 0.2053931 0.9948061 -0.08551496 -0.05520933 0.8386606 -0.4501239 -0.3066543 0.7940633 -0.4082934 -0.4502887 0.8662993 -0.4749157 -0.1548565 0.3831684 0.1192995 -0.915942 0.9184634 0.3954626 0.005859553 0.8839036 -0.4618199 -0.07373487 0.5039353 -0.05688804 -0.861866 0.5833535 -0.169781 -0.7942752 0.6604727 -0.2685412 -0.7011858 0.7340916 -0.3495122 -0.5821948 0.3021737 -0.5312532 -0.7914931 0.1570528 -0.4692661 -0.8689786 0.4087814 -0.5841479 -0.7011911 0.5040925 -0.637921 -0.5821922 0.5747675 -0.6832938 -0.4502798 0.6251022 -0.7181564 -0.3057757 0.655127 -0.7392992 -0.1557094 -0.02908468 -0.4127401 -0.9103844 -0.1811593 -0.9834364 0.005859553 0.6469364 -0.7589708 -0.07373327 0.2589254 -0.8734003 -0.4124678 0.1760365 -0.83245 -0.5253933 0.317433 -0.9057875 -0.2806876 0.3503288 -0.9258274 -0.1418222 -0.3589978 -0.6545767 -0.6653195 -0.3996757 -0.8933496 0.2053923 0.3047372 -0.950835 -0.05520975 -0.2314619 -0.690357 -0.6854434 -0.06027644 -0.7401036 -0.6697861 0.06854659 -0.78206 -0.619422 -0.2406426 -0.9701086 -0.03131252 0.6181992 -0.7726576 -0.1443258 0.3125787 -0.3919594 -0.8652529 0.2564235 -0.3215213 -0.9115213 0.3819468 -0.4789671 -0.7903842 0.4506187 -0.5650359 -0.691142 0.508936 -0.6452035 -0.5698215 0.5530382 -0.7043218 -0.4450613 0.5934159 -0.7456763 -0.3030254 0.3736143 -0.4684981 0.800576 0.7759566 -0.3558261 -0.5208447 0.7508364 -0.2410416 -0.6149339 0.7966709 -0.443107 -0.4110619 0.8115078 -0.5088481 -0.2872781 0.8244809 -0.5484637 -0.1393514 0.7180505 0.2043551 -0.6653138 0.9598483 0.1908344 0.2056055 0.8591758 -0.5086935 -0.05520915 0.7256762 0.0619837 -0.6852388 0.7294708 -0.09784466 -0.6769778 0.4088652 -0.06344932 -0.9103865 0.9990931 -0.0421769 0.005859553 0.5959811 -0.799606 -0.07373464 0.5744404 -0.8037648 -0.1548565 0.4304385 -0.260021 -0.8643563 0.4465537 -0.4048648 -0.7979187 0.4773262 -0.533116 -0.6985322 0.5097432 -0.6334098 -0.5821974 0.539736 -0.7122319 -0.4487882 0.5610877 -0.7683103 -0.308026 0.1742935 -0.7924541 -0.5844982 0.1129518 -0.7067959 -0.698342 0.2213574 -0.865012 -0.4502835 0.2515712 -0.9182671 -0.3057736 0.2694834 -0.9503335 -0.1557083 -0.2053017 -0.3592398 -0.9103834 -0.5899276 -0.8074348 0.005859553 0.2535557 -0.9645065 -0.07373499 -0.06207567 -0.4909595 -0.868968 0.04174989 -0.609769 -0.7914789 -0.08606475 -0.9861435 -0.1418237 -0.1070004 -0.953817 -0.2806852 -0.6074763 -0.433977 -0.6653094 -0.7476637 -0.631446 0.205609 -0.1379748 -0.9888958 -0.0552082 -0.508091 -0.5215502 -0.6854407 -0.3754467 -0.6406583 -0.6697736 -0.2776054 -0.7408306 -0.6116415 -0.206282 -0.8212216 -0.5320178 -0.1456386 -0.8992542 -0.4124698 0.168038 -0.7089579 -0.6849395 0.1257092 -0.5874674 -0.7994244 0.1861063 -0.7925235 -0.5807505 0.1969124 -0.876004 -0.4402757 0.2111008 -0.9293077 -0.3030245 0.2217206 -0.9643705 -0.1443244 0.09149748 -0.4009347 -0.911526 0.1333698 -0.5843552 0.8004633 -0.6377246 -0.7696277 -0.03131246 0.1048024 -0.506708 -0.855724 0.50485 -0.8518849 -0.139351 0.5103462 -0.810566 -0.2872796 0.7398474 -0.113379 -0.6631525 0.9476491 -0.2444886 0.2053936 0.5533751 -0.8311004 -0.05520927 0.6937955 -0.2703095 -0.6675184 0.6168786 -0.4002249 -0.6777027 0.5686987 -0.5412007 -0.619422 0.5410789 -0.656656 -0.5253919 0.5227606 -0.7484488 -0.4081005 0.201825 -0.6838184 -0.701184 0.2309707 -0.5619537 -0.7942674 0.1844294 -0.791859 -0.58219 0.1772576 -0.8758808 -0.4487901 0.1721559 -0.9356725 -0.3080251 0.1688016 -0.9734095 -0.1548544 0.3321727 -0.2251718 -0.9159471 0.8818516 -0.4714908 0.005859673 0.1900095 -0.9790097 -0.07373321 0.2697002 -0.4294695 -0.8618688 -0.1717327 -0.9364882 -0.305774 -0.1758542 -0.8753952 -0.450287 -0.1695309 -0.9731469 -0.1557059 -0.3408384 -0.2345706 -0.9103878 -0.8818516 -0.4714908 0.005859673 -0.1900095 -0.9790097 -0.07373321 -0.2689642 -0.4153944 -0.8689683 -0.2226353 -0.5640808 -0.7951393 -0.2017919 -0.6894252 -0.6956816 -0.1867787 -0.7895978 -0.5845075 -0.6189917 -0.4079815 -0.6711187 -0.6840687 -0.2494376 -0.6854422 -0.5697375 -0.5470615 -0.6132888 -0.5386682 -0.6558934 -0.5288105 -0.5238639 -0.7469905 -0.4093555 -0.5108634 -0.8111128 -0.2848066 -0.5041757 -0.852124 -0.1403268 -0.7356052 -0.1274178 -0.6653194 -0.9476491 -0.2444886 0.2053936 -0.5533751 -0.8311004 -0.05520927 -0.200145 -0.8769696 -0.4368826 -0.1821085 -0.7979266 -0.5745865 -0.2116478 -0.9274053 -0.308423 -0.2202554 -0.96501 -0.1422795 -0.09149748 -0.4009347 -0.911526 -0.1333698 -0.5843552 0.8004633 -0.9085165 -0.4166742 -0.03131234 -0.1254047 -0.5019849 -0.8557366 -0.1516193 -0.5916757 -0.79179 -0.165533 -0.695977 -0.6987237 0.507804 -0.5445793 -0.6675094 0.6173809 -0.4231541 -0.6631603 0.3865587 -0.6340101 -0.6697788 0.2847704 -0.7290316 -0.6224297 0.2025563 -0.8264003 -0.5253889 0.1462487 -0.9011448 -0.4081047 0.1081309 -0.9517233 -0.287281 0.08521014 -0.98657 -0.1393516 0.7477091 -0.6314632 0.2053911 0.1379748 -0.9888958 -0.0552082 -0.2203204 -0.8660525 -0.4487896 -0.1773781 -0.7934712 -0.5821861 -0.2508376 -0.9177134 -0.3080306 -0.2702502 -0.950255 -0.1548559 0.2015797 -0.3470041 -0.9159442 0.5899276 -0.8074348 0.005859553 -0.2535557 -0.9645065 -0.07373499 0.05664378 -0.503965 -0.8618647 -0.03570783 -0.6065143 -0.7942703 -0.1148433 -0.7036785 -0.701176 -0.5959811 -0.799606 -0.07373464 -0.5744404 -0.8037648 -0.1548565 -0.4225664 -0.25755 -0.8689681 -0.4088652 -0.06344932 -0.9103865 -0.4507037 -0.4128298 -0.7914782 -0.4785414 -0.5285319 -0.7011792 -0.5097432 -0.6334098 -0.5821974 -0.539736 -0.7122319 -0.4487882 -0.5610877 -0.7683103 -0.308026 -0.9990901 -0.04217678 0.006347835 -0.7724103 -0.3568609 -0.525388 -0.7472013 -0.2408574 -0.6194175 -0.7957317 -0.4475057 -0.4081051 -0.8115078 -0.5088481 -0.2872781 -0.8244809 -0.5484637 -0.1393514 -0.7180505 0.2043551 -0.6653138 -0.9598483 0.1908344 0.2056055 -0.8591758 -0.5086935 -0.05520915 -0.7245603 0.07205617 -0.6854344 -0.7349693 -0.1059024 -0.6697797 -0.2564235 -0.3215213 -0.9115213 -0.3737083 -0.4686231 0.800459 -0.999334 0.01873844 -0.0313121 -0.6171365 -0.7738851 -0.1422823 -0.3308008 -0.3978522 -0.8557363 -0.3809078 -0.464591 -0.7994151 -0.4506187 -0.5650359 -0.691142 -0.5157759 -0.6397453 -0.5698256 -0.5623433 -0.6990685 -0.4416711 -0.5930815 -0.7437248 -0.3084281 -0.1772266 -0.8360201 -0.519289 -0.06854659 -0.78206 -0.619422 -0.2556596 -0.8738573 -0.4135357 -0.3155125 -0.9043899 -0.2872818 -0.3512436 -0.9258561 -0.1393499 0.3589978 -0.6545767 -0.6653195 0.3996757 -0.8933496 0.2053923 -0.3047372 -0.950835 -0.05520975 0.2224213 -0.7032152 -0.6752905 0.07168835 -0.7318379 -0.6776977 -0.6557718 -0.7389068 -0.1548557 -0.6241793 -0.7179954 -0.3080306 0.02908468 -0.4127401 -0.9103844 0.181164 -0.9834316 0.006470143 -0.6469364 -0.7589708 -0.07373327 -0.1577222 -0.4775004 -0.8643594 -0.295338 -0.5309492 -0.7942723 -0.4087814 -0.5841479 -0.7011911 -0.5035969 -0.6402618 -0.5800474 -0.5721451 -0.6852495 -0.4506477 -0.6604727 -0.2685412 -0.7011858 -0.5851764 -0.1764013 -0.7914866 -0.7340916 -0.3495122 -0.5821948 -0.7940747 -0.4082836 -0.4502778 -0.8392555 -0.4496132 -0.3057748 -0.8665463 -0.4741849 -0.1557116 -0.3959227 0.1202142 -0.9103811 -0.9184634 0.3954626 0.005859553 -0.8839036 -0.4618199 -0.07373487 -0.4924582 -0.04867815 -0.8689739 -0.9533413 -0.1050451 -0.2830299 -0.9106435 -0.05615603 -0.4093592 -0.980574 -0.1355041 -0.1418215 -0.5582836 0.4956586 -0.6653136 -0.7819758 0.5884199 0.2056112 -0.9948061 -0.08551496 -0.05520933 -0.6215329 0.3792983 -0.6854411 -0.7081403 0.2234626 -0.6697775 -0.777705 0.1071549 -0.6194294 -0.8507541 0.01358103 -0.5253885 -0.5571287 -0.2503493 -0.7917911 -0.4706702 -0.2149176 -0.8557336 -0.6473427 -0.30449 -0.698737 -0.7422845 -0.3525867 -0.5698214 -0.8099786 -0.3858232 -0.4416733 -0.8569186 -0.414512 -0.3063824 -0.8908569 -0.4307487 -0.1443255 -0.3705354 -0.1784161 -0.9115214 -0.540037 -0.260054 0.8004573 -0.89223 0.4504945 -0.0313127 -0.6766743 -0.6779256 -0.2872783 -0.609495 -0.6763926 -0.4135324 -0.7181906 -0.68175 -0.1393531 0.05407994 -0.7465294 -0.663151 -0.02749776 -0.978293 0.2053942 -0.6871189 -0.7244444 -0.05520999 -0.1091369 -0.7365523 -0.6675177 -0.2546501 -0.6975409 -0.6697687 -0.3924144 -0.677188 -0.6224368 -0.5224232 -0.6763302 -0.5192798 -0.4964641 -0.3502137 -0.7942756 -0.358693 -0.3585099 -0.8618643 -0.621769 -0.3489267 -0.7011802 -0.7315411 -0.3583239 -0.5800446 -0.8128131 -0.3691275 -0.4506438 -0.8739027 -0.3760513 -0.3080251 -0.9114354 -0.381189 -0.1548561 -0.1456077 -0.3739534 -0.9159462 -0.2634434 -0.9646571 0.005859673 -0.9121829 -0.4030951 -0.07373392 -0.8933656 -0.02206552 -0.4487887 -0.8113616 0.006378531 -0.5845099 -0.9508396 -0.03961318 -0.3071398 -0.9864731 -0.05124175 -0.1557091 -0.3045486 0.280103 -0.9103804 -0.6559227 0.7548055 0.005859673 -0.9967463 -0.03256362 -0.07373356 -0.4648109 0.1697795 -0.8689798 -0.6037642 0.09494566 -0.7914886 -0.7142118 0.0471217 -0.6983418 -0.4025142 0.6177643 -0.6755366 -0.2879158 0.6888127 -0.6653131 -0.5362473 0.521293 -0.6638467 -0.6509482 0.4368546 -0.6208256 -0.7593204 0.3792024 -0.5288081 -0.8460153 0.3430938 -0.4080991 -0.9043373 0.3163899 -0.2864813 -0.9429474 0.301925 -0.1403266 -0.4492496 0.869475 0.2053974 -0.9333976 0.3545714 -0.0552091 -0.8995195 0 -0.4368807 -0.8184411 0 -0.5745904 -0.9512485 0 -0.3084256 -0.9898266 0 -0.1422801 -0.411249 0 -0.9115231 -0.5993943 0 0.8004539 -0.608401 0.7930119 -0.0313127 -0.5328053 0 -0.846238 -0.6087679 0 -0.7933484 -0.7080218 0 -0.7061907 -0.9333976 -0.3545714 -0.0552091 -0.9428659 -0.3026303 -0.1393515 -0.4093548 -0.6216773 -0.6677919 -0.2751592 -0.6960771 -0.6631472 -0.5362473 -0.521293 -0.6638467 -0.6473785 -0.4398462 -0.6224441 -0.7627339 -0.3792611 -0.5238302 -0.8454695 -0.3414472 -0.4106034 -0.903804 -0.317189 -0.2872799 -0.4492377 -0.8694825 0.205392 -0.814562 -0.005432426 -0.5800512 -0.7115879 -0.04458868 -0.7011808 -0.8924759 0.02008169 -0.450648 -0.9505206 0.04034638 -0.3080303 -0.9865676 0.05200487 -0.154855 -0.2934443 -0.2737288 -0.9159492 -0.6559227 -0.7548055 0.005859673 -0.9967463 0.03256362 -0.07373356 -0.4718872 -0.1627892 -0.8665 -0.6037625 -0.09497588 -0.7914864 -0.9110244 0.381824 -0.1557082 -0.8747975 0.3758113 -0.3057702 -0.1456077 0.3739534 -0.9159462 -0.2634434 0.9646571 0.005859673 -0.9121829 0.4030951 -0.07373392 -0.3545141 0.3514011 -0.8665086 -0.5027731 0.347522 -0.7914845 -0.621769 0.3489267 -0.7011802 -0.7309693 0.3560084 -0.5821874 -0.8143202 0.3662335 -0.4502841 -0.3924144 0.677188 -0.6224368 -0.2685381 0.6999266 -0.6618082 -0.5198053 0.6736227 -0.5253903 -0.6116965 0.6769466 -0.4093541 -0.6765269 0.6798535 -0.2830383 -0.7173326 0.6821435 -0.1418246 0.05407994 0.7465294 -0.663151 -0.02749776 0.978293 0.2053942 -0.6871189 0.7244444 -0.05520999 -0.09543234 0.7290336 -0.6777926 -0.8922249 0.4279078 -0.1443247 -0.8583683 0.4114979 -0.3063879 -0.3705354 0.1784161 -0.9115214 -0.5398848 0.2599931 0.8005799 -0.2040833 0.9784526 -0.03131288 -0.4516872 0.2175118 -0.8652557 -0.5693992 0.2742162 -0.7749774 -0.6379113 0.3072057 -0.7061827 -0.7373898 0.3550983 -0.5745969 -0.8104403 0.3902809 -0.4368839 -0.7741168 -0.1153927 -0.622437 -0.7095115 -0.225232 -0.6677306 -0.8517559 -0.01074266 -0.5238288 -0.9098924 0.05917626 -0.4106021 -0.9519272 0.1063292 -0.2872781 -0.9808009 0.1364216 -0.1393514 -0.5499266 -0.5077489 -0.663153 -0.7820198 -0.5884376 0.2053931 -0.9948061 0.08551496 -0.05520933 -0.6348558 -0.3713244 -0.6775519 -0.3831684 -0.1192995 -0.915942 -0.91846 -0.3954612 0.006469905 -0.8839036 0.4618199 -0.07373487 -0.8662993 0.4749157 -0.1548565 -0.5039353 0.05688804 -0.861866 -0.5833737 0.1697781 -0.7942611 -0.6604727 0.2685412 -0.7011858 -0.7362585 0.348505 -0.5800584 -0.7953729 0.4053316 -0.4506533 -0.8388761 0.4487822 -0.3080284 -0.5008801 0.6383384 -0.5845026 -0.4084364 0.5877969 -0.698337 -0.574275 0.6846925 -0.4487811 -0.6238109 0.7186949 -0.3071445 -0.655127 0.7392992 -0.1557094 0.02908468 0.4127401 -0.9103844 0.1811593 0.9834364 0.005859553 -0.6469364 0.7589708 -0.07373327 -0.1570528 0.4692661 -0.8689786 -0.3021737 0.5312532 -0.7914931 -0.3518596 0.9254743 -0.1403288 -0.3164535 0.9043143 -0.2864837 0.3589978 0.6545767 -0.6653195 0.3996484 0.8933264 0.2055465 -0.3047372 0.950835 -0.05520975 0.2314619 0.690357 -0.6854434 0.06173962 0.7471324 -0.6618016 -0.06430333 0.7813148 -0.6208158 -0.1769208 0.8300964 -0.5288092 -0.2592316 0.8753567 -0.4081051 -0.4414338 0.5535624 -0.7061904 -0.3804863 0.4900206 -0.7842895 -0.5102906 0.6398776 -0.5745958 -0.5608342 0.7032707 -0.4368928 -0.5930815 0.7437248 -0.3084281 -0.6171365 0.7738851 -0.1422823 -0.2563951 0.3215238 -0.9115284 -0.3737083 0.4686231 0.800459 0.2406426 0.9701086 -0.03131252 -0.3142602 0.4110378 -0.8557387 -0.8115078 0.5088481 -0.2872781 -0.7957317 0.4475057 -0.4081051 -0.8244809 0.5484637 -0.1393514 -0.7157707 -0.2188544 -0.6631554 -0.9598483 -0.1908344 0.2056055 -0.8591758 0.5086935 -0.05520915 -0.7412797 -0.06753885 -0.6677896 -0.7419123 0.09421157 -0.6638452 -0.7475324 0.2318834 -0.622435 -0.7724103 0.3568609 -0.525388 -0.4507037 0.4128298 -0.7914782 -0.4214984 0.2674383 -0.8664965 -0.4785414 0.5285319 -0.7011792 -0.5097432 0.6334098 -0.5821974 -0.539736 0.7122319 -0.4487882 -0.5610877 0.7683103 -0.308026 -0.5744404 0.8037648 -0.1548565 -0.3969669 0.05874997 -0.9159508 -0.9990931 0.0421769 0.005859553 -0.5959811 0.799606 -0.07373464 -0.2501928 0.9181874 -0.3071408 -0.2203204 0.8660525 -0.4487896 -0.2694834 0.9503335 -0.1557083 0.2053017 0.3592398 -0.9103834 0.5899276 0.8074348 0.005859553 -0.2535557 0.9645065 -0.07373499 0.06207567 0.4909595 -0.868968 -0.04174989 0.609769 -0.7914789 -0.1129518 0.7067959 -0.698342 -0.1742935 0.7924541 -0.5844982 0.3797783 0.6463618 -0.6618044 0.508091 0.5215502 -0.6854407 0.2810493 0.7318452 -0.6208171 0.2007258 0.8246638 -0.5288091 0.1462487 0.9011448 -0.4081047 0.1072431 0.9520652 -0.2864802 0.08450675 0.9864924 -0.1403258 0.6074763 0.433977 -0.6653094 0.7476637 0.631446 0.205609 0.1379748 0.9888958 -0.0552082 -0.200145 0.8769696 -0.4368826 -0.1821085 0.7979266 -0.5745865 -0.2116478 0.9274053 -0.308423 -0.2202554 0.96501 -0.1422795 -0.09149748 0.4009347 -0.911526 -0.1333396 0.5842344 0.8005565 0.6377246 0.7696277 -0.03131246 -0.1048024 0.506708 -0.855724 -0.1301965 0.6065765 -0.784292 -0.1575397 0.6902814 -0.7061819 -0.6971811 0.2607562 -0.667791 -0.7398474 0.113379 -0.6631525 -0.6275417 0.4067943 -0.6638599 -0.5728801 0.5332659 -0.6224436 -0.5410789 0.656656 -0.5253919 -0.5227606 0.7484488 -0.4081005 -0.5103462 0.810566 -0.2872796 -0.50485 0.8518849 -0.139351 -0.9476491 0.2444886 0.2053936 -0.5533751 0.8311004 -0.05520927 -0.1772576 0.8758808 -0.4487901 -0.1844294 0.791859 -0.58219 -0.1721559 0.9356725 -0.3080251 -0.1688016 0.9734095 -0.1548544 -0.3321727 0.2251718 -0.9159471 -0.8818489 0.4714893 0.006347954 -0.1900095 0.9790097 -0.07373321 -0.2637172 0.4238214 -0.8665038 -0.2269394 0.5675012 -0.7914803 -0.201825 0.6838184 -0.701184 0.1900095 0.9790097 -0.07373321 0.1695309 0.9731469 -0.1557059 0.2689642 0.4153944 -0.8689683 0.3408384 0.2345706 -0.9103878 0.2269394 0.5675012 -0.7914803 0.2048741 0.6858232 -0.6983361 0.1867787 0.7895978 -0.5845075 0.1772576 0.8758808 -0.4487901 0.172953 0.9358143 -0.3071466 0.8818516 0.4714908 0.005859673 0.5386682 0.6558934 -0.5288105 0.5707672 0.5374099 -0.6208184 0.5227606 0.7484488 -0.4081005 0.5096979 0.8112561 -0.2864819 0.5041757 0.852124 -0.1403268 0.7356052 0.1274178 -0.6653194 0.9476491 0.2444886 0.2053936 0.5533751 0.8311004 -0.05520927 0.6840687 0.2494376 -0.6854422 0.6226195 0.4175619 -0.661806 0.2202554 0.96501 -0.1422795 0.2116478 0.9274053 -0.308423 0.09149748 0.4009347 -0.911526 0.1333698 0.5843552 0.8004633 0.9085165 0.4166742 -0.03131234 0.1254047 0.5019849 -0.8557366 0.1458528 0.6030049 -0.7842909 0.1575397 0.6902814 -0.7061819 0.1821085 0.7979266 -0.5745865 0.200145 0.8769696 -0.4368826 -0.2847704 0.7290316 -0.6224297 -0.3865587 0.6340101 -0.6697788 -0.2025563 0.8264003 -0.5253889 -0.1462487 0.9011448 -0.4081047 -0.1081309 0.9517233 -0.287281 -0.08521014 0.98657 -0.1393516 -0.6173809 0.4231541 -0.6631603 -0.7477091 0.6314632 0.2053911 -0.1379748 0.9888958 -0.0552082 -0.507804 0.5445793 -0.6675094 0.2702502 0.950255 -0.1548559 0.2508376 0.9177134 -0.3080306 -0.2015797 0.3470041 -0.9159442 -0.5899264 0.8074332 0.006195247 0.2535557 0.9645065 -0.07373499 -0.05664378 0.503965 -0.8618647 0.03570783 0.6065143 -0.7942703 0.1148433 0.7036785 -0.701176 0.1773781 0.7934712 -0.5821861 0.2203204 0.8660525 -0.4487896 0.482173 0.5289894 -0.6983405 0.4507037 0.4128298 -0.7914782 0.5108946 0.6303475 -0.5845074 0.539736 0.7122319 -0.4487882 0.5618551 0.7681027 -0.3071434 0.5749856 0.8032098 -0.15571 0.4088652 0.06344932 -0.9103865 0.9990901 0.04217678 0.006347835 0.5959811 0.799606 -0.07373464 0.4225664 0.25755 -0.8689681 0.8112204 0.5097557 -0.28648 0.7957317 0.4475057 -0.4081051 0.8239771 0.5489722 -0.1403254 0.7180505 -0.2043551 -0.6653138 0.9598483 -0.1908344 0.2056055 0.8591758 0.5086935 -0.05520915 0.7245603 -0.07205617 -0.6854344 0.7421342 0.106054 -0.6618078 0.7474127 0.2365535 -0.6208195 0.7699142 0.3571997 -0.5288106 0.3930571 0.4800064 -0.7842831 0.3308008 0.3978522 -0.8557363 0.4414338 0.5535624 -0.7061904 0.5102906 0.6398776 -0.5745958 0.5608342 0.7032707 -0.4368928 0.5930815 0.7437248 -0.3084281 0.6171365 0.7738851 -0.1422823 0.2564235 0.3215213 -0.9115213 0.3737083 0.4686231 0.800459 0.999334 -0.01873844 -0.0313121 0.3155125 0.9043899 -0.2872818 0.2592316 0.8753567 -0.4081051 0.3512436 0.9258561 -0.1393499 -0.3726362 0.6491377 -0.663146 -0.3996757 0.8933496 0.2053923 0.3047372 0.950835 -0.05520975 -0.2212038 0.7109773 -0.6675179 -0.07318437 0.7389549 -0.6697685 0.0597251 0.780394 -0.6224292 0.1760365 0.83245 -0.5253933 0.295338 0.5309492 -0.7942723 0.1676123 0.4786352 -0.8618668 0.4087814 0.5841479 -0.7011911 0.5040925 0.637921 -0.5821922 0.5742545 0.6847045 -0.4487889 0.6241793 0.7179954 -0.3080306 0.6557718 0.7389068 -0.1548557 -0.03103804 0.400107 -0.9159428 -0.181164 0.9834316 0.006470143 0.6469364 0.7589708 -0.07373327 0.7953159 0.4075006 -0.4487939 0.7337979 0.3462681 -0.5844991 0.8388761 0.4487822 -0.3080284 0.8662993 0.4749157 -0.1548565 0.3959227 -0.1202142 -0.9103811 0.9184634 -0.3954626 0.005859553 0.8839036 0.4618199 -0.07373487 0.4924582 0.04867815 -0.8689739 0.5851764 0.1764013 -0.7914866 0.6639418 0.2674078 -0.6983368 0.9948061 0.08551496 -0.05520933 0.9808009 0.1364216 -0.1393514 0.6215329 -0.3792983 -0.6854411 0.5582836 -0.4956586 -0.6653136 0.7146602 -0.2264499 -0.6618015 0.7760362 -0.11115 -0.6208168 0.8486527 -0.01220774 -0.5288096 0.9110953 0.05792576 -0.4081053 0.9519242 0.1063594 -0.2872772 0.7819758 -0.5884199 0.2056112 0.7373898 0.3550983 -0.5745969 0.6379113 0.3072057 -0.7061827 0.8104403 0.3902809 -0.4368839 0.8570507 0.4127162 -0.3084308 0.8918038 0.4294673 -0.1422808 0.3705354 0.1784161 -0.9115214 0.540037 0.260054 0.8004573 0.89223 -0.4504945 -0.0313127 0.4706702 0.2149176 -0.8557336 0.5624074 0.2619156 -0.7842819 -0.05407994 0.7465294 -0.663151 0.02749776 0.978293 0.2053942 0.6871189 0.7244444 -0.05520999 0.7181906 0.68175 -0.1393531 0.1091369 0.7365523 -0.6675177 0.2546501 0.6975409 -0.6697687 0.3924144 0.677188 -0.6224368 0.5198053 0.6736227 -0.5253903 0.6133557 0.6761959 -0.4081103 0.6766743 0.6779256 -0.2872783 0.7309693 0.3560084 -0.5821874 0.621769 0.3489267 -0.7011802 0.8144721 0.3677287 -0.4487883 0.8739027 0.3760513 -0.3080251 0.9114354 0.381189 -0.1548561 0.1456077 0.3739534 -0.9159462 0.2634434 0.9646571 0.005859673 0.9121829 0.4030951 -0.07373392 0.358693 0.3585099 -0.8618643 0.4964641 0.3502137 -0.7942756 0.9865676 0.05200487 -0.154855 0.9505296 0.04034674 -0.3080027 0.3045486 -0.280103 -0.9103804 0.6559227 -0.7548055 0.005859673 0.9967463 0.03256362 -0.07373356 0.4648109 -0.1697795 -0.8689798 0.6037642 -0.09494566 -0.7914886 0.7142118 -0.0471217 -0.6983418 0.8113616 -0.006378531 -0.5845099 0.8933656 0.02206552 -0.4487887 0.6537253 -0.4414019 -0.6146605 0.5456252 -0.5140987 -0.6618124 0.7547395 -0.3838399 -0.5320105 0.8460153 -0.3430938 -0.4080991 0.903804 -0.317189 -0.2872799 0.9428659 -0.3026303 -0.1393515 0.2879158 -0.6888127 -0.6653131 0.4492496 -0.869475 0.2053974 0.9333976 -0.3545714 -0.0552091 0.3954145 -0.6114031 -0.6854441 0.989529 -0.001556456 -0.144326 0.9519059 -0.001648008 -0.3063861 0.411249 0 -0.9115231 0.5993943 0 0.8004539 0.608401 -0.7930119 -0.0313127 0.5173277 -0.01055955 -0.8557224 0.6203405 -0.008026599 -0.7842916 0.8971688 -0.003784358 -0.4416718 0.8130902 -0.004333674 -0.5821216 0.7199587 0 -0.6940169 0.8358635 -0.3248478 0.4424998 0.7910761 -0.1837838 0.5834571 0.4492496 0.869475 0.2053974 0.9333976 0.3545714 -0.0552091 0.6328816 -0.5086979 0.5836843 -0.3552772 0.7305446 0.5831661 -0.7927079 0.1776832 0.583132 -0.8940823 0.06997984 0.4424023 -0.6216735 0.7795487 0.07632815 0.5027699 0.7427408 0.4422202 0.7752441 0.4510406 0.4422206 0.6371 0.5040339 0.5831411 -0.7752441 0.4510406 0.4422206 0.2218747 0.9721285 0.07574868 0.6122472 -0.6554321 0.4422243 0.7923914 0.1776196 0.5835815 -0.003143489 0.8123683 0.5831363 -0.1307153 0.887326 0.4422286 0.7909899 0.1837545 0.5835832 0.8358635 0.3248478 0.4424998 0.6216446 0.7795507 0.07654201 0.9971224 0 0.07580959 0.2672014 -0.8561738 0.4422329 0.8983777 -0.4326325 0.07580834 -0.1307153 -0.8872347 0.4424118 0.3553102 -0.7305497 0.5831397 0.5027699 -0.7427408 0.4422202 0.003143429 0.8123539 0.5831565 -0.3496302 -0.7332894 0.5831341 -0.5027813 -0.7427271 0.4422302 -0.3553369 -0.7305418 0.5831333 0.3496302 0.7332894 0.5831341 0.2672014 0.8561738 0.4422329 -0.2218747 -0.9721285 0.07574868 -0.8941669 -0.06998169 0.4422308 0.8941669 -0.06998169 0.4422308 0.2218749 -0.9720687 0.07651174 0.6217035 -0.7795785 0.07577878 -0.6371 -0.5040339 0.5831411 0.6122282 0.6554443 0.4422326 0.1307153 -0.887326 0.4422286 -0.8983275 -0.4326072 0.07654172 -0.8358635 0.3248478 0.4424998 -0.7912924 0.1838149 0.583154 0.7752441 -0.4510406 0.4422206 0.7927079 -0.1776832 0.583132 -0.9971224 0 0.07580959 -0.2671979 0.8561623 0.4422574 -0.6328816 0.5086979 0.5836843 -0.6331887 -0.5089437 0.5831367 -0.6121523 -0.6553369 0.4424965 0.1307153 0.887326 0.4422286 0.003143489 -0.8123683 0.5831363 0.3496239 -0.7332764 0.5831543 -0.2672014 -0.8561738 0.4422329 -0.8359936 -0.3248814 0.4422294 -0.2218749 0.9720687 0.07651174 -0.5027699 0.7427408 0.4422202 0.3551234 0.7302065 0.583683 -0.6371 0.5040339 0.5831411 0.8983275 0.4326072 0.07654172 -0.7909899 -0.1837545 0.5835832 0.8941669 0.06998169 0.4422308 -0.7752441 -0.4510406 0.4422206 -0.003143429 -0.8121366 0.583459 -0.6216446 -0.7795507 0.07654201 0.6331887 0.5089437 0.5831367 -0.7927079 -0.1776832 0.583132 -0.6122472 0.6554321 0.4422243 0.6371 -0.5040339 0.5831411 -0.3496239 0.7332764 0.5831543 -0.8983777 0.4326325 0.07580834 0.2313341 -0.1113944 -0.9664761 0.1493295 -0.1403569 -0.9787751 -0.1492996 -0.1403575 -0.9787796 -0.2313341 -0.1113944 -0.9664761 0.00476098 0.1001945 -0.9949566 -0.01663285 0.2042636 -0.9787746 0.08130329 -0.05871903 -0.9949582 -0.20283 -0.02920675 -0.9787784 0.05713117 0.2503457 -0.9664694 0.09872978 0.01760959 -0.9949585 -0.09662371 -0.02694845 -0.9949561 0.1036124 0.1767972 -0.9787785 0.2567565 0 -0.9664762 0.1954438 -0.06164836 -0.9787755 0.1954438 0.06164836 -0.9787755 -0.04776257 -0.0882005 -0.994957 0.03915607 0.09235107 -0.9949563 -0.07361221 -0.1912331 -0.9787805 -0.03915607 0.09235107 -0.9949563 -0.1601018 -0.2007529 -0.9664708 -0.1036124 0.1767972 -0.9787785 0.09872978 -0.01760959 -0.9949585 -0.1700825 -0.1143243 -0.9787758 -0.05713117 0.2503457 -0.9664694 -0.07535195 -0.0661962 -0.9949574 0.01663285 0.2042636 -0.9787746 -0.00476098 -0.1001945 -0.9949566 -0.00476098 0.1001945 -0.9949566 0.01663285 -0.2042636 -0.9787746 -0.07535195 0.0661962 -0.9949574 -0.05713117 -0.2503457 -0.9664694 -0.1700529 0.1143248 -0.9787808 -0.1036124 -0.1767972 -0.9787785 -0.1600721 0.2007539 -0.9664755 -0.03915607 -0.09235107 -0.9949563 -0.07361221 0.1912331 -0.9787805 0.03915607 -0.09235107 -0.9949563 -0.04776257 0.0882005 -0.994957 0.1036124 -0.1767972 -0.9787785 -0.09662371 0.02694845 -0.9949561 0.05710077 -0.2503461 -0.9664711 -0.20283 0.02920675 -0.9787784 0.08130329 0.05871903 -0.9949582 -0.01663285 -0.2042636 -0.9787746 -0.2313341 0.1113944 -0.9664761 0.1492996 0.1403575 -0.9787796 0.00476098 -0.1001945 -0.9949566 -0.1493295 0.1403569 -0.9787751 0.2313341 0.1113944 -0.9664761 0.07535195 -0.0661962 -0.9949574 -0.08130329 0.05871903 -0.9949582 0.20283 0.02920675 -0.9787784 0.1700825 -0.1143243 -0.9787758 -0.09872978 -0.01760959 -0.9949585 0.09662371 0.02694845 -0.9949561 0.1601018 -0.2007529 -0.9664708 -0.1954438 -0.06164836 -0.9787755 0.04776257 0.0882005 -0.994957 0.07364261 -0.1912327 -0.9787783 -0.256785 0 -0.9664686 0.07361221 0.1912331 -0.9787805 0.04779303 -0.08820039 -0.9949556 -0.1954438 0.06164836 -0.9787755 0.1601018 0.2007529 -0.9664708 0.09662371 -0.02694845 -0.9949561 -0.09872978 0.01760959 -0.9949585 0.1700825 0.1143243 -0.9787758 0.20283 -0.02920675 -0.9787784 -0.08130329 -0.05871903 -0.9949582 0.07535195 0.0661962 -0.9949574 -0.4338883 0.9009668 0 -3.01312e-7 -1 -2.03913e-7 -6.58942e-7 1 2.03913e-7 0.4338883 0.9009668 0 -0.4338842 -0.9009687 -2.54448e-6 0.7818291 0.6234928 -2.54445e-6 -0.7818341 -0.6234866 -2.54447e-6 0.9749274 0.2225235 0 -0.9749274 -0.2225235 0 0.9749274 -0.2225235 0 -0.9749274 0.2225235 0 0.7818341 -0.6234866 0 -0.7818291 0.6234928 0 0.4338842 -0.9009687 0 -0.4032831 0.9142385 0.0391258 0.03332692 0.9986785 0.03912556 0.4633358 0.8853187 0.03912502 0.8015905 0.596592 0.03912574 0.9810612 0.1897056 0.0391252 0.9662257 -0.25471 0.03912508 0.7600222 -0.6487183 0.03912574 0.4032831 -0.9142385 0.0391258 -0.03332692 -0.9986785 0.03912556 -0.4633358 -0.8853187 0.03912502 -0.8015905 -0.596592 0.03912574 -0.9810612 -0.1897056 0.0391252 -0.9662257 0.25471 0.03912508 -0.7600222 0.6487183 0.03912574 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

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

+
+ + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

5 0 4 1 14 2 6 3 5 0 15 4 7 5 6 3 16 6 8 7 7 5 17 8 8 7 18 9 19 10 2 11 1 12 11 13 9 14 19 10 20 15 3 16 2 11 12 17 4 1 3 16 13 18 19 10 18 9 28 19 12 17 11 13 21 20 19 10 29 21 30 22 13 18 12 17 22 23 13 18 23 24 24 25 15 4 14 2 24 25 15 4 25 26 26 27 16 6 26 27 27 28 18 9 17 8 27 28 25 26 24 25 34 29 26 27 25 26 35 30 26 27 36 31 37 32 28 19 27 28 37 32 28 19 38 33 39 34 21 20 31 35 32 36 30 22 29 21 39 34 22 23 32 36 33 37 23 24 33 37 34 29 38 33 37 32 47 38 38 33 48 39 49 40 31 35 41 41 42 42 40 43 39 34 49 40 32 36 42 42 43 44 33 37 43 44 44 45 34 29 44 45 45 46 35 30 45 46 46 47 36 31 46 47 47 38 96 93 95 92 105 97 96 93 106 98 107 99 97 94 107 99 108 100 99 88 98 95 108 100 92 89 91 96 101 101 99 88 109 102 110 103 93 90 92 89 102 104 93 90 103 105 104 106 95 92 94 91 104 106 102 104 101 101 111 107 109 102 119 108 120 109 103 105 102 104 112 110 103 105 113 111 114 112 104 106 114 112 115 113 106 98 105 97 115 113 107 99 106 98 116 114 107 99 117 115 118 116 109 102 108 100 118 116 116 114 115 113 125 117 117 115 116 114 126 118 117 115 127 119 128 120 119 108 118 116 128 120 111 107 121 121 122 122 120 109 119 108 129 123 113 111 112 110 122 122 113 111 123 124 124 125 114 112 124 125 125 117 129 123 128 120 138 126 121 121 131 127 132 128 130 129 129 123 139 130 122 122 132 128 133 131 123 124 133 131 134 132 124 125 134 132 135 133 126 118 125 117 135 133 126 118 136 134 137 135 127 119 137 135 138 126 134 132 144 136 145 137 135 133 145 137 146 138 136 134 146 138 147 139 137 135 147 139 148 140 139 130 138 126 148 140 131 127 141 141 142 142 140 143 139 130 149 144 132 128 142 142 143 145 133 131 143 145 144 136 193 192 192 190 202 195 193 192 203 196 204 197 194 193 204 197 205 198 196 185 195 194 205 198 197 186 196 185 206 199 197 186 207 200 208 201 199 188 198 187 208 201 192 190 191 189 201 202 199 188 209 203 210 204 207 200 206 199 216 205 207 200 217 206 218 207 209 203 208 201 218 207 202 195 201 202 211 208 209 203 219 209 220 210 203 196 202 195 212 211 203 196 213 212 214 213 204 197 214 213 215 214 206 199 205 198 215 214 220 210 219 209 229 215 213 212 212 211 222 216 213 212 223 217 224 218 215 214 214 213 224 218 216 205 215 214 225 219 216 205 226 220 227 221 217 206 227 221 228 222 219 209 218 207 228 222 211 208 221 223 222 216 226 220 225 219 235 224 226 220 236 225 237 226 228 222 227 221 237 226 229 215 228 222 238 227 221 223 231 228 232 229 230 230 229 215 239 231 223 217 222 216 232 229 223 217 233 232 234 233 225 219 224 218 234 233 231 228 241 234 242 235 240 236 239 231 249 237 232 229 242 235 243 238 233 232 243 238 244 239 235 224 234 233 244 239 235 224 245 240 246 241 236 225 246 241 247 242 238 227 237 226 247 242 238 227 248 243 249 237 297 287 307 293 308 294 299 289 298 288 308 294 292 291 291 290 301 295 299 289 309 296 310 297 293 283 292 291 302 298 293 283 303 299 304 300 294 284 304 300 305 301 296 286 295 285 305 301 297 287 296 286 306 302 303 299 313 303 314 304 304 300 314 304 315 305 306 302 305 301 315 305 306 302 316 306 317 307 307 293 317 307 318 308 309 296 308 294 318 308 302 298 301 295 311 309 309 296 319 310 320 311 303 299 302 298 312 312 316 306 326 313 327 314 317 307 327 314 328 315 319 310 318 308 328 315 311 309 321 316 322 317 319 310 329 318 330 319 313 303 312 312 322 317 314 304 313 303 323 320 315 305 314 304 324 321 316 306 315 305 325 322 322 317 332 323 333 324 323 320 333 324 334 325 325 322 324 321 334 325 326 313 325 322 335 326 326 313 336 327 337 328 328 315 327 314 337 328 329 318 328 315 338 329 321 316 331 330 332 323 330 319 329 318 339 331 336 327 346 332 347 333 338 329 337 328 347 333 338 329 348 334 349 335 331 330 341 336 342 337 340 338 339 331 349 335 332 323 342 337 343 339 334 325 333 324 343 339 335 326 334 325 344 340 335 326 345 341 346 332 394 387 404 391 405 392 396 389 395 388 405 392 397 390 396 389 406 393 397 390 407 394 408 395 399 385 398 381 408 395 392 383 391 382 401 396 399 385 409 397 410 398 393 386 392 383 402 399 394 387 393 386 403 400 402 399 401 396 411 401 409 397 419 402 420 403 403 400 402 399 412 404 403 400 413 405 414 406 404 391 414 406 415 407 406 393 405 392 415 407 406 393 416 408 417 409 407 394 417 409 418 410 409 397 408 395 418 410 416 408 415 407 425 411 416 408 426 412 427 413 417 409 427 413 428 414 419 402 418 410 428 414 411 401 421 415 422 416 419 402 429 417 430 418 413 405 412 404 422 416 413 405 423 419 424 420 414 406 424 420 425 411 429 417 428 414 438 421 421 415 431 422 432 423 430 418 429 417 439 424 423 419 422 416 432 423 423 419 433 425 434 426 425 411 424 420 434 426 426 412 425 411 435 427 426 412 436 428 437 429 428 414 427 413 437 429 435 427 434 426 444 430 435 427 445 431 446 432 436 428 446 432 447 433 438 421 437 429 447 433 438 421 448 434 449 435 431 422 441 436 442 437 440 438 439 424 449 435 432 423 442 437 443 439 433 425 443 439 444 430 493 486 492 484 502 489 493 486 503 490 504 491 494 487 504 491 505 492 496 479 495 488 505 492 497 480 496 479 506 493 497 480 507 494 508 495 499 482 498 481 508 495 492 484 491 483 501 496 499 482 509 497 510 498 507 494 506 493 516 499 507 494 517 500 518 501 509 497 508 495 518 501 502 489 501 496 511 502 509 497 519 503 520 504 503 490 502 489 512 505 504 491 503 490 513 506 504 491 514 507 515 508 506 493 505 492 515 508 520 504 519 503 529 509 513 506 512 505 522 510 514 507 513 506 523 511 514 507 524 512 525 513 516 499 515 508 525 513 516 499 526 514 527 515 517 500 527 515 528 516 519 503 518 501 528 516 512 505 511 502 521 517 526 514 525 513 535 518 526 514 536 519 537 520 528 516 527 515 537 520 529 509 528 516 538 521 521 517 531 522 532 523 530 524 529 509 539 525 523 511 522 510 532 523 523 511 533 526 534 527 525 513 524 512 534 527 539 525 538 521 548 528 531 522 541 529 542 530 540 531 539 525 549 532 532 523 542 530 543 533 533 526 543 533 544 534 535 518 534 527 544 534 535 518 545 535 546 536 536 519 546 536 547 537 538 521 537 520 547 537 597 581 608 587 609 588 599 583 598 582 609 588 592 585 591 584 602 589 599 583 610 590 611 591 593 577 592 585 603 592 593 577 604 593 605 594 594 578 605 594 606 595 596 580 595 579 606 595 597 581 596 580 607 596 604 593 614 597 615 598 605 594 615 598 616 599 607 596 606 595 616 599 608 587 607 596 617 600 608 587 618 601 619 602 610 590 609 588 619 602 603 592 602 589 612 603 610 590 620 604 621 605 604 593 603 592 613 606 617 600 627 607 628 608 619 602 618 601 628 608 620 604 619 602 629 609 612 603 622 610 623 611 620 604 630 612 631 613 614 597 613 606 623 611 614 597 624 614 625 615 616 599 615 598 625 615 617 600 616 599 626 616 631 613 630 612 640 617 624 614 623 611 633 618 624 614 634 619 635 620 626 616 625 615 635 620 627 607 626 616 636 621 627 607 637 622 638 623 629 609 628 608 638 623 629 609 639 624 640 617 622 610 632 625 633 618 636 621 646 626 647 627 637 622 647 627 648 628 639 624 638 623 648 628 639 624 649 629 650 630 632 625 642 631 643 632 641 633 640 617 650 630 633 618 643 632 644 634 634 619 644 634 645 635 636 621 635 620 645 635 694 680 693 678 2 11 694 680 3 16 4 1 695 681 4 1 5 0 0 684 5 0 6 3 696 682 6 3 7 5 697 683 7 5 8 7 698 675 8 7 9 14 693 678 692 677 1 12 699 676 9 14 10 687 860 840 870 841 869 842 861 843 871 844 870 841 862 845 872 846 871 844 863 847 873 848 872 846 874 849 873 848 863 847 857 850 867 851 866 852 875 853 874 849 864 854 858 855 868 856 867 851 859 857 869 842 868 856 874 849 884 858 883 859 867 851 877 860 876 861 885 862 884 858 874 849 868 856 878 863 877 860 879 864 878 863 868 856 870 841 880 865 879 864 881 866 880 865 870 841 872 846 882 867 881 866 873 848 883 859 882 867 880 865 890 868 889 869 881 866 891 870 890 868 892 871 891 870 881 866 893 872 892 871 882 867 894 873 893 872 883 859 887 874 886 875 876 861 885 862 895 876 894 873 888 877 887 874 877 860 889 869 888 877 878 863 893 872 903 878 902 879 904 880 903 878 893 872 897 881 896 882 886 875 895 876 905 883 904 880 898 884 897 881 887 874 899 885 898 884 888 877 900 886 899 885 889 869 901 887 900 886 890 868 902 879 901 887 891 870 951 934 961 938 960 939 962 940 961 938 951 934 963 941 962 940 952 935 954 929 964 942 963 941 947 931 957 943 956 944 965 945 964 942 954 929 948 930 958 946 957 943 949 932 959 947 958 946 950 933 960 939 959 947 957 943 967 948 966 949 975 950 974 951 964 942 968 952 967 948 957 943 969 953 968 952 958 946 960 939 970 954 969 953 961 938 971 955 970 954 962 940 972 956 971 955 973 957 972 956 962 940 964 942 974 951 973 957 971 955 981 958 980 959 972 956 982 960 981 958 983 961 982 960 972 956 974 951 984 962 983 961 977 963 976 964 966 949 975 950 985 965 984 962 968 952 978 966 977 963 979 967 978 966 968 952 980 959 979 967 969 953 984 962 994 968 993 969 987 970 986 971 976 964 985 965 995 972 994 968 978 966 988 973 987 970 989 974 988 973 978 966 980 959 990 975 989 974 981 958 991 976 990 975 992 977 991 976 981 958 993 969 992 977 982 960 1000 978 999 979 989 974 991 976 1001 980 1000 978 1002 981 1001 980 991 976 1003 982 1002 981 992 977 994 968 1004 983 1003 982 997 984 996 985 986 971 995 972 1005 986 1004 983 998 987 997 984 987 970 999 979 998 987 988 973 1048 1035 1058 1038 1057 1039 1059 1040 1058 1038 1048 1035 1060 1041 1059 1040 1049 1036 1051 1029 1061 1042 1060 1041 1052 1028 1062 1043 1061 1042 1063 1044 1062 1043 1052 1028 1054 1031 1064 1045 1063 1044 1047 1032 1057 1039 1056 1046 1065 1047 1064 1045 1054 1031 1062 1043 1072 1048 1071 1049 1073 1050 1072 1048 1062 1043 1064 1045 1074 1051 1073 1050 1057 1039 1067 1052 1066 1053 1075 1054 1074 1051 1064 1045 1058 1038 1068 1055 1067 1052 1069 1056 1068 1055 1058 1038 1070 1057 1069 1056 1059 1040 1061 1042 1071 1049 1070 1057 1075 1054 1085 1058 1084 1059 1068 1055 1078 1060 1077 1061 1079 1062 1078 1060 1068 1055 1070 1057 1080 1063 1079 1062 1071 1049 1081 1064 1080 1063 1082 1065 1081 1064 1071 1049 1083 1066 1082 1065 1072 1048 1074 1051 1084 1059 1083 1066 1077 1061 1076 1067 1066 1053 1091 1068 1090 1069 1080 1063 1092 1070 1091 1068 1081 1064 1083 1066 1093 1071 1092 1070 1094 1072 1093 1071 1083 1066 1087 1073 1086 1074 1076 1067 1085 1058 1095 1075 1094 1072 1078 1060 1088 1076 1087 1073 1089 1077 1088 1076 1078 1060 1080 1063 1090 1069 1089 1077 1097 1078 1096 1079 1086 1074 1095 1075 1105 1080 1104 1081 1098 1082 1097 1078 1087 1073 1099 1083 1098 1082 1088 1076 1100 1084 1099 1083 1089 1077 1101 1085 1100 1084 1090 1069 1102 1086 1101 1085 1091 1068 1093 1071 1103 1087 1102 1086 1104 1081 1103 1087 1093 1071 1163 1138 1162 1139 1152 1132 1154 1134 1164 1140 1163 1138 1147 1135 1157 1141 1156 1142 1165 1143 1164 1140 1154 1134 1148 1129 1158 1144 1157 1141 1159 1145 1158 1144 1148 1129 1160 1146 1159 1145 1149 1128 1151 1131 1161 1147 1160 1146 1162 1139 1161 1147 1151 1131 1169 1148 1168 1149 1158 1144 1170 1150 1169 1148 1159 1145 1161 1147 1171 1151 1170 1150 1172 1152 1171 1151 1161 1147 1173 1153 1172 1152 1162 1139 1164 1140 1174 1154 1173 1153 1157 1141 1167 1155 1166 1156 1175 1157 1174 1154 1164 1140 1158 1144 1168 1149 1167 1155 1182 1158 1181 1159 1171 1151 1183 1160 1182 1158 1172 1152 1174 1154 1184 1161 1183 1160 1177 1162 1176 1163 1166 1156 1185 1164 1184 1161 1174 1154 1178 1165 1177 1162 1167 1155 1169 1148 1179 1166 1178 1165 1180 1167 1179 1166 1169 1148 1171 1151 1181 1159 1180 1167 1178 1165 1188 1168 1187 1169 1189 1170 1188 1168 1178 1165 1180 1167 1190 1171 1189 1170 1181 1159 1191 1172 1190 1171 1192 1173 1191 1172 1181 1159 1183 1160 1193 1174 1192 1173 1184 1161 1194 1175 1193 1174 1187 1169 1186 1176 1176 1163 1185 1164 1195 1177 1194 1175 1202 1178 1201 1179 1191 1172 1193 1174 1203 1180 1202 1178 1204 1181 1203 1180 1193 1174 1197 1182 1196 1183 1186 1176 1195 1177 1205 1184 1204 1181 1198 1185 1197 1182 1187 1169 1189 1170 1199 1186 1198 1185 1190 1171 1200 1187 1199 1186 1201 1179 1200 1187 1190 1171 1260 1238 1259 1239 1249 1234 1251 1236 1261 1240 1260 1238 1252 1237 1262 1241 1261 1240 1263 1242 1262 1241 1252 1237 1254 1228 1264 1243 1263 1242 1247 1230 1257 1244 1256 1245 1265 1246 1264 1243 1254 1228 1248 1233 1258 1247 1257 1244 1249 1234 1259 1239 1258 1247 1257 1244 1267 1248 1266 1249 1275 1250 1274 1251 1264 1243 1258 1247 1268 1252 1267 1248 1269 1253 1268 1252 1258 1247 1270 1254 1269 1253 1259 1239 1261 1240 1271 1255 1270 1254 1272 1256 1271 1255 1261 1240 1273 1257 1272 1256 1262 1241 1264 1243 1274 1251 1273 1257 1271 1255 1281 1258 1280 1259 1282 1260 1281 1258 1271 1255 1283 1261 1282 1260 1272 1256 1274 1251 1284 1262 1283 1261 1277 1263 1276 1264 1266 1249 1285 1265 1284 1262 1274 1251 1268 1252 1278 1266 1277 1263 1279 1267 1278 1266 1268 1252 1280 1259 1279 1267 1269 1253 1284 1262 1294 1268 1293 1269 1287 1270 1286 1271 1276 1264 1285 1265 1295 1272 1294 1268 1278 1266 1288 1273 1287 1270 1289 1274 1288 1273 1278 1266 1280 1259 1290 1275 1289 1274 1281 1258 1291 1276 1290 1275 1292 1277 1291 1276 1281 1258 1283 1261 1293 1269 1292 1277 1290 1275 1300 1278 1299 1279 1301 1280 1300 1278 1290 1275 1302 1281 1301 1280 1291 1276 1293 1269 1303 1282 1302 1281 1304 1283 1303 1282 1293 1269 1297 1284 1296 1285 1286 1271 1295 1272 1305 1286 1304 1283 1298 1287 1297 1284 1287 1270 1299 1279 1298 1287 1288 1273 1348 1335 1358 1338 1357 1339 1359 1340 1358 1338 1348 1335 1360 1341 1359 1340 1349 1336 1351 1329 1361 1342 1360 1341 1352 1328 1362 1343 1361 1342 1363 1344 1362 1343 1352 1328 1354 1331 1364 1345 1363 1344 1347 1332 1357 1339 1356 1346 1365 1347 1364 1345 1354 1331 1362 1343 1372 1348 1371 1349 1373 1350 1372 1348 1362 1343 1364 1345 1374 1351 1373 1350 1357 1339 1367 1352 1366 1353 1375 1354 1374 1351 1364 1345 1358 1338 1368 1355 1367 1352 1359 1340 1369 1356 1368 1355 1370 1357 1369 1356 1359 1340 1361 1342 1371 1349 1370 1357 1375 1354 1385 1358 1384 1359 1368 1355 1378 1360 1377 1361 1369 1356 1379 1362 1378 1360 1380 1363 1379 1362 1369 1356 1371 1349 1381 1364 1380 1363 1382 1365 1381 1364 1371 1349 1383 1366 1382 1365 1372 1348 1374 1351 1384 1359 1383 1366 1367 1352 1377 1361 1376 1367 1381 1364 1391 1368 1390 1369 1392 1370 1391 1368 1381 1364 1383 1366 1393 1371 1392 1370 1384 1359 1394 1372 1393 1371 1387 1373 1386 1374 1376 1367 1385 1358 1395 1375 1394 1372 1378 1360 1388 1376 1387 1373 1389 1377 1388 1376 1378 1360 1380 1363 1390 1369 1389 1377 1404 1378 1403 1379 1393 1371 1397 1380 1396 1381 1386 1374 1395 1375 1405 1382 1404 1378 1398 1383 1397 1380 1387 1373 1399 1384 1398 1383 1388 1376 1390 1369 1400 1385 1399 1384 1401 1386 1400 1385 1390 1369 1402 1387 1401 1386 1391 1368 1393 1371 1403 1379 1402 1387 1464 1438 1463 1439 1452 1432 1454 1434 1465 1440 1464 1438 1447 1435 1458 1441 1457 1442 1466 1443 1465 1440 1454 1434 1448 1429 1459 1444 1458 1441 1460 1445 1459 1444 1448 1429 1461 1446 1460 1445 1449 1428 1451 1431 1462 1447 1461 1446 1452 1432 1463 1439 1462 1447 1470 1448 1469 1449 1459 1444 1471 1450 1470 1448 1460 1445 1462 1447 1472 1451 1471 1450 1463 1439 1473 1452 1472 1451 1474 1453 1473 1452 1463 1439 1465 1440 1475 1454 1474 1453 1458 1441 1468 1455 1467 1456 1476 1457 1475 1454 1465 1440 1459 1444 1469 1449 1468 1455 1483 1458 1482 1459 1472 1451 1484 1460 1483 1458 1473 1452 1485 1461 1484 1460 1474 1453 1468 1455 1478 1462 1477 1463 1476 1457 1486 1464 1485 1461 1469 1449 1479 1465 1478 1462 1480 1466 1479 1465 1469 1449 1471 1450 1481 1467 1480 1466 1472 1451 1482 1459 1481 1467 1486 1464 1496 1468 1495 1469 1479 1465 1489 1470 1488 1471 1490 1472 1489 1470 1479 1465 1481 1467 1491 1473 1490 1472 1482 1459 1492 1474 1491 1473 1493 1475 1492 1474 1482 1459 1484 1460 1494 1476 1493 1475 1495 1469 1494 1476 1484 1460 1488 1471 1487 1477 1477 1463 1502 1478 1501 1479 1491 1473 1503 1480 1502 1478 1492 1474 1494 1476 1504 1481 1503 1480 1505 1482 1504 1481 1494 1476 1498 1483 1497 1484 1487 1477 1496 1468 1506 1485 1505 1482 1499 1486 1498 1483 1488 1471 1500 1487 1499 1486 1489 1470 1491 1473 1501 1479 1500 1487 1549 1533 858 855 857 850 859 857 858 855 1549 1533 860 840 859 857 1550 1534 861 843 860 840 855 1537 862 845 861 843 1551 1536 863 847 862 845 1552 1535 864 854 863 847 1553 1529 1548 1530 857 850 856 1540 865 1541 864 854 1554 1528 15 4 5 0 14 2 16 6 6 3 15 4 17 8 7 5 16 6 18 9 8 7 17 8 9 14 8 7 19 10 12 17 2 11 11 13 10 687 9 14 20 15 13 18 3 16 12 17 14 2 4 1 13 18 29 21 19 10 28 19 22 23 12 17 21 20 20 15 19 10 30 22 23 24 13 18 22 23 14 2 13 18 24 25 25 26 15 4 24 25 16 6 15 4 26 27 17 8 16 6 27 28 28 19 18 9 27 28 35 30 25 26 34 29 36 31 26 27 35 30 27 28 26 27 37 32 38 33 28 19 37 32 29 21 28 19 39 34 22 23 21 20 32 36 40 43 30 22 39 34 23 24 22 23 33 37 24 25 23 24 34 29 48 39 38 33 47 38 39 34 38 33 49 40 32 36 31 35 42 42 50 1694 40 43 49 40 33 37 32 36 43 44 34 29 33 37 44 45 35 30 34 29 45 46 36 31 35 30 46 47 37 32 36 31 47 38 106 98 96 93 105 97 97 94 96 93 107 99 98 95 97 94 108 100 109 102 99 88 108 100 102 104 92 89 101 101 100 1695 99 88 110 103 103 105 93 90 102 104 94 91 93 90 104 106 105 97 95 92 104 106 112 110 102 104 111 107 110 103 109 102 120 109 113 111 103 105 112 110 104 106 103 105 114 112 105 97 104 106 115 113 116 114 106 98 115 113 117 115 107 99 116 114 108 100 107 99 118 116 119 108 109 102 118 116 126 118 116 114 125 117 127 119 117 115 126 118 118 116 117 115 128 120 129 123 119 108 128 120 112 110 111 107 122 122 130 129 120 109 129 123 123 124 113 111 122 122 114 112 113 111 124 125 115 113 114 112 125 117 139 130 129 123 138 126 122 122 121 121 132 128 140 143 130 129 139 130 123 124 122 122 133 131 124 125 123 124 134 132 125 117 124 125 135 133 136 134 126 118 135 133 127 119 126 118 137 135 128 120 127 119 138 126 135 133 134 132 145 137 136 134 135 133 146 138 137 135 136 134 147 139 138 126 137 135 148 140 149 144 139 130 148 140 132 128 131 127 142 142 150 1696 140 143 149 144 133 131 132 128 143 145 134 132 133 131 144 136 203 196 193 192 202 195 194 193 193 192 204 197 195 194 194 193 205 198 206 199 196 185 205 198 207 200 197 186 206 199 198 187 197 186 208 201 209 203 199 188 208 201 202 195 192 190 201 202 200 1697 199 188 210 204 217 206 207 200 216 205 208 201 207 200 218 207 219 209 209 203 218 207 212 211 202 195 211 208 210 204 209 203 220 210 213 212 203 196 212 211 204 197 203 196 214 213 205 198 204 197 215 214 216 205 206 199 215 214 230 230 220 210 229 215 223 217 213 212 222 216 214 213 213 212 224 218 225 219 215 214 224 218 226 220 216 205 225 219 217 206 216 205 227 221 218 207 217 206 228 222 229 215 219 209 228 222 212 211 211 208 222 216 236 225 226 220 235 224 227 221 226 220 237 226 238 227 228 222 237 226 239 231 229 215 238 227 222 216 221 223 232 229 240 236 230 230 239 231 233 232 223 217 232 229 224 218 223 217 234 233 235 224 225 219 234 233 232 229 231 228 242 235 250 1698 240 236 249 237 233 232 232 229 243 238 234 233 233 232 244 239 245 240 235 224 244 239 236 225 235 224 246 241 237 226 236 225 247 242 248 243 238 227 247 242 239 231 238 227 249 237 298 288 297 287 308 294 309 296 299 289 308 294 302 298 292 291 301 295 300 1699 299 289 310 297 303 299 293 283 302 298 294 284 293 283 304 300 295 285 294 284 305 301 306 302 296 286 305 301 307 293 297 287 306 302 304 300 303 299 314 304 305 301 304 300 315 305 316 306 306 302 315 305 307 293 306 302 317 307 308 294 307 293 318 308 319 310 309 296 318 308 312 312 302 298 311 309 310 297 309 296 320 311 313 303 303 299 312 312 317 307 316 306 327 314 318 308 317 307 328 315 329 318 319 310 328 315 312 312 311 309 322 317 320 311 319 310 330 319 323 320 313 303 322 317 324 321 314 304 323 320 325 322 315 305 324 321 326 313 316 306 325 322 323 320 322 317 333 324 324 321 323 320 334 325 335 326 325 322 334 325 336 327 326 313 335 326 327 314 326 313 337 328 338 329 328 315 337 328 339 331 329 318 338 329 322 317 321 316 332 323 340 338 330 319 339 331 337 328 336 327 347 333 348 334 338 329 347 333 339 331 338 329 349 335 332 323 331 330 342 337 350 1700 340 338 349 335 333 324 332 323 343 339 344 340 334 325 343 339 345 341 335 326 344 340 336 327 335 326 346 332 395 388 394 387 405 392 406 393 396 389 405 392 407 394 397 390 406 393 398 381 397 390 408 395 409 397 399 385 408 395 402 399 392 383 401 396 400 1701 399 385 410 398 403 400 393 386 402 399 404 391 394 387 403 400 412 404 402 399 411 401 410 398 409 397 420 403 413 405 403 400 412 404 404 391 403 400 414 406 405 392 404 391 415 407 416 408 406 393 415 407 407 394 406 393 417 409 408 395 407 394 418 410 419 402 409 397 418 410 426 412 416 408 425 411 417 409 416 408 427 413 418 410 417 409 428 414 429 417 419 402 428 414 412 404 411 401 422 416 420 403 419 402 430 418 423 419 413 405 422 416 414 406 413 405 424 420 415 407 414 406 425 411 439 424 429 417 438 421 422 416 421 415 432 423 440 438 430 418 439 424 433 425 423 419 432 423 424 420 423 419 434 426 435 427 425 411 434 426 436 428 426 412 435 427 427 413 426 412 437 429 438 421 428 414 437 429 445 431 435 427 444 430 436 428 435 427 446 432 437 429 436 428 447 433 448 434 438 421 447 433 439 424 438 421 449 435 432 423 431 422 442 437 450 1702 440 438 449 435 433 425 432 423 443 439 434 426 433 425 444 430 503 490 493 486 502 489 494 487 493 486 504 491 495 488 494 487 505 492 506 493 496 479 505 492 507 494 497 480 506 493 498 481 497 480 508 495 509 497 499 482 508 495 502 489 492 484 501 496 500 1703 499 482 510 498 517 500 507 494 516 499 508 495 507 494 518 501 519 503 509 497 518 501 512 505 502 489 511 502 510 498 509 497 520 504 513 506 503 490 512 505 514 507 504 491 513 506 505 492 504 491 515 508 516 499 506 493 515 508 530 524 520 504 529 509 523 511 513 506 522 510 524 512 514 507 523 511 515 508 514 507 525 513 526 514 516 499 525 513 517 500 516 499 527 515 518 501 517 500 528 516 529 509 519 503 528 516 522 510 512 505 521 517 536 519 526 514 535 518 527 515 526 514 537 520 538 521 528 516 537 520 539 525 529 509 538 521 522 510 521 517 532 523 540 531 530 524 539 525 533 526 523 511 532 523 524 512 523 511 534 527 535 518 525 513 534 527 549 532 539 525 548 528 532 523 531 522 542 530 550 1704 540 531 549 532 533 526 532 523 543 533 534 527 533 526 544 534 545 535 535 518 544 534 536 519 535 518 546 536 537 520 536 519 547 537 548 528 538 521 547 537 598 582 597 581 609 588 610 590 599 583 609 588 603 592 592 585 602 589 600 1705 599 583 611 591 604 593 593 577 603 592 594 578 593 577 605 594 595 579 594 578 606 595 607 596 596 580 606 595 608 587 597 581 607 596 605 594 604 593 615 598 606 595 605 594 616 599 617 600 607 596 616 599 618 601 608 587 617 600 609 588 608 587 619 602 620 604 610 590 619 602 613 606 603 592 612 603 611 591 610 590 621 605 614 597 604 593 613 606 618 601 617 600 628 608 629 609 619 602 628 608 630 612 620 604 629 609 613 606 612 603 623 611 621 605 620 604 631 613 624 614 614 597 623 611 615 598 614 597 625 615 626 616 616 599 625 615 627 607 617 600 626 616 641 633 631 613 640 617 634 619 624 614 633 618 625 615 624 614 635 620 636 621 626 616 635 620 637 622 627 607 636 621 628 608 627 607 638 623 639 624 629 609 638 623 630 612 629 609 640 617 623 611 622 610 633 618 637 622 636 621 647 627 638 623 637 622 648 628 649 629 639 624 648 628 640 617 639 624 650 630 633 618 632 625 643 632 651 1706 641 633 650 630 634 619 633 618 644 634 635 620 634 619 645 635 646 626 636 621 645 635 3 16 694 680 2 11 695 681 694 680 4 1 0 684 695 681 5 0 696 682 0 684 6 3 697 683 696 682 7 5 698 675 697 683 8 7 699 676 698 675 9 14 2 11 693 678 1 12 700 1707 699 676 10 687 859 857 860 840 869 842 860 840 861 843 870 841 861 843 862 845 871 844 862 845 863 847 872 846 864 854 874 849 863 847 856 1540 857 850 866 852 865 1541 875 853 864 854 857 850 858 855 867 851 858 855 859 857 868 856 873 848 874 849 883 859 866 852 867 851 876 861 875 853 885 862 874 849 867 851 868 856 877 860 869 842 879 864 868 856 869 842 870 841 879 864 871 844 881 866 870 841 871 844 872 846 881 866 872 846 873 848 882 867 879 864 880 865 889 869 880 865 881 866 890 868 882 867 892 871 881 866 883 859 893 872 882 867 884 858 894 873 883 859 877 860 887 874 876 861 884 858 885 862 894 873 878 863 888 877 877 860 879 864 889 869 878 863 892 871 893 872 902 879 894 873 904 880 893 872 887 874 897 881 886 875 894 873 895 876 904 880 888 877 898 884 887 874 889 869 899 885 888 877 890 868 900 886 889 869 891 870 901 887 890 868 892 871 902 879 891 870 950 933 951 934 960 939 952 935 962 940 951 934 953 936 963 941 952 935 953 936 954 929 963 941 946 937 947 931 956 944 955 928 965 945 954 929 947 931 948 930 957 943 948 930 949 932 958 946 949 932 950 933 959 947 956 944 957 943 966 949 965 945 975 950 964 942 958 946 968 952 957 943 959 947 969 953 958 946 959 947 960 939 969 953 960 939 961 938 970 954 961 938 962 940 971 955 963 941 973 957 962 940 963 941 964 942 973 957 970 954 971 955 980 959 971 955 972 956 981 958 973 957 983 961 972 956 973 957 974 951 983 961 967 948 977 963 966 949 974 951 975 950 984 962 967 948 968 952 977 963 969 953 979 967 968 952 970 954 980 959 969 953 983 961 984 962 993 969 977 963 987 970 976 964 984 962 985 965 994 968 977 963 978 966 987 970 979 967 989 974 978 966 979 967 980 959 989 974 980 959 981 958 990 975 982 960 992 977 981 958 983 961 993 969 982 960 990 975 1000 978 989 974 990 975 991 976 1000 978 992 977 1002 981 991 976 993 969 1003 982 992 977 993 969 994 968 1003 982 987 970 997 984 986 971 994 968 995 972 1004 983 988 973 998 987 987 970 989 974 999 979 988 973 1047 1032 1048 1035 1057 1039 1049 1036 1059 1040 1048 1035 1050 1037 1060 1041 1049 1036 1050 1037 1051 1029 1060 1041 1051 1029 1052 1028 1061 1042 1053 1030 1063 1044 1052 1028 1053 1030 1054 1031 1063 1044 1046 1033 1047 1032 1056 1046 1055 1034 1065 1047 1054 1031 1061 1042 1062 1043 1071 1049 1063 1044 1073 1050 1062 1043 1063 1044 1064 1045 1073 1050 1056 1046 1057 1039 1066 1053 1065 1047 1075 1054 1064 1045 1057 1039 1058 1038 1067 1052 1059 1040 1069 1056 1058 1038 1060 1041 1070 1057 1059 1040 1060 1041 1061 1042 1070 1057 1074 1051 1075 1054 1084 1059 1067 1052 1068 1055 1077 1061 1069 1056 1079 1062 1068 1055 1069 1056 1070 1057 1079 1062 1070 1057 1071 1049 1080 1063 1072 1048 1082 1065 1071 1049 1073 1050 1083 1066 1072 1048 1073 1050 1074 1051 1083 1066 1067 1052 1077 1061 1066 1053 1081 1064 1091 1068 1080 1063 1082 1065 1092 1070 1081 1064 1082 1065 1083 1066 1092 1070 1084 1059 1094 1072 1083 1066 1077 1061 1087 1073 1076 1067 1084 1059 1085 1058 1094 1072 1077 1061 1078 1060 1087 1073 1079 1062 1089 1077 1078 1060 1079 1062 1080 1063 1089 1077 1087 1073 1097 1078 1086 1074 1094 1072 1095 1075 1104 1081 1088 1076 1098 1082 1087 1073 1089 1077 1099 1083 1088 1076 1090 1069 1100 1084 1089 1077 1091 1068 1101 1085 1090 1069 1092 1070 1102 1086 1091 1068 1092 1070 1093 1071 1102 1086 1094 1072 1104 1081 1093 1071 1153 1133 1163 1138 1152 1132 1153 1133 1154 1134 1163 1138 1146 1136 1147 1135 1156 1142 1155 1137 1165 1143 1154 1134 1147 1135 1148 1129 1157 1141 1149 1128 1159 1145 1148 1129 1150 1130 1160 1146 1149 1128 1150 1130 1151 1131 1160 1146 1152 1132 1162 1139 1151 1131 1159 1145 1169 1148 1158 1144 1160 1146 1170 1150 1159 1145 1160 1146 1161 1147 1170 1150 1162 1139 1172 1152 1161 1147 1163 1138 1173 1153 1162 1139 1163 1138 1164 1140 1173 1153 1156 1142 1157 1141 1166 1156 1165 1143 1175 1157 1164 1140 1157 1141 1158 1144 1167 1155 1172 1152 1182 1158 1171 1151 1173 1153 1183 1160 1172 1152 1173 1153 1174 1154 1183 1160 1167 1155 1177 1162 1166 1156 1175 1157 1185 1164 1174 1154 1168 1149 1178 1165 1167 1155 1168 1149 1169 1148 1178 1165 1170 1150 1180 1167 1169 1148 1170 1150 1171 1151 1180 1167 1177 1162 1178 1165 1187 1169 1179 1166 1189 1170 1178 1165 1179 1166 1180 1167 1189 1170 1180 1167 1181 1159 1190 1171 1182 1158 1192 1173 1181 1159 1182 1158 1183 1160 1192 1173 1183 1160 1184 1161 1193 1174 1177 1162 1187 1169 1176 1163 1184 1161 1185 1164 1194 1175 1192 1173 1202 1178 1191 1172 1192 1173 1193 1174 1202 1178 1194 1175 1204 1181 1193 1174 1187 1169 1197 1182 1186 1176 1194 1175 1195 1177 1204 1181 1188 1168 1198 1185 1187 1169 1188 1168 1189 1170 1198 1185 1189 1170 1190 1171 1199 1186 1191 1172 1201 1179 1190 1171 1250 1235 1260 1238 1249 1234 1250 1235 1251 1236 1260 1238 1251 1236 1252 1237 1261 1240 1253 1229 1263 1242 1252 1237 1253 1229 1254 1228 1263 1242 1246 1231 1247 1230 1256 1245 1255 1232 1265 1246 1254 1228 1247 1230 1248 1233 1257 1244 1248 1233 1249 1234 1258 1247 1256 1245 1257 1244 1266 1249 1265 1246 1275 1250 1264 1243 1257 1244 1258 1247 1267 1248 1259 1239 1269 1253 1258 1247 1260 1238 1270 1254 1259 1239 1260 1238 1261 1240 1270 1254 1262 1241 1272 1256 1261 1240 1263 1242 1273 1257 1262 1241 1263 1242 1264 1243 1273 1257 1270 1254 1271 1255 1280 1259 1272 1256 1282 1260 1271 1255 1273 1257 1283 1261 1272 1256 1273 1257 1274 1251 1283 1261 1267 1248 1277 1263 1266 1249 1275 1250 1285 1265 1274 1251 1267 1248 1268 1252 1277 1263 1269 1253 1279 1267 1268 1252 1270 1254 1280 1259 1269 1253 1283 1261 1284 1262 1293 1269 1277 1263 1287 1270 1276 1264 1284 1262 1285 1265 1294 1268 1277 1263 1278 1266 1287 1270 1279 1267 1289 1274 1278 1266 1279 1267 1280 1259 1289 1274 1280 1259 1281 1258 1290 1275 1282 1260 1292 1277 1281 1258 1282 1260 1283 1261 1292 1277 1289 1274 1290 1275 1299 1279 1291 1276 1301 1280 1290 1275 1292 1277 1302 1281 1291 1276 1292 1277 1293 1269 1302 1281 1294 1268 1304 1283 1293 1269 1287 1270 1297 1284 1286 1271 1294 1268 1295 1272 1304 1283 1288 1273 1298 1287 1287 1270 1289 1274 1299 1279 1288 1273 1347 1332 1348 1335 1357 1339 1349 1336 1359 1340 1348 1335 1350 1337 1360 1341 1349 1336 1350 1337 1351 1329 1360 1341 1351 1329 1352 1328 1361 1342 1353 1330 1363 1344 1352 1328 1353 1330 1354 1331 1363 1344 1346 1333 1347 1332 1356 1346 1355 1334 1365 1347 1354 1331 1361 1342 1362 1343 1371 1349 1363 1344 1373 1350 1362 1343 1363 1344 1364 1345 1373 1350 1356 1346 1357 1339 1366 1353 1365 1347 1375 1354 1364 1345 1357 1339 1358 1338 1367 1352 1358 1338 1359 1340 1368 1355 1360 1341 1370 1357 1359 1340 1360 1341 1361 1342 1370 1357 1374 1351 1375 1354 1384 1359 1367 1352 1368 1355 1377 1361 1368 1355 1369 1356 1378 1360 1370 1357 1380 1363 1369 1356 1370 1357 1371 1349 1380 1363 1372 1348 1382 1365 1371 1349 1373 1350 1383 1366 1372 1348 1373 1350 1374 1351 1383 1366 1366 1353 1367 1352 1376 1367 1380 1363 1381 1364 1390 1369 1382 1365 1392 1370 1381 1364 1382 1365 1383 1366 1392 1370 1383 1366 1384 1359 1393 1371 1377 1361 1387 1373 1376 1367 1384 1359 1385 1358 1394 1372 1377 1361 1378 1360 1387 1373 1379 1362 1389 1377 1378 1360 1379 1362 1380 1363 1389 1377 1394 1372 1404 1378 1393 1371 1387 1373 1397 1380 1386 1374 1394 1372 1395 1375 1404 1378 1388 1376 1398 1383 1387 1373 1389 1377 1399 1384 1388 1376 1389 1377 1390 1369 1399 1384 1391 1368 1401 1386 1390 1369 1392 1370 1402 1387 1391 1368 1392 1370 1393 1371 1402 1387 1453 1433 1464 1438 1452 1432 1453 1433 1454 1434 1464 1438 1446 1436 1447 1435 1457 1442 1455 1437 1466 1443 1454 1434 1447 1435 1448 1429 1458 1441 1449 1428 1460 1445 1448 1429 1450 1430 1461 1446 1449 1428 1450 1430 1451 1431 1461 1446 1451 1431 1452 1432 1462 1447 1460 1445 1470 1448 1459 1444 1461 1446 1471 1450 1460 1445 1461 1446 1462 1447 1471 1450 1462 1447 1463 1439 1472 1451 1464 1438 1474 1453 1463 1439 1464 1438 1465 1440 1474 1453 1457 1442 1458 1441 1467 1456 1466 1443 1476 1457 1465 1440 1458 1441 1459 1444 1468 1455 1473 1452 1483 1458 1472 1451 1474 1453 1484 1460 1473 1452 1475 1454 1485 1461 1474 1453 1467 1456 1468 1455 1477 1463 1475 1454 1476 1457 1485 1461 1468 1455 1469 1449 1478 1462 1470 1448 1480 1466 1469 1449 1470 1448 1471 1450 1480 1466 1471 1450 1472 1451 1481 1467 1485 1461 1486 1464 1495 1469 1478 1462 1479 1465 1488 1471 1480 1466 1490 1472 1479 1465 1480 1466 1481 1467 1490 1472 1481 1467 1482 1459 1491 1473 1483 1458 1493 1475 1482 1459 1483 1458 1484 1460 1493 1475 1485 1461 1495 1469 1484 1460 1478 1462 1488 1471 1477 1463 1492 1474 1502 1478 1491 1473 1493 1475 1503 1480 1492 1474 1493 1475 1494 1476 1503 1480 1495 1469 1505 1482 1494 1476 1488 1471 1498 1483 1487 1477 1495 1469 1496 1468 1505 1482 1489 1470 1499 1486 1488 1471 1490 1472 1500 1487 1489 1470 1490 1472 1491 1473 1500 1487 1548 1530 1549 1533 857 850 1550 1534 859 857 1549 1533 855 1537 860 840 1550 1534 1551 1536 861 843 855 1537 1552 1535 862 845 1551 1536 1553 1529 863 847 1552 1535 1554 1528 864 854 1553 1529 1547 1531 1548 1530 856 1540 1555 1532 865 1541 1554 1528

+
+ + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

300 826 706 826 715 826 700 827 714 827 715 827 350 828 707 828 715 828 400 829 708 829 715 829 50 830 701 830 715 830 450 831 709 831 715 831 100 832 702 832 715 832 500 833 710 833 715 833 150 834 703 834 715 834 550 835 711 835 715 835 200 836 704 836 715 836 600 837 712 837 715 837 250 838 705 838 715 838 651 839 713 839 715 839 1155 1680 1570 1680 1561 1680 1555 1681 1570 1681 1569 1681 1205 1682 1570 1682 1562 1682 1255 1683 1570 1683 1563 1683 905 1684 1570 1684 1556 1684 1305 1685 1570 1685 1564 1685 955 1686 1570 1686 1557 1686 1355 1687 1570 1687 1565 1687 1005 1688 1570 1688 1558 1688 1405 1689 1570 1689 1566 1689 1055 1690 1570 1690 1559 1690 1455 1691 1570 1691 1567 1691 1105 1692 1570 1692 1560 1692 1506 1693 1570 1693 1568 1693

+
+
+
+
+ + + + + 0.6858805 -0.3173701 0.6548619 7.481132 0.7276338 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953432 0.4452454 5.343665 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 0.5567018 0 0 0 0 0.5567018 0 0 0 0 0.5567018 1.164695 0 0 0 1 + + + + + + + + + + + + + + + +
diff --git a/models/parachute_small/model.config b/models/parachute_small/model.config new file mode 100644 index 0000000..83e179b --- /dev/null +++ b/models/parachute_small/model.config @@ -0,0 +1,18 @@ + + + + Parachute small + 1.0 + model.sdf + Apache License, Version 2.0 + + Aurelien Roy + aurroy@hotmail.com + + + + A parachute. It avoids hitting the ground too hard ;-) + This model has been imported from github.com/AurelienRoy/ardupilot_sitl_gazebo_plugin.git + + + diff --git a/models/parachute_small/model.sdf b/models/parachute_small/model.sdf new file mode 100644 index 0000000..1e3ffa2 --- /dev/null +++ b/models/parachute_small/model.sdf @@ -0,0 +1,66 @@ + + + + 0 0 0 0 0 0 + + 0 0 0 0 0 0 + + 0 0 2.3 0 0 0 + 0.1 + + 0.06250 + 0.00 + 0.00 + 0.06250 + 0.00 + 0.06250 + + + + 0 0 2.3 0 0 0 + + + 1.25 + + + + + 0 0 0 0 0 0 + + + 2 2 2 + meshes/parachute_small.dae + + + + + + + + 0.025 + + + + 0.0 0.3 0.7 + 0.0 0.3 0.7 + 0.1 0.1 0.1 1 + + + + + 0 + 0 + 1.75 + 1.5708 + 0 + 0.01 + 0 0 1.25 + 3 + 1.204 + 0 0 0 + 0 0 1 + chute + + + diff --git a/models/zephyr/meshes/parachute_small.dae b/models/zephyr/meshes/parachute_small.dae new file mode 100644 index 0000000..8d3be3a --- /dev/null +++ b/models/zephyr/meshes/parachute_small.dae @@ -0,0 +1,174 @@ + + + + + Blender User + Blender 2.75.0 commit date:2015-07-07, commit time:14:56, hash:c27589e + + 2015-11-30T00:26:27 + 2015-11-30T00:26:27 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0.5200037 0.5200037 0.5200037 1 + + + 0.5200037 0.5200037 0.5200037 1 + + + 0.09782609 0.09782609 0.09782609 1 + + + 50 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.3815912 0.002340029 0.004364488 1 + + + 0.3815912 0.002340029 0.004364488 1 + + + 0.2065217 0.04548923 0.04548923 1 + + + 50 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.3508343 0.2753002 0.109524 1 + + + 0.3508343 0.2753002 0.109524 1 + + + 1 + + + + + + + + + + + + + + + + + + + + + + -0.7071068 0 0.7071068 -0.1643761 0.01479417 1.042025 -0.3247048 0.02922403 1.003378 -0.4770381 0.04293423 0.9400242 -0.6176251 0.05558729 0.8535241 -0.7430042 0.06687164 0.7460074 -0.8500881 0.07650935 0.6201215 -0.93624 0.08426314 0.4789662 -0.9993385 0.08994215 0.3260172 -1.03783 0.09340643 0.1650404 -1.050767 0.09457075 -0.03003466 -0.1661515 0.0301522 1.048885 -0.3282119 0.05956178 1.026631 -0.4821906 0.0875048 0.9618088 -0.6242961 0.1132931 0.8733041 -0.7510293 0.1362919 0.7632958 -0.8592699 0.1559346 0.6344926 -0.9463522 0.1717377 0.4900661 -1.010132 0.1833121 0.3335725 -1.049039 0.1903727 0.1688652 -1.062116 0.1927458 -1.65927e-7 -0.1627799 0.04492461 1.048885 -0.3215516 0.08874279 1.026631 -0.4724055 0.1303759 0.9618088 -0.6116273 0.1687986 0.8733041 -0.7357888 0.203065 0.7632958 -0.8418328 0.2323313 0.6344926 -0.9271481 0.2558768 0.4900661 -0.9896339 0.2731218 0.3335725 -1.027752 0.2836416 0.1688652 -1.040562 0.2871772 -1.65927e-7 -0.1545167 0.05799138 1.042025 -0.3052287 0.1145545 1.003378 -0.4484249 0.168297 0.9400242 -0.5805795 0.2178953 0.8535241 -0.6984382 0.2621285 0.7460074 -0.799099 0.2999072 0.6201215 -0.8800835 0.3303011 0.4789662 -0.9393973 0.352562 0.3260172 -0.97558 0.3661416 0.1650404 -0.9877406 0.3707056 -0.03003466 -0.1409425 0.06787472 1.03354 -0.2784147 0.1340778 0.9692877 -0.4090312 0.1969795 0.8910065 -0.5295762 0.2550308 0.809017 -0.6370812 0.3068025 0.7071068 -0.7288991 0.3510197 0.5877853 -0.8027692 0.3865936 0.4539905 -0.8568723 0.4126483 0.309017 -0.8898765 0.4285423 0.1564344 -0.9009689 0.4338841 -0.08259546 -0.1416788 0.08464962 1.042025 -0.279869 0.1672144 1.003378 -0.4111679 0.2456619 0.9400242 -0.5323426 0.3180603 0.8535241 -0.6404091 0.3826271 0.7460074 -0.7327066 0.4377723 0.6201215 -0.8069627 0.4821381 0.4789662 -0.8613485 0.5146322 0.3260172 -0.8945251 0.5344542 0.1650404 -0.9056754 0.5411163 -0.03003466 -0.1366148 0.09925705 1.048885 -0.2698658 0.1960695 1.026631 -0.3964717 0.2880541 0.9618088 -0.5133152 0.3729458 0.8733041 -0.6175192 0.4486545 0.7632958 -0.7065178 0.5133158 0.6344926 -0.7781198 0.5653375 0.4900661 -0.8305616 0.6034387 0.3335725 -0.8625524 0.6266815 0.1688652 -0.8733041 0.6344932 -1.65927e-7 -0.1271675 0.1111036 1.048885 -0.2512038 0.2194708 1.026631 -0.3690546 0.322434 0.9618088 -0.4778181 0.4174578 0.8733041 -0.5748162 0.5022025 0.7632958 -0.6576604 0.5745812 0.6344926 -0.7243108 0.6328119 0.4900661 -0.7731262 0.6754605 0.3335725 -0.8029047 0.7014773 0.1688652 -0.8129129 0.7102213 -1.65927e-7 -0.1140531 0.1192911 1.042025 -0.2252981 0.2356442 1.003378 -0.3309955 0.346195 0.9400242 -0.4285427 0.4482212 0.8535241 -0.5155377 0.5392109 0.7460074 -0.5898385 0.6169235 0.6201215 -0.6496155 0.6794453 0.4789662 -0.6933968 0.7252368 0.3260172 -0.7201043 0.7531709 0.1650404 -0.7290805 0.7625593 -0.03003466 -0.09753501 0.1223061 1.03354 -0.1926687 0.2415999 0.9692877 -0.2830582 0.3549447 0.8910065 -0.3664779 0.4595496 0.809017 -0.4408737 0.5528389 0.7071068 -0.5044137 0.6325156 0.5877853 -0.5555334 0.6966176 0.4539905 -0.592974 0.7435665 0.309017 -0.6158134 0.7722065 0.1564344 -0.6234896 0.7818322 -0.08259546 -0.09092003 0.1377392 1.042025 -0.1796016 0.272086 1.003378 -0.2638608 0.3997331 0.9400242 -0.3416229 0.5175375 0.8535241 -0.410973 0.6225985 0.7460074 -0.4702036 0.7123291 0.6201215 -0.5178562 0.7845197 0.4789662 -0.5527577 0.8373929 0.3260172 -0.5740481 0.8696468 0.1650404 -0.5812037 0.8804871 -0.03003466 -0.08001959 0.1487028 1.048885 -0.1580692 0.2937432 1.026631 -0.2322266 0.4315508 0.9618088 -0.3006659 0.558732 0.8733041 -0.3617017 0.6721556 0.7632958 -0.4138312 0.7690285 0.6344926 -0.4557708 0.8469654 0.4900661 -0.4864879 0.904047 0.3335725 -0.5052258 0.9388682 0.1688652 -0.5115235 0.9505714 -1.65927e-7 -0.0663678 0.1552772 1.048885 -0.131102 0.30673 1.026631 -0.1926078 0.4506301 0.9618088 -0.2493711 0.5834343 0.8733041 -0.2999941 0.7018724 0.7632958 -0.3432301 0.8030282 0.6344926 -0.3780146 0.8844108 0.4900661 -0.4034913 0.944016 0.3335725 -0.4190325 0.9803768 0.1688652 -0.4242557 0.9925974 -1.65927e-7 -0.05099982 0.1569637 1.042025 -0.1007444 0.3100616 1.003378 -0.1480082 0.4555248 0.9400242 -0.1916277 0.5897714 0.8535241 -0.2305286 0.7094959 0.7460074 -0.263753 0.8117505 0.6201215 -0.2904831 0.894017 0.4789662 -0.3100605 0.9542697 0.3260172 -0.322003 0.9910254 0.1650404 -0.3260167 1.003379 -0.03003466 -0.03480935 0.1525132 1.03354 -0.06876224 0.3012701 0.9692877 -0.1010218 0.4426088 0.8910065 -0.1307941 0.573049 0.809017 -0.1573456 0.6893788 0.7071068 -0.1800227 0.7887341 0.5877853 -0.1982672 0.868668 0.4539905 -0.2116296 0.9272123 0.309017 -0.2197809 0.9629258 0.1564344 -0.2225204 0.9749289 -0.08259546 -0.02215325 0.1635478 1.042025 -0.04376173 0.3230675 1.003378 -0.06429255 0.4746323 0.9400242 -0.08324044 0.6145101 0.8535241 -0.1001385 0.7392566 0.7460074 -0.1145707 0.8458004 0.6201215 -0.126182 0.9315177 0.4789662 -0.1346862 0.9942977 0.3260172 -0.1398739 1.032595 0.1650404 -0.1416173 1.045467 -0.03003466 -0.007575333 0.1686962 1.048885 -0.01496499 0.3332375 1.026631 -0.021986 0.4895734 0.9618088 -0.0284658 0.6338545 0.8733041 -0.03424459 0.762528 0.7632958 -0.03917998 0.8724257 0.6344926 -0.04315078 0.9608414 0.4900661 -0.04605913 1.025598 0.3335725 -0.04783308 1.065101 0.1688652 -0.04842925 1.078377 -1.65927e-7 0.007576942 0.1686962 1.048885 0.01496636 0.3332375 1.026631 0.02198749 0.4895734 0.9618088 0.02846699 0.6338545 0.8733041 0.03424572 0.762528 0.7632958 0.03918135 0.8724257 0.6344926 0.04315203 0.9608414 0.4900661 0.04606014 1.025598 0.3335725 0.04783433 1.065101 0.1688652 0.04843068 1.078377 -1.65927e-7 0.02215486 0.1635478 1.042025 0.04376316 0.3230676 1.003378 0.06429404 0.4746323 0.9400242 0.08324164 0.6145101 0.8535241 0.1001396 0.7392566 0.7460074 0.1145721 0.8458004 0.6201215 0.1261833 0.9315178 0.4789662 0.1346873 0.9942977 0.3260172 0.1398751 1.032595 0.1650404 0.1416187 1.045467 -0.03003466 0.0348109 0.1525132 1.03354 0.06876361 0.3012701 0.9692877 0.1010233 0.4426088 0.8910065 0.1307953 0.573049 0.809017 0.1573467 0.6893788 0.7071068 0.180024 0.7887341 0.5877853 0.1982684 0.8686681 0.4539905 0.2116307 0.9272123 0.309017 0.2197821 0.9629259 0.1564344 0.2225218 0.9749289 -0.08259546 0.05100142 0.1569638 1.042025 0.1007458 0.3100616 1.003378 0.1480097 0.4555248 0.9400242 0.1916289 0.5897714 0.8535241 0.2305297 0.7094959 0.7460074 0.2637544 0.8117505 0.6201215 0.2904844 0.8940172 0.4789662 0.3100615 0.9542697 0.3260172 0.3220043 0.9910255 0.1650404 0.3260182 1.003379 -0.03003466 0.06636947 0.1552772 1.048885 0.1311033 0.30673 1.026631 0.1926093 0.4506301 0.9618088 0.2493724 0.5834343 0.8733041 0.2999952 0.7018723 0.7632958 0.3432314 0.8030282 0.6344926 0.378016 0.884411 0.4900661 0.4034923 0.944016 0.3335725 0.4190338 0.9803769 0.1688652 0.4242572 0.9925974 -1.65927e-7 0.0800212 0.1487029 1.048885 0.1580706 0.2937433 1.026631 0.2322281 0.4315508 0.9618088 0.3006671 0.5587321 0.8733041 0.3617029 0.6721554 0.7632958 0.4138326 0.7690285 0.6344926 0.4557722 0.8469656 0.4900661 0.4864889 0.904047 0.3335725 0.5052273 0.9388684 0.1688652 0.511525 0.9505714 -1.65927e-7 0.09092164 0.1377393 1.042025 0.179603 0.272086 1.003378 0.2638623 0.3997331 0.9400242 0.3416242 0.5175376 0.8535241 0.4109742 0.6225984 0.7460074 0.4702051 0.712329 0.6201215 0.5178577 0.78452 0.4789662 0.5527587 0.8373929 0.3260172 0.5740495 0.869647 0.1650404 0.5812051 0.8804872 -0.03003466 0.09753662 0.1223061 1.03354 0.1926701 0.2415999 0.9692877 0.2830597 0.3549447 0.8910065 0.3664792 0.4595497 0.809017 0.4408748 0.5528388 0.7071068 0.5044151 0.6325156 0.5877853 0.5555347 0.6966179 0.4539905 0.592975 0.7435666 0.309017 0.6158149 0.7722067 0.1564344 0.6234911 0.7818323 -0.08259546 0.1140548 0.1192912 1.042025 0.2252996 0.2356442 1.003378 0.330997 0.3461949 0.9400242 0.4285441 0.4482213 0.8535241 0.5155389 0.5392108 0.7460074 0.58984 0.6169234 0.6201215 0.6496169 0.6794456 0.4789662 0.6933978 0.725237 0.3260172 0.7201058 0.753171 0.1650404 0.7290819 0.7625594 -0.03003466 0.1271691 0.1111037 1.048885 0.2512053 0.2194709 1.026631 0.3690561 0.322434 0.9618088 0.4778195 0.4174578 0.8733041 0.5748173 0.5022023 0.7632958 0.6576619 0.5745812 0.6344926 0.7243122 0.6328121 0.4900661 0.7731272 0.6754607 0.3335725 0.8029061 0.7014774 0.1688652 0.8129144 0.7102214 -1.65927e-7 0.1366165 0.09925711 1.048885 0.2698673 0.1960695 1.026631 0.3964732 0.2880541 0.9618088 0.5133166 0.3729459 0.8733041 0.6175203 0.4486544 0.7632958 0.7065193 0.5133159 0.6344926 0.7781212 0.5653378 0.4900661 0.8305627 0.603439 0.3335725 0.8625538 0.6266816 0.1688652 0.8733056 0.6344932 -1.65927e-7 0.1416804 0.08464968 1.042025 0.2798705 0.1672145 1.003378 0.4111695 0.2456619 0.9400242 0.532344 0.3180603 0.8535241 0.6404103 0.382627 0.7460074 0.7327082 0.4377723 0.6201215 0.8069641 0.4821384 0.4789662 0.8613495 0.5146324 0.3260172 0.8945266 0.5344544 0.1650404 0.9056769 0.5411164 -0.03003466 0.1409442 0.06787478 1.03354 0.2784162 0.1340779 0.9692877 0.4090328 0.1969795 0.8910065 0.5295776 0.2550309 0.809017 0.6370823 0.3068025 0.7071068 0.7289006 0.3510197 0.5877853 0.8027707 0.3865938 0.4539905 0.8568735 0.4126485 0.309017 0.889878 0.4285424 0.1564344 0.9009704 0.4338842 -0.08259546 0.1545184 0.05799144 1.042025 0.3052302 0.1145547 1.003378 0.4484264 0.168297 0.9400242 0.5805808 0.2178955 0.8535241 0.6984393 0.2621285 0.7460074 0.7991006 0.2999072 0.6201215 0.8800851 0.3303014 0.4789662 0.9393985 0.3525622 0.3260172 0.9755817 0.3661417 0.1650404 0.9877424 0.3707057 -0.03003466 0.1627816 0.04492467 1.048885 0.3215531 0.08874291 1.026631 0.4724071 0.1303759 0.9618088 0.6116287 0.1687987 0.8733041 0.73579 0.203065 0.7632958 0.8418343 0.2323313 0.6344926 0.9271497 0.2558771 0.4900661 0.9896349 0.273122 0.3335725 1.027753 0.2836418 0.1688652 1.040564 0.2871774 -1.65927e-7 0.1661533 0.03015226 1.048885 0.3282135 0.05956196 1.026631 0.4821921 0.08750486 0.9618088 0.6242975 0.1132933 0.8733041 0.7510305 0.136292 0.7632958 0.8592714 0.1559346 0.6344926 0.946354 0.171738 0.4900661 1.010133 0.1833124 0.3335725 1.049041 0.1903728 0.1688652 1.062118 0.1927459 -1.65927e-7 0.1643779 0.01479423 1.042025 0.3247064 0.02922415 1.003378 0.4770396 0.04293435 0.9400242 0.6176266 0.05558747 0.8535241 0.7430054 0.06687182 0.7460074 0.8500897 0.07650941 0.6201215 0.9362418 0.08426344 0.4789662 0.9993398 0.08994251 0.3260172 1.037832 0.09340655 0.1650404 1.050768 0.09457087 -0.03003466 0.1564362 0 1.03354 0.3090186 1.37144e-7 0.9692877 0.4539921 0 0.8910065 0.5877867 1.53908e-7 0.809017 0.7071079 2.06062e-7 0.7071068 0.8090186 0 0.5877853 0.8910084 2.43315e-7 0.4539905 0.9510578 3.55074e-7 0.309017 0.9876901 0 0.1564344 1.000002 0 -0.08259546 0.1643779 -0.01479411 1.042025 0.3247064 -0.02922385 1.003378 0.4770396 -0.04293417 0.9400242 0.6176266 -0.05558711 0.8535241 0.7430054 -0.06687134 0.7460074 0.8500897 -0.07650929 0.6201215 0.9362418 -0.0842629 0.4789662 0.9993399 -0.08994174 0.3260172 1.037832 -0.09340631 0.1650404 1.050768 -0.09457063 -0.03003466 0.1661533 -0.03015214 1.048885 0.3282135 -0.05956166 1.026631 0.4821922 -0.08750468 0.9618088 0.6242976 -0.1132929 0.8733041 0.7510305 -0.1362915 0.7632958 0.8592714 -0.1559345 0.6344926 0.9463541 -0.1717375 0.4900661 1.010134 -0.1833117 0.3335725 1.049041 -0.1903726 0.1688652 1.062118 -0.1927456 -1.65927e-7 0.1627816 -0.04492455 1.048885 0.3215532 -0.08874261 1.026631 0.4724071 -0.1303757 0.9618088 0.6116289 -0.1687984 0.8733041 0.73579 -0.2030646 0.7632958 0.8418344 -0.2323312 0.6344926 0.9271499 -0.2558766 0.4900661 0.9896352 -0.2731213 0.3335725 1.027753 -0.2836415 0.1688652 1.040564 -0.2871772 -1.65927e-7 0.1545184 -0.05799132 1.042025 0.3052303 -0.1145544 1.003378 0.4484265 -0.1682968 0.9400242 0.5805811 -0.2178952 0.8535241 0.6984393 -0.2621281 0.7460074 0.7991006 -0.2999071 0.6201215 0.8800853 -0.3303009 0.4789662 0.9393987 -0.3525615 0.3260172 0.9755817 -0.3661415 0.1650404 0.9877427 -0.3707056 -0.03003466 0.1409442 -0.06787472 1.03354 0.2784163 -0.1340777 0.9692877 0.4090328 -0.1969793 0.8910065 0.5295777 -0.2550306 0.809017 0.6370823 -0.306802 0.7071068 0.7289006 -0.3510196 0.5877853 0.802771 -0.3865935 0.4539905 0.8568738 -0.4126479 0.309017 0.8898781 -0.4285422 0.1564344 0.9009708 -0.4338841 -0.08259546 0.1416805 -0.08464962 1.042025 0.2798707 -0.1672143 1.003378 0.4111695 -0.2456617 0.9400242 0.5323442 -0.3180602 0.8535241 0.6404103 -0.3826266 0.7460074 0.7327082 -0.4377722 0.6201215 0.8069646 -0.4821381 0.4789662 0.8613499 -0.5146318 0.3260172 0.8945267 -0.5344542 0.1650404 0.9056773 -0.5411164 -0.03003466 0.1366165 -0.09925705 1.048885 0.2698674 -0.1960694 1.026631 0.3964733 -0.288054 0.9618088 0.5133168 -0.3729457 0.8733041 0.6175204 -0.448654 0.7632958 0.7065193 -0.5133157 0.6344926 0.7781217 -0.5653375 0.4900661 0.8305631 -0.6034384 0.3335725 0.862554 -0.6266815 0.1688652 0.873306 -0.6344932 -1.65927e-7 0.1271692 -0.1111035 1.048885 0.2512055 -0.2194707 1.026631 0.3690562 -0.322434 0.9618088 0.4778197 -0.4174576 0.8733041 0.5748174 -0.5022019 0.7632958 0.6576618 -0.5745811 0.6344926 0.7243127 -0.6328119 0.4900661 0.7731277 -0.6754602 0.3335725 0.8029063 -0.7014773 0.1688652 0.8129148 -0.7102214 -1.65927e-7 0.1140549 -0.1192911 1.042025 0.2252998 -0.2356441 1.003378 0.3309971 -0.3461949 0.9400242 0.4285442 -0.4482211 0.8535241 0.515539 -0.5392104 0.7460074 0.5898399 -0.6169234 0.6201215 0.6496174 -0.6794455 0.4789662 0.6933984 -0.7252366 0.3260172 0.720106 -0.7531709 0.1650404 0.7290824 -0.7625594 -0.03003466 0.09753668 -0.1223061 1.03354 0.1926704 -0.2415997 0.9692877 0.2830598 -0.3549447 0.8910065 0.3664794 -0.4595495 0.809017 0.4408749 -0.5528385 0.7071068 0.5044151 -0.6325156 0.5877853 0.5555351 -0.6966178 0.4539905 0.5929754 -0.7435663 0.309017 0.6158151 -0.7722066 0.1564344 0.6234914 -0.7818323 -0.08259546 0.0909217 -0.1377391 1.042025 0.1796033 -0.2720859 1.003378 0.2638624 -0.3997331 0.9400242 0.3416244 -0.5175374 0.8535241 0.4109743 -0.6225979 0.7460074 0.4702051 -0.712329 0.6201215 0.5178582 -0.7845199 0.4789662 0.5527591 -0.8373928 0.3260172 0.5740497 -0.8696469 0.1650404 0.5812055 -0.8804873 -0.03003466 0.08002126 -0.1487028 1.048885 0.1580709 -0.2937432 1.026631 0.2322282 -0.4315508 0.9618088 0.3006674 -0.558732 0.8733041 0.361703 -0.672155 0.7632958 0.4138327 -0.7690285 0.6344926 0.4557726 -0.8469656 0.4900661 0.4864894 -0.904047 0.3335725 0.5052275 -0.9388684 0.1688652 0.5115253 -0.9505716 -1.65927e-7 0.06636953 -0.1552771 1.048885 0.1311036 -0.30673 1.026631 0.1926094 -0.4506302 0.9618088 0.2493727 -0.5834342 0.8733041 0.2999954 -0.7018719 0.7632958 0.3432315 -0.8030282 0.6344926 0.3780164 -0.884411 0.4900661 0.4034928 -0.944016 0.3335725 0.4190341 -0.9803769 0.1688652 0.4242575 -0.9925976 -1.65927e-7 0.05100148 -0.1569637 1.042025 0.100746 -0.3100616 1.003378 0.1480098 -0.4555248 0.9400242 0.1916292 -0.5897714 0.8535241 0.23053 -0.7094955 0.7460074 0.2637545 -0.8117505 0.6201215 0.2904847 -0.8940173 0.4789662 0.310062 -0.9542697 0.3260172 0.3220046 -0.9910255 0.1650404 0.3260185 -1.003379 -0.03003466 0.03481096 -0.1525132 1.03354 0.06876385 -0.3012701 0.9692877 0.1010233 -0.4426088 0.8910065 0.1307955 -0.573049 0.809017 0.1573471 -0.6893784 0.7071068 0.1800242 -0.7887341 0.5877853 0.1982687 -0.8686683 0.4539905 0.2116311 -0.9272123 0.309017 0.2197824 -0.9629259 0.1564344 0.222522 -0.9749292 -0.08259546 0.02215492 -0.1635478 1.042025 0.04376339 -0.3230676 1.003378 0.06429409 -0.4746324 0.9400242 0.08324193 -0.6145101 0.8535241 0.10014 -0.7392562 0.7460074 0.1145722 -0.8458004 0.6201215 0.1261836 -0.931518 0.4789662 0.1346877 -0.9942978 0.3260172 0.1398754 -1.032595 0.1650404 0.141619 -1.045467 -0.03003466 0.007577002 -0.1686962 1.048885 0.0149666 -0.3332376 1.026631 0.02198755 -0.4895735 0.9618088 0.02846735 -0.6338546 0.8733041 0.03424614 -0.7625275 0.7632958 0.03918141 -0.8724257 0.6344926 0.04315233 -0.9608417 0.4900661 0.04606062 -1.025598 0.3335725 0.04783457 -1.065101 0.1688652 0.04843086 -1.078378 -1.65927e-7 -0.007575213 -0.1686962 1.048885 -0.01496475 -0.3332376 1.026631 -0.02198594 -0.4895736 0.9618088 -0.0284655 -0.6338546 0.8733041 -0.03424412 -0.7625275 0.7632958 -0.03917986 -0.8724257 0.6344926 -0.04315048 -0.9608418 0.4900661 -0.04605865 -1.025598 0.3335725 -0.04783284 -1.065101 0.1688652 -0.04842913 -1.078378 -1.65927e-7 -0.02215313 -0.1635478 1.042025 -0.04376149 -0.3230677 1.003378 -0.06429249 -0.4746325 0.9400242 -0.08324015 -0.6145102 0.8535241 -0.100138 -0.7392562 0.7460074 -0.1145706 -0.8458004 0.6201215 -0.1261817 -0.9315181 0.4789662 -0.1346858 -0.9942979 0.3260172 -0.1398736 -1.032595 0.1650404 -0.1416172 -1.045467 -0.03003466 -0.03480923 -0.1525132 1.03354 -0.068762 -0.3012703 0.9692877 -0.1010218 -0.442609 0.8910065 -0.1307938 -0.5730491 0.809017 -0.1573451 -0.6893784 0.7071068 -0.1800226 -0.7887341 0.5877853 -0.198267 -0.8686685 0.4539905 -0.2116292 -0.9272125 0.309017 -0.2197807 -0.962926 0.1564344 -0.2225204 -0.9749292 -0.08259546 -0.0509997 -0.1569638 1.042025 -0.1007442 -0.3100618 1.003378 -0.1480082 -0.4555249 0.9400242 -0.1916275 -0.5897715 0.8535241 -0.2305281 -0.7094956 0.7460074 -0.2637529 -0.8117505 0.6201215 -0.2904829 -0.8940176 0.4789662 -0.3100601 -0.95427 0.3260172 -0.3220028 -0.9910256 0.1650404 -0.3260167 -1.003379 -0.03003466 -0.06636774 -0.1552772 1.048885 -0.1311018 -0.3067302 1.026631 -0.1926078 -0.4506303 0.9618088 -0.2493709 -0.5834344 0.8733041 -0.2999935 -0.7018721 0.7632958 -0.34323 -0.8030282 0.6344926 -0.3780146 -0.8844114 0.4900661 -0.4034909 -0.9440163 0.3335725 -0.4190323 -0.980377 0.1688652 -0.4242558 -0.9925978 -1.65927e-7 -0.08001953 -0.1487028 1.048885 -0.1580691 -0.2937435 1.026631 -0.2322266 -0.4315509 0.9618088 -0.3006657 -0.5587322 0.8733041 -0.3617011 -0.6721552 0.7632958 -0.4138311 -0.7690285 0.6344926 -0.4557709 -0.846966 0.4900661 -0.4864875 -0.9040473 0.3335725 -0.5052258 -0.9388685 0.1688652 -0.5115236 -0.9505719 -1.65927e-7 -0.09091997 -0.1377392 1.042025 -0.1796016 -0.2720863 1.003378 -0.2638608 -0.3997333 0.9400242 -0.3416227 -0.5175377 0.8535241 -0.4109724 -0.6225982 0.7460074 -0.4702036 -0.712329 0.6201215 -0.5178564 -0.7845204 0.4789662 -0.5527574 -0.8373932 0.3260172 -0.5740481 -0.8696471 0.1650404 -0.5812038 -0.8804876 -0.03003466 -0.09753501 -0.1223061 1.03354 -0.1926687 -0.2416001 0.9692877 -0.2830583 -0.3549449 0.8910065 -0.3664778 -0.4595498 0.809017 -0.4408732 -0.5528387 0.7071068 -0.5044137 -0.6325156 0.5877853 -0.5555335 -0.6966182 0.4539905 -0.5929738 -0.7435668 0.309017 -0.6158135 -0.7722069 0.1564344 -0.6234898 -0.7818326 -0.08259546 -0.1643761 0.01479417 1.042025 -0.1140531 -0.1192911 1.042025 -0.2252981 -0.2356445 1.003378 -0.3309956 -0.3461951 0.9400242 -0.4285426 -0.4482215 0.8535241 -0.5155372 -0.5392107 0.7460074 -0.5898385 -0.6169235 0.6201215 -0.6496158 -0.6794459 0.4789662 -0.6933968 -0.7252372 0.3260172 -0.7201044 -0.7531712 0.1650404 -0.7290807 -0.7625597 -0.03003466 -0.1271675 -0.1111037 1.048885 -0.2512039 -0.2194711 1.026631 -0.3690548 -0.3224342 0.9618088 -0.4778181 -0.417458 0.8733041 -0.5748157 -0.5022022 0.7632958 -0.6576604 -0.5745812 0.6344926 -0.7243111 -0.6328125 0.4900661 -0.7731262 -0.6754609 0.3335725 -0.8029047 -0.7014777 0.1688652 -0.8129132 -0.7102218 -1.65927e-7 -0.1366148 -0.09925711 1.048885 -0.2698659 -0.1960698 1.026631 -0.3964719 -0.2880543 0.9618088 -0.5133152 -0.3729461 0.8733041 -0.6175187 -0.4486544 0.7632958 -0.7065179 -0.5133159 0.6344926 -0.7781201 -0.5653381 0.4900661 -0.8305616 -0.6034392 0.3335725 -0.8625525 -0.6266818 0.1688652 -0.8733044 -0.6344936 -1.65927e-7 -0.1416788 -0.08464968 1.042025 -0.2798691 -0.1672146 1.003378 -0.4111682 -0.245662 0.9400242 -0.5323426 -0.3180605 0.8535241 -0.6404086 -0.382627 0.7460074 -0.7327067 -0.4377724 0.6201215 -0.8069632 -0.4821387 0.4789662 -0.8613486 -0.5146325 0.3260172 -0.8945252 -0.5344546 0.1650404 -0.9056757 -0.5411167 -0.03003466 -0.1409426 -0.06787478 1.03354 -0.2784148 -0.134078 0.9692877 -0.4090315 -0.1969795 0.8910065 -0.5295762 -0.2550311 0.809017 -0.6370807 -0.3068025 0.7071068 -0.7288992 -0.3510198 0.5877853 -0.8027697 -0.3865941 0.4539905 -0.8568725 -0.4126486 0.309017 -0.8898767 -0.4285426 0.1564344 -0.9009693 -0.4338846 -0.08259546 -0.1545168 -0.05799144 1.042025 -0.3052289 -0.1145547 1.003378 -0.4484252 -0.1682971 0.9400242 -0.5805795 -0.2178956 0.8535241 -0.6984377 -0.2621286 0.7460074 -0.7990992 -0.2999073 0.6201215 -0.8800841 -0.3303016 0.4789662 -0.9393975 -0.3525623 0.3260172 -0.9755803 -0.3661419 0.1650404 -0.9877412 -0.370706 -0.03003466 -0.1627799 -0.04492467 1.048885 -0.3215517 -0.08874297 1.026631 -0.4724058 -0.1303759 0.9618088 -0.6116273 -0.1687988 0.8733041 -0.7357884 -0.2030651 0.7632958 -0.8418329 -0.2323314 0.6344926 -0.9271488 -0.2558772 0.4900661 -0.9896341 -0.2731221 0.3335725 -1.027752 -0.2836419 0.1688652 -1.040563 -0.2871776 -1.65927e-7 -0.1661517 -0.03015226 1.048885 -0.3282122 -0.05956196 1.026631 -0.4821909 -0.08750486 0.9618088 -0.6242962 -0.1132934 0.8733041 -0.7510289 -0.136292 0.7632958 -0.85927 -0.1559347 0.6344926 -0.946353 -0.171738 0.4900661 -1.010133 -0.1833124 0.3335725 -1.04904 -0.190373 0.1688652 -1.062117 -0.1927461 -1.65927e-7 -0.1643763 -0.01479423 1.042025 -0.3247051 -0.02922415 1.003378 -0.4770384 -0.04293429 0.9400242 -0.6176252 -0.05558753 0.8535241 -0.7430039 -0.06687182 0.7460074 -0.8500883 -0.07650947 0.6201215 -0.9362408 -0.08426344 0.4789662 -0.9993388 -0.08994239 0.3260172 -1.03783 -0.09340667 0.1650404 -1.050767 -0.09457105 -0.03003466 -0.1564346 0 1.03354 -0.3090173 0 0.9692877 -0.4539908 0 0.8910065 -0.5877854 -1.96269e-7 0.809017 -0.8090173 0 0.5877853 -0.8910074 -1.73918e-7 0.4539905 -0.9510569 -1.96269e-7 0.309017 -0.9876888 -2.0372e-7 0.1564344 -1.000001 -2.40973e-7 -0.08259546 -0.8817924 0.4246492 -0.06851685 -0.6102191 0.7651914 -0.06851685 -0.2177842 0.9541782 -0.06851685 0.2177856 0.9541782 -0.06851685 0.6102205 0.7651916 -0.06851685 0.8817939 0.4246493 -0.06851685 0.9787175 0 -0.06851685 0.8817943 -0.4246492 -0.06851685 0.6102209 -0.7651916 -0.06851685 0.2177858 -0.9541785 -0.06851685 -0.2177842 -0.9541786 -0.06851685 -0.6102192 -0.7651919 -0.06851685 -0.8817928 -0.4246497 -0.06851685 -0.9787164 -2.38385e-7 -0.06851685 7.32286e-7 -1.21337e-7 -2.088751 -0.1661515 0.0301522 1.048885 -0.1627799 0.04492461 1.048885 -0.1545167 0.05799138 1.042025 -0.1409425 0.06787472 1.03354 -0.1416788 0.08464962 1.042025 -0.1366148 0.09925705 1.048885 -0.1271675 0.1111036 1.048885 -0.1140531 0.1192911 1.042025 -0.09753501 0.1223061 1.03354 -0.09092003 0.1377392 1.042025 -0.08001959 0.1487028 1.048885 -0.0663678 0.1552772 1.048885 -0.05099982 0.1569637 1.042025 -0.03480935 0.1525132 1.03354 -0.02215325 0.1635478 1.042025 -0.007575333 0.1686962 1.048885 0.007576942 0.1686962 1.048885 0.02215486 0.1635478 1.042025 0.0348109 0.1525132 1.03354 0.05100142 0.1569638 1.042025 0.06636947 0.1552772 1.048885 0.0800212 0.1487029 1.048885 0.09092164 0.1377393 1.042025 0.09753662 0.1223061 1.03354 0.1140548 0.1192912 1.042025 0.1271691 0.1111037 1.048885 0.1366165 0.09925711 1.048885 0.1416804 0.08464968 1.042025 0.1409442 0.06787478 1.03354 0.1545184 0.05799144 1.042025 0.1627816 0.04492467 1.048885 0.1661533 0.03015226 1.048885 0.1643779 0.01479423 1.042025 0.1564362 0 1.03354 0.1643779 -0.01479411 1.042025 0.1661533 -0.03015214 1.048885 0.1627816 -0.04492455 1.048885 0.1545184 -0.05799132 1.042025 0.1409442 -0.06787472 1.03354 0.1416805 -0.08464962 1.042025 0.1366165 -0.09925705 1.048885 0.1271692 -0.1111035 1.048885 0.1140549 -0.1192911 1.042025 0.09753668 -0.1223061 1.03354 0.0909217 -0.1377391 1.042025 0.08002126 -0.1487028 1.048885 0.06636953 -0.1552771 1.048885 0.05100148 -0.1569637 1.042025 0.03481096 -0.1525132 1.03354 0.02215492 -0.1635478 1.042025 0.007577002 -0.1686962 1.048885 -0.007575213 -0.1686962 1.048885 -0.02215313 -0.1635478 1.042025 -0.03480923 -0.1525132 1.03354 -0.0509997 -0.1569638 1.042025 -0.06636774 -0.1552772 1.048885 -0.08001953 -0.1487028 1.048885 -0.09091997 -0.1377392 1.042025 -0.09753501 -0.1223061 1.03354 -0.1140531 -0.1192911 1.042025 -0.1271675 -0.1111037 1.048885 -0.1366148 -0.09925711 1.048885 -0.1416788 -0.08464968 1.042025 -0.1409426 -0.06787478 1.03354 -0.1545168 -0.05799144 1.042025 -0.1627799 -0.04492467 1.048885 -0.1661517 -0.03015226 1.048885 -0.1643763 -0.01479423 1.042025 -0.1564346 0 1.03354 -0.08197021 0.007377505 1.053733 -0.08134949 0.01476287 1.053802 -0.07969868 0.02199566 1.053802 -0.07705354 0.02891898 1.053733 -0.07426726 0.03576564 1.053202 -0.07065159 0.04221284 1.053733 -0.06688791 0.04859751 1.053802 -0.06226241 0.05439776 1.053802 -0.05687528 0.05948776 1.053733 -0.05139428 0.06444746 1.053202 -0.04533928 0.06868743 1.053733 -0.03917819 0.07280683 1.053802 -0.03249406 0.07602572 1.053802 -0.02543199 0.07827425 1.053733 -0.01834189 0.0803647 1.053202 -0.01104688 0.08155757 1.053733 -0.003708541 0.08259582 1.053802 0.00371015 0.08259582 1.053802 0.01104855 0.08155763 1.053733 0.0183435 0.0803647 1.053202 0.02543365 0.0782743 1.053733 0.03249573 0.07602572 1.053802 0.03917986 0.07280683 1.053802 0.04534095 0.06868743 1.053733 0.05139595 0.06444752 1.053202 0.05687695 0.05948781 1.053733 0.06226408 0.05439776 1.053802 0.06688958 0.04859757 1.053802 0.07065325 0.0422129 1.053733 0.07426893 0.03576564 1.053202 0.07705527 0.02891904 1.053733 0.07970035 0.02199572 1.053802 0.08135122 0.01476293 1.053802 0.08197194 0.007377564 1.053733 0.08243227 0 1.053202 0.08197194 -0.007377445 1.053733 0.08135122 -0.01476287 1.053802 0.07970035 -0.0219956 1.053802 0.07705527 -0.02891898 1.053733 0.07426893 -0.03576558 1.053202 0.07065325 -0.04221278 1.053733 0.06688958 -0.04859751 1.053802 0.06226408 -0.0543977 1.053802 0.05687701 -0.05948776 1.053733 0.05139595 -0.06444746 1.053202 0.04534101 -0.06868737 1.053733 0.03917986 -0.07280677 1.053802 0.03249579 -0.07602566 1.053802 0.02543371 -0.07827425 1.053733 0.01834356 -0.08036464 1.053202 0.01104855 -0.08155757 1.053733 0.00371021 -0.08259576 1.053802 -0.003708481 -0.08259576 1.053802 -0.01104682 -0.08155757 1.053733 -0.01834183 -0.08036464 1.053202 -0.02543199 -0.07827425 1.053733 -0.03249406 -0.07602566 1.053802 -0.03917813 -0.07280677 1.053802 -0.04533928 -0.06868737 1.053733 -0.05139428 -0.06444746 1.053202 -0.05687528 -0.05948776 1.053733 -0.06226235 -0.05439776 1.053802 -0.06688791 -0.04859751 1.053802 -0.07065159 -0.04221284 1.053733 -0.07426732 -0.03576564 1.053202 -0.0770536 -0.02891898 1.053733 -0.07969874 -0.02199566 1.053802 -0.08134955 -0.01476287 1.053802 -0.08197033 -0.007377505 1.053733 -0.0824306 0 1.053202 -0.692779 0 0.6953256 -0.1610454 0.01449441 1.023457 -0.3181254 0.02863186 0.9855934 -0.467372 0.0420643 0.9235236 -0.6051104 0.054461 0.8387761 -0.727949 0.06551665 0.733438 -0.8328631 0.07495909 0.610103 -0.9172693 0.08255577 0.4718078 -0.9790893 0.08811968 0.3219579 -1.016801 0.09151381 0.1642429 -1.029475 0.09265452 -0.02687948 -0.1627849 0.02954125 1.030179 -0.3215615 0.05835491 1.008375 -0.4724201 0.08573174 0.9448667 -0.6116462 0.1109975 0.8581554 -0.7358115 0.1335302 0.7503761 -0.8418588 0.1527749 0.6241828 -0.9271766 0.1682578 0.4826827 -0.9896644 0.1795977 0.3293601 -1.027783 0.1865153 0.1679901 -1.040595 0.1888402 0.002546489 -0.1594815 0.04401427 1.030179 -0.3150361 0.08694463 1.008375 -0.4628334 0.1277341 0.9448667 -0.5992342 0.1653783 0.8581554 -0.7208798 0.1989504 0.7503761 -0.824775 0.2276237 0.6241828 -0.9083617 0.250692 0.4826827 -0.9695813 0.2675876 0.3293601 -1.006927 0.2778943 0.1679901 -1.019478 0.2813583 0.002546489 -0.1513857 0.05681627 1.023457 -0.299044 0.1122334 0.9855934 -0.4393386 0.1648868 0.9235236 -0.5688154 0.2134802 0.8387761 -0.684286 0.2568171 0.733438 -0.7829072 0.2938303 0.610103 -0.8622506 0.3236083 0.4718078 -0.9203627 0.3454182 0.3219579 -0.9558122 0.3587226 0.1642429 -0.9677264 0.3631941 -0.02687948 -0.1380866 0.06649941 1.015144 -0.2727732 0.131361 0.9521941 -0.4007432 0.1929881 0.8754991 -0.5188456 0.2498632 0.7951709 -0.6241722 0.3005859 0.6953256 -0.7141297 0.3439071 0.5784218 -0.786503 0.3787602 0.4473382 -0.8395099 0.404287 0.3053022 -0.8718453 0.4198589 0.1558112 -0.8827129 0.4250925 -0.07837527 -0.138808 0.08293437 1.023457 -0.2741981 0.1638262 0.9855934 -0.4028366 0.2406841 0.9235236 -0.5215559 0.3116155 0.8387761 -0.6274328 0.3748741 0.733438 -0.7178601 0.4289019 0.610103 -0.7906115 0.4723687 0.4718078 -0.8438953 0.5042044 0.3219579 -0.8763996 0.5236248 0.1642429 -0.887324 0.5301519 -0.02687948 -0.1338466 0.09724581 1.030179 -0.2643976 0.1920966 1.008375 -0.3884381 0.2822174 0.9448667 -0.5029141 0.3653889 0.8581554 -0.6050066 0.4395636 0.7503761 -0.6922019 0.5029147 0.6241828 -0.762353 0.5538824 0.4826827 -0.8137322 0.5912115 0.3293601 -0.8450748 0.6139833 0.1679901 -0.8556087 0.6216367 0.002546489 -0.1245907 0.1088523 1.030179 -0.2461138 0.2150238 1.008375 -0.3615766 0.3159007 0.9448667 -0.4681363 0.408999 0.8581554 -0.5631689 0.4920265 0.7503761 -0.6443344 0.5629386 0.6241828 -0.7096344 0.6199895 0.4826827 -0.7574607 0.6617739 0.3293601 -0.7866357 0.6872636 0.1679901 -0.7964411 0.6958304 0.002546489 -0.1117421 0.1168739 1.023457 -0.220733 0.2308694 0.9855934 -0.3242886 0.3391802 0.9235236 -0.4198593 0.4391391 0.8387761 -0.5050916 0.5282851 0.733438 -0.5778868 0.6044231 0.610103 -0.6364526 0.665678 0.4718078 -0.6793468 0.7105417 0.3219579 -0.7055131 0.7379097 0.1642429 -0.7143074 0.7471079 -0.02687948 -0.0955587 0.1198278 1.015144 -0.1887647 0.2367044 0.9521941 -0.2773227 0.3477526 0.8754991 -0.3590521 0.4502379 0.7951709 -0.4319404 0.541637 0.6953256 -0.4941929 0.6196992 0.5784218 -0.5442768 0.6825023 0.4473382 -0.5809587 0.7285 0.3053022 -0.6033354 0.7565596 0.1558112 -0.6108561 0.7659902 -0.07837527 -0.08907771 0.1349482 1.023457 -0.1759624 0.2665728 0.9855934 -0.2585142 0.3916335 0.9235236 -0.3347007 0.5070509 0.8387761 -0.4026456 0.609983 0.733438 -0.460676 0.6978955 0.610103 -0.5073632 0.7686234 0.4718078 -0.5415574 0.8204252 0.3219579 -0.5624164 0.8520255 0.1642429 -0.569427 0.8626461 -0.02687948 -0.07839816 0.1456897 1.030179 -0.1548663 0.2877912 1.008375 -0.2275211 0.4228064 0.9448667 -0.2945736 0.5474107 0.8581554 -0.3543727 0.658536 0.7503761 -0.4054459 0.753446 0.6241828 -0.4465357 0.8298037 0.4826827 -0.4766303 0.8857287 0.3293601 -0.4949886 0.9198443 0.1679901 -0.5011587 0.9313103 0.002546489 -0.065023 0.1521309 1.030179 -0.1284455 0.3005148 1.008375 -0.188705 0.4414992 0.9448667 -0.2443182 0.5716124 0.8581554 -0.2939154 0.6876506 0.7503761 -0.3362753 0.7867568 0.6241828 -0.3703551 0.8664904 0.4826827 -0.3953155 0.9248878 0.3293601 -0.4105418 0.9605118 0.1679901 -0.4156592 0.9724848 0.002546489 -0.04996639 0.1537833 1.023457 -0.09870302 0.3037789 0.9855934 -0.1450092 0.4462947 0.9235236 -0.1877448 0.5778211 0.8387761 -0.2258574 0.6951197 0.733438 -0.2584087 0.7953023 0.610103 -0.2845971 0.8759019 0.4718078 -0.3037778 0.9349337 0.3219579 -0.3154784 0.9709447 0.1642429 -0.3194108 0.9830477 -0.02687948 -0.03410398 0.1494229 1.015144 -0.06736892 0.2951655 0.9521941 -0.09897482 0.4336404 0.8754991 -0.1281438 0.5614376 0.7951709 -0.1541574 0.6754102 0.6953256 -0.176375 0.7727523 0.5784218 -0.1942497 0.8510665 0.4473382 -0.2073414 0.9084246 0.3053022 -0.2153275 0.9434144 0.1558112 -0.2180115 0.9551743 -0.07837527 -0.02170431 0.1602339 1.023457 -0.04287499 0.3165213 0.9855934 -0.06298983 0.465015 0.9235236 -0.08155375 0.6020585 0.8387761 -0.09810942 0.7242773 0.733438 -0.1122492 0.8286623 0.610103 -0.1236252 0.9126428 0.4718078 -0.1319571 0.9741507 0.3219579 -0.1370397 1.011672 0.1642429 -0.1387478 1.024283 -0.02687948 -0.007421791 0.165278 1.030179 -0.01466172 0.3264852 1.008375 -0.02154052 0.4796534 0.9448667 -0.02788901 0.621011 0.8581554 -0.03355067 0.7470772 0.7503761 -0.03838604 0.8547481 0.6241828 -0.04227644 0.9413722 0.4826827 -0.04512584 1.004816 0.3293601 -0.04686385 1.043519 0.1679901 -0.04744791 1.056527 0.002546489 0.0074234 0.165278 1.030179 0.01466315 0.3264852 1.008375 0.02154195 0.4796534 0.9448667 0.0278902 0.621011 0.8581554 0.03355181 0.7470772 0.7503761 0.03838741 0.8547481 0.6241828 0.04227769 0.9413722 0.4826827 0.04512685 1.004816 0.3293601 0.0468651 1.043519 0.1679901 0.04744935 1.056527 0.002546489 0.02170592 0.1602339 1.023457 0.04287642 0.3165214 0.9855934 0.06299126 0.465015 0.9235236 0.08155494 0.6020585 0.8387761 0.09811055 0.7242773 0.733438 0.1122506 0.8286623 0.610103 0.1236265 0.9126428 0.4718078 0.1319581 0.9741507 0.3219579 0.1370409 1.011672 0.1642429 0.1387492 1.024283 -0.02687948 0.03410553 0.1494229 1.015144 0.06737029 0.2951656 0.9521941 0.09897631 0.4336404 0.8754991 0.128145 0.5614376 0.7951709 0.1541585 0.6754102 0.6953256 0.1763763 0.7727523 0.5784218 0.194251 0.8510667 0.4473382 0.2073425 0.9084246 0.3053022 0.2153288 0.9434145 0.1558112 0.2180129 0.9551743 -0.07837527 0.049968 0.1537833 1.023457 0.09870445 0.303779 0.9855934 0.1450106 0.4462947 0.9235236 0.187746 0.5778211 0.8387761 0.2258586 0.6951196 0.733438 0.2584101 0.7953023 0.610103 0.2845984 0.8759021 0.4718078 0.3037789 0.9349337 0.3219579 0.3154796 0.9709448 0.1642429 0.3194122 0.9830477 -0.02687948 0.06502467 0.1521309 1.030179 0.1284469 0.3005148 1.008375 0.1887065 0.4414992 0.9448667 0.2443194 0.5716124 0.8581554 0.2939165 0.6876506 0.7503761 0.3362767 0.7867568 0.6241828 0.3703564 0.8664905 0.4826827 0.3953166 0.9248878 0.3293601 0.4105431 0.9605119 0.1679901 0.4156606 0.9724848 0.002546489 0.07839977 0.1456898 1.030179 0.1548677 0.2877913 1.008375 0.2275226 0.4228064 0.9448667 0.2945749 0.5474107 0.8581554 0.3543738 0.6585358 0.7503761 0.4054473 0.753446 0.6241828 0.446537 0.8298039 0.4826827 0.4766314 0.8857287 0.3293601 0.4949901 0.9198445 0.1679901 0.5011602 0.9313104 0.002546489 0.08907938 0.1349483 1.023457 0.1759638 0.2665728 0.9855934 0.2585158 0.3916335 0.9235236 0.334702 0.5070509 0.8387761 0.4026468 0.6099829 0.733438 0.4606775 0.6978954 0.610103 0.5073646 0.7686236 0.4718078 0.5415584 0.8204252 0.3219579 0.5624178 0.8520257 0.1642429 0.5694285 0.8626462 -0.02687948 0.09556031 0.1198279 1.015144 0.1887661 0.2367044 0.9521941 0.2773241 0.3477526 0.8754991 0.3590534 0.450238 0.7951709 0.4319416 0.5416368 0.6953256 0.4941944 0.6196991 0.5784218 0.5442782 0.6825026 0.4473382 0.5809597 0.7285 0.3053022 0.6033369 0.7565597 0.1558112 0.6108575 0.7659903 -0.07837527 0.1117438 0.116874 1.023457 0.2207344 0.2308694 0.9855934 0.3242902 0.3391801 0.9235236 0.4198606 0.4391391 0.8387761 0.5050928 0.528285 0.733438 0.5778883 0.6044229 0.610103 0.636454 0.6656782 0.4718078 0.6793478 0.7105418 0.3219579 0.7055146 0.7379098 0.1642429 0.7143089 0.7471079 -0.02687948 0.1245924 0.1088525 1.030179 0.2461152 0.2150238 1.008375 0.3615781 0.3159006 0.9448667 0.4681377 0.408999 0.8581554 0.56317 0.4920264 0.7503761 0.6443359 0.5629386 0.6241828 0.7096357 0.6199897 0.4826827 0.7574617 0.6617741 0.3293601 0.7866371 0.6872637 0.1679901 0.7964427 0.6958304 0.002546489 0.1338483 0.09724593 1.030179 0.2643991 0.1920967 1.008375 0.3884396 0.2822174 0.9448667 0.5029155 0.3653891 0.8581554 0.6050078 0.4395635 0.7503761 0.6922034 0.5029147 0.6241828 0.7623544 0.5538825 0.4826827 0.8137333 0.5912117 0.3293601 0.8450763 0.6139835 0.1679901 0.8556102 0.6216368 0.002546489 0.1388096 0.08293449 1.023457 0.2741997 0.1638263 0.9855934 0.4028381 0.2406841 0.9235236 0.5215573 0.3116157 0.8387761 0.6274339 0.374874 0.733438 0.7178617 0.4289019 0.610103 0.7906129 0.472369 0.4718078 0.8438963 0.5042046 0.3219579 0.8764012 0.523625 0.1642429 0.8873255 0.530152 -0.02687948 0.1380883 0.06649947 1.015144 0.2727747 0.1313611 0.9521941 0.4007447 0.1929881 0.8754991 0.5188469 0.2498633 0.7951709 0.6241734 0.3005858 0.6953256 0.7141312 0.3439071 0.5784218 0.7865045 0.3787605 0.4473382 0.839511 0.4042872 0.3053022 0.8718468 0.4198591 0.1558112 0.8827144 0.4250926 -0.07837527 0.1513875 0.05681639 1.023457 0.2990455 0.1122335 0.9855934 0.4393401 0.1648869 0.9235236 0.5688167 0.2134803 0.8387761 0.6842871 0.2568171 0.733438 0.7829087 0.2938303 0.610103 0.8622522 0.3236086 0.4718078 0.9203639 0.3454183 0.3219579 0.9558139 0.3587228 0.1642429 0.9677281 0.3631942 -0.02687948 0.1594833 0.04401439 1.030179 0.3150376 0.08694475 1.008375 0.4628349 0.1277341 0.9448667 0.5992355 0.1653784 0.8581554 0.7208809 0.1989504 0.7503761 0.8247766 0.2276237 0.6241828 0.9083633 0.2506923 0.4826827 0.9695824 0.2675879 0.3293601 1.006928 0.2778944 0.1679901 1.01948 0.2813584 0.002546489 0.1627866 0.02954131 1.030179 0.321563 0.05835509 1.008375 0.4724217 0.0857318 0.9448667 0.6116476 0.1109977 0.8581554 0.7358126 0.1335303 0.7503761 0.8418603 0.152775 0.6241828 0.9271784 0.1682581 0.4826827 0.9896655 0.179598 0.3293601 1.027785 0.1865154 0.1679901 1.040596 0.1888403 0.002546489 0.1610472 0.01449447 1.023457 0.318127 0.02863198 0.9855934 0.4673736 0.04206436 0.9235236 0.6051118 0.05446112 0.8387761 0.7279502 0.06551682 0.733438 0.8328647 0.07495915 0.610103 0.9172711 0.08255606 0.4718078 0.9790906 0.08812004 0.3219579 1.016803 0.09151393 0.1642429 1.029477 0.09265464 -0.02687948 0.1532664 0 1.015144 0.3027571 1.34388e-7 0.9521941 0.444793 0 0.8754991 0.5758767 1.50812e-7 0.7951709 0.6927801 2.0191e-7 0.6953256 0.7926257 0 0.5784218 0.8729543 2.38408e-7 0.4473382 0.9317869 3.47902e-7 0.3053022 0.9676769 0 0.1558112 0.9797392 0 -0.07837527 0.1610472 -0.01449435 1.023457 0.318127 -0.02863168 0.9855934 0.4673736 -0.04206418 0.9235236 0.6051119 -0.05446082 0.8387761 0.7279502 -0.06551641 0.733438 0.8328647 -0.07495898 0.610103 0.9172711 -0.08255553 0.4718078 0.9790908 -0.08811926 0.3219579 1.016803 -0.09151369 0.1642429 1.029477 -0.0926544 -0.02687948 0.1627866 -0.02954119 1.030179 0.3215631 -0.05835479 1.008375 0.4724217 -0.08573162 0.9448667 0.6116477 -0.1109973 0.8581554 0.7358126 -0.1335299 0.7503761 0.8418604 -0.1527749 0.6241828 0.9271785 -0.1682576 0.4826827 0.9896657 -0.1795973 0.3293601 1.027785 -0.1865152 0.1679901 1.040597 -0.1888401 0.002546489 0.1594833 -0.04401427 1.030179 0.3150377 -0.08694446 1.008375 0.462835 -0.127734 0.9448667 0.5992357 -0.1653781 0.8581554 0.7208809 -0.19895 0.7503761 0.8247767 -0.2276235 0.6241828 0.9083635 -0.2506919 0.4826827 0.9695827 -0.2675872 0.3293601 1.006928 -0.2778942 0.1679901 1.01948 -0.2813582 0.002546489 0.1513875 -0.05681627 1.023457 0.2990456 -0.1122332 0.9855934 0.4393402 -0.1648867 0.9235236 0.568817 -0.2134801 0.8387761 0.6842871 -0.2568167 0.733438 0.7829088 -0.2938302 0.610103 0.8622525 -0.3236082 0.4718078 0.9203641 -0.3454177 0.3219579 0.9558139 -0.3587225 0.1642429 0.9677285 -0.3631941 -0.02687948 0.1380883 -0.06649941 1.015144 0.2727748 -0.1313609 0.9521941 0.4007447 -0.192988 0.8754991 0.5188471 -0.249863 0.7951709 0.6241734 -0.3005855 0.6953256 0.7141312 -0.343907 0.5784218 0.7865048 -0.3787601 0.4473382 0.8395113 -0.4042866 0.3053022 0.8718469 -0.4198588 0.1558112 0.8827148 -0.4250925 -0.07837527 0.1388097 -0.08293437 1.023457 0.2741998 -0.1638261 0.9855934 0.4028382 -0.240684 0.9235236 0.5215575 -0.3116154 0.8387761 0.6274339 -0.3748736 0.733438 0.7178617 -0.4289019 0.610103 0.7906134 -0.4723687 0.4718078 0.8438968 -0.504204 0.3219579 0.8764013 -0.5236248 0.1642429 0.8873259 -0.5301519 -0.02687948 0.1338483 -0.09724581 1.030179 0.2643992 -0.1920965 1.008375 0.3884397 -0.2822173 0.9448667 0.5029157 -0.3653889 0.8581554 0.6050078 -0.4395631 0.7503761 0.6922034 -0.5029146 0.6241828 0.7623549 -0.5538824 0.4826827 0.8137338 -0.5912112 0.3293601 0.8450764 -0.6139833 0.1679901 0.8556106 -0.6216368 0.002546489 0.1245924 -0.1088523 1.030179 0.2461154 -0.2150236 1.008375 0.3615782 -0.3159006 0.9448667 0.4681379 -0.4089989 0.8581554 0.5631701 -0.4920259 0.7503761 0.6443359 -0.5629386 0.6241828 0.7096362 -0.6199895 0.4826827 0.7574621 -0.6617736 0.3293601 0.7866374 -0.6872636 0.1679901 0.7964431 -0.6958305 0.002546489 0.1117438 -0.1168739 1.023457 0.2207347 -0.2308693 0.9855934 0.3242903 -0.3391801 0.9235236 0.4198608 -0.439139 0.8387761 0.5050929 -0.5282846 0.733438 0.5778883 -0.6044229 0.610103 0.6364545 -0.6656782 0.4718078 0.6793483 -0.7105414 0.3219579 0.7055148 -0.7379097 0.1642429 0.7143093 -0.747108 -0.02687948 0.09556037 -0.1198278 1.015144 0.1887664 -0.2367043 0.9521941 0.2773243 -0.3477526 0.8754991 0.3590536 -0.4502378 0.7951709 0.4319417 -0.5416365 0.6953256 0.4941944 -0.6196991 0.5784218 0.5442786 -0.6825025 0.4473382 0.5809602 -0.7284998 0.3053022 0.6033371 -0.7565596 0.1558112 0.6108579 -0.7659904 -0.07837527 0.08907938 -0.1349482 1.023457 0.1759641 -0.2665727 0.9855934 0.2585158 -0.3916335 0.9235236 0.3347022 -0.5070508 0.8387761 0.4026469 -0.6099825 0.733438 0.4606775 -0.6978954 0.610103 0.507365 -0.7686235 0.4718078 0.5415588 -0.820425 0.3219579 0.562418 -0.8520256 0.1642429 0.5694288 -0.8626463 -0.02687948 0.07839983 -0.1456897 1.030179 0.154868 -0.2877912 1.008375 0.2275226 -0.4228065 0.9448667 0.2945752 -0.5474106 0.8581554 0.3543741 -0.6585354 0.7503761 0.4054474 -0.753446 0.6241828 0.4465374 -0.8298039 0.4826827 0.4766318 -0.8857286 0.3293601 0.4949903 -0.9198445 0.1679901 0.5011605 -0.9313105 0.002546489 0.06502473 -0.1521308 1.030179 0.1284471 -0.3005148 1.008375 0.1887066 -0.4414993 0.9448667 0.2443197 -0.5716124 0.8581554 0.2939168 -0.6876502 0.7503761 0.3362768 -0.7867568 0.6241828 0.3703567 -0.8664906 0.4826827 0.395317 -0.9248878 0.3293601 0.4105433 -0.9605119 0.1679901 0.4156609 -0.972485 0.002546489 0.04996806 -0.1537832 1.023457 0.09870469 -0.303779 0.9855934 0.1450107 -0.4462947 0.9235236 0.1877464 -0.5778211 0.8387761 0.2258589 -0.6951193 0.733438 0.2584102 -0.7953023 0.610103 0.2845988 -0.8759022 0.4718078 0.3037793 -0.9349337 0.3219579 0.3154799 -0.9709448 0.1642429 0.3194125 -0.9830479 -0.02687948 0.03410565 -0.1494228 1.015144 0.06737053 -0.2951656 0.9521941 0.09897637 -0.4336404 0.8754991 0.1281453 -0.5614376 0.7951709 0.1541588 -0.6754098 0.6953256 0.1763764 -0.7727523 0.5784218 0.1942513 -0.8510668 0.4473382 0.2073429 -0.9084246 0.3053022 0.2153291 -0.9434145 0.1558112 0.2180132 -0.9551746 -0.07837527 0.02170604 -0.1602339 1.023457 0.04287666 -0.3165214 0.9855934 0.06299138 -0.4650151 0.9235236 0.08155524 -0.6020585 0.8387761 0.09811097 -0.7242769 0.733438 0.1122507 -0.8286623 0.610103 0.1236268 -0.912643 0.4718078 0.1319586 -0.9741507 0.3219579 0.1370412 -1.011672 0.1642429 0.1387494 -1.024283 -0.02687948 0.00742352 -0.165278 1.030179 0.01466339 -0.3264853 1.008375 0.02154207 -0.4796535 0.9448667 0.02789056 -0.621011 0.8581554 0.03355222 -0.7470767 0.7503761 0.03838753 -0.8547481 0.6241828 0.04227799 -0.9413726 0.4826827 0.04512733 -1.004816 0.3293601 0.04686534 -1.043519 0.1679901 0.04744952 -1.056527 0.002546489 -0.007421731 -0.165278 1.030179 -0.01466149 -0.3264853 1.008375 -0.0215404 -0.4796535 0.9448667 -0.02788871 -0.6210111 0.8581554 -0.0335502 -0.7470767 0.7503761 -0.03838598 -0.8547481 0.6241828 -0.04227614 -0.9413726 0.4826827 -0.04512536 -1.004816 0.3293601 -0.04686361 -1.043519 0.1679901 -0.0474478 -1.056527 0.002546489 -0.02170425 -0.1602339 1.023457 -0.04287475 -0.3165215 0.9855934 -0.06298977 -0.4650152 0.9235236 -0.08155345 -0.6020587 0.8387761 -0.09810894 -0.7242769 0.733438 -0.1122491 -0.8286623 0.610103 -0.123625 -0.9126431 0.4718078 -0.1319566 -0.9741508 0.3219579 -0.1370394 -1.011672 0.1642429 -0.1387477 -1.024283 -0.02687948 -0.03410392 -0.1494229 1.015144 -0.06736874 -0.2951658 0.9521941 -0.09897482 -0.4336405 0.8754991 -0.1281436 -0.5614377 0.7951709 -0.1541569 -0.6754099 0.6953256 -0.1763749 -0.7727523 0.5784218 -0.1942496 -0.851067 0.4473382 -0.207341 -0.9084247 0.3053022 -0.2153273 -0.9434146 0.1558112 -0.2180115 -0.9551746 -0.07837527 -0.04996633 -0.1537833 1.023457 -0.09870284 -0.3037791 0.9855934 -0.1450091 -0.4462949 0.9235236 -0.1877446 -0.5778212 0.8387761 -0.225857 -0.6951193 0.733438 -0.2584086 -0.7953023 0.610103 -0.284597 -0.8759025 0.4718078 -0.3037775 -0.934934 0.3219579 -0.3154782 -0.9709449 0.1642429 -0.3194108 -0.983048 -0.02687948 -0.06502294 -0.1521309 1.030179 -0.1284453 -0.3005151 1.008375 -0.1887051 -0.4414994 0.9448667 -0.244318 -0.5716125 0.8581554 -0.2939148 -0.6876503 0.7503761 -0.3362752 -0.7867568 0.6241828 -0.370355 -0.8664909 0.4826827 -0.3953151 -0.9248881 0.3293601 -0.4105417 -0.9605121 0.1679901 -0.4156593 -0.9724852 0.002546489 -0.0783981 -0.1456897 1.030179 -0.1548662 -0.2877915 1.008375 -0.2275211 -0.4228066 0.9448667 -0.2945734 -0.5474109 0.8581554 -0.3543721 -0.6585356 0.7503761 -0.4054458 -0.753446 0.6241828 -0.4465358 -0.8298043 0.4826827 -0.47663 -0.885729 0.3293601 -0.4949886 -0.9198446 0.1679901 -0.5011588 -0.9313108 0.002546489 -0.08907765 -0.1349483 1.023457 -0.1759623 -0.2665731 0.9855934 -0.2585144 -0.3916336 0.9235236 -0.3347005 -0.507051 0.8387761 -0.4026451 -0.6099827 0.733438 -0.460676 -0.6978954 0.610103 -0.5073633 -0.768624 0.4718078 -0.5415571 -0.8204254 0.3219579 -0.5624164 -0.8520258 0.1642429 -0.5694271 -0.8626466 -0.02687948 -0.09555864 -0.1198279 1.015144 -0.1887647 -0.2367047 0.9521941 -0.2773228 -0.3477528 0.8754991 -0.359052 -0.4502381 0.7951709 -0.4319399 -0.5416367 0.6953256 -0.4941929 -0.6196992 0.5784218 -0.544277 -0.6825029 0.4473382 -0.5809586 -0.7285002 0.3053022 -0.6033355 -0.7565599 0.1558112 -0.6108562 -0.7659907 -0.07837527 -0.1610454 0.01449441 1.023457 -0.1117421 -0.116874 1.023457 -0.220733 -0.2308697 0.9855934 -0.3242888 -0.3391803 0.9235236 -0.4198592 -0.4391393 0.8387761 -0.505091 -0.5282849 0.733438 -0.5778868 -0.6044231 0.610103 -0.6364529 -0.6656785 0.4718078 -0.6793467 -0.710542 0.3219579 -0.7055132 -0.7379099 0.1642429 -0.7143076 -0.7471083 -0.02687948 -0.1245907 -0.1088524 1.030179 -0.2461138 -0.2150241 1.008375 -0.3615768 -0.3159008 0.9448667 -0.4681363 -0.4089992 0.8581554 -0.5631684 -0.4920263 0.7503761 -0.6443345 -0.5629387 0.6241828 -0.7096347 -0.61999 0.4826827 -0.7574607 -0.6617743 0.3293601 -0.7866358 -0.6872639 0.1679901 -0.7964414 -0.6958308 0.002546489 -0.1338466 -0.09724587 1.030179 -0.2643977 -0.1920969 1.008375 -0.3884384 -0.2822176 0.9448667 -0.5029141 -0.3653892 0.8581554 -0.6050061 -0.4395635 0.7503761 -0.692202 -0.5029147 0.6241828 -0.7623534 -0.5538829 0.4826827 -0.8137323 -0.5912119 0.3293601 -0.8450749 -0.6139836 0.1679901 -0.855609 -0.6216371 0.002546489 -0.138808 -0.08293443 1.023457 -0.2741982 -0.1638265 0.9855934 -0.4028368 -0.2406843 0.9235236 -0.5215559 -0.3116158 0.8387761 -0.6274322 -0.374874 0.733438 -0.7178602 -0.428902 0.610103 -0.790612 -0.4723693 0.4718078 -0.8438954 -0.5042047 0.3219579 -0.8763998 -0.5236251 0.1642429 -0.8873243 -0.5301523 -0.02687948 -0.1380867 -0.06649947 1.015144 -0.2727734 -0.1313613 0.9521941 -0.4007434 -0.1929882 0.8754991 -0.5188456 -0.2498635 0.7951709 -0.6241717 -0.3005859 0.6953256 -0.7141298 -0.3439072 0.5784218 -0.7865035 -0.3787607 0.4473382 -0.83951 -0.4042873 0.3053022 -0.8718455 -0.4198592 0.1558112 -0.8827133 -0.4250929 -0.07837527 -0.1513858 -0.05681639 1.023457 -0.2990441 -0.1122335 0.9855934 -0.4393389 -0.1648869 0.9235236 -0.5688154 -0.2134805 0.8387761 -0.6842855 -0.2568172 0.733438 -0.7829073 -0.2938304 0.610103 -0.8622513 -0.3236088 0.4718078 -0.9203629 -0.3454185 0.3219579 -0.9558125 -0.3587229 0.1642429 -0.967727 -0.3631946 -0.02687948 -0.1594816 -0.04401439 1.030179 -0.3150362 -0.08694481 1.008375 -0.4628336 -0.1277341 0.9448667 -0.5992342 -0.1653785 0.8581554 -0.7208794 -0.1989505 0.7503761 -0.8247752 -0.2276238 0.6241828 -0.9083623 -0.2506925 0.4826827 -0.9695816 -0.2675879 0.3293601 -1.006927 -0.2778946 0.1679901 -1.019479 -0.2813587 0.002546489 -0.162785 -0.02954131 1.030179 -0.3215617 -0.05835509 1.008375 -0.4724204 -0.0857318 0.9448667 -0.6116463 -0.1109977 0.8581554 -0.7358111 -0.1335303 0.7503761 -0.8418589 -0.1527751 0.6241828 -0.9271774 -0.1682582 0.4826827 -0.9896646 -0.179598 0.3293601 -1.027783 -0.1865156 0.1679901 -1.040595 -0.1888406 0.002546489 -0.1610456 -0.01449441 1.023457 -0.3181257 -0.02863198 0.9855934 -0.4673723 -0.0420643 0.9235236 -0.6051105 -0.05446118 0.8387761 -0.7279487 -0.06551682 0.733438 -0.8328633 -0.07495915 0.610103 -0.9172701 -0.082556 0.4718078 -0.9790896 -0.08811992 0.3219579 -1.016801 -0.09151405 0.1642429 -1.029476 -0.09265482 -0.02687948 -0.1532648 0 1.015144 -0.3027558 0 0.9521941 -0.4447917 0 0.8754991 -0.5758754 -1.92269e-7 0.7951709 -0.7926244 0 0.5784218 -0.8729533 -1.7037e-7 0.4473382 -0.931786 -1.92269e-7 0.3053022 -0.9676757 -1.99569e-7 0.1558112 -0.9797381 -2.36067e-7 -0.07837527 -0.8817924 0.4246492 -0.06851685 -0.6102191 0.7651914 -0.06851685 -0.2177842 0.9541782 -0.06851685 0.2177856 0.9541782 -0.06851685 0.6102205 0.7651916 -0.06851685 0.8817939 0.4246493 -0.06851685 0.9787175 0 -0.06851685 0.8817943 -0.4246492 -0.06851685 0.6102209 -0.7651916 -0.06851685 0.2177858 -0.9541785 -0.06851685 -0.2177842 -0.9541786 -0.06851685 -0.6102192 -0.7651919 -0.06851685 -0.8817928 -0.4246497 -0.06851685 -0.9787164 -2.38385e-7 -0.06851685 7.32286e-7 -1.21337e-7 -2.088751 -0.1627849 0.02954125 1.030179 -0.1594815 0.04401427 1.030179 -0.1513857 0.05681627 1.023457 -0.1380866 0.06649941 1.015144 -0.138808 0.08293437 1.023457 -0.1338466 0.09724581 1.030179 -0.1245907 0.1088523 1.030179 -0.1117421 0.1168739 1.023457 -0.0955587 0.1198278 1.015144 -0.08907771 0.1349482 1.023457 -0.07839816 0.1456897 1.030179 -0.065023 0.1521309 1.030179 -0.04996639 0.1537833 1.023457 -0.03410398 0.1494229 1.015144 -0.02170431 0.1602339 1.023457 -0.007421791 0.165278 1.030179 0.0074234 0.165278 1.030179 0.02170592 0.1602339 1.023457 0.03410553 0.1494229 1.015144 0.049968 0.1537833 1.023457 0.06502467 0.1521309 1.030179 0.07839977 0.1456898 1.030179 0.08907938 0.1349483 1.023457 0.09556031 0.1198279 1.015144 0.1117438 0.116874 1.023457 0.1245924 0.1088525 1.030179 0.1338483 0.09724593 1.030179 0.1388096 0.08293449 1.023457 0.1380883 0.06649947 1.015144 0.1513875 0.05681639 1.023457 0.1594833 0.04401439 1.030179 0.1627866 0.02954131 1.030179 0.1610472 0.01449447 1.023457 0.1532664 0 1.015144 0.1610472 -0.01449435 1.023457 0.1627866 -0.02954119 1.030179 0.1594833 -0.04401427 1.030179 0.1513875 -0.05681627 1.023457 0.1380883 -0.06649941 1.015144 0.1388097 -0.08293437 1.023457 0.1338483 -0.09724581 1.030179 0.1245924 -0.1088523 1.030179 0.1117438 -0.1168739 1.023457 0.09556037 -0.1198278 1.015144 0.08907938 -0.1349482 1.023457 0.07839983 -0.1456897 1.030179 0.06502473 -0.1521308 1.030179 0.04996806 -0.1537832 1.023457 0.03410565 -0.1494228 1.015144 0.02170604 -0.1602339 1.023457 0.00742352 -0.165278 1.030179 -0.007421731 -0.165278 1.030179 -0.02170425 -0.1602339 1.023457 -0.03410392 -0.1494229 1.015144 -0.04996633 -0.1537833 1.023457 -0.06502294 -0.1521309 1.030179 -0.0783981 -0.1456897 1.030179 -0.08907765 -0.1349483 1.023457 -0.09555864 -0.1198279 1.015144 -0.1117421 -0.116874 1.023457 -0.1245907 -0.1088524 1.030179 -0.1338466 -0.09724587 1.030179 -0.138808 -0.08293443 1.023457 -0.1380867 -0.06649947 1.015144 -0.1513858 -0.05681639 1.023457 -0.1594816 -0.04401439 1.030179 -0.162785 -0.02954131 1.030179 -0.1610456 -0.01449441 1.023457 -0.1532648 0 1.015144 -0.08030927 0.007228016 1.034929 -0.07970112 0.01446378 1.034996 -0.07808375 0.02154994 1.034996 -0.07549226 0.028333 1.034929 -0.07276242 0.03504091 1.034408 -0.06922 0.04135751 1.034929 -0.06553256 0.04761278 1.034996 -0.06100076 0.05329549 1.034996 -0.05572283 0.05828237 1.034929 -0.05035293 0.06314158 1.034408 -0.04442059 0.06729561 1.034929 -0.03838431 0.07133156 1.034996 -0.03183567 0.07448524 1.034996 -0.02491664 0.07668823 1.034929 -0.0179702 0.0787363 1.034408 -0.01082301 0.07990503 1.034929 -0.003633379 0.08092224 1.034996 0.003634989 0.08092224 1.034996 0.01082468 0.07990503 1.034929 0.01797181 0.0787363 1.034408 0.02491831 0.07668828 1.034929 0.03183734 0.07448524 1.034996 0.03838598 0.07133156 1.034996 0.04442226 0.06729567 1.034929 0.05035454 0.06314164 1.034408 0.0557245 0.05828243 1.034929 0.06100243 0.05329555 1.034996 0.06553423 0.04761284 1.034996 0.06922161 0.04135757 1.034929 0.07276409 0.03504097 1.034408 0.07549393 0.02833306 1.034929 0.07808548 0.02154999 1.034996 0.07970285 0.01446378 1.034996 0.080311 0.007228076 1.034929 0.08076196 0 1.034408 0.080311 -0.007227957 1.034929 0.07970285 -0.01446372 1.034996 0.07808548 -0.02154994 1.034996 0.07549393 -0.028333 1.034929 0.07276409 -0.03504091 1.034408 0.06922167 -0.04135745 1.034929 0.06553423 -0.04761278 1.034996 0.06100243 -0.05329549 1.034996 0.0557245 -0.05828237 1.034929 0.05035459 -0.06314158 1.034408 0.04442226 -0.06729561 1.034929 0.03838598 -0.0713315 1.034996 0.03183734 -0.07448518 1.034996 0.02491837 -0.07668817 1.034929 0.01797187 -0.07873624 1.034408 0.01082468 -0.07990497 1.034929 0.003635048 -0.08092218 1.034996 -0.00363332 -0.08092218 1.034996 -0.01082301 -0.07990497 1.034929 -0.01797014 -0.07873624 1.034408 -0.02491664 -0.07668823 1.034929 -0.03183561 -0.07448518 1.034996 -0.03838425 -0.07133156 1.034996 -0.04442059 -0.06729561 1.034929 -0.05035287 -0.06314158 1.034408 -0.05572283 -0.05828237 1.034929 -0.06100076 -0.05329549 1.034996 -0.06553256 -0.04761278 1.034996 -0.06922 -0.04135751 1.034929 -0.07276242 -0.03504091 1.034408 -0.07549226 -0.028333 1.034929 -0.07808381 -0.02154999 1.034996 -0.07970118 -0.01446378 1.034996 -0.08030933 -0.007228016 1.034929 -0.08076035 0 1.034408 + + + + + + + + + + -0.6525359 -0.4471096 0.6117924 -0.5306315 -0.5253517 0.6651586 -0.5994818 -0.09152603 0.7951381 -0.7574163 -0.3894508 0.5240693 -0.7144243 -0.04077363 0.6985238 -0.8419654 -0.3479806 0.4123152 -0.813043 -0.003601312 0.5821925 -0.9045135 -0.3189815 0.2830305 -0.8925853 0.02331638 0.4502754 -0.9512246 0.04092633 0.3057726 -0.9864731 0.05124175 0.1557091 -0.2751592 -0.6960771 0.6631472 -0.1534833 -0.2970477 0.9424466 -0.1018124 -0.1171637 0.9878801 -0.9422732 -0.303328 0.1418216 -0.9967463 0.03256362 0.07373356 -0.4093548 -0.6216773 0.6677919 -0.2934443 -0.2737288 0.9159492 -0.4718872 -0.1627892 0.8665 -0.8739027 0.3760513 0.3080251 -0.04089593 0.149728 0.9878811 -0.9114354 0.381189 0.1548561 -0.9121829 0.4030951 0.07373392 -0.1456077 0.3739534 0.9159462 -0.3545141 0.3514011 0.8665086 -0.5027731 0.347522 0.7914845 -0.623019 0.3523747 0.6983405 -0.7282428 0.357804 0.5844987 -0.8144721 0.3677287 0.4487883 -0.2668008 0.6929741 0.6697794 -0.4055753 0.6736903 0.6177784 -0.5195875 0.6711148 0.5288043 -0.6133557 0.6761959 0.4081103 -0.6766743 0.6779256 0.2872783 -0.7181906 0.68175 0.1393531 -0.00939995 0.3342482 0.9424383 0.05407994 0.7465294 0.663151 -0.09543234 0.7290336 0.6777926 -0.8064376 0.3893325 0.4450605 -0.8591849 0.4107925 0.3050424 -0.8918038 0.4294673 0.1422808 -0.1460938 0.07034593 0.9867665 -0.3705354 0.1784161 0.9115214 -0.6871189 0.7244444 0.05520999 -0.4614873 0.2339634 0.8557398 -0.5376878 0.2679893 0.7994208 -0.6511596 0.3135552 0.6911399 -0.7384743 0.3604934 0.5698249 -0.6439212 -0.3738887 0.6675124 -0.6942288 -0.2388462 0.678969 -0.7810723 -0.1085865 0.6149269 -0.8535017 -0.01608365 0.5208418 -0.9080557 0.05371302 0.4153911 -0.9529137 0.108219 0.2832739 -0.2671614 -0.2010272 0.9424505 -0.9808009 0.1364216 0.1393514 -0.9948061 0.08551496 0.05520933 -0.5499266 -0.5077489 0.663153 -0.7940633 0.4082934 0.4502887 -0.8386606 0.4501239 0.3066543 -0.142556 -0.06137448 0.9878821 -0.8662993 0.4749157 0.1548565 -0.8839036 0.4618199 0.07373487 -0.3831684 -0.1192995 0.915942 -0.5039353 0.05688804 0.861866 -0.5779997 0.170998 0.7979198 -0.6613806 0.2732074 0.6985224 -0.7340916 0.3495122 0.5821948 -0.1570528 0.4692661 0.8689786 -0.3021737 0.5312532 0.7914931 -0.4087814 0.5841479 0.7011911 -0.5040925 0.637921 0.5821922 -0.5747675 0.6832938 0.4502798 -0.6251022 0.7181564 0.3057757 0.02810823 0.1526575 0.9878795 -0.655127 0.7392992 0.1557094 0.02908468 0.4127401 0.9103844 -0.1760365 0.83245 0.5253933 -0.2589254 0.8734003 0.4124678 -0.317433 0.9057875 0.2806876 0.1365439 0.3052249 0.9424402 0.3589978 0.6545767 0.6653195 -0.6469364 0.7589708 0.07373327 -0.3503288 0.9258274 0.1418222 0.2314619 0.690357 0.6854434 0.06027644 0.7401036 0.6697861 -0.06854659 0.78206 0.619422 -0.3047372 0.950835 0.05520975 -0.6181992 0.7726576 0.1443258 -0.2563951 0.3215238 0.9115284 -0.3142602 0.4110378 0.8557387 -0.3681843 0.474727 0.7994214 -0.4506187 0.5650359 0.691142 -0.508936 0.6452035 0.5698215 -0.5530382 0.7043218 0.4450613 -0.5934159 0.7456763 0.3030254 -0.1010786 0.1267756 0.986768 -0.7472013 0.2408574 0.6194175 -0.7759566 0.3558261 0.5208447 -0.7966709 0.443107 0.4110619 -0.8115078 0.5088481 0.2872781 -0.3279615 -0.06518942 0.9424392 -0.8244809 0.5484637 0.1393514 -0.8591758 0.5086935 0.05520915 -0.7157707 -0.2188544 0.6631554 -0.7423768 -0.0574674 0.6675135 -0.7294365 0.09293055 0.6777067 -0.155069 0.006531119 0.9878821 -0.5744404 0.8037648 0.1548565 -0.5959811 0.799606 0.07373464 -0.3969669 0.05874997 0.9159508 -0.4293451 0.2699124 0.8618643 -0.4519284 0.4060886 0.7942624 -0.4785414 0.5285319 0.7011792 -0.5097432 0.6334098 0.5821974 -0.539736 0.7122319 0.4487882 -0.5610877 0.7683103 0.308026 -0.1172845 0.7087122 0.6956806 -0.1742935 0.7924541 0.5844982 -0.2213574 0.865012 0.4502835 -0.2515712 0.9182671 0.3057736 0.09155827 0.1253128 0.9878836 0.2015504 0.3470062 0.9159499 -0.2694834 0.9503335 0.1557083 0.05368345 0.4962745 0.8665044 -0.0441302 0.6048219 0.7951372 0.1070004 0.953817 0.2806852 0.2554488 0.2157428 0.9424442 0.6173809 0.4231541 0.6631603 -0.2535557 0.9645065 0.07373499 0.08606475 0.9861435 0.1418237 0.5104613 0.5291694 0.6777971 0.3806694 0.636148 0.6711233 0.2759544 0.7400901 0.6132829 0.2007258 0.8246638 0.5288091 0.1456386 0.8992542 0.4124698 -0.1200925 0.5988756 0.7917866 -0.1528072 0.6988789 0.6987263 -0.1821085 0.7979266 0.5745865 -0.1969124 0.876004 0.4402757 -0.2111008 0.9293077 0.3030245 -0.03607326 0.1580876 0.986766 -0.09149748 0.4009347 0.911526 0.1379748 0.9888958 0.0552082 -0.2217206 0.9643705 0.1443244 -0.1048024 0.506708 0.855724 -0.5103462 0.810566 0.2872796 -0.3237433 0.08352988 0.9424507 -0.50485 0.8518849 0.139351 -0.5533751 0.8311004 0.05520927 -0.7398474 0.113379 0.6631525 -0.6937955 0.2703095 0.6675184 -0.6233807 0.4034914 0.6697695 -0.5728801 0.5332659 0.6224436 -0.5394634 0.6592221 0.5238373 -0.5210316 0.7482809 0.4106114 -0.2309707 0.5619537 0.7942674 -0.201825 0.6838184 0.701184 -0.1865655 0.7929261 0.5800529 -0.1789975 0.8745698 0.4506525 -0.1721559 0.9356725 0.3080251 -0.1368792 0.07318538 0.9878806 -0.1688016 0.9734095 0.1548544 -0.1900095 0.9790097 0.07373321 -0.3321727 0.2251718 0.9159471 -0.2697002 0.4294695 0.8618688 0.1758542 0.8753952 0.450287 0.1717327 0.9364882 0.305774 0.1368792 0.07318538 0.9878806 0.3408384 0.2345706 0.9103878 0.1695309 0.9731469 0.1557059 0.2689676 0.4153692 0.8689792 0.2226353 0.5640808 0.7951393 0.2017919 0.6894252 0.6956816 0.1867787 0.7895978 0.5845075 0.6840687 0.2494376 0.6854422 0.6189917 0.4079815 0.6711187 0.5697375 0.5470615 0.6132888 0.5386682 0.6558934 0.5288105 0.5238639 0.7469905 0.4093555 0.5108634 0.8111128 0.2848066 0.3237526 0.08353227 0.9424471 0.7356052 0.1274178 0.6653194 0.1900095 0.9790097 0.07373321 0.5041757 0.852124 0.1403268 0.1821085 0.7979266 0.5745865 0.200145 0.8769696 0.4368826 0.2116478 0.9274053 0.308423 0.2202554 0.96501 0.1422795 0.03607326 0.1580876 0.986766 0.09149748 0.4009347 0.911526 0.5533751 0.8311004 0.05520927 0.1254047 0.5019849 0.8557366 0.1516193 0.5916757 0.79179 0.165533 0.695977 0.6987237 -0.6173809 0.4231541 0.6631603 -0.507804 0.5445793 0.6675094 -0.3865587 0.6340101 0.6697788 -0.2847704 0.7290316 0.6224297 -0.2025563 0.8264003 0.5253889 -0.1462487 0.9011448 0.4081047 -0.1081309 0.9517233 0.287281 -0.2554431 0.2157075 0.9424538 -0.08521014 0.98657 0.1393516 -0.1379748 0.9888958 0.0552082 0.1773781 0.7934712 0.5821861 0.2203204 0.8660525 0.4487896 0.2508376 0.9177134 0.3080306 -0.09155791 0.1253428 0.9878798 0.2702502 0.950255 0.1548559 0.2535557 0.9645065 0.07373499 -0.2015797 0.3470041 0.9159442 -0.05664378 0.503965 0.8618647 0.03570783 0.6065143 0.7942703 0.1148433 0.7036785 0.701176 0.5749856 0.8032098 0.15571 0.4088652 0.06344932 0.9103865 0.4225664 0.25755 0.8689681 0.4507037 0.4128298 0.7914782 0.482173 0.5289894 0.6983405 0.5108946 0.6303475 0.5845074 0.539736 0.7122319 0.4487882 0.5618551 0.7681027 0.3071434 0.1550988 0.006531059 0.9878774 0.7474268 0.236558 0.6208007 0.7699142 0.3571997 0.5288106 0.7957317 0.4475057 0.4081051 0.8112204 0.5097557 0.28648 0.3279615 -0.06518942 0.9424392 0.7180505 -0.2043551 0.6653138 0.5959811 0.799606 0.07373464 0.8239771 0.5489722 0.1403254 0.7245603 -0.07205617 0.6854344 0.7421342 0.106054 0.6618078 0.1010786 0.1267756 0.986768 0.2564235 0.3215213 0.9115213 0.8591758 0.5086935 0.05520915 0.6171365 0.7738851 0.1422823 0.3308008 0.3978522 0.8557363 0.3930571 0.4800064 0.7842831 0.4414338 0.5535624 0.7061904 0.5157759 0.6397453 0.5698256 0.5623433 0.6990685 0.4416711 0.5930815 0.7437248 0.3084281 0.0597251 0.780394 0.6224292 0.1772266 0.8360201 0.519289 0.2556596 0.8738573 0.4135357 0.3155125 0.9043899 0.2872818 -0.1365439 0.3052249 0.9424402 0.3512436 0.9258561 0.1393499 0.3047372 0.950835 0.05520975 -0.3726362 0.6491377 0.663146 -0.2212328 0.7109725 0.6675134 -0.07318437 0.7389549 0.6697685 0.6241793 0.7179954 0.3080306 -0.02810823 0.1526575 0.9878795 0.6557718 0.7389068 0.1548557 0.6469364 0.7589708 0.07373327 -0.03103804 0.400107 0.9159428 0.1676123 0.4786352 0.8618668 0.295338 0.5309492 0.7942723 0.4087814 0.5841479 0.7011911 0.5035969 0.6402618 0.5800474 0.5721451 0.6852495 0.4506477 0.5851764 0.1764013 0.7914866 0.6604727 0.2685412 0.7011858 0.7340916 0.3495122 0.5821948 0.7940633 0.4082934 0.4502887 0.8392555 0.4496132 0.3057748 0.142556 -0.06137448 0.9878821 0.3959227 -0.1202142 0.9103811 0.8665463 0.4741849 0.1557116 0.4924582 0.04867815 0.8689739 0.9106435 0.05615603 0.4093592 0.9526748 0.106297 0.2848014 0.2671614 -0.2010272 0.9424505 0.5582836 -0.4956586 0.6653136 0.8839036 0.4618199 0.07373487 0.9805687 0.1370904 0.1403254 0.6215329 -0.3792983 0.6854411 0.7146602 -0.2264499 0.6618015 0.7741168 -0.1153927 0.622437 0.8507541 -0.01358103 0.5253885 0.4706702 0.2149176 0.8557336 0.5624074 0.2619156 0.7842819 0.6379113 0.3072057 0.7061827 0.7373898 0.3550983 0.5745969 0.8104403 0.3902809 0.4368839 0.8570507 0.4127162 0.3084308 0.8918038 0.4294673 0.1422808 0.1460938 0.07034593 0.9867665 0.3705354 0.1784161 0.9115214 0.9948061 0.08551496 0.05520933 0.6135876 0.6744733 0.4106047 0.6766743 0.6779256 0.2872783 0.00939995 0.3342482 0.9424383 0.7181906 0.68175 0.1393531 0.6871189 0.7244444 0.05520999 -0.05407994 0.7465294 0.663151 0.1091369 0.7365523 0.6675177 0.2546501 0.6975409 0.6697687 0.3924144 0.677188 0.6224368 0.5226408 0.6726424 0.523831 0.358693 0.3585099 0.8618643 0.4964641 0.3502137 0.7942756 0.621769 0.3489267 0.7011802 0.7315411 0.3583239 0.5800446 0.8128131 0.3691275 0.4506438 0.8739027 0.3760513 0.3080251 0.04089593 0.149728 0.9878811 0.9114354 0.381189 0.1548561 0.9121829 0.4030951 0.07373392 0.1456077 0.3739534 0.9159462 0.8113616 -0.006378531 0.5845099 0.8933656 0.02206552 0.4487887 0.9508396 0.03961318 0.3071398 0.1018124 -0.1171637 0.9878801 0.2934443 -0.2737288 0.9159492 0.9864731 0.05124175 0.1557091 0.9967463 0.03256362 0.07373356 0.4718872 -0.1627892 0.8665 0.6037642 -0.09494566 0.7914886 0.7142118 -0.0471217 0.6983418 0.2751592 -0.6960771 0.6631472 0.4093548 -0.6216773 0.6677919 0.5362473 -0.521293 0.6638467 0.6509482 -0.4368546 0.6208256 0.7593204 -0.3792024 0.5288081 0.8460153 -0.3430938 0.4080991 0.9043373 -0.3163899 0.2864813 0.1534833 -0.2970477 0.9424466 0.9429474 -0.301925 0.1403266 0.8184411 0 0.5745904 0.8995195 0 0.4368807 0.9512485 0 0.3084256 0.9898266 0 0.1422801 0.1621468 0 0.9867667 0.411249 0 0.9115231 0.9333976 -0.3545714 0.0552091 0.5328053 0 0.846238 0.6087679 0 0.7933484 0.7080218 0 0.7061907 0.9428659 0.3026303 0.1393515 0.9333976 0.3545714 0.0552091 0.2751592 0.6960771 0.6631472 0.4093548 0.6216773 0.6677919 0.5362473 0.521293 0.6638467 0.6473785 0.4398462 0.6224441 0.7627339 0.3792611 0.5238302 0.8454695 0.3414472 0.4106034 0.903804 0.317189 0.2872799 0.1534789 0.2970392 0.9424501 0.7115879 0.04458868 0.7011808 0.814562 0.005432426 0.5800512 0.8924759 -0.02008169 0.450648 0.9505206 -0.04034638 0.3080303 0.1018124 0.1171637 0.9878801 0.9865676 -0.05200487 0.154855 0.9967463 -0.03256362 0.07373356 0.2934443 0.2737288 0.9159492 0.4718872 0.1627892 0.8665 0.6037642 0.09494566 0.7914886 0.8747975 -0.3758113 0.3057702 0.04089593 -0.149728 0.9878811 0.1456077 -0.3739534 0.9159462 0.9110244 -0.381824 0.1557082 0.9121829 -0.4030951 0.07373392 0.3545141 -0.3514011 0.8665086 0.5027731 -0.347522 0.7914845 0.623019 -0.3523747 0.6983405 0.7282428 -0.357804 0.5844987 0.8143202 -0.3662335 0.4502841 0.2685381 -0.6999266 0.6618082 0.3969342 -0.6760333 0.6208239 0.5195875 -0.6711148 0.5288043 0.6116965 -0.6769466 0.4093541 0.6765269 -0.6798535 0.2830383 0.009399771 -0.3342115 0.9424514 -0.05407994 -0.7465294 0.663151 0.7173326 -0.6821435 0.1418246 0.09543234 -0.7290336 0.6777926 0.8583683 -0.4114979 0.3063879 0.1460938 -0.07034593 0.9867665 0.3705354 -0.1784161 0.9115214 0.6871189 -0.7244444 0.05520999 0.8922249 -0.4279078 0.1443247 0.4516872 -0.2175118 0.8652557 0.5693992 -0.2742162 0.7749774 0.6379113 -0.3072057 0.7061827 0.7373898 -0.3550983 0.5745969 0.8104403 -0.3902809 0.4368839 0.7095115 0.225232 0.6677306 0.7741168 0.1153927 0.622437 0.8517559 0.01074266 0.5238288 0.9098924 -0.05917626 0.4106021 0.9519272 -0.1063292 0.2872781 0.2671691 0.2010329 0.9424471 0.9808009 -0.1364216 0.1393514 0.9948061 -0.08551496 0.05520933 0.5499266 0.5077489 0.663153 0.6348558 0.3713244 0.6775519 0.142556 0.06137448 0.9878821 0.8662993 -0.4749157 0.1548565 0.8839036 -0.4618199 0.07373487 0.3831684 0.1192995 0.915942 0.5039353 -0.05688804 0.861866 0.5833535 -0.169781 0.7942752 0.6604727 -0.2685412 0.7011858 0.7362585 -0.348505 0.5800584 0.7953729 -0.4053316 0.4506533 0.8388761 -0.4487822 0.3080284 0.4084364 -0.5877969 0.698337 0.5008801 -0.6383384 0.5845026 0.574275 -0.6846925 0.4487811 0.6238109 -0.7186949 0.3071445 -0.02810823 -0.1526575 0.9878795 -0.02908468 -0.4127401 0.9103844 0.655127 -0.7392992 0.1557094 0.6469364 -0.7589708 0.07373327 0.1570528 -0.4692661 0.8689786 0.3021737 -0.5312532 0.7914931 0.3164535 -0.9043143 0.2864837 -0.1365439 -0.3052249 0.9424402 -0.3589978 -0.6545767 0.6653195 0.3518596 -0.9254743 0.1403288 -0.2314619 -0.690357 0.6854434 -0.06173962 -0.7471324 0.6618016 0.06430333 -0.7813148 0.6208158 0.1769208 -0.8300964 0.5288092 0.2592316 -0.8753567 0.4081051 0.3804863 -0.4900206 0.7842895 0.4414338 -0.5535624 0.7061904 0.5102906 -0.6398776 0.5745958 0.5608342 -0.7032707 0.4368928 0.5930815 -0.7437248 0.3084281 0.6171554 -0.7738706 0.1422796 0.1011088 -0.1267752 0.986765 0.2563951 -0.3215238 0.9115284 0.3047372 -0.950835 0.05520975 0.3142602 -0.4110378 0.8557387 0.7957317 -0.4475057 0.4081051 0.8115078 -0.5088481 0.2872781 0.3279615 0.06518942 0.9424392 0.8244809 -0.5484637 0.1393514 0.8591758 -0.5086935 0.05520915 0.7157707 0.2188544 0.6631554 0.7412797 0.06753885 0.6677896 0.7419123 -0.09421157 0.6638452 0.7475324 -0.2318834 0.622435 0.7724103 -0.3568609 0.525388 0.4214984 -0.2674383 0.8664965 0.4507037 -0.4128298 0.7914782 0.4785414 -0.5285319 0.7011792 0.5097432 -0.6334098 0.5821974 0.539736 -0.7122319 0.4487882 0.5610877 -0.7683103 0.308026 0.1550988 -0.006531059 0.9878774 0.5744404 -0.8037648 0.1548565 0.5959811 -0.799606 0.07373464 0.3969669 -0.05874997 0.9159508 0.2203204 -0.8660525 0.4487896 0.2501928 -0.9181874 0.3071408 -0.09155827 -0.1253128 0.9878836 0.2694834 -0.9503335 0.1557083 0.2535557 -0.9645065 0.07373499 -0.2053017 -0.3592398 0.9103834 -0.06207567 -0.4909595 0.868968 0.04174989 -0.609769 0.7914789 0.1129518 -0.7067959 0.698342 0.1742935 -0.7924541 0.5844982 -0.508091 -0.5215502 0.6854407 -0.3797783 -0.6463618 0.6618044 -0.2810493 -0.7318452 0.6208171 -0.2007258 -0.8246638 0.5288091 -0.1462487 -0.9011448 0.4081047 -0.1072431 -0.9520652 0.2864802 -0.2554488 -0.2157428 0.9424442 -0.6074763 -0.433977 0.6653094 -0.08450675 -0.9864924 0.1403258 0.1821085 -0.7979266 0.5745865 0.200145 -0.8769696 0.4368826 0.2116478 -0.9274053 0.308423 0.2202554 -0.96501 0.1422795 0.03607326 -0.1580876 0.986766 0.09149748 -0.4009347 0.911526 -0.1379748 -0.9888958 0.0552082 0.1048024 -0.506708 0.855724 0.1301965 -0.6065765 0.784292 0.1575397 -0.6902814 0.7061819 0.7398474 -0.113379 0.6631525 0.6971811 -0.2607562 0.667791 0.6275417 -0.4067943 0.6638599 0.5728801 -0.5332659 0.6224436 0.5410789 -0.656656 0.5253919 0.5227606 -0.7484488 0.4081005 0.5103462 -0.810566 0.2872796 0.3237526 -0.08353227 0.9424471 0.50485 -0.8518849 0.139351 0.5533751 -0.8311004 0.05520927 0.1844294 -0.791859 0.58219 0.1772576 -0.8758808 0.4487901 0.1721575 -0.9356813 0.3079975 0.1368792 -0.07318538 0.9878806 0.1688016 -0.9734095 0.1548544 0.1900095 -0.9790097 0.07373321 0.3321727 -0.2251718 0.9159471 0.2637172 -0.4238214 0.8665038 0.2269394 -0.5675012 0.7914803 0.201825 -0.6838184 0.701184 -0.1695309 -0.9731469 0.1557059 -0.3408384 -0.2345706 0.9103878 -0.2689676 -0.4153692 0.8689792 -0.2269394 -0.5675012 0.7914803 -0.2048741 -0.6858232 0.6983361 -0.1867787 -0.7895978 0.5845075 -0.1772576 -0.8758808 0.4487901 -0.172953 -0.9358143 0.3071466 -0.1368792 -0.07318538 0.9878806 -0.5707672 -0.5374099 0.6208184 -0.5386682 -0.6558934 0.5288105 -0.5227606 -0.7484488 0.4081005 -0.5111078 -0.810991 0.2847151 -0.3237433 -0.08352988 0.9424507 -0.7356052 -0.1274178 0.6653194 -0.1900095 -0.9790097 0.07373321 -0.5053987 -0.8511512 0.1418229 -0.6840687 -0.2494376 0.6854422 -0.6226195 -0.4175619 0.661806 -0.2101836 -0.9284152 0.3063791 -0.03607326 -0.1580876 0.986766 -0.09149748 -0.4009347 0.911526 -0.5533751 -0.8311004 0.05520927 -0.2186385 -0.9650739 0.1443247 -0.1254047 -0.5019849 0.8557366 -0.1458528 -0.6030049 0.7842909 -0.1575397 -0.6902814 0.7061819 -0.1821085 -0.7979266 0.5745865 -0.200145 -0.8769696 0.4368826 0.3865587 -0.6340101 0.6697788 0.2847704 -0.7290316 0.6224297 0.2025563 -0.8264003 0.5253889 0.1462487 -0.9011448 0.4081047 0.1081309 -0.9517233 0.287281 0.2554488 -0.2157428 0.9424442 0.08521014 -0.98657 0.1393516 0.1379748 -0.9888958 0.0552082 0.6173809 -0.4231541 0.6631603 0.507804 -0.5445793 0.6675094 -0.25084 -0.917722 0.308003 0.09155827 -0.1253128 0.9878836 -0.2702502 -0.950255 0.1548559 -0.2535557 -0.9645065 0.07373499 0.2015797 -0.3470041 0.9159442 0.05664378 -0.503965 0.8618647 -0.03570783 -0.6065143 0.7942703 -0.1148433 -0.7036785 0.701176 -0.1773781 -0.7934712 0.5821861 -0.2203204 -0.8660525 0.4487896 -0.4507037 -0.4128298 0.7914782 -0.482173 -0.5289894 0.6983405 -0.5108946 -0.6303475 0.5845074 -0.539736 -0.7122319 0.4487882 -0.5618551 -0.7681027 0.3071434 -0.1550988 -0.006531059 0.9878774 -0.5749856 -0.8032098 0.15571 -0.5959811 -0.799606 0.07373464 -0.4088652 -0.06344932 0.9103865 -0.4225664 -0.25755 0.8689681 -0.7957317 -0.4475057 0.4081051 -0.8112204 -0.5097557 0.28648 -0.3279249 0.06518822 0.9424521 -0.7180505 0.2043551 0.6653138 -0.8239771 -0.5489722 0.1403254 -0.7245603 0.07205617 0.6854344 -0.7421342 -0.106054 0.6618078 -0.7474127 -0.2365535 0.6208195 -0.7699142 -0.3571997 0.5288106 -0.3308008 -0.3978522 0.8557363 -0.3930571 -0.4800064 0.7842831 -0.4414338 -0.5535624 0.7061904 -0.5102906 -0.6398776 0.5745958 -0.5608342 -0.7032707 0.4368928 -0.5930815 -0.7437248 0.3084281 -0.6171365 -0.7738851 0.1422823 -0.1011088 -0.1267752 0.986765 -0.2564235 -0.3215213 0.9115213 -0.8591758 -0.5086935 0.05520915 -0.2592031 -0.8753636 0.4081083 -0.3155125 -0.9043899 0.2872818 0.1365439 -0.3052249 0.9424402 -0.3512436 -0.9258561 0.1393499 -0.3047372 -0.950835 0.05520975 0.3726362 -0.6491377 0.663146 0.2212328 -0.7109725 0.6675134 0.07318437 -0.7389549 0.6697685 -0.0597251 -0.780394 0.6224292 -0.1760365 -0.83245 0.5253933 -0.1676123 -0.4786352 0.8618668 -0.295338 -0.5309492 0.7942723 -0.4087814 -0.5841479 0.7011911 -0.5040925 -0.637921 0.5821922 -0.5742545 -0.6847045 0.4487889 -0.6241793 -0.7179954 0.3080306 0.02810823 -0.1526575 0.9878795 -0.6557718 -0.7389068 0.1548557 -0.6469364 -0.7589708 0.07373327 0.03103804 -0.400107 0.9159428 -0.7337979 -0.3462681 0.5844991 -0.7953159 -0.4075006 0.4487939 -0.8388761 -0.4487822 0.3080284 -0.142556 0.06137448 0.9878821 -0.3959227 0.1202142 0.9103811 -0.8662993 -0.4749157 0.1548565 -0.8839036 -0.4618199 0.07373487 -0.4924582 -0.04867815 0.8689739 -0.5851764 -0.1764013 0.7914866 -0.6639418 -0.2674078 0.6983368 -0.9808009 -0.1364216 0.1393514 -0.5582836 0.4956586 0.6653136 -0.6215329 0.3792983 0.6854411 -0.7146602 0.2264499 0.6618015 -0.7760362 0.11115 0.6208168 -0.8486527 0.01220774 0.5288096 -0.9110953 -0.05792576 0.4081053 -0.9519242 -0.1063594 0.2872772 -0.2671614 0.2010272 0.9424505 -0.6379113 -0.3072057 0.7061827 -0.7373898 -0.3550983 0.5745969 -0.8104403 -0.3902809 0.4368839 -0.8570399 -0.4127416 0.3084269 -0.8918038 -0.4294673 0.1422808 -0.1460938 -0.07034593 0.9867665 -0.3705354 -0.1784161 0.9115214 -0.9948061 -0.08551496 0.05520933 -0.4706702 -0.2149176 0.8557336 -0.5624074 -0.2619156 0.7842819 -0.00939995 -0.3342482 0.9424383 -0.7181906 -0.68175 0.1393531 -0.6871189 -0.7244444 0.05520999 0.05407994 -0.7465294 0.663151 -0.1091369 -0.7365523 0.6675177 -0.2546501 -0.6975409 0.6697687 -0.3924144 -0.677188 0.6224368 -0.5198053 -0.6736227 0.5253903 -0.6133557 -0.6761959 0.4081103 -0.6766743 -0.6779256 0.2872783 -0.621769 -0.3489267 0.7011802 -0.7309693 -0.3560084 0.5821874 -0.8144721 -0.3677287 0.4487883 -0.8739027 -0.3760513 0.3080251 -0.04089593 -0.149728 0.9878811 -0.9114354 -0.381189 0.1548561 -0.9121829 -0.4030951 0.07373392 -0.1456077 -0.3739534 0.9159462 -0.358693 -0.3585099 0.8618643 -0.4964641 -0.3502137 0.7942756 -0.9505296 -0.04034674 0.3080027 -0.9865676 -0.05200487 0.154855 -0.1018124 0.1171637 0.9878801 -0.9967463 -0.03256362 0.07373356 -0.3045486 0.280103 0.9103804 -0.4648109 0.1697795 0.8689798 -0.6037642 0.09494566 0.7914886 -0.7142118 0.0471217 0.6983418 -0.8113616 0.006378531 0.5845099 -0.8933656 -0.02206552 0.4487887 -0.5456252 0.5140987 0.6618124 -0.6509482 0.4368546 0.6208256 -0.7593204 0.3792024 0.5288081 -0.8460153 0.3430938 0.4080991 -0.903804 0.317189 0.2872799 -0.9428659 0.3026303 0.1393515 -0.1534789 0.2970392 0.9424501 -0.2879158 0.6888127 0.6653131 -0.3954145 0.6114031 0.6854441 -0.9519059 0.001648008 0.3063861 -0.989529 0.001556456 0.144326 -0.1621468 0 0.9867667 -0.411249 0 0.9115231 -0.9333976 0.3545714 0.0552091 -0.5173053 0.01055973 0.8557358 -0.6203405 0.008026599 0.7842916 -0.8174007 0.009430468 0.5759924 -0.8971688 0.003784358 0.4416718 -0.7140334 0.00601232 0.7000859 -0.09775251 0.02270615 0.9949517 -0.220682 0.08575803 0.9715684 -0.9333976 -0.3545714 0.0552091 0.04388642 -0.09024488 0.9949522 -0.0782203 0.06286925 0.9949518 0.2360333 -0.0184639 0.9715696 0.09793555 -0.02194315 0.9949509 -0.1326967 -0.1960542 0.9715732 0.06375372 -0.07992869 0.9947598 -0.07870864 -0.06225883 0.9949517 -0.2046306 -0.1190245 0.9715759 -0.02273648 -0.0996744 0.9947604 0.2046298 -0.1190546 0.9715722 -0.1615981 0.1730122 0.9715723 -0.09793555 -0.02194315 0.9949509 0.03448629 -0.2342324 0.9715688 3.66229e-4 -0.1003467 0.9949525 -0.2206529 -0.08575856 0.9715749 -0.09775251 -0.02270615 0.9949517 -0.06375372 -0.07992869 0.9947598 -0.0705294 0.2259932 0.9715723 -0.1022379 0 0.99476 0.03448659 0.2342036 0.9715757 -0.09213608 0.0443437 0.9947586 -0.1326967 0.1960542 0.9715732 -0.04388642 0.09024488 0.9949522 0.04318445 0.09058058 0.9949524 -3.66229e-4 -0.1003467 0.9949525 0.04388642 0.09024488 0.9949522 0.1327267 0.1960534 0.9715692 -0.0705294 -0.2259932 0.9715723 -0.04318445 -0.09058058 0.9949524 0.2360333 0.0184639 0.9715696 0.02273643 0.09970462 0.9947573 -0.02273643 0.09970462 0.9947573 -0.2360333 0.0184639 0.9715696 -0.06375372 0.07992869 0.9947598 0.07870864 0.06225883 0.9949517 -0.1615981 -0.1730122 0.9715723 0.0921058 0.04434382 0.9947614 -0.03448629 0.2342324 0.9715688 0.09775251 -0.02270615 0.9949517 0.220682 -0.08575803 0.9715684 -0.2046298 0.1190546 0.9715722 -0.09790533 0.02194321 0.9949538 0.0705294 -0.2259932 0.9715723 0.1022681 0 0.9947569 0.0782203 -0.06286925 0.9949518 0.1615981 0.1730122 0.9715723 0.0782203 0.06286925 0.9949518 -0.03448659 -0.2342036 0.9715757 -3.66229e-4 0.1003467 0.9949525 -0.04318445 0.09058058 0.9949524 0.0705294 0.2259932 0.9715723 0.220682 0.08575803 0.9715684 0.02273643 -0.09970462 0.9947573 0.1326967 -0.1960542 0.9715732 -0.04388642 -0.09024488 0.9949522 0.07870864 -0.06225883 0.9949517 -0.0921058 -0.04434382 0.9947614 0.09775251 0.02270615 0.9949517 -0.2360333 -0.0184639 0.9715696 0.2046298 0.1190546 0.9715722 3.66229e-4 0.1003467 0.9949525 0.06375372 0.07992869 0.9947598 -0.0782203 -0.06286925 0.9949518 0.09793555 0.02194315 0.9949509 0.1615981 -0.1730122 0.9715723 -0.07870864 0.06225883 0.9949517 0.04318445 -0.09058058 0.9949524 0.09213608 -0.0443437 0.9947586 -0.1493295 0.1403569 0.9787751 0.2313341 0.1113944 0.9664761 0.1493295 0.1403569 0.9787751 0.01663285 -0.2042636 0.9787746 -0.00476098 -0.1001945 0.9949566 -0.08130329 0.05871903 0.9949582 0.20283 0.02920675 0.9787784 -0.05713117 -0.2503457 0.9664694 -0.09872978 -0.01760959 0.9949585 0.09659349 0.02694851 0.9949591 -0.1036124 -0.1767972 0.9787785 -0.1954438 0.06164836 0.9787755 -0.1954438 -0.06164836 0.9787755 0.04776257 0.0882005 0.994957 -0.03915607 -0.09235107 0.9949563 0.07364261 0.1912327 0.9787783 0.03915607 -0.09235107 0.9949563 0.1601018 0.2007529 0.9664708 0.1036124 -0.1767972 0.9787785 -0.09872978 0.01760959 0.9949585 0.1700529 0.1143248 0.9787808 0.05713117 -0.2503457 0.9664694 0.07535195 0.0661962 0.9949574 -0.01660233 -0.2042637 0.9787752 0.00476098 0.1001945 0.9949566 0.00476098 -0.1001945 0.9949566 -0.01660233 0.2042637 0.9787752 0.07535195 -0.0661962 0.9949574 0.05713117 0.2503457 0.9664694 0.1700529 -0.1143248 0.9787808 0.1036124 0.1767972 0.9787785 0.1601018 -0.2007529 0.9664708 0.03915607 0.09235107 0.9949563 0.07364261 -0.1912327 0.9787783 -0.03915607 0.09235107 0.9949563 0.04779303 -0.08820039 0.9949556 -0.1036124 0.1767972 0.9787785 0.09662371 -0.02694845 0.9949561 -0.05713117 0.2503457 0.9664694 0.20283 -0.02920675 0.9787784 -0.08130329 -0.05871903 0.9949582 0.01660233 0.2042637 0.9787752 0.2313341 -0.1113944 0.9664761 -0.1493295 -0.1403569 0.9787751 -0.00476098 0.1001945 0.9949566 0.1493295 -0.1403569 0.9787751 -0.2313341 -0.1113944 0.9664761 -0.07535195 0.0661962 0.9949574 0.08130329 -0.05871903 0.9949582 -0.20283 -0.02920675 0.9787784 -0.1700529 0.1143248 0.9787808 0.09872978 0.01760959 0.9949585 -0.09662371 -0.02694845 0.9949561 -0.1601018 0.2007529 0.9664708 0.1954438 0.06164836 0.9787755 -0.04776257 -0.0882005 0.994957 -0.07364261 0.1912327 0.9787783 0.256785 0 0.9664686 -0.07361221 -0.1912331 0.9787805 -0.04779303 0.08820039 0.9949556 0.1954438 -0.06164836 0.9787755 -0.1600721 -0.2007539 0.9664755 -0.09662371 0.02694845 0.9949561 0.09872978 -0.01760959 0.9949585 -0.1700529 -0.1143248 0.9787808 -0.20283 0.02920675 0.9787784 -0.256785 0 0.9664686 0.08130329 0.05871903 0.9949582 -0.07535195 -0.0661962 0.9949574 -0.2313341 0.1113944 0.9664761 0.4338842 -0.9009687 5.24891e-7 -1.21099e-7 1 0 2.3653e-7 -1 0 -0.4338834 -0.9009692 5.2489e-7 0.4338834 0.9009692 5.2489e-7 -0.7818319 -0.6234894 0 0.7818319 0.6234894 0 -0.9749281 -0.2225202 2.62444e-7 0.9749279 0.2225211 0 -0.9749279 0.2225211 2.62445e-7 0.9749279 -0.2225211 0 -0.7818319 0.6234894 5.2489e-7 0.7818319 -0.6234894 5.2489e-7 -0.4338834 0.9009692 5.2489e-7 0.6525359 0.4471096 -0.6117924 0.7144243 0.04077363 -0.6985238 0.5994818 0.09152603 -0.7951381 0.7574163 0.3894508 -0.5240693 0.813043 0.003601312 -0.5821925 0.8419654 0.3479806 -0.4123152 0.8925853 -0.02331638 -0.4502754 0.9045135 0.3189815 -0.2830305 0.9512246 -0.04092633 -0.3057726 0.9864731 -0.05124175 -0.1557091 0.2751592 0.6960771 -0.6631472 0.2934443 0.2737288 -0.9159492 0.6559213 0.7548039 0.006195366 0.9967463 -0.03256362 -0.07373356 0.9422732 0.303328 -0.1418216 0.4093548 0.6216773 -0.6677919 0.4718872 0.1627892 -0.8665 0.5306315 0.5253517 -0.6651586 0.9114354 -0.381189 -0.1548561 0.8748281 -0.3750179 -0.3066552 0.1456077 -0.3739534 -0.9159462 0.2634429 -0.9646552 0.006195366 0.9121829 -0.4030951 -0.07373392 0.3545141 -0.3514011 -0.8665086 0.5027731 -0.347522 -0.7914845 0.623019 -0.3523747 -0.6983405 0.7282428 -0.357804 -0.5844987 0.8143202 -0.3662335 -0.4502841 0.4055753 -0.6736903 -0.6177784 0.2668008 -0.6929741 -0.6697794 0.5195875 -0.6711148 -0.5288043 0.6116965 -0.6769466 -0.4093541 0.6762802 -0.6790269 -0.2856009 0.7181906 -0.68175 -0.1393531 -0.05407994 -0.7465294 -0.663151 0.02749776 -0.978293 0.2053942 0.6871189 -0.7244444 -0.05520999 0.09543234 -0.7290336 -0.6777926 0.8590343 -0.412594 -0.3030288 0.8064376 -0.3893325 -0.4450605 0.8908569 -0.4307487 -0.1443255 0.3705354 -0.1784161 -0.9115214 0.540037 -0.260054 0.8004573 0.2040833 -0.9784526 -0.03131288 0.4516872 -0.2175118 -0.8652557 0.5519417 -0.2657926 -0.790389 0.6537851 -0.3215821 -0.6849453 0.7323677 -0.3631472 -0.5759876 0.70293 0.2222445 -0.6756454 0.6348558 0.3713244 -0.6775519 0.7821391 0.1100512 -0.6133084 0.8513847 0.0222482 -0.5240699 0.9080557 -0.05371302 -0.4153911 0.9535771 -0.1069703 -0.2815105 0.9808023 -0.1348347 -0.1408776 0.5499266 0.5077489 -0.663153 0.7820198 0.5884376 0.2053931 0.9948061 -0.08551496 -0.05520933 0.8386606 -0.4501239 -0.3066543 0.7940633 -0.4082934 -0.4502887 0.8662993 -0.4749157 -0.1548565 0.3831684 0.1192995 -0.915942 0.9184634 0.3954626 0.005859553 0.8839036 -0.4618199 -0.07373487 0.5039353 -0.05688804 -0.861866 0.5833535 -0.169781 -0.7942752 0.6604727 -0.2685412 -0.7011858 0.7340916 -0.3495122 -0.5821948 0.3021737 -0.5312532 -0.7914931 0.1570528 -0.4692661 -0.8689786 0.4087814 -0.5841479 -0.7011911 0.5040925 -0.637921 -0.5821922 0.5747675 -0.6832938 -0.4502798 0.6251022 -0.7181564 -0.3057757 0.655127 -0.7392992 -0.1557094 -0.02908468 -0.4127401 -0.9103844 -0.1811593 -0.9834364 0.005859553 0.6469364 -0.7589708 -0.07373327 0.2589254 -0.8734003 -0.4124678 0.1760365 -0.83245 -0.5253933 0.317433 -0.9057875 -0.2806876 0.3503288 -0.9258274 -0.1418222 -0.3589978 -0.6545767 -0.6653195 -0.3996757 -0.8933496 0.2053923 0.3047372 -0.950835 -0.05520975 -0.2314619 -0.690357 -0.6854434 -0.06027644 -0.7401036 -0.6697861 0.06854659 -0.78206 -0.619422 -0.2406426 -0.9701086 -0.03131252 0.6181992 -0.7726576 -0.1443258 0.3125787 -0.3919594 -0.8652529 0.2564235 -0.3215213 -0.9115213 0.3819468 -0.4789671 -0.7903842 0.4506187 -0.5650359 -0.691142 0.508936 -0.6452035 -0.5698215 0.5530382 -0.7043218 -0.4450613 0.5934159 -0.7456763 -0.3030254 0.3736143 -0.4684981 0.800576 0.7759566 -0.3558261 -0.5208447 0.7508364 -0.2410416 -0.6149339 0.7966709 -0.443107 -0.4110619 0.8115078 -0.5088481 -0.2872781 0.8244809 -0.5484637 -0.1393514 0.7180505 0.2043551 -0.6653138 0.9598483 0.1908344 0.2056055 0.8591758 -0.5086935 -0.05520915 0.7256762 0.0619837 -0.6852388 0.7294708 -0.09784466 -0.6769778 0.4088652 -0.06344932 -0.9103865 0.9990931 -0.0421769 0.005859553 0.5959811 -0.799606 -0.07373464 0.5744404 -0.8037648 -0.1548565 0.4304385 -0.260021 -0.8643563 0.4465537 -0.4048648 -0.7979187 0.4773262 -0.533116 -0.6985322 0.5097432 -0.6334098 -0.5821974 0.539736 -0.7122319 -0.4487882 0.5610877 -0.7683103 -0.308026 0.1742935 -0.7924541 -0.5844982 0.1129518 -0.7067959 -0.698342 0.2213574 -0.865012 -0.4502835 0.2515712 -0.9182671 -0.3057736 0.2694834 -0.9503335 -0.1557083 -0.2053017 -0.3592398 -0.9103834 -0.5899276 -0.8074348 0.005859553 0.2535557 -0.9645065 -0.07373499 -0.06207567 -0.4909595 -0.868968 0.04174989 -0.609769 -0.7914789 -0.08606475 -0.9861435 -0.1418237 -0.1070004 -0.953817 -0.2806852 -0.6074763 -0.433977 -0.6653094 -0.7476637 -0.631446 0.205609 -0.1379748 -0.9888958 -0.0552082 -0.508091 -0.5215502 -0.6854407 -0.3754467 -0.6406583 -0.6697736 -0.2776054 -0.7408306 -0.6116415 -0.206282 -0.8212216 -0.5320178 -0.1456386 -0.8992542 -0.4124698 0.168038 -0.7089579 -0.6849395 0.1257092 -0.5874674 -0.7994244 0.1861063 -0.7925235 -0.5807505 0.1969124 -0.876004 -0.4402757 0.2111008 -0.9293077 -0.3030245 0.2217206 -0.9643705 -0.1443244 0.09149748 -0.4009347 -0.911526 0.1333698 -0.5843552 0.8004633 -0.6377246 -0.7696277 -0.03131246 0.1048024 -0.506708 -0.855724 0.50485 -0.8518849 -0.139351 0.5103462 -0.810566 -0.2872796 0.7398474 -0.113379 -0.6631525 0.9476491 -0.2444886 0.2053936 0.5533751 -0.8311004 -0.05520927 0.6937955 -0.2703095 -0.6675184 0.6168786 -0.4002249 -0.6777027 0.5686987 -0.5412007 -0.619422 0.5410789 -0.656656 -0.5253919 0.5227606 -0.7484488 -0.4081005 0.201825 -0.6838184 -0.701184 0.2309707 -0.5619537 -0.7942674 0.1844294 -0.791859 -0.58219 0.1772576 -0.8758808 -0.4487901 0.1721559 -0.9356725 -0.3080251 0.1688016 -0.9734095 -0.1548544 0.3321727 -0.2251718 -0.9159471 0.8818516 -0.4714908 0.005859673 0.1900095 -0.9790097 -0.07373321 0.2697002 -0.4294695 -0.8618688 -0.1717327 -0.9364882 -0.305774 -0.1758542 -0.8753952 -0.450287 -0.1695309 -0.9731469 -0.1557059 -0.3408384 -0.2345706 -0.9103878 -0.8818516 -0.4714908 0.005859673 -0.1900095 -0.9790097 -0.07373321 -0.2689642 -0.4153944 -0.8689683 -0.2226353 -0.5640808 -0.7951393 -0.2017919 -0.6894252 -0.6956816 -0.1867787 -0.7895978 -0.5845075 -0.6189917 -0.4079815 -0.6711187 -0.6840687 -0.2494376 -0.6854422 -0.5697375 -0.5470615 -0.6132888 -0.5386682 -0.6558934 -0.5288105 -0.5238639 -0.7469905 -0.4093555 -0.5108634 -0.8111128 -0.2848066 -0.5041757 -0.852124 -0.1403268 -0.7356052 -0.1274178 -0.6653194 -0.9476491 -0.2444886 0.2053936 -0.5533751 -0.8311004 -0.05520927 -0.200145 -0.8769696 -0.4368826 -0.1821085 -0.7979266 -0.5745865 -0.2116478 -0.9274053 -0.308423 -0.2202554 -0.96501 -0.1422795 -0.09149748 -0.4009347 -0.911526 -0.1333698 -0.5843552 0.8004633 -0.9085165 -0.4166742 -0.03131234 -0.1254047 -0.5019849 -0.8557366 -0.1516193 -0.5916757 -0.79179 -0.165533 -0.695977 -0.6987237 0.507804 -0.5445793 -0.6675094 0.6173809 -0.4231541 -0.6631603 0.3865587 -0.6340101 -0.6697788 0.2847704 -0.7290316 -0.6224297 0.2025563 -0.8264003 -0.5253889 0.1462487 -0.9011448 -0.4081047 0.1081309 -0.9517233 -0.287281 0.08521014 -0.98657 -0.1393516 0.7477091 -0.6314632 0.2053911 0.1379748 -0.9888958 -0.0552082 -0.2203204 -0.8660525 -0.4487896 -0.1773781 -0.7934712 -0.5821861 -0.2508376 -0.9177134 -0.3080306 -0.2702502 -0.950255 -0.1548559 0.2015797 -0.3470041 -0.9159442 0.5899276 -0.8074348 0.005859553 -0.2535557 -0.9645065 -0.07373499 0.05664378 -0.503965 -0.8618647 -0.03570783 -0.6065143 -0.7942703 -0.1148433 -0.7036785 -0.701176 -0.5959811 -0.799606 -0.07373464 -0.5744404 -0.8037648 -0.1548565 -0.4225664 -0.25755 -0.8689681 -0.4088652 -0.06344932 -0.9103865 -0.4507037 -0.4128298 -0.7914782 -0.4785414 -0.5285319 -0.7011792 -0.5097432 -0.6334098 -0.5821974 -0.539736 -0.7122319 -0.4487882 -0.5610877 -0.7683103 -0.308026 -0.9990901 -0.04217678 0.006347835 -0.7724103 -0.3568609 -0.525388 -0.7472013 -0.2408574 -0.6194175 -0.7957317 -0.4475057 -0.4081051 -0.8115078 -0.5088481 -0.2872781 -0.8244809 -0.5484637 -0.1393514 -0.7180505 0.2043551 -0.6653138 -0.9598483 0.1908344 0.2056055 -0.8591758 -0.5086935 -0.05520915 -0.7245603 0.07205617 -0.6854344 -0.7349693 -0.1059024 -0.6697797 -0.2564235 -0.3215213 -0.9115213 -0.3737083 -0.4686231 0.800459 -0.999334 0.01873844 -0.0313121 -0.6171365 -0.7738851 -0.1422823 -0.3308008 -0.3978522 -0.8557363 -0.3809078 -0.464591 -0.7994151 -0.4506187 -0.5650359 -0.691142 -0.5157759 -0.6397453 -0.5698256 -0.5623433 -0.6990685 -0.4416711 -0.5930815 -0.7437248 -0.3084281 -0.1772266 -0.8360201 -0.519289 -0.06854659 -0.78206 -0.619422 -0.2556596 -0.8738573 -0.4135357 -0.3155125 -0.9043899 -0.2872818 -0.3512436 -0.9258561 -0.1393499 0.3589978 -0.6545767 -0.6653195 0.3996757 -0.8933496 0.2053923 -0.3047372 -0.950835 -0.05520975 0.2224213 -0.7032152 -0.6752905 0.07168835 -0.7318379 -0.6776977 -0.6557718 -0.7389068 -0.1548557 -0.6241793 -0.7179954 -0.3080306 0.02908468 -0.4127401 -0.9103844 0.181164 -0.9834316 0.006470143 -0.6469364 -0.7589708 -0.07373327 -0.1577222 -0.4775004 -0.8643594 -0.295338 -0.5309492 -0.7942723 -0.4087814 -0.5841479 -0.7011911 -0.5035969 -0.6402618 -0.5800474 -0.5721451 -0.6852495 -0.4506477 -0.6604727 -0.2685412 -0.7011858 -0.5851764 -0.1764013 -0.7914866 -0.7340916 -0.3495122 -0.5821948 -0.7940747 -0.4082836 -0.4502778 -0.8392555 -0.4496132 -0.3057748 -0.8665463 -0.4741849 -0.1557116 -0.3959227 0.1202142 -0.9103811 -0.9184634 0.3954626 0.005859553 -0.8839036 -0.4618199 -0.07373487 -0.4924582 -0.04867815 -0.8689739 -0.9533413 -0.1050451 -0.2830299 -0.9106435 -0.05615603 -0.4093592 -0.980574 -0.1355041 -0.1418215 -0.5582836 0.4956586 -0.6653136 -0.7819758 0.5884199 0.2056112 -0.9948061 -0.08551496 -0.05520933 -0.6215329 0.3792983 -0.6854411 -0.7081403 0.2234626 -0.6697775 -0.777705 0.1071549 -0.6194294 -0.8507541 0.01358103 -0.5253885 -0.5571287 -0.2503493 -0.7917911 -0.4706702 -0.2149176 -0.8557336 -0.6473427 -0.30449 -0.698737 -0.7422845 -0.3525867 -0.5698214 -0.8099786 -0.3858232 -0.4416733 -0.8569186 -0.414512 -0.3063824 -0.8908569 -0.4307487 -0.1443255 -0.3705354 -0.1784161 -0.9115214 -0.540037 -0.260054 0.8004573 -0.89223 0.4504945 -0.0313127 -0.6766743 -0.6779256 -0.2872783 -0.609495 -0.6763926 -0.4135324 -0.7181906 -0.68175 -0.1393531 0.05407994 -0.7465294 -0.663151 -0.02749776 -0.978293 0.2053942 -0.6871189 -0.7244444 -0.05520999 -0.1091369 -0.7365523 -0.6675177 -0.2546501 -0.6975409 -0.6697687 -0.3924144 -0.677188 -0.6224368 -0.5224232 -0.6763302 -0.5192798 -0.4964641 -0.3502137 -0.7942756 -0.358693 -0.3585099 -0.8618643 -0.621769 -0.3489267 -0.7011802 -0.7315411 -0.3583239 -0.5800446 -0.8128131 -0.3691275 -0.4506438 -0.8739027 -0.3760513 -0.3080251 -0.9114354 -0.381189 -0.1548561 -0.1456077 -0.3739534 -0.9159462 -0.2634434 -0.9646571 0.005859673 -0.9121829 -0.4030951 -0.07373392 -0.8933656 -0.02206552 -0.4487887 -0.8113616 0.006378531 -0.5845099 -0.9508396 -0.03961318 -0.3071398 -0.9864731 -0.05124175 -0.1557091 -0.3045486 0.280103 -0.9103804 -0.6559227 0.7548055 0.005859673 -0.9967463 -0.03256362 -0.07373356 -0.4648109 0.1697795 -0.8689798 -0.6037642 0.09494566 -0.7914886 -0.7142118 0.0471217 -0.6983418 -0.4025142 0.6177643 -0.6755366 -0.2879158 0.6888127 -0.6653131 -0.5362473 0.521293 -0.6638467 -0.6509482 0.4368546 -0.6208256 -0.7593204 0.3792024 -0.5288081 -0.8460153 0.3430938 -0.4080991 -0.9043373 0.3163899 -0.2864813 -0.9429474 0.301925 -0.1403266 -0.4492496 0.869475 0.2053974 -0.9333976 0.3545714 -0.0552091 -0.8995195 0 -0.4368807 -0.8184411 0 -0.5745904 -0.9512485 0 -0.3084256 -0.9898266 0 -0.1422801 -0.411249 0 -0.9115231 -0.5993943 0 0.8004539 -0.608401 0.7930119 -0.0313127 -0.5328053 0 -0.846238 -0.6087679 0 -0.7933484 -0.7080218 0 -0.7061907 -0.9333976 -0.3545714 -0.0552091 -0.9428659 -0.3026303 -0.1393515 -0.4093548 -0.6216773 -0.6677919 -0.2751592 -0.6960771 -0.6631472 -0.5362473 -0.521293 -0.6638467 -0.6473785 -0.4398462 -0.6224441 -0.7627339 -0.3792611 -0.5238302 -0.8454695 -0.3414472 -0.4106034 -0.903804 -0.317189 -0.2872799 -0.4492377 -0.8694825 0.205392 -0.814562 -0.005432426 -0.5800512 -0.7115879 -0.04458868 -0.7011808 -0.8924759 0.02008169 -0.450648 -0.9505206 0.04034638 -0.3080303 -0.9865676 0.05200487 -0.154855 -0.2934443 -0.2737288 -0.9159492 -0.6559227 -0.7548055 0.005859673 -0.9967463 0.03256362 -0.07373356 -0.4718872 -0.1627892 -0.8665 -0.6037625 -0.09497588 -0.7914864 -0.9110244 0.381824 -0.1557082 -0.8747975 0.3758113 -0.3057702 -0.1456077 0.3739534 -0.9159462 -0.2634434 0.9646571 0.005859673 -0.9121829 0.4030951 -0.07373392 -0.3545141 0.3514011 -0.8665086 -0.5027731 0.347522 -0.7914845 -0.621769 0.3489267 -0.7011802 -0.7309693 0.3560084 -0.5821874 -0.8143202 0.3662335 -0.4502841 -0.3924144 0.677188 -0.6224368 -0.2685381 0.6999266 -0.6618082 -0.5198053 0.6736227 -0.5253903 -0.6116965 0.6769466 -0.4093541 -0.6765269 0.6798535 -0.2830383 -0.7173326 0.6821435 -0.1418246 0.05407994 0.7465294 -0.663151 -0.02749776 0.978293 0.2053942 -0.6871189 0.7244444 -0.05520999 -0.09543234 0.7290336 -0.6777926 -0.8922249 0.4279078 -0.1443247 -0.8583683 0.4114979 -0.3063879 -0.3705354 0.1784161 -0.9115214 -0.5398848 0.2599931 0.8005799 -0.2040833 0.9784526 -0.03131288 -0.4516872 0.2175118 -0.8652557 -0.5693992 0.2742162 -0.7749774 -0.6379113 0.3072057 -0.7061827 -0.7373898 0.3550983 -0.5745969 -0.8104403 0.3902809 -0.4368839 -0.7741168 -0.1153927 -0.622437 -0.7095115 -0.225232 -0.6677306 -0.8517559 -0.01074266 -0.5238288 -0.9098924 0.05917626 -0.4106021 -0.9519272 0.1063292 -0.2872781 -0.9808009 0.1364216 -0.1393514 -0.5499266 -0.5077489 -0.663153 -0.7820198 -0.5884376 0.2053931 -0.9948061 0.08551496 -0.05520933 -0.6348558 -0.3713244 -0.6775519 -0.3831684 -0.1192995 -0.915942 -0.91846 -0.3954612 0.006469905 -0.8839036 0.4618199 -0.07373487 -0.8662993 0.4749157 -0.1548565 -0.5039353 0.05688804 -0.861866 -0.5833737 0.1697781 -0.7942611 -0.6604727 0.2685412 -0.7011858 -0.7362585 0.348505 -0.5800584 -0.7953729 0.4053316 -0.4506533 -0.8388761 0.4487822 -0.3080284 -0.5008801 0.6383384 -0.5845026 -0.4084364 0.5877969 -0.698337 -0.574275 0.6846925 -0.4487811 -0.6238109 0.7186949 -0.3071445 -0.655127 0.7392992 -0.1557094 0.02908468 0.4127401 -0.9103844 0.1811593 0.9834364 0.005859553 -0.6469364 0.7589708 -0.07373327 -0.1570528 0.4692661 -0.8689786 -0.3021737 0.5312532 -0.7914931 -0.3518596 0.9254743 -0.1403288 -0.3164535 0.9043143 -0.2864837 0.3589978 0.6545767 -0.6653195 0.3996484 0.8933264 0.2055465 -0.3047372 0.950835 -0.05520975 0.2314619 0.690357 -0.6854434 0.06173962 0.7471324 -0.6618016 -0.06430333 0.7813148 -0.6208158 -0.1769208 0.8300964 -0.5288092 -0.2592316 0.8753567 -0.4081051 -0.4414338 0.5535624 -0.7061904 -0.3804863 0.4900206 -0.7842895 -0.5102906 0.6398776 -0.5745958 -0.5608342 0.7032707 -0.4368928 -0.5930815 0.7437248 -0.3084281 -0.6171365 0.7738851 -0.1422823 -0.2563951 0.3215238 -0.9115284 -0.3737083 0.4686231 0.800459 0.2406426 0.9701086 -0.03131252 -0.3142602 0.4110378 -0.8557387 -0.8115078 0.5088481 -0.2872781 -0.7957317 0.4475057 -0.4081051 -0.8244809 0.5484637 -0.1393514 -0.7157707 -0.2188544 -0.6631554 -0.9598483 -0.1908344 0.2056055 -0.8591758 0.5086935 -0.05520915 -0.7412797 -0.06753885 -0.6677896 -0.7419123 0.09421157 -0.6638452 -0.7475324 0.2318834 -0.622435 -0.7724103 0.3568609 -0.525388 -0.4507037 0.4128298 -0.7914782 -0.4214984 0.2674383 -0.8664965 -0.4785414 0.5285319 -0.7011792 -0.5097432 0.6334098 -0.5821974 -0.539736 0.7122319 -0.4487882 -0.5610877 0.7683103 -0.308026 -0.5744404 0.8037648 -0.1548565 -0.3969669 0.05874997 -0.9159508 -0.9990931 0.0421769 0.005859553 -0.5959811 0.799606 -0.07373464 -0.2501928 0.9181874 -0.3071408 -0.2203204 0.8660525 -0.4487896 -0.2694834 0.9503335 -0.1557083 0.2053017 0.3592398 -0.9103834 0.5899276 0.8074348 0.005859553 -0.2535557 0.9645065 -0.07373499 0.06207567 0.4909595 -0.868968 -0.04174989 0.609769 -0.7914789 -0.1129518 0.7067959 -0.698342 -0.1742935 0.7924541 -0.5844982 0.3797783 0.6463618 -0.6618044 0.508091 0.5215502 -0.6854407 0.2810493 0.7318452 -0.6208171 0.2007258 0.8246638 -0.5288091 0.1462487 0.9011448 -0.4081047 0.1072431 0.9520652 -0.2864802 0.08450675 0.9864924 -0.1403258 0.6074763 0.433977 -0.6653094 0.7476637 0.631446 0.205609 0.1379748 0.9888958 -0.0552082 -0.200145 0.8769696 -0.4368826 -0.1821085 0.7979266 -0.5745865 -0.2116478 0.9274053 -0.308423 -0.2202554 0.96501 -0.1422795 -0.09149748 0.4009347 -0.911526 -0.1333396 0.5842344 0.8005565 0.6377246 0.7696277 -0.03131246 -0.1048024 0.506708 -0.855724 -0.1301965 0.6065765 -0.784292 -0.1575397 0.6902814 -0.7061819 -0.6971811 0.2607562 -0.667791 -0.7398474 0.113379 -0.6631525 -0.6275417 0.4067943 -0.6638599 -0.5728801 0.5332659 -0.6224436 -0.5410789 0.656656 -0.5253919 -0.5227606 0.7484488 -0.4081005 -0.5103462 0.810566 -0.2872796 -0.50485 0.8518849 -0.139351 -0.9476491 0.2444886 0.2053936 -0.5533751 0.8311004 -0.05520927 -0.1772576 0.8758808 -0.4487901 -0.1844294 0.791859 -0.58219 -0.1721559 0.9356725 -0.3080251 -0.1688016 0.9734095 -0.1548544 -0.3321727 0.2251718 -0.9159471 -0.8818489 0.4714893 0.006347954 -0.1900095 0.9790097 -0.07373321 -0.2637172 0.4238214 -0.8665038 -0.2269394 0.5675012 -0.7914803 -0.201825 0.6838184 -0.701184 0.1900095 0.9790097 -0.07373321 0.1695309 0.9731469 -0.1557059 0.2689642 0.4153944 -0.8689683 0.3408384 0.2345706 -0.9103878 0.2269394 0.5675012 -0.7914803 0.2048741 0.6858232 -0.6983361 0.1867787 0.7895978 -0.5845075 0.1772576 0.8758808 -0.4487901 0.172953 0.9358143 -0.3071466 0.8818516 0.4714908 0.005859673 0.5386682 0.6558934 -0.5288105 0.5707672 0.5374099 -0.6208184 0.5227606 0.7484488 -0.4081005 0.5096979 0.8112561 -0.2864819 0.5041757 0.852124 -0.1403268 0.7356052 0.1274178 -0.6653194 0.9476491 0.2444886 0.2053936 0.5533751 0.8311004 -0.05520927 0.6840687 0.2494376 -0.6854422 0.6226195 0.4175619 -0.661806 0.2202554 0.96501 -0.1422795 0.2116478 0.9274053 -0.308423 0.09149748 0.4009347 -0.911526 0.1333698 0.5843552 0.8004633 0.9085165 0.4166742 -0.03131234 0.1254047 0.5019849 -0.8557366 0.1458528 0.6030049 -0.7842909 0.1575397 0.6902814 -0.7061819 0.1821085 0.7979266 -0.5745865 0.200145 0.8769696 -0.4368826 -0.2847704 0.7290316 -0.6224297 -0.3865587 0.6340101 -0.6697788 -0.2025563 0.8264003 -0.5253889 -0.1462487 0.9011448 -0.4081047 -0.1081309 0.9517233 -0.287281 -0.08521014 0.98657 -0.1393516 -0.6173809 0.4231541 -0.6631603 -0.7477091 0.6314632 0.2053911 -0.1379748 0.9888958 -0.0552082 -0.507804 0.5445793 -0.6675094 0.2702502 0.950255 -0.1548559 0.2508376 0.9177134 -0.3080306 -0.2015797 0.3470041 -0.9159442 -0.5899264 0.8074332 0.006195247 0.2535557 0.9645065 -0.07373499 -0.05664378 0.503965 -0.8618647 0.03570783 0.6065143 -0.7942703 0.1148433 0.7036785 -0.701176 0.1773781 0.7934712 -0.5821861 0.2203204 0.8660525 -0.4487896 0.482173 0.5289894 -0.6983405 0.4507037 0.4128298 -0.7914782 0.5108946 0.6303475 -0.5845074 0.539736 0.7122319 -0.4487882 0.5618551 0.7681027 -0.3071434 0.5749856 0.8032098 -0.15571 0.4088652 0.06344932 -0.9103865 0.9990901 0.04217678 0.006347835 0.5959811 0.799606 -0.07373464 0.4225664 0.25755 -0.8689681 0.8112204 0.5097557 -0.28648 0.7957317 0.4475057 -0.4081051 0.8239771 0.5489722 -0.1403254 0.7180505 -0.2043551 -0.6653138 0.9598483 -0.1908344 0.2056055 0.8591758 0.5086935 -0.05520915 0.7245603 -0.07205617 -0.6854344 0.7421342 0.106054 -0.6618078 0.7474127 0.2365535 -0.6208195 0.7699142 0.3571997 -0.5288106 0.3930571 0.4800064 -0.7842831 0.3308008 0.3978522 -0.8557363 0.4414338 0.5535624 -0.7061904 0.5102906 0.6398776 -0.5745958 0.5608342 0.7032707 -0.4368928 0.5930815 0.7437248 -0.3084281 0.6171365 0.7738851 -0.1422823 0.2564235 0.3215213 -0.9115213 0.3737083 0.4686231 0.800459 0.999334 -0.01873844 -0.0313121 0.3155125 0.9043899 -0.2872818 0.2592316 0.8753567 -0.4081051 0.3512436 0.9258561 -0.1393499 -0.3726362 0.6491377 -0.663146 -0.3996757 0.8933496 0.2053923 0.3047372 0.950835 -0.05520975 -0.2212038 0.7109773 -0.6675179 -0.07318437 0.7389549 -0.6697685 0.0597251 0.780394 -0.6224292 0.1760365 0.83245 -0.5253933 0.295338 0.5309492 -0.7942723 0.1676123 0.4786352 -0.8618668 0.4087814 0.5841479 -0.7011911 0.5040925 0.637921 -0.5821922 0.5742545 0.6847045 -0.4487889 0.6241793 0.7179954 -0.3080306 0.6557718 0.7389068 -0.1548557 -0.03103804 0.400107 -0.9159428 -0.181164 0.9834316 0.006470143 0.6469364 0.7589708 -0.07373327 0.7953159 0.4075006 -0.4487939 0.7337979 0.3462681 -0.5844991 0.8388761 0.4487822 -0.3080284 0.8662993 0.4749157 -0.1548565 0.3959227 -0.1202142 -0.9103811 0.9184634 -0.3954626 0.005859553 0.8839036 0.4618199 -0.07373487 0.4924582 0.04867815 -0.8689739 0.5851764 0.1764013 -0.7914866 0.6639418 0.2674078 -0.6983368 0.9948061 0.08551496 -0.05520933 0.9808009 0.1364216 -0.1393514 0.6215329 -0.3792983 -0.6854411 0.5582836 -0.4956586 -0.6653136 0.7146602 -0.2264499 -0.6618015 0.7760362 -0.11115 -0.6208168 0.8486527 -0.01220774 -0.5288096 0.9110953 0.05792576 -0.4081053 0.9519242 0.1063594 -0.2872772 0.7819758 -0.5884199 0.2056112 0.7373898 0.3550983 -0.5745969 0.6379113 0.3072057 -0.7061827 0.8104403 0.3902809 -0.4368839 0.8570507 0.4127162 -0.3084308 0.8918038 0.4294673 -0.1422808 0.3705354 0.1784161 -0.9115214 0.540037 0.260054 0.8004573 0.89223 -0.4504945 -0.0313127 0.4706702 0.2149176 -0.8557336 0.5624074 0.2619156 -0.7842819 -0.05407994 0.7465294 -0.663151 0.02749776 0.978293 0.2053942 0.6871189 0.7244444 -0.05520999 0.7181906 0.68175 -0.1393531 0.1091369 0.7365523 -0.6675177 0.2546501 0.6975409 -0.6697687 0.3924144 0.677188 -0.6224368 0.5198053 0.6736227 -0.5253903 0.6133557 0.6761959 -0.4081103 0.6766743 0.6779256 -0.2872783 0.7309693 0.3560084 -0.5821874 0.621769 0.3489267 -0.7011802 0.8144721 0.3677287 -0.4487883 0.8739027 0.3760513 -0.3080251 0.9114354 0.381189 -0.1548561 0.1456077 0.3739534 -0.9159462 0.2634434 0.9646571 0.005859673 0.9121829 0.4030951 -0.07373392 0.358693 0.3585099 -0.8618643 0.4964641 0.3502137 -0.7942756 0.9865676 0.05200487 -0.154855 0.9505296 0.04034674 -0.3080027 0.3045486 -0.280103 -0.9103804 0.6559227 -0.7548055 0.005859673 0.9967463 0.03256362 -0.07373356 0.4648109 -0.1697795 -0.8689798 0.6037642 -0.09494566 -0.7914886 0.7142118 -0.0471217 -0.6983418 0.8113616 -0.006378531 -0.5845099 0.8933656 0.02206552 -0.4487887 0.6537253 -0.4414019 -0.6146605 0.5456252 -0.5140987 -0.6618124 0.7547395 -0.3838399 -0.5320105 0.8460153 -0.3430938 -0.4080991 0.903804 -0.317189 -0.2872799 0.9428659 -0.3026303 -0.1393515 0.2879158 -0.6888127 -0.6653131 0.4492496 -0.869475 0.2053974 0.9333976 -0.3545714 -0.0552091 0.3954145 -0.6114031 -0.6854441 0.989529 -0.001556456 -0.144326 0.9519059 -0.001648008 -0.3063861 0.411249 0 -0.9115231 0.5993943 0 0.8004539 0.608401 -0.7930119 -0.0313127 0.5173277 -0.01055955 -0.8557224 0.6203405 -0.008026599 -0.7842916 0.8971688 -0.003784358 -0.4416718 0.8130902 -0.004333674 -0.5821216 0.7199587 0 -0.6940169 0.8358635 -0.3248478 0.4424998 0.7910761 -0.1837838 0.5834571 0.4492496 0.869475 0.2053974 0.9333976 0.3545714 -0.0552091 0.6328816 -0.5086979 0.5836843 -0.3552772 0.7305446 0.5831661 -0.7927079 0.1776832 0.583132 -0.8940823 0.06997984 0.4424023 -0.6216735 0.7795487 0.07632815 0.5027699 0.7427408 0.4422202 0.7752441 0.4510406 0.4422206 0.6371 0.5040339 0.5831411 -0.7752441 0.4510406 0.4422206 0.2218747 0.9721285 0.07574868 0.6122472 -0.6554321 0.4422243 0.7923914 0.1776196 0.5835815 -0.003143489 0.8123683 0.5831363 -0.1307153 0.887326 0.4422286 0.7909899 0.1837545 0.5835832 0.8358635 0.3248478 0.4424998 0.6216446 0.7795507 0.07654201 0.9971224 0 0.07580959 0.2672014 -0.8561738 0.4422329 0.8983777 -0.4326325 0.07580834 -0.1307153 -0.8872347 0.4424118 0.3553102 -0.7305497 0.5831397 0.5027699 -0.7427408 0.4422202 0.003143429 0.8123539 0.5831565 -0.3496302 -0.7332894 0.5831341 -0.5027813 -0.7427271 0.4422302 -0.3553369 -0.7305418 0.5831333 0.3496302 0.7332894 0.5831341 0.2672014 0.8561738 0.4422329 -0.2218747 -0.9721285 0.07574868 -0.8941669 -0.06998169 0.4422308 0.8941669 -0.06998169 0.4422308 0.2218749 -0.9720687 0.07651174 0.6217035 -0.7795785 0.07577878 -0.6371 -0.5040339 0.5831411 0.6122282 0.6554443 0.4422326 0.1307153 -0.887326 0.4422286 -0.8983275 -0.4326072 0.07654172 -0.8358635 0.3248478 0.4424998 -0.7912924 0.1838149 0.583154 0.7752441 -0.4510406 0.4422206 0.7927079 -0.1776832 0.583132 -0.9971224 0 0.07580959 -0.2671979 0.8561623 0.4422574 -0.6328816 0.5086979 0.5836843 -0.6331887 -0.5089437 0.5831367 -0.6121523 -0.6553369 0.4424965 0.1307153 0.887326 0.4422286 0.003143489 -0.8123683 0.5831363 0.3496239 -0.7332764 0.5831543 -0.2672014 -0.8561738 0.4422329 -0.8359936 -0.3248814 0.4422294 -0.2218749 0.9720687 0.07651174 -0.5027699 0.7427408 0.4422202 0.3551234 0.7302065 0.583683 -0.6371 0.5040339 0.5831411 0.8983275 0.4326072 0.07654172 -0.7909899 -0.1837545 0.5835832 0.8941669 0.06998169 0.4422308 -0.7752441 -0.4510406 0.4422206 -0.003143429 -0.8121366 0.583459 -0.6216446 -0.7795507 0.07654201 0.6331887 0.5089437 0.5831367 -0.7927079 -0.1776832 0.583132 -0.6122472 0.6554321 0.4422243 0.6371 -0.5040339 0.5831411 -0.3496239 0.7332764 0.5831543 -0.8983777 0.4326325 0.07580834 0.2313341 -0.1113944 -0.9664761 0.1493295 -0.1403569 -0.9787751 -0.1492996 -0.1403575 -0.9787796 -0.2313341 -0.1113944 -0.9664761 0.00476098 0.1001945 -0.9949566 -0.01663285 0.2042636 -0.9787746 0.08130329 -0.05871903 -0.9949582 -0.20283 -0.02920675 -0.9787784 0.05713117 0.2503457 -0.9664694 0.09872978 0.01760959 -0.9949585 -0.09662371 -0.02694845 -0.9949561 0.1036124 0.1767972 -0.9787785 0.2567565 0 -0.9664762 0.1954438 -0.06164836 -0.9787755 0.1954438 0.06164836 -0.9787755 -0.04776257 -0.0882005 -0.994957 0.03915607 0.09235107 -0.9949563 -0.07361221 -0.1912331 -0.9787805 -0.03915607 0.09235107 -0.9949563 -0.1601018 -0.2007529 -0.9664708 -0.1036124 0.1767972 -0.9787785 0.09872978 -0.01760959 -0.9949585 -0.1700825 -0.1143243 -0.9787758 -0.05713117 0.2503457 -0.9664694 -0.07535195 -0.0661962 -0.9949574 0.01663285 0.2042636 -0.9787746 -0.00476098 -0.1001945 -0.9949566 -0.00476098 0.1001945 -0.9949566 0.01663285 -0.2042636 -0.9787746 -0.07535195 0.0661962 -0.9949574 -0.05713117 -0.2503457 -0.9664694 -0.1700529 0.1143248 -0.9787808 -0.1036124 -0.1767972 -0.9787785 -0.1600721 0.2007539 -0.9664755 -0.03915607 -0.09235107 -0.9949563 -0.07361221 0.1912331 -0.9787805 0.03915607 -0.09235107 -0.9949563 -0.04776257 0.0882005 -0.994957 0.1036124 -0.1767972 -0.9787785 -0.09662371 0.02694845 -0.9949561 0.05710077 -0.2503461 -0.9664711 -0.20283 0.02920675 -0.9787784 0.08130329 0.05871903 -0.9949582 -0.01663285 -0.2042636 -0.9787746 -0.2313341 0.1113944 -0.9664761 0.1492996 0.1403575 -0.9787796 0.00476098 -0.1001945 -0.9949566 -0.1493295 0.1403569 -0.9787751 0.2313341 0.1113944 -0.9664761 0.07535195 -0.0661962 -0.9949574 -0.08130329 0.05871903 -0.9949582 0.20283 0.02920675 -0.9787784 0.1700825 -0.1143243 -0.9787758 -0.09872978 -0.01760959 -0.9949585 0.09662371 0.02694845 -0.9949561 0.1601018 -0.2007529 -0.9664708 -0.1954438 -0.06164836 -0.9787755 0.04776257 0.0882005 -0.994957 0.07364261 -0.1912327 -0.9787783 -0.256785 0 -0.9664686 0.07361221 0.1912331 -0.9787805 0.04779303 -0.08820039 -0.9949556 -0.1954438 0.06164836 -0.9787755 0.1601018 0.2007529 -0.9664708 0.09662371 -0.02694845 -0.9949561 -0.09872978 0.01760959 -0.9949585 0.1700825 0.1143243 -0.9787758 0.20283 -0.02920675 -0.9787784 -0.08130329 -0.05871903 -0.9949582 0.07535195 0.0661962 -0.9949574 -0.4338883 0.9009668 0 -3.01312e-7 -1 -2.03913e-7 -6.58942e-7 1 2.03913e-7 0.4338883 0.9009668 0 -0.4338842 -0.9009687 -2.54448e-6 0.7818291 0.6234928 -2.54445e-6 -0.7818341 -0.6234866 -2.54447e-6 0.9749274 0.2225235 0 -0.9749274 -0.2225235 0 0.9749274 -0.2225235 0 -0.9749274 0.2225235 0 0.7818341 -0.6234866 0 -0.7818291 0.6234928 0 0.4338842 -0.9009687 0 -0.4032831 0.9142385 0.0391258 0.03332692 0.9986785 0.03912556 0.4633358 0.8853187 0.03912502 0.8015905 0.596592 0.03912574 0.9810612 0.1897056 0.0391252 0.9662257 -0.25471 0.03912508 0.7600222 -0.6487183 0.03912574 0.4032831 -0.9142385 0.0391258 -0.03332692 -0.9986785 0.03912556 -0.4633358 -0.8853187 0.03912502 -0.8015905 -0.596592 0.03912574 -0.9810612 -0.1897056 0.0391252 -0.9662257 0.25471 0.03912508 -0.7600222 0.6487183 0.03912574 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

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

+
+ + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

5 0 4 1 14 2 6 3 5 0 15 4 7 5 6 3 16 6 8 7 7 5 17 8 8 7 18 9 19 10 2 11 1 12 11 13 9 14 19 10 20 15 3 16 2 11 12 17 4 1 3 16 13 18 19 10 18 9 28 19 12 17 11 13 21 20 19 10 29 21 30 22 13 18 12 17 22 23 13 18 23 24 24 25 15 4 14 2 24 25 15 4 25 26 26 27 16 6 26 27 27 28 18 9 17 8 27 28 25 26 24 25 34 29 26 27 25 26 35 30 26 27 36 31 37 32 28 19 27 28 37 32 28 19 38 33 39 34 21 20 31 35 32 36 30 22 29 21 39 34 22 23 32 36 33 37 23 24 33 37 34 29 38 33 37 32 47 38 38 33 48 39 49 40 31 35 41 41 42 42 40 43 39 34 49 40 32 36 42 42 43 44 33 37 43 44 44 45 34 29 44 45 45 46 35 30 45 46 46 47 36 31 46 47 47 38 96 93 95 92 105 97 96 93 106 98 107 99 97 94 107 99 108 100 99 88 98 95 108 100 92 89 91 96 101 101 99 88 109 102 110 103 93 90 92 89 102 104 93 90 103 105 104 106 95 92 94 91 104 106 102 104 101 101 111 107 109 102 119 108 120 109 103 105 102 104 112 110 103 105 113 111 114 112 104 106 114 112 115 113 106 98 105 97 115 113 107 99 106 98 116 114 107 99 117 115 118 116 109 102 108 100 118 116 116 114 115 113 125 117 117 115 116 114 126 118 117 115 127 119 128 120 119 108 118 116 128 120 111 107 121 121 122 122 120 109 119 108 129 123 113 111 112 110 122 122 113 111 123 124 124 125 114 112 124 125 125 117 129 123 128 120 138 126 121 121 131 127 132 128 130 129 129 123 139 130 122 122 132 128 133 131 123 124 133 131 134 132 124 125 134 132 135 133 126 118 125 117 135 133 126 118 136 134 137 135 127 119 137 135 138 126 134 132 144 136 145 137 135 133 145 137 146 138 136 134 146 138 147 139 137 135 147 139 148 140 139 130 138 126 148 140 131 127 141 141 142 142 140 143 139 130 149 144 132 128 142 142 143 145 133 131 143 145 144 136 193 192 192 190 202 195 193 192 203 196 204 197 194 193 204 197 205 198 196 185 195 194 205 198 197 186 196 185 206 199 197 186 207 200 208 201 199 188 198 187 208 201 192 190 191 189 201 202 199 188 209 203 210 204 207 200 206 199 216 205 207 200 217 206 218 207 209 203 208 201 218 207 202 195 201 202 211 208 209 203 219 209 220 210 203 196 202 195 212 211 203 196 213 212 214 213 204 197 214 213 215 214 206 199 205 198 215 214 220 210 219 209 229 215 213 212 212 211 222 216 213 212 223 217 224 218 215 214 214 213 224 218 216 205 215 214 225 219 216 205 226 220 227 221 217 206 227 221 228 222 219 209 218 207 228 222 211 208 221 223 222 216 226 220 225 219 235 224 226 220 236 225 237 226 228 222 227 221 237 226 229 215 228 222 238 227 221 223 231 228 232 229 230 230 229 215 239 231 223 217 222 216 232 229 223 217 233 232 234 233 225 219 224 218 234 233 231 228 241 234 242 235 240 236 239 231 249 237 232 229 242 235 243 238 233 232 243 238 244 239 235 224 234 233 244 239 235 224 245 240 246 241 236 225 246 241 247 242 238 227 237 226 247 242 238 227 248 243 249 237 297 287 307 293 308 294 299 289 298 288 308 294 292 291 291 290 301 295 299 289 309 296 310 297 293 283 292 291 302 298 293 283 303 299 304 300 294 284 304 300 305 301 296 286 295 285 305 301 297 287 296 286 306 302 303 299 313 303 314 304 304 300 314 304 315 305 306 302 305 301 315 305 306 302 316 306 317 307 307 293 317 307 318 308 309 296 308 294 318 308 302 298 301 295 311 309 309 296 319 310 320 311 303 299 302 298 312 312 316 306 326 313 327 314 317 307 327 314 328 315 319 310 318 308 328 315 311 309 321 316 322 317 319 310 329 318 330 319 313 303 312 312 322 317 314 304 313 303 323 320 315 305 314 304 324 321 316 306 315 305 325 322 322 317 332 323 333 324 323 320 333 324 334 325 325 322 324 321 334 325 326 313 325 322 335 326 326 313 336 327 337 328 328 315 327 314 337 328 329 318 328 315 338 329 321 316 331 330 332 323 330 319 329 318 339 331 336 327 346 332 347 333 338 329 337 328 347 333 338 329 348 334 349 335 331 330 341 336 342 337 340 338 339 331 349 335 332 323 342 337 343 339 334 325 333 324 343 339 335 326 334 325 344 340 335 326 345 341 346 332 394 387 404 391 405 392 396 389 395 388 405 392 397 390 396 389 406 393 397 390 407 394 408 395 399 385 398 381 408 395 392 383 391 382 401 396 399 385 409 397 410 398 393 386 392 383 402 399 394 387 393 386 403 400 402 399 401 396 411 401 409 397 419 402 420 403 403 400 402 399 412 404 403 400 413 405 414 406 404 391 414 406 415 407 406 393 405 392 415 407 406 393 416 408 417 409 407 394 417 409 418 410 409 397 408 395 418 410 416 408 415 407 425 411 416 408 426 412 427 413 417 409 427 413 428 414 419 402 418 410 428 414 411 401 421 415 422 416 419 402 429 417 430 418 413 405 412 404 422 416 413 405 423 419 424 420 414 406 424 420 425 411 429 417 428 414 438 421 421 415 431 422 432 423 430 418 429 417 439 424 423 419 422 416 432 423 423 419 433 425 434 426 425 411 424 420 434 426 426 412 425 411 435 427 426 412 436 428 437 429 428 414 427 413 437 429 435 427 434 426 444 430 435 427 445 431 446 432 436 428 446 432 447 433 438 421 437 429 447 433 438 421 448 434 449 435 431 422 441 436 442 437 440 438 439 424 449 435 432 423 442 437 443 439 433 425 443 439 444 430 493 486 492 484 502 489 493 486 503 490 504 491 494 487 504 491 505 492 496 479 495 488 505 492 497 480 496 479 506 493 497 480 507 494 508 495 499 482 498 481 508 495 492 484 491 483 501 496 499 482 509 497 510 498 507 494 506 493 516 499 507 494 517 500 518 501 509 497 508 495 518 501 502 489 501 496 511 502 509 497 519 503 520 504 503 490 502 489 512 505 504 491 503 490 513 506 504 491 514 507 515 508 506 493 505 492 515 508 520 504 519 503 529 509 513 506 512 505 522 510 514 507 513 506 523 511 514 507 524 512 525 513 516 499 515 508 525 513 516 499 526 514 527 515 517 500 527 515 528 516 519 503 518 501 528 516 512 505 511 502 521 517 526 514 525 513 535 518 526 514 536 519 537 520 528 516 527 515 537 520 529 509 528 516 538 521 521 517 531 522 532 523 530 524 529 509 539 525 523 511 522 510 532 523 523 511 533 526 534 527 525 513 524 512 534 527 539 525 538 521 548 528 531 522 541 529 542 530 540 531 539 525 549 532 532 523 542 530 543 533 533 526 543 533 544 534 535 518 534 527 544 534 535 518 545 535 546 536 536 519 546 536 547 537 538 521 537 520 547 537 597 581 608 587 609 588 599 583 598 582 609 588 592 585 591 584 602 589 599 583 610 590 611 591 593 577 592 585 603 592 593 577 604 593 605 594 594 578 605 594 606 595 596 580 595 579 606 595 597 581 596 580 607 596 604 593 614 597 615 598 605 594 615 598 616 599 607 596 606 595 616 599 608 587 607 596 617 600 608 587 618 601 619 602 610 590 609 588 619 602 603 592 602 589 612 603 610 590 620 604 621 605 604 593 603 592 613 606 617 600 627 607 628 608 619 602 618 601 628 608 620 604 619 602 629 609 612 603 622 610 623 611 620 604 630 612 631 613 614 597 613 606 623 611 614 597 624 614 625 615 616 599 615 598 625 615 617 600 616 599 626 616 631 613 630 612 640 617 624 614 623 611 633 618 624 614 634 619 635 620 626 616 625 615 635 620 627 607 626 616 636 621 627 607 637 622 638 623 629 609 628 608 638 623 629 609 639 624 640 617 622 610 632 625 633 618 636 621 646 626 647 627 637 622 647 627 648 628 639 624 638 623 648 628 639 624 649 629 650 630 632 625 642 631 643 632 641 633 640 617 650 630 633 618 643 632 644 634 634 619 644 634 645 635 636 621 635 620 645 635 694 680 693 678 2 11 694 680 3 16 4 1 695 681 4 1 5 0 0 684 5 0 6 3 696 682 6 3 7 5 697 683 7 5 8 7 698 675 8 7 9 14 693 678 692 677 1 12 699 676 9 14 10 687 860 840 870 841 869 842 861 843 871 844 870 841 862 845 872 846 871 844 863 847 873 848 872 846 874 849 873 848 863 847 857 850 867 851 866 852 875 853 874 849 864 854 858 855 868 856 867 851 859 857 869 842 868 856 874 849 884 858 883 859 867 851 877 860 876 861 885 862 884 858 874 849 868 856 878 863 877 860 879 864 878 863 868 856 870 841 880 865 879 864 881 866 880 865 870 841 872 846 882 867 881 866 873 848 883 859 882 867 880 865 890 868 889 869 881 866 891 870 890 868 892 871 891 870 881 866 893 872 892 871 882 867 894 873 893 872 883 859 887 874 886 875 876 861 885 862 895 876 894 873 888 877 887 874 877 860 889 869 888 877 878 863 893 872 903 878 902 879 904 880 903 878 893 872 897 881 896 882 886 875 895 876 905 883 904 880 898 884 897 881 887 874 899 885 898 884 888 877 900 886 899 885 889 869 901 887 900 886 890 868 902 879 901 887 891 870 951 934 961 938 960 939 962 940 961 938 951 934 963 941 962 940 952 935 954 929 964 942 963 941 947 931 957 943 956 944 965 945 964 942 954 929 948 930 958 946 957 943 949 932 959 947 958 946 950 933 960 939 959 947 957 943 967 948 966 949 975 950 974 951 964 942 968 952 967 948 957 943 969 953 968 952 958 946 960 939 970 954 969 953 961 938 971 955 970 954 962 940 972 956 971 955 973 957 972 956 962 940 964 942 974 951 973 957 971 955 981 958 980 959 972 956 982 960 981 958 983 961 982 960 972 956 974 951 984 962 983 961 977 963 976 964 966 949 975 950 985 965 984 962 968 952 978 966 977 963 979 967 978 966 968 952 980 959 979 967 969 953 984 962 994 968 993 969 987 970 986 971 976 964 985 965 995 972 994 968 978 966 988 973 987 970 989 974 988 973 978 966 980 959 990 975 989 974 981 958 991 976 990 975 992 977 991 976 981 958 993 969 992 977 982 960 1000 978 999 979 989 974 991 976 1001 980 1000 978 1002 981 1001 980 991 976 1003 982 1002 981 992 977 994 968 1004 983 1003 982 997 984 996 985 986 971 995 972 1005 986 1004 983 998 987 997 984 987 970 999 979 998 987 988 973 1048 1035 1058 1038 1057 1039 1059 1040 1058 1038 1048 1035 1060 1041 1059 1040 1049 1036 1051 1029 1061 1042 1060 1041 1052 1028 1062 1043 1061 1042 1063 1044 1062 1043 1052 1028 1054 1031 1064 1045 1063 1044 1047 1032 1057 1039 1056 1046 1065 1047 1064 1045 1054 1031 1062 1043 1072 1048 1071 1049 1073 1050 1072 1048 1062 1043 1064 1045 1074 1051 1073 1050 1057 1039 1067 1052 1066 1053 1075 1054 1074 1051 1064 1045 1058 1038 1068 1055 1067 1052 1069 1056 1068 1055 1058 1038 1070 1057 1069 1056 1059 1040 1061 1042 1071 1049 1070 1057 1075 1054 1085 1058 1084 1059 1068 1055 1078 1060 1077 1061 1079 1062 1078 1060 1068 1055 1070 1057 1080 1063 1079 1062 1071 1049 1081 1064 1080 1063 1082 1065 1081 1064 1071 1049 1083 1066 1082 1065 1072 1048 1074 1051 1084 1059 1083 1066 1077 1061 1076 1067 1066 1053 1091 1068 1090 1069 1080 1063 1092 1070 1091 1068 1081 1064 1083 1066 1093 1071 1092 1070 1094 1072 1093 1071 1083 1066 1087 1073 1086 1074 1076 1067 1085 1058 1095 1075 1094 1072 1078 1060 1088 1076 1087 1073 1089 1077 1088 1076 1078 1060 1080 1063 1090 1069 1089 1077 1097 1078 1096 1079 1086 1074 1095 1075 1105 1080 1104 1081 1098 1082 1097 1078 1087 1073 1099 1083 1098 1082 1088 1076 1100 1084 1099 1083 1089 1077 1101 1085 1100 1084 1090 1069 1102 1086 1101 1085 1091 1068 1093 1071 1103 1087 1102 1086 1104 1081 1103 1087 1093 1071 1163 1138 1162 1139 1152 1132 1154 1134 1164 1140 1163 1138 1147 1135 1157 1141 1156 1142 1165 1143 1164 1140 1154 1134 1148 1129 1158 1144 1157 1141 1159 1145 1158 1144 1148 1129 1160 1146 1159 1145 1149 1128 1151 1131 1161 1147 1160 1146 1162 1139 1161 1147 1151 1131 1169 1148 1168 1149 1158 1144 1170 1150 1169 1148 1159 1145 1161 1147 1171 1151 1170 1150 1172 1152 1171 1151 1161 1147 1173 1153 1172 1152 1162 1139 1164 1140 1174 1154 1173 1153 1157 1141 1167 1155 1166 1156 1175 1157 1174 1154 1164 1140 1158 1144 1168 1149 1167 1155 1182 1158 1181 1159 1171 1151 1183 1160 1182 1158 1172 1152 1174 1154 1184 1161 1183 1160 1177 1162 1176 1163 1166 1156 1185 1164 1184 1161 1174 1154 1178 1165 1177 1162 1167 1155 1169 1148 1179 1166 1178 1165 1180 1167 1179 1166 1169 1148 1171 1151 1181 1159 1180 1167 1178 1165 1188 1168 1187 1169 1189 1170 1188 1168 1178 1165 1180 1167 1190 1171 1189 1170 1181 1159 1191 1172 1190 1171 1192 1173 1191 1172 1181 1159 1183 1160 1193 1174 1192 1173 1184 1161 1194 1175 1193 1174 1187 1169 1186 1176 1176 1163 1185 1164 1195 1177 1194 1175 1202 1178 1201 1179 1191 1172 1193 1174 1203 1180 1202 1178 1204 1181 1203 1180 1193 1174 1197 1182 1196 1183 1186 1176 1195 1177 1205 1184 1204 1181 1198 1185 1197 1182 1187 1169 1189 1170 1199 1186 1198 1185 1190 1171 1200 1187 1199 1186 1201 1179 1200 1187 1190 1171 1260 1238 1259 1239 1249 1234 1251 1236 1261 1240 1260 1238 1252 1237 1262 1241 1261 1240 1263 1242 1262 1241 1252 1237 1254 1228 1264 1243 1263 1242 1247 1230 1257 1244 1256 1245 1265 1246 1264 1243 1254 1228 1248 1233 1258 1247 1257 1244 1249 1234 1259 1239 1258 1247 1257 1244 1267 1248 1266 1249 1275 1250 1274 1251 1264 1243 1258 1247 1268 1252 1267 1248 1269 1253 1268 1252 1258 1247 1270 1254 1269 1253 1259 1239 1261 1240 1271 1255 1270 1254 1272 1256 1271 1255 1261 1240 1273 1257 1272 1256 1262 1241 1264 1243 1274 1251 1273 1257 1271 1255 1281 1258 1280 1259 1282 1260 1281 1258 1271 1255 1283 1261 1282 1260 1272 1256 1274 1251 1284 1262 1283 1261 1277 1263 1276 1264 1266 1249 1285 1265 1284 1262 1274 1251 1268 1252 1278 1266 1277 1263 1279 1267 1278 1266 1268 1252 1280 1259 1279 1267 1269 1253 1284 1262 1294 1268 1293 1269 1287 1270 1286 1271 1276 1264 1285 1265 1295 1272 1294 1268 1278 1266 1288 1273 1287 1270 1289 1274 1288 1273 1278 1266 1280 1259 1290 1275 1289 1274 1281 1258 1291 1276 1290 1275 1292 1277 1291 1276 1281 1258 1283 1261 1293 1269 1292 1277 1290 1275 1300 1278 1299 1279 1301 1280 1300 1278 1290 1275 1302 1281 1301 1280 1291 1276 1293 1269 1303 1282 1302 1281 1304 1283 1303 1282 1293 1269 1297 1284 1296 1285 1286 1271 1295 1272 1305 1286 1304 1283 1298 1287 1297 1284 1287 1270 1299 1279 1298 1287 1288 1273 1348 1335 1358 1338 1357 1339 1359 1340 1358 1338 1348 1335 1360 1341 1359 1340 1349 1336 1351 1329 1361 1342 1360 1341 1352 1328 1362 1343 1361 1342 1363 1344 1362 1343 1352 1328 1354 1331 1364 1345 1363 1344 1347 1332 1357 1339 1356 1346 1365 1347 1364 1345 1354 1331 1362 1343 1372 1348 1371 1349 1373 1350 1372 1348 1362 1343 1364 1345 1374 1351 1373 1350 1357 1339 1367 1352 1366 1353 1375 1354 1374 1351 1364 1345 1358 1338 1368 1355 1367 1352 1359 1340 1369 1356 1368 1355 1370 1357 1369 1356 1359 1340 1361 1342 1371 1349 1370 1357 1375 1354 1385 1358 1384 1359 1368 1355 1378 1360 1377 1361 1369 1356 1379 1362 1378 1360 1380 1363 1379 1362 1369 1356 1371 1349 1381 1364 1380 1363 1382 1365 1381 1364 1371 1349 1383 1366 1382 1365 1372 1348 1374 1351 1384 1359 1383 1366 1367 1352 1377 1361 1376 1367 1381 1364 1391 1368 1390 1369 1392 1370 1391 1368 1381 1364 1383 1366 1393 1371 1392 1370 1384 1359 1394 1372 1393 1371 1387 1373 1386 1374 1376 1367 1385 1358 1395 1375 1394 1372 1378 1360 1388 1376 1387 1373 1389 1377 1388 1376 1378 1360 1380 1363 1390 1369 1389 1377 1404 1378 1403 1379 1393 1371 1397 1380 1396 1381 1386 1374 1395 1375 1405 1382 1404 1378 1398 1383 1397 1380 1387 1373 1399 1384 1398 1383 1388 1376 1390 1369 1400 1385 1399 1384 1401 1386 1400 1385 1390 1369 1402 1387 1401 1386 1391 1368 1393 1371 1403 1379 1402 1387 1464 1438 1463 1439 1452 1432 1454 1434 1465 1440 1464 1438 1447 1435 1458 1441 1457 1442 1466 1443 1465 1440 1454 1434 1448 1429 1459 1444 1458 1441 1460 1445 1459 1444 1448 1429 1461 1446 1460 1445 1449 1428 1451 1431 1462 1447 1461 1446 1452 1432 1463 1439 1462 1447 1470 1448 1469 1449 1459 1444 1471 1450 1470 1448 1460 1445 1462 1447 1472 1451 1471 1450 1463 1439 1473 1452 1472 1451 1474 1453 1473 1452 1463 1439 1465 1440 1475 1454 1474 1453 1458 1441 1468 1455 1467 1456 1476 1457 1475 1454 1465 1440 1459 1444 1469 1449 1468 1455 1483 1458 1482 1459 1472 1451 1484 1460 1483 1458 1473 1452 1485 1461 1484 1460 1474 1453 1468 1455 1478 1462 1477 1463 1476 1457 1486 1464 1485 1461 1469 1449 1479 1465 1478 1462 1480 1466 1479 1465 1469 1449 1471 1450 1481 1467 1480 1466 1472 1451 1482 1459 1481 1467 1486 1464 1496 1468 1495 1469 1479 1465 1489 1470 1488 1471 1490 1472 1489 1470 1479 1465 1481 1467 1491 1473 1490 1472 1482 1459 1492 1474 1491 1473 1493 1475 1492 1474 1482 1459 1484 1460 1494 1476 1493 1475 1495 1469 1494 1476 1484 1460 1488 1471 1487 1477 1477 1463 1502 1478 1501 1479 1491 1473 1503 1480 1502 1478 1492 1474 1494 1476 1504 1481 1503 1480 1505 1482 1504 1481 1494 1476 1498 1483 1497 1484 1487 1477 1496 1468 1506 1485 1505 1482 1499 1486 1498 1483 1488 1471 1500 1487 1499 1486 1489 1470 1491 1473 1501 1479 1500 1487 1549 1533 858 855 857 850 859 857 858 855 1549 1533 860 840 859 857 1550 1534 861 843 860 840 855 1537 862 845 861 843 1551 1536 863 847 862 845 1552 1535 864 854 863 847 1553 1529 1548 1530 857 850 856 1540 865 1541 864 854 1554 1528 15 4 5 0 14 2 16 6 6 3 15 4 17 8 7 5 16 6 18 9 8 7 17 8 9 14 8 7 19 10 12 17 2 11 11 13 10 687 9 14 20 15 13 18 3 16 12 17 14 2 4 1 13 18 29 21 19 10 28 19 22 23 12 17 21 20 20 15 19 10 30 22 23 24 13 18 22 23 14 2 13 18 24 25 25 26 15 4 24 25 16 6 15 4 26 27 17 8 16 6 27 28 28 19 18 9 27 28 35 30 25 26 34 29 36 31 26 27 35 30 27 28 26 27 37 32 38 33 28 19 37 32 29 21 28 19 39 34 22 23 21 20 32 36 40 43 30 22 39 34 23 24 22 23 33 37 24 25 23 24 34 29 48 39 38 33 47 38 39 34 38 33 49 40 32 36 31 35 42 42 50 1694 40 43 49 40 33 37 32 36 43 44 34 29 33 37 44 45 35 30 34 29 45 46 36 31 35 30 46 47 37 32 36 31 47 38 106 98 96 93 105 97 97 94 96 93 107 99 98 95 97 94 108 100 109 102 99 88 108 100 102 104 92 89 101 101 100 1695 99 88 110 103 103 105 93 90 102 104 94 91 93 90 104 106 105 97 95 92 104 106 112 110 102 104 111 107 110 103 109 102 120 109 113 111 103 105 112 110 104 106 103 105 114 112 105 97 104 106 115 113 116 114 106 98 115 113 117 115 107 99 116 114 108 100 107 99 118 116 119 108 109 102 118 116 126 118 116 114 125 117 127 119 117 115 126 118 118 116 117 115 128 120 129 123 119 108 128 120 112 110 111 107 122 122 130 129 120 109 129 123 123 124 113 111 122 122 114 112 113 111 124 125 115 113 114 112 125 117 139 130 129 123 138 126 122 122 121 121 132 128 140 143 130 129 139 130 123 124 122 122 133 131 124 125 123 124 134 132 125 117 124 125 135 133 136 134 126 118 135 133 127 119 126 118 137 135 128 120 127 119 138 126 135 133 134 132 145 137 136 134 135 133 146 138 137 135 136 134 147 139 138 126 137 135 148 140 149 144 139 130 148 140 132 128 131 127 142 142 150 1696 140 143 149 144 133 131 132 128 143 145 134 132 133 131 144 136 203 196 193 192 202 195 194 193 193 192 204 197 195 194 194 193 205 198 206 199 196 185 205 198 207 200 197 186 206 199 198 187 197 186 208 201 209 203 199 188 208 201 202 195 192 190 201 202 200 1697 199 188 210 204 217 206 207 200 216 205 208 201 207 200 218 207 219 209 209 203 218 207 212 211 202 195 211 208 210 204 209 203 220 210 213 212 203 196 212 211 204 197 203 196 214 213 205 198 204 197 215 214 216 205 206 199 215 214 230 230 220 210 229 215 223 217 213 212 222 216 214 213 213 212 224 218 225 219 215 214 224 218 226 220 216 205 225 219 217 206 216 205 227 221 218 207 217 206 228 222 229 215 219 209 228 222 212 211 211 208 222 216 236 225 226 220 235 224 227 221 226 220 237 226 238 227 228 222 237 226 239 231 229 215 238 227 222 216 221 223 232 229 240 236 230 230 239 231 233 232 223 217 232 229 224 218 223 217 234 233 235 224 225 219 234 233 232 229 231 228 242 235 250 1698 240 236 249 237 233 232 232 229 243 238 234 233 233 232 244 239 245 240 235 224 244 239 236 225 235 224 246 241 237 226 236 225 247 242 248 243 238 227 247 242 239 231 238 227 249 237 298 288 297 287 308 294 309 296 299 289 308 294 302 298 292 291 301 295 300 1699 299 289 310 297 303 299 293 283 302 298 294 284 293 283 304 300 295 285 294 284 305 301 306 302 296 286 305 301 307 293 297 287 306 302 304 300 303 299 314 304 305 301 304 300 315 305 316 306 306 302 315 305 307 293 306 302 317 307 308 294 307 293 318 308 319 310 309 296 318 308 312 312 302 298 311 309 310 297 309 296 320 311 313 303 303 299 312 312 317 307 316 306 327 314 318 308 317 307 328 315 329 318 319 310 328 315 312 312 311 309 322 317 320 311 319 310 330 319 323 320 313 303 322 317 324 321 314 304 323 320 325 322 315 305 324 321 326 313 316 306 325 322 323 320 322 317 333 324 324 321 323 320 334 325 335 326 325 322 334 325 336 327 326 313 335 326 327 314 326 313 337 328 338 329 328 315 337 328 339 331 329 318 338 329 322 317 321 316 332 323 340 338 330 319 339 331 337 328 336 327 347 333 348 334 338 329 347 333 339 331 338 329 349 335 332 323 331 330 342 337 350 1700 340 338 349 335 333 324 332 323 343 339 344 340 334 325 343 339 345 341 335 326 344 340 336 327 335 326 346 332 395 388 394 387 405 392 406 393 396 389 405 392 407 394 397 390 406 393 398 381 397 390 408 395 409 397 399 385 408 395 402 399 392 383 401 396 400 1701 399 385 410 398 403 400 393 386 402 399 404 391 394 387 403 400 412 404 402 399 411 401 410 398 409 397 420 403 413 405 403 400 412 404 404 391 403 400 414 406 405 392 404 391 415 407 416 408 406 393 415 407 407 394 406 393 417 409 408 395 407 394 418 410 419 402 409 397 418 410 426 412 416 408 425 411 417 409 416 408 427 413 418 410 417 409 428 414 429 417 419 402 428 414 412 404 411 401 422 416 420 403 419 402 430 418 423 419 413 405 422 416 414 406 413 405 424 420 415 407 414 406 425 411 439 424 429 417 438 421 422 416 421 415 432 423 440 438 430 418 439 424 433 425 423 419 432 423 424 420 423 419 434 426 435 427 425 411 434 426 436 428 426 412 435 427 427 413 426 412 437 429 438 421 428 414 437 429 445 431 435 427 444 430 436 428 435 427 446 432 437 429 436 428 447 433 448 434 438 421 447 433 439 424 438 421 449 435 432 423 431 422 442 437 450 1702 440 438 449 435 433 425 432 423 443 439 434 426 433 425 444 430 503 490 493 486 502 489 494 487 493 486 504 491 495 488 494 487 505 492 506 493 496 479 505 492 507 494 497 480 506 493 498 481 497 480 508 495 509 497 499 482 508 495 502 489 492 484 501 496 500 1703 499 482 510 498 517 500 507 494 516 499 508 495 507 494 518 501 519 503 509 497 518 501 512 505 502 489 511 502 510 498 509 497 520 504 513 506 503 490 512 505 514 507 504 491 513 506 505 492 504 491 515 508 516 499 506 493 515 508 530 524 520 504 529 509 523 511 513 506 522 510 524 512 514 507 523 511 515 508 514 507 525 513 526 514 516 499 525 513 517 500 516 499 527 515 518 501 517 500 528 516 529 509 519 503 528 516 522 510 512 505 521 517 536 519 526 514 535 518 527 515 526 514 537 520 538 521 528 516 537 520 539 525 529 509 538 521 522 510 521 517 532 523 540 531 530 524 539 525 533 526 523 511 532 523 524 512 523 511 534 527 535 518 525 513 534 527 549 532 539 525 548 528 532 523 531 522 542 530 550 1704 540 531 549 532 533 526 532 523 543 533 534 527 533 526 544 534 545 535 535 518 544 534 536 519 535 518 546 536 537 520 536 519 547 537 548 528 538 521 547 537 598 582 597 581 609 588 610 590 599 583 609 588 603 592 592 585 602 589 600 1705 599 583 611 591 604 593 593 577 603 592 594 578 593 577 605 594 595 579 594 578 606 595 607 596 596 580 606 595 608 587 597 581 607 596 605 594 604 593 615 598 606 595 605 594 616 599 617 600 607 596 616 599 618 601 608 587 617 600 609 588 608 587 619 602 620 604 610 590 619 602 613 606 603 592 612 603 611 591 610 590 621 605 614 597 604 593 613 606 618 601 617 600 628 608 629 609 619 602 628 608 630 612 620 604 629 609 613 606 612 603 623 611 621 605 620 604 631 613 624 614 614 597 623 611 615 598 614 597 625 615 626 616 616 599 625 615 627 607 617 600 626 616 641 633 631 613 640 617 634 619 624 614 633 618 625 615 624 614 635 620 636 621 626 616 635 620 637 622 627 607 636 621 628 608 627 607 638 623 639 624 629 609 638 623 630 612 629 609 640 617 623 611 622 610 633 618 637 622 636 621 647 627 638 623 637 622 648 628 649 629 639 624 648 628 640 617 639 624 650 630 633 618 632 625 643 632 651 1706 641 633 650 630 634 619 633 618 644 634 635 620 634 619 645 635 646 626 636 621 645 635 3 16 694 680 2 11 695 681 694 680 4 1 0 684 695 681 5 0 696 682 0 684 6 3 697 683 696 682 7 5 698 675 697 683 8 7 699 676 698 675 9 14 2 11 693 678 1 12 700 1707 699 676 10 687 859 857 860 840 869 842 860 840 861 843 870 841 861 843 862 845 871 844 862 845 863 847 872 846 864 854 874 849 863 847 856 1540 857 850 866 852 865 1541 875 853 864 854 857 850 858 855 867 851 858 855 859 857 868 856 873 848 874 849 883 859 866 852 867 851 876 861 875 853 885 862 874 849 867 851 868 856 877 860 869 842 879 864 868 856 869 842 870 841 879 864 871 844 881 866 870 841 871 844 872 846 881 866 872 846 873 848 882 867 879 864 880 865 889 869 880 865 881 866 890 868 882 867 892 871 881 866 883 859 893 872 882 867 884 858 894 873 883 859 877 860 887 874 876 861 884 858 885 862 894 873 878 863 888 877 877 860 879 864 889 869 878 863 892 871 893 872 902 879 894 873 904 880 893 872 887 874 897 881 886 875 894 873 895 876 904 880 888 877 898 884 887 874 889 869 899 885 888 877 890 868 900 886 889 869 891 870 901 887 890 868 892 871 902 879 891 870 950 933 951 934 960 939 952 935 962 940 951 934 953 936 963 941 952 935 953 936 954 929 963 941 946 937 947 931 956 944 955 928 965 945 954 929 947 931 948 930 957 943 948 930 949 932 958 946 949 932 950 933 959 947 956 944 957 943 966 949 965 945 975 950 964 942 958 946 968 952 957 943 959 947 969 953 958 946 959 947 960 939 969 953 960 939 961 938 970 954 961 938 962 940 971 955 963 941 973 957 962 940 963 941 964 942 973 957 970 954 971 955 980 959 971 955 972 956 981 958 973 957 983 961 972 956 973 957 974 951 983 961 967 948 977 963 966 949 974 951 975 950 984 962 967 948 968 952 977 963 969 953 979 967 968 952 970 954 980 959 969 953 983 961 984 962 993 969 977 963 987 970 976 964 984 962 985 965 994 968 977 963 978 966 987 970 979 967 989 974 978 966 979 967 980 959 989 974 980 959 981 958 990 975 982 960 992 977 981 958 983 961 993 969 982 960 990 975 1000 978 989 974 990 975 991 976 1000 978 992 977 1002 981 991 976 993 969 1003 982 992 977 993 969 994 968 1003 982 987 970 997 984 986 971 994 968 995 972 1004 983 988 973 998 987 987 970 989 974 999 979 988 973 1047 1032 1048 1035 1057 1039 1049 1036 1059 1040 1048 1035 1050 1037 1060 1041 1049 1036 1050 1037 1051 1029 1060 1041 1051 1029 1052 1028 1061 1042 1053 1030 1063 1044 1052 1028 1053 1030 1054 1031 1063 1044 1046 1033 1047 1032 1056 1046 1055 1034 1065 1047 1054 1031 1061 1042 1062 1043 1071 1049 1063 1044 1073 1050 1062 1043 1063 1044 1064 1045 1073 1050 1056 1046 1057 1039 1066 1053 1065 1047 1075 1054 1064 1045 1057 1039 1058 1038 1067 1052 1059 1040 1069 1056 1058 1038 1060 1041 1070 1057 1059 1040 1060 1041 1061 1042 1070 1057 1074 1051 1075 1054 1084 1059 1067 1052 1068 1055 1077 1061 1069 1056 1079 1062 1068 1055 1069 1056 1070 1057 1079 1062 1070 1057 1071 1049 1080 1063 1072 1048 1082 1065 1071 1049 1073 1050 1083 1066 1072 1048 1073 1050 1074 1051 1083 1066 1067 1052 1077 1061 1066 1053 1081 1064 1091 1068 1080 1063 1082 1065 1092 1070 1081 1064 1082 1065 1083 1066 1092 1070 1084 1059 1094 1072 1083 1066 1077 1061 1087 1073 1076 1067 1084 1059 1085 1058 1094 1072 1077 1061 1078 1060 1087 1073 1079 1062 1089 1077 1078 1060 1079 1062 1080 1063 1089 1077 1087 1073 1097 1078 1086 1074 1094 1072 1095 1075 1104 1081 1088 1076 1098 1082 1087 1073 1089 1077 1099 1083 1088 1076 1090 1069 1100 1084 1089 1077 1091 1068 1101 1085 1090 1069 1092 1070 1102 1086 1091 1068 1092 1070 1093 1071 1102 1086 1094 1072 1104 1081 1093 1071 1153 1133 1163 1138 1152 1132 1153 1133 1154 1134 1163 1138 1146 1136 1147 1135 1156 1142 1155 1137 1165 1143 1154 1134 1147 1135 1148 1129 1157 1141 1149 1128 1159 1145 1148 1129 1150 1130 1160 1146 1149 1128 1150 1130 1151 1131 1160 1146 1152 1132 1162 1139 1151 1131 1159 1145 1169 1148 1158 1144 1160 1146 1170 1150 1159 1145 1160 1146 1161 1147 1170 1150 1162 1139 1172 1152 1161 1147 1163 1138 1173 1153 1162 1139 1163 1138 1164 1140 1173 1153 1156 1142 1157 1141 1166 1156 1165 1143 1175 1157 1164 1140 1157 1141 1158 1144 1167 1155 1172 1152 1182 1158 1171 1151 1173 1153 1183 1160 1172 1152 1173 1153 1174 1154 1183 1160 1167 1155 1177 1162 1166 1156 1175 1157 1185 1164 1174 1154 1168 1149 1178 1165 1167 1155 1168 1149 1169 1148 1178 1165 1170 1150 1180 1167 1169 1148 1170 1150 1171 1151 1180 1167 1177 1162 1178 1165 1187 1169 1179 1166 1189 1170 1178 1165 1179 1166 1180 1167 1189 1170 1180 1167 1181 1159 1190 1171 1182 1158 1192 1173 1181 1159 1182 1158 1183 1160 1192 1173 1183 1160 1184 1161 1193 1174 1177 1162 1187 1169 1176 1163 1184 1161 1185 1164 1194 1175 1192 1173 1202 1178 1191 1172 1192 1173 1193 1174 1202 1178 1194 1175 1204 1181 1193 1174 1187 1169 1197 1182 1186 1176 1194 1175 1195 1177 1204 1181 1188 1168 1198 1185 1187 1169 1188 1168 1189 1170 1198 1185 1189 1170 1190 1171 1199 1186 1191 1172 1201 1179 1190 1171 1250 1235 1260 1238 1249 1234 1250 1235 1251 1236 1260 1238 1251 1236 1252 1237 1261 1240 1253 1229 1263 1242 1252 1237 1253 1229 1254 1228 1263 1242 1246 1231 1247 1230 1256 1245 1255 1232 1265 1246 1254 1228 1247 1230 1248 1233 1257 1244 1248 1233 1249 1234 1258 1247 1256 1245 1257 1244 1266 1249 1265 1246 1275 1250 1264 1243 1257 1244 1258 1247 1267 1248 1259 1239 1269 1253 1258 1247 1260 1238 1270 1254 1259 1239 1260 1238 1261 1240 1270 1254 1262 1241 1272 1256 1261 1240 1263 1242 1273 1257 1262 1241 1263 1242 1264 1243 1273 1257 1270 1254 1271 1255 1280 1259 1272 1256 1282 1260 1271 1255 1273 1257 1283 1261 1272 1256 1273 1257 1274 1251 1283 1261 1267 1248 1277 1263 1266 1249 1275 1250 1285 1265 1274 1251 1267 1248 1268 1252 1277 1263 1269 1253 1279 1267 1268 1252 1270 1254 1280 1259 1269 1253 1283 1261 1284 1262 1293 1269 1277 1263 1287 1270 1276 1264 1284 1262 1285 1265 1294 1268 1277 1263 1278 1266 1287 1270 1279 1267 1289 1274 1278 1266 1279 1267 1280 1259 1289 1274 1280 1259 1281 1258 1290 1275 1282 1260 1292 1277 1281 1258 1282 1260 1283 1261 1292 1277 1289 1274 1290 1275 1299 1279 1291 1276 1301 1280 1290 1275 1292 1277 1302 1281 1291 1276 1292 1277 1293 1269 1302 1281 1294 1268 1304 1283 1293 1269 1287 1270 1297 1284 1286 1271 1294 1268 1295 1272 1304 1283 1288 1273 1298 1287 1287 1270 1289 1274 1299 1279 1288 1273 1347 1332 1348 1335 1357 1339 1349 1336 1359 1340 1348 1335 1350 1337 1360 1341 1349 1336 1350 1337 1351 1329 1360 1341 1351 1329 1352 1328 1361 1342 1353 1330 1363 1344 1352 1328 1353 1330 1354 1331 1363 1344 1346 1333 1347 1332 1356 1346 1355 1334 1365 1347 1354 1331 1361 1342 1362 1343 1371 1349 1363 1344 1373 1350 1362 1343 1363 1344 1364 1345 1373 1350 1356 1346 1357 1339 1366 1353 1365 1347 1375 1354 1364 1345 1357 1339 1358 1338 1367 1352 1358 1338 1359 1340 1368 1355 1360 1341 1370 1357 1359 1340 1360 1341 1361 1342 1370 1357 1374 1351 1375 1354 1384 1359 1367 1352 1368 1355 1377 1361 1368 1355 1369 1356 1378 1360 1370 1357 1380 1363 1369 1356 1370 1357 1371 1349 1380 1363 1372 1348 1382 1365 1371 1349 1373 1350 1383 1366 1372 1348 1373 1350 1374 1351 1383 1366 1366 1353 1367 1352 1376 1367 1380 1363 1381 1364 1390 1369 1382 1365 1392 1370 1381 1364 1382 1365 1383 1366 1392 1370 1383 1366 1384 1359 1393 1371 1377 1361 1387 1373 1376 1367 1384 1359 1385 1358 1394 1372 1377 1361 1378 1360 1387 1373 1379 1362 1389 1377 1378 1360 1379 1362 1380 1363 1389 1377 1394 1372 1404 1378 1393 1371 1387 1373 1397 1380 1386 1374 1394 1372 1395 1375 1404 1378 1388 1376 1398 1383 1387 1373 1389 1377 1399 1384 1388 1376 1389 1377 1390 1369 1399 1384 1391 1368 1401 1386 1390 1369 1392 1370 1402 1387 1391 1368 1392 1370 1393 1371 1402 1387 1453 1433 1464 1438 1452 1432 1453 1433 1454 1434 1464 1438 1446 1436 1447 1435 1457 1442 1455 1437 1466 1443 1454 1434 1447 1435 1448 1429 1458 1441 1449 1428 1460 1445 1448 1429 1450 1430 1461 1446 1449 1428 1450 1430 1451 1431 1461 1446 1451 1431 1452 1432 1462 1447 1460 1445 1470 1448 1459 1444 1461 1446 1471 1450 1460 1445 1461 1446 1462 1447 1471 1450 1462 1447 1463 1439 1472 1451 1464 1438 1474 1453 1463 1439 1464 1438 1465 1440 1474 1453 1457 1442 1458 1441 1467 1456 1466 1443 1476 1457 1465 1440 1458 1441 1459 1444 1468 1455 1473 1452 1483 1458 1472 1451 1474 1453 1484 1460 1473 1452 1475 1454 1485 1461 1474 1453 1467 1456 1468 1455 1477 1463 1475 1454 1476 1457 1485 1461 1468 1455 1469 1449 1478 1462 1470 1448 1480 1466 1469 1449 1470 1448 1471 1450 1480 1466 1471 1450 1472 1451 1481 1467 1485 1461 1486 1464 1495 1469 1478 1462 1479 1465 1488 1471 1480 1466 1490 1472 1479 1465 1480 1466 1481 1467 1490 1472 1481 1467 1482 1459 1491 1473 1483 1458 1493 1475 1482 1459 1483 1458 1484 1460 1493 1475 1485 1461 1495 1469 1484 1460 1478 1462 1488 1471 1477 1463 1492 1474 1502 1478 1491 1473 1493 1475 1503 1480 1492 1474 1493 1475 1494 1476 1503 1480 1495 1469 1505 1482 1494 1476 1488 1471 1498 1483 1487 1477 1495 1469 1496 1468 1505 1482 1489 1470 1499 1486 1488 1471 1490 1472 1500 1487 1489 1470 1490 1472 1491 1473 1500 1487 1548 1530 1549 1533 857 850 1550 1534 859 857 1549 1533 855 1537 860 840 1550 1534 1551 1536 861 843 855 1537 1552 1535 862 845 1551 1536 1553 1529 863 847 1552 1535 1554 1528 864 854 1553 1529 1547 1531 1548 1530 856 1540 1555 1532 865 1541 1554 1528

+
+ + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

300 826 706 826 715 826 700 827 714 827 715 827 350 828 707 828 715 828 400 829 708 829 715 829 50 830 701 830 715 830 450 831 709 831 715 831 100 832 702 832 715 832 500 833 710 833 715 833 150 834 703 834 715 834 550 835 711 835 715 835 200 836 704 836 715 836 600 837 712 837 715 837 250 838 705 838 715 838 651 839 713 839 715 839 1155 1680 1570 1680 1561 1680 1555 1681 1570 1681 1569 1681 1205 1682 1570 1682 1562 1682 1255 1683 1570 1683 1563 1683 905 1684 1570 1684 1556 1684 1305 1685 1570 1685 1564 1685 955 1686 1570 1686 1557 1686 1355 1687 1570 1687 1565 1687 1005 1688 1570 1688 1558 1688 1405 1689 1570 1689 1566 1689 1055 1690 1570 1690 1559 1690 1455 1691 1570 1691 1567 1691 1105 1692 1570 1692 1560 1692 1506 1693 1570 1693 1568 1693

+
+
+
+
+ + + + + 0.6858805 -0.3173701 0.6548619 7.481132 0.7276338 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953432 0.4452454 5.343665 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 0.5567018 0 0 0 0 0.5567018 0 0 0 0 0.5567018 1.164695 0 0 0 1 + + + + + + + + + + + + + + + +
diff --git a/models/zephyr_with_parachute/model.config b/models/zephyr_with_parachute/model.config new file mode 100644 index 0000000..efa046c --- /dev/null +++ b/models/zephyr_with_parachute/model.config @@ -0,0 +1,27 @@ + + + + Zephyr Delta Wing With Parachute + 1.0 + model.sdf + + + Cole Biesemeyer + cole.bsmr@gmail.com + + + + Nate Koenig + natekoenig@gmail.com + + + + Rhys Mainwaring + rhys.mainwaring@me.com + + + + A model of a Zephyr delta wing with Ardupilot and Parachute plugins. + + + diff --git a/models/zephyr_with_parachute/model.sdf b/models/zephyr_with_parachute/model.sdf new file mode 100644 index 0000000..9340d1d --- /dev/null +++ b/models/zephyr_with_parachute/model.sdf @@ -0,0 +1,315 @@ + + + + + model://zephyr + + + + + 0 0 0.1 0 0 -1.5707963 + + 0 0 0 0 0 0 + 0.1 + + 0.0001 + 0 + 0 + 0.0001 + 0 + 0.0001 + + + + + + 0.05 + + + + + + parachute_attachment_link + zephyr::wing + + + + + + + + 0.13 + 3.7 + 0.06417112299 + -1.8 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + 0 -0.1 0 + 0.50 + 1.2041 + 0 -1 0 + 0 0 1 + zephyr::wing + + + + 0.15 + 6.8 + 0.06417112299 + -1.8 + 0.6391428111 + -3.85 + -0.9233984055 + 0 + 0.7 0.20 0 + 0.10 + 1.2041 + 0 -1 0 + 0 0 1 + zephyr::wing + zephyr::flap_left_joint + -5.0 + + + + 0.15 + 6.8 + 0.06417112299 + -1.8 + 0.6391428111 + -3.85 + -0.9233984055 + 0 + -0.7 0.20 0 + 0.10 + 1.2041 + 0 -1 0 + 0 0 1 + zephyr::wing + zephyr::flap_right_joint + -5.0 + + + + 0.0 + 4.752798721 + 0.6417112299 + -1.8 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + -0.76 0.30 0.025 + 0.12 + 1.2041 + 0 -1 0 + 1 0 0 + zephyr::wing + + + + 0.0 + 4.752798721 + 0.6417112299 + -1.8 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + 0.76 0.30 0.025 + 0.12 + 1.2041 + 0 -1 0 + 1 0 0 + zephyr::wing + + + + 0.30 + 1.4 + 4.2500 + 0.10 + 0.00 + -0.025 + 0.0 + 0.0 + 0.02 + 1.2041 + 0 0 0.074205 + -1 0 0 + 0 -1 0 + zephyr::propeller + + + + 0.30 + 1.4 + 4.2500 + 0.10 + 0.00 + -0.025 + 0.0 + 0.0 + 0.02 + 1.2041 + 0 0 -0.074205 + 1 0 0 + 0 -1 0 + zephyr::propeller + + + + zephyr::propeller_joint + + + zephyr::flap_left_joint + + + zephyr::flap_right_joint + + + + + 127.0.0.1 + 9002 + 5 + 1 + + + 0 0 0 3.141593 0 -1.5707963 + 0 0 0 3.141593 0 0 + + + zephyr::imu_link::imu_sensor + + + + + + zephyr::propeller_joint + 1 + 838 + 0 + 1100 + 1900 + VELOCITY + 0.20 + 0 + 0 + 0 + 0 + 2.5 + 0.0 + + + + + zephyr::flap_left_joint + 1 + -1.048 + -0.5 + 1100 + 1900 + POSITION + 10.0 + 0 + 0 + 0 + 0 + 2.5 + -2.5 + + + + + zephyr::flap_right_joint + 1 + -1.048 + -0.5 + 1100 + 1900 + POSITION + 10.0 + 0 + 0 + 0 + 0 + 2.5 + -2.5 + + + + + parachute_attachment_joint + COMMAND + /parachute/cmd_release + 1100 + 1900 + + + + + + diff --git a/src/ParachutePlugin.cc b/src/ParachutePlugin.cc new file mode 100644 index 0000000..6074d1c --- /dev/null +++ b/src/ParachutePlugin.cc @@ -0,0 +1,390 @@ +/* + * Copyright (C) 2016 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include "ParachutePlugin.hh" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace gz { +namespace sim { +inline namespace GZ_SIM_VERSION_NAMESPACE { +namespace systems { + +////////////////////////////////////////////////// +class ParachutePlugin::Impl +{ + /// \brief Callback for subscription to the release command. + /// + /// \param _msg + /// The command message. Should be a normalised PWM level in [0, 1]. + public: void OnCommand(const msgs::Double &_msg); + + /// \brief World occupied by the parent model. + public: World world{kNullEntity}; + + /// \brief Name of the world entity. + public: std::string worldName; + + /// \brief Model entity that will release the parachute. + public: Model parentModel{kNullEntity}; + + /// \brief Name of the model entity. + public: std::string parentModelName; + + /// \brief Link entity to attach the parachute. + public: Link parentLink{kNullEntity}; + + /// \brief Name of the link entity to attach the parachute. + public: std::string parentLinkName; + + /// \brief The parachute model. + public: Model childModel{kNullEntity}; + + /// \brief Link entity of the parachute model to attach to parent. + public: Link childLink{kNullEntity}; + + /// \brief Name of the parachute model. + public: std::string childModelName; + + /// \brief Name of the link entity in parachute to attach to parent. + public: std::string childLinkName; + + /// \brief The detachable joint entity created when the parachute is attached. + public: Entity detachableJointEntity{kNullEntity}; + + /// \brief A flag set when the parachute has it's initial position saved. + public: bool initPosSaved{false}; + + /// \brief The pose of the parachute when first created. + public: math::Pose3d initialPos; + + /// \brief The pose of the parachute relative to the parent link. + public: math::Pose3d childPose{0.0, 0.0, 0.0, 0.0, 0.0, 0.0}; + + /// \brief Name of the topic to subscribe to release commands. + public: std::string commandTopic; + + /// \brief Value of the most recently received command. + public: std::atomic command{0.0}; + + /// \brief Flag set to true if parachute released and attachment required. + public: std::atomic attachRequested{false}; + + /// \brief Flag set to true if the model is correctly initialised. + public: bool validConfig{false}; + + /// \brief Flag set to true if the parachute is created and attached. + public: bool attached{false}; + + /// \brief Flag set to true if the parachute should be created and attached. + public: bool shouldAttach{false}; + + /// \brief Flag set to true when the parachute pose is set + /// and it is ready to attach. + public: bool modelOk{false}; + + /// \brief Flag set to true when the parachute model has been created. + public: bool parachuteCreated{false}; + + /// \brief Transport node for subscriptions. + public: transport::Node node; +}; + +////////////////////////////////////////////////// +void ParachutePlugin::Impl::OnCommand(const msgs::Double &_msg) + { + this->command = _msg.data(); + if (this->command > 0.9) + { + this->attachRequested = true; + } +} + +////////////////////////////////////////////////// +////////////////////////////////////////////////// +ParachutePlugin::~ParachutePlugin() = default; + +////////////////////////////////////////////////// +ParachutePlugin::ParachutePlugin() : + impl(std::make_unique()) +{ +} + +////////////////////////////////////////////////// +void ParachutePlugin::Configure( + const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &) +{ + // capture model entity + this->impl->parentModel = Model(_entity); + if (!this->impl->parentModel.Valid(_ecm)) + { + gzerr << "ParachutePlugin should be attached to a model. " + "Failed to initialize.\n"; + return; + } + this->impl->parentModelName = this->impl->parentModel.Name(_ecm); + + // retrieve world entity + this->impl->world = World( + _ecm.EntityByComponents(components::World())); + if (!this->impl->world.Valid(_ecm)) + { + gzerr << "ParachutePlugin - world not found. " + "Failed to initialize.\n"; + return; + } + if (this->impl->world.Name(_ecm).has_value()) + { + this->impl->worldName = this->impl->world.Name(_ecm).value(); + } + + // parameters + if (_sdf->HasElement("parent_link")) + { + this->impl->parentLinkName = _sdf->Get("parent_link"); + } + else + { + gzerr << "ParachutePlugin requires parameter 'parent_link'. " + "Failed to initialize.\n"; + return; + } + + if (_sdf->HasElement("child_model")) + { + this->impl->childModelName = _sdf->Get("child_model"); + } + else + { + gzerr << "ParachutePlugin requires parameter 'child_model'. " + "Failed to initialize.\n"; + return; + } + + if (_sdf->HasElement("child_link")) + { + this->impl->childLinkName = _sdf->Get("child_link"); + } + else + { + gzerr << "ParachutePlugin requires parameter 'child_link'. " + "Failed to initialize.\n"; + return; + } + + if (_sdf->HasElement("child_pose")) + { + this->impl->childPose = _sdf->Get("child_pose"); + gzdbg << "child_pos: pos: " << this->impl->childPose.Pos() << std::endl; + gzdbg << "child_pos: rot: " << this->impl->childPose.Rot() << std::endl; + } + + // configure parachute release command topic + { + std::vector topics; + if (_sdf->HasElement("cmd_topic")) + { + topics.push_back(_sdf->Get("cmd_topic")); + } + topics.push_back("/model/" + this->impl->parentModelName + + "/parachute/cmd_release"); + this->impl->commandTopic = validTopic(topics); + } + + // resolve links + this->impl->parentLink = Link(_ecm.EntityByComponents( + components::Link(), + components::ParentEntity(this->impl->parentModel.Entity()), + components::Name(this->impl->parentLinkName))); + if (!this->impl->parentLink.Valid(_ecm)) + { + gzerr << "ParachutePlugin - parent link [" + << this->impl->parentLinkName + << "] not found. " + "Failed to initialize.\n"; + return; + } + this->impl->parentLink.EnableVelocityChecks(_ecm); + + // subscriptions + this->impl->node.Subscribe( + this->impl->commandTopic, + &ParachutePlugin::Impl::OnCommand, this->impl.get()); + + gzdbg << "ParachutePlugin subscribing to messages on " + << "[" << this->impl->commandTopic << "]\n"; + + this->impl->validConfig = true; +} + +////////////////////////////////////////////////// +void ParachutePlugin::PreUpdate( + const UpdateInfo &/*_info*/, + EntityComponentManager &_ecm) +{ + GZ_PROFILE("ParachutePlugin::PreUpdate"); + if (this->impl->validConfig && + this->impl->shouldAttach && + !this->impl->attached) + { + // create parachute + if (!this->impl->parachuteCreated) + { + bool result; + msgs::EntityFactory req; + msgs::Boolean res; + + // request creation of parachute (child) model + req.set_sdf_filename(this->impl->childModelName); + bool executed = this->impl->node.Request( + "world/" + this->impl->worldName + "/create", + req, 5000, res, result); + if (executed) + { + if (result) + { + gzdbg << "Parachute model created.\n"; + this->impl->parachuteCreated = true; + } + else + { + gzerr << "Failed to create parachute model.\n"; + this->impl->shouldAttach = false; + } + } + else + { + gzdbg << "Parachute model creation timed out.\n"; + this->impl->shouldAttach = false; + } + } + + // retrive parachute model entity + this->impl->childModel = Model(_ecm.EntityByComponents( + components::Model(), + components::Name(this->impl->childModelName))); + + if (this->impl->childModel.Valid(_ecm)) + { + this->impl->childLink = Link(_ecm.EntityByComponents( + components::Link(), + components::ParentEntity(this->impl->childModel.Entity()), + components::Name(this->impl->childLinkName))); + + // parent link world pose + auto X_WPl = worldPose(this->impl->parentLink.Entity(), _ecm); + auto X_PC = this->impl->childPose; + auto X_WC = X_WPl * X_PC; + + // debug - check pose + gzdbg << "X_WPl: " << X_WPl.Pos() << ", " + << X_WPl.Rot().Euler() << "\n"; + gzdbg << "X_PC: " << X_PC.Pos() << ", " + << X_PC.Rot().Euler() << "\n"; + gzdbg << "X_WC: " << X_WC.Pos() << ", " + << X_WC.Rot().Euler() << "\n"; + + this->impl->childModel.SetWorldPoseCmd(_ecm, X_WC); + X_WC = worldPose(this->impl->childModel.Entity(), _ecm); + + // debug - check if child pose has updated + gzdbg << "X_WC: " << X_WC.Pos() << ", " + << X_WC.Rot().Euler() << "\n"; + + if (!this->impl->initPosSaved) + { + this->impl->initialPos = X_WC; + this->impl->initPosSaved = true; + } + + if (this->impl->initialPos != X_WC) + { + gzdbg << "Model OK\n"; + this->impl->modelOk = true; + } + + if (this->impl->childLink.Valid(_ecm) && + this->impl->modelOk) + { + // connect the models using a detachable joint + this->impl->detachableJointEntity = _ecm.CreateEntity(); + + _ecm.CreateComponent( + this->impl->detachableJointEntity, + components::DetachableJoint({ + this->impl->parentLink.Entity(), + this->impl->childLink.Entity(), + "fixed"})); + this->impl->attached = true; + this->impl->shouldAttach = false; + } + else if (!this->impl->childLink.Valid(_ecm)) + { + gzerr << "ParachutePlugin - child link [" + << this->impl->childLinkName + << "] not found. " + "Failed to create joint.\n"; + } + } + } + + // attach requested + if (this->impl->attachRequested && + this->impl->detachableJointEntity == kNullEntity && + !this->impl->shouldAttach) + { + gzdbg << "Parachute release requested!\n"; + this->impl->shouldAttach = true; + this->impl->attachRequested = false; + } +} + +////////////////////////////////////////////////// + +} // namespace systems +} +} // namespace sim +} // namespace gz + +GZ_ADD_PLUGIN( + gz::sim::systems::ParachutePlugin, + gz::sim::System, + gz::sim::systems::ParachutePlugin::ISystemConfigure, + gz::sim::systems::ParachutePlugin::ISystemPreUpdate) + +GZ_ADD_PLUGIN_ALIAS( + gz::sim::systems::ParachutePlugin, + "ParachutePlugin") diff --git a/tests/worlds/test_parachute.sdf b/tests/worlds/test_parachute.sdf new file mode 100755 index 0000000..37f7195 --- /dev/null +++ b/tests/worlds/test_parachute.sdf @@ -0,0 +1,142 @@ + + + + + + 0.001 + 0.1 + + + + + + + + + + 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 + + + + model://runway + + + + 0 0 50 0 0 0 + + + 0.25 + + 0.000417 + 0.00 + 0.00 + 0.000417 + 0.00 + 0.000417 + + + + + + 1 1 1 + + + + 1 1 0 + 1 1 0 + 0.1 0.1 0 1 + + + + + + 1 1 1 + + + + + + 0 0 0.6 0 0 0 + + 0.025 + + 0.0000417 + 0.00 + 0.00 + 0.0000417 + 0.00 + 0.0000417 + + + + + + 0.05 + + + + 0.7 0.7 0.7 + 0.7 0.7 0.7 + 0.1 0.1 0.1 1 + + + + + + 0.05 + + + + + + attachment_link + base_link + + + + attachment_link + parachute_small + chute + 0 0 0 0 0 0 + /parachute/cmd_release + + + + + diff --git a/worlds/zephyr_parachute.sdf b/worlds/zephyr_parachute.sdf new file mode 100755 index 0000000..7d8b99e --- /dev/null +++ b/worlds/zephyr_parachute.sdf @@ -0,0 +1,154 @@ + + + + + + 0.001 + -1.0 + + + + + + + + + + + + + 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 + + + + model://runway + + + + 0 0 0.422 -1.5707963 0 1.5707963 + model://zephyr_with_parachute + + + parachute_attachment_link + parachute_small + chute + 0 0 0 0 -1.0 0 + /parachute/cmd_release + + + + + + +